Commit 0d1a709d authored by DonLakeFlyer's avatar DonLakeFlyer

parent 979e9922
......@@ -3665,6 +3665,22 @@ void Vehicle::stopCalibration(void)
0); // unused
}
void Vehicle::startUAVCANBusConfig(void)
{
sendMavCommand(defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
true, // showError
1); // start config
}
void Vehicle::stopUAVCANBusConfig(void)
{
sendMavCommand(defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
true, // showError
0); // stop config
}
void Vehicle::setSoloFirmware(bool soloFirmware)
{
if (soloFirmware != _soloFirmware) {
......
......@@ -1003,6 +1003,9 @@ public:
void startCalibration (CalibrationType calType);
void stopCalibration (void);
void startUAVCANBusConfig(void);
void stopUAVCANBusConfig(void);
Fact* roll () { return &_rollFact; }
Fact* pitch () { return &_pitchFact; }
Fact* heading () { return &_headingFact; }
......
......@@ -348,41 +348,6 @@ void UAS::receiveMessage(mavlink_message_t message)
#pragma warning(pop, 0)
#endif
void UAS::startBusConfig(UASInterface::StartBusConfigType calType)
{
if (!_vehicle) {
return;
}
int actuatorCal = 0;
switch (calType) {
case StartBusConfigActuators:
actuatorCal = 1;
break;
case EndBusConfigActuators:
actuatorCal = 0;
break;
}
_vehicle->sendMavCommand(_vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
true, // showError
actuatorCal); // actuators
}
void UAS::stopBusConfig(void)
{
if (!_vehicle) {
return;
}
_vehicle->sendMavCommand(_vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
true, // showError
0); // cancel
}
/**
* Check if time is smaller than 40 years, assuming no system without Unix
* timestamp runs longer than 40 years continuously without reboot. In worst case
......
......@@ -180,9 +180,6 @@ public slots:
/** @brief Receive a message from one of the communication links. */
virtual void receiveMessage(mavlink_message_t message);
void startBusConfig(StartBusConfigType calType);
void stopBusConfig(void);
signals:
void imageStarted(quint64 timestamp);
/** @brief A new camera image has arrived */
......
......@@ -39,17 +39,6 @@ public:
/** @brief The time interval the robot is switched on **/
virtual quint64 getUptime() const = 0;
enum StartBusConfigType {
StartBusConfigActuators,
EndBusConfigActuators,
};
/// Starts the specified bus configuration
virtual void startBusConfig(StartBusConfigType calType) = 0;
/// Ends any current bus configuration
virtual void stopBusConfig(void) = 0;
public slots:
/** @brief Order the robot to pair its receiver **/
virtual void pairRX(int rxType, int rxSubType) = 0;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment