@ -348,95 +348,6 @@ void UAS::receiveMessage(mavlink_message_t message)
@@ -348,95 +348,6 @@ void UAS::receiveMessage(mavlink_message_t message)
# pragma warning(pop, 0)
# endif
void UAS : : startCalibration ( UASInterface : : StartCalibrationType calType )
{
if ( ! _vehicle ) {
return ;
}
int gyroCal = 0 ;
int magCal = 0 ;
int airspeedCal = 0 ;
int radioCal = 0 ;
int accelCal = 0 ;
int pressureCal = 0 ;
int escCal = 0 ;
switch ( calType ) {
case StartCalibrationGyro :
gyroCal = 1 ;
break ;
case StartCalibrationMag :
magCal = 1 ;
break ;
case StartCalibrationAirspeed :
airspeedCal = 1 ;
break ;
case StartCalibrationRadio :
radioCal = 1 ;
break ;
case StartCalibrationCopyTrims :
radioCal = 2 ;
break ;
case StartCalibrationAccel :
accelCal = 1 ;
break ;
case StartCalibrationLevel :
accelCal = 2 ;
break ;
case StartCalibrationPressure :
pressureCal = 1 ;
break ;
case StartCalibrationEsc :
escCal = 1 ;
break ;
case StartCalibrationUavcanEsc :
escCal = 2 ;
break ;
case StartCalibrationCompassMot :
airspeedCal = 1 ; // ArduPilot, bit of a hack
break ;
}
// We can't use sendMavCommand here since we have no idea how long it will be before the command returns a result. This in turn
// causes the retry logic to break down.
mavlink_message_t msg ;
mavlink_msg_command_long_pack_chan ( mavlink - > getSystemId ( ) ,
mavlink - > getComponentId ( ) ,
_vehicle - > priorityLink ( ) - > mavlinkChannel ( ) ,
& msg ,
uasId ,
_vehicle - > defaultComponentId ( ) , // target component
MAV_CMD_PREFLIGHT_CALIBRATION , // command id
0 , // 0=first transmission of command
gyroCal , // gyro cal
magCal , // mag cal
pressureCal , // ground pressure
radioCal , // radio cal
accelCal , // accel cal
airspeedCal , // PX4: airspeed cal, ArduPilot: compass mot
escCal ) ; // esc cal
_vehicle - > sendMessageOnLinkThreadSafe ( _vehicle - > priorityLink ( ) , msg ) ;
}
void UAS : : stopCalibration ( void )
{
if ( ! _vehicle ) {
return ;
}
_vehicle - > sendMavCommand ( _vehicle - > defaultComponentId ( ) , // target component
MAV_CMD_PREFLIGHT_CALIBRATION , // command id
true , // showError
0 , // gyro cal
0 , // mag cal
0 , // ground pressure
0 , // radio cal
0 , // accel cal
0 , // airspeed cal
0 ) ; // unused
}
void UAS : : startBusConfig ( UASInterface : : StartBusConfigType calType )
{
if ( ! _vehicle ) {