From c61022f596e094b9558bb037c9e561cf70d106c8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 20 Sep 2023 10:09:44 +1000 Subject: [PATCH] Copter: handle DO_CHANGE_SPEED as both COMMAND_LONG and COMMAND_INT --- ArduCopter/GCS_Mavlink.cpp | 16 +++++++++++----- ArduCopter/GCS_Mavlink.h | 1 + 2 files changed, 12 insertions(+), 5 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index d83d00560c..192b034e3b 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -739,6 +739,10 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_do_reposition(const mavlink_co MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { switch(packet.command) { + + case MAV_CMD_DO_CHANGE_SPEED: + return handle_MAV_CMD_DO_CHANGE_SPEED(packet); + #if MODE_FOLLOW_ENABLED == ENABLED case MAV_CMD_DO_FOLLOW: // param1: sysid of target to follow @@ -873,7 +877,13 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ } return MAV_RESULT_FAILED; - case MAV_CMD_DO_CHANGE_SPEED: + default: + return GCS_MAVLINK::handle_command_long_packet(packet, msg); + } +} + +MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet) +{ // param1 : Speed type (0 or 1=Ground Speed, 2=Climb Speed, 3=Descent Speed) // param2 : new speed in m/s // param3 : unused @@ -897,10 +907,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ } } return MAV_RESULT_FAILED; - - default: - return GCS_MAVLINK::handle_command_long_packet(packet, msg); - } } #if MODE_AUTO_ENABLED == ENABLED diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index bf6ca7e6cb..f721a0c204 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -98,6 +98,7 @@ private: #endif // HAL_HIGH_LATENCY2_ENABLED + MAV_RESULT handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet); MAV_RESULT handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet); MAV_RESULT handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet);