|
|
|
@ -3012,6 +3012,19 @@ void GCS_MAVLINK::handle_optical_flow(const mavlink_message_t &msg)
@@ -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
@@ -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; |
|
|
|
|