diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index be15da6bb9..e80f84bc77 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -645,7 +645,10 @@ protected: MAV_RESULT handle_command_do_set_roi_none(); virtual MAV_RESULT handle_command_mount(const mavlink_command_long_t &packet, const mavlink_message_t &msg); - MAV_RESULT handle_command_mag_cal(const mavlink_command_long_t &packet); + + MAV_RESULT handle_command_mag_cal(const mavlink_command_int_t &packet); + MAV_RESULT handle_command_fixed_mag_cal_yaw(const mavlink_command_int_t &packet); + MAV_RESULT try_command_long_as_command_int(const mavlink_command_long_t &packet); virtual MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet); MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet); @@ -670,8 +673,6 @@ protected: void handle_optical_flow(const mavlink_message_t &msg); - MAV_RESULT handle_command_fixed_mag_cal_yaw(const mavlink_command_int_t &packet); - void handle_manual_control(const mavlink_message_t &msg); // default empty handling of LANDING_TARGET diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index aa0274d82d..9a673f7e77 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3712,22 +3712,25 @@ void GCS_MAVLINK::handle_optical_flow(const mavlink_message_t &msg) #endif +#if COMPASS_CAL_ENABLED /* handle MAV_CMD_FIXED_MAG_CAL_YAW */ MAV_RESULT GCS_MAVLINK::handle_command_fixed_mag_cal_yaw(const mavlink_command_int_t &packet) { -#if COMPASS_CAL_ENABLED Compass &compass = AP::compass(); return compass.mag_cal_fixed_yaw(packet.param1, uint8_t(packet.param2), packet.param3, packet.param4); -#else - return MAV_RESULT_UNSUPPORTED; -#endif } +MAV_RESULT GCS_MAVLINK::handle_command_mag_cal(const mavlink_command_int_t &packet) +{ + return AP::compass().handle_mag_cal_command(packet); +} +#endif // COMPASS_CAL_ENABLED + /* handle MAV_CMD_CAN_FORWARD */ @@ -4426,13 +4429,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_battery_reset(const mavlink_command_long_ return MAV_RESULT_FAILED; } -#if COMPASS_CAL_ENABLED -MAV_RESULT GCS_MAVLINK::handle_command_mag_cal(const mavlink_command_long_t &packet) -{ - return AP::compass().handle_mag_cal_command(packet); -} -#endif - #if AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet) { @@ -4696,15 +4692,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t break; #endif // HAL_HIGH_LATENCY2_ENABLED -#if COMPASS_CAL_ENABLED - case MAV_CMD_DO_START_MAG_CAL: - case MAV_CMD_DO_ACCEPT_MAG_CAL: - case MAV_CMD_DO_CANCEL_MAG_CAL: { - result = handle_command_mag_cal(packet); - break; - } -#endif - case MAV_CMD_START_RX_PAIR: result = handle_rc_bind(packet); break; @@ -5146,8 +5133,15 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p #endif case MAV_CMD_COMPONENT_ARM_DISARM: return handle_command_component_arm_disarm(packet); + +#if COMPASS_CAL_ENABLED case MAV_CMD_FIXED_MAG_CAL_YAW: return handle_command_fixed_mag_cal_yaw(packet); + case MAV_CMD_DO_START_MAG_CAL: + case MAV_CMD_DO_ACCEPT_MAG_CAL: + case MAV_CMD_DO_CANCEL_MAG_CAL: + return handle_command_mag_cal(packet); +#endif #if AP_SCRIPTING_ENABLED case MAV_CMD_SCRIPTING: