mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: deprecate MAV_CMD_NAV_SET_YAW_SPEED
This commit is contained in:
parent
4ae8379616
commit
cc3fe56a08
@ -680,14 +680,18 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in
|
|||||||
}
|
}
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
|
|
||||||
|
#if AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED
|
||||||
case MAV_CMD_NAV_SET_YAW_SPEED:
|
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);
|
return handle_command_nav_set_yaw_speed(packet, msg);
|
||||||
|
#endif
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
|
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)
|
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)
|
// 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;
|
return MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_do_reposition(const mavlink_command_int_t &packet)
|
MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_do_reposition(const mavlink_command_int_t &packet)
|
||||||
{
|
{
|
||||||
|
@ -2,6 +2,11 @@
|
|||||||
|
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
|
||||||
|
// 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
|
class GCS_MAVLINK_Rover : public GCS_MAVLINK
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
Loading…
Reference in New Issue
Block a user