diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index 3b8e9a9c25..ae75ca7369 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -680,14 +680,18 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in } return MAV_RESULT_FAILED; +#if AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED case MAV_CMD_NAV_SET_YAW_SPEED: + send_received_message_deprecation_warning("MAV_CMD_NAV_SET_YAW_SPEED"); return handle_command_nav_set_yaw_speed(packet, msg); +#endif default: return GCS_MAVLINK::handle_command_int_packet(packet, msg); } } +#if AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED MAV_RESULT GCS_MAVLINK_Rover::handle_command_nav_set_yaw_speed(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { // param1 : yaw angle (may be absolute or relative) @@ -709,6 +713,7 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_nav_set_yaw_speed(const mavlink_com } return MAV_RESULT_ACCEPTED; } +#endif MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_do_reposition(const mavlink_command_int_t &packet) { diff --git a/Rover/GCS_Mavlink.h b/Rover/GCS_Mavlink.h index 14ab0a8194..2c22249c0a 100644 --- a/Rover/GCS_Mavlink.h +++ b/Rover/GCS_Mavlink.h @@ -2,6 +2,11 @@ #include + // set 0 in 4.6, remove feature in 4.7: +#ifndef AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED +#define AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED 1 +#endif + class GCS_MAVLINK_Rover : public GCS_MAVLINK { public: