mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: handle mag cal as both COMMAND_LONG and COMMAND_INT
This commit is contained in:
parent
1e83e61b25
commit
d50c429355
|
@ -196,7 +196,7 @@ public:
|
|||
/*
|
||||
handle an incoming MAG_CAL command
|
||||
*/
|
||||
MAV_RESULT handle_mag_cal_command(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_mag_cal_command(const mavlink_command_int_t &packet);
|
||||
|
||||
bool send_mag_cal_progress(const class GCS_MAVLINK& link);
|
||||
bool send_mag_cal_report(const class GCS_MAVLINK& link);
|
||||
|
|
|
@ -371,7 +371,7 @@ uint8_t Compass::_get_cal_mask()
|
|||
/*
|
||||
handle an incoming MAG_CAL command
|
||||
*/
|
||||
MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_long_t &packet)
|
||||
MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_int_t &packet)
|
||||
{
|
||||
MAV_RESULT result = MAV_RESULT_FAILED;
|
||||
|
||||
|
@ -392,7 +392,7 @@ MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_long_t &packet)
|
|||
bool retry = !is_zero(packet.param2);
|
||||
bool autosave = !is_zero(packet.param3);
|
||||
float delay = packet.param4;
|
||||
bool autoreboot = !is_zero(packet.param5);
|
||||
bool autoreboot = packet.x != 0;
|
||||
|
||||
if (mag_mask == 0) { // 0 means all
|
||||
_reset_compass_id();
|
||||
|
|
Loading…
Reference in New Issue