GCS_MAVLink: support MAV_CMD_FIXED_MAG_CAL_YAW

This commit is contained in:
Andrew Tridgell 2019-11-21 14:54:07 +11:00
parent facedb5156
commit 48e116afca
2 changed files with 19 additions and 0 deletions

View File

@ -417,6 +417,8 @@ protected:
void handle_optical_flow(const mavlink_message_t &msg);
MAV_RESULT handle_fixed_mag_cal_yaw(const mavlink_command_long_t &packet);
// vehicle-overridable message send function
virtual bool try_send_message(enum ap_message id);
virtual void send_global_position_int();

View File

@ -3012,6 +3012,19 @@ void GCS_MAVLINK::handle_optical_flow(const mavlink_message_t &msg)
optflow->handle_msg(msg);
}
/*
handle MAV_CMD_FIXED_MAG_CAL_YAW
*/
MAV_RESULT GCS_MAVLINK::handle_fixed_mag_cal_yaw(const mavlink_command_long_t &packet)
{
Compass &compass = AP::compass();
return compass.mag_cal_fixed_yaw(packet.param1,
uint8_t(packet.param2),
packet.param3,
packet.param4);
}
/*
handle messages which don't require vehicle specific data
*/
@ -3731,6 +3744,10 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
return MAV_RESULT_UNSUPPORTED;
case MAV_CMD_FIXED_MAG_CAL_YAW:
result = handle_fixed_mag_cal_yaw(packet);
break;
default:
result = MAV_RESULT_UNSUPPORTED;
break;