From d41e677c086ac5b1202ecac76c65763286a2059c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 28 Jul 2023 09:52:04 +1000 Subject: [PATCH] Copter: correct return error return codes for DO_FOLLOW in the case it wasn't compiled in the return code would be correct. in the case that the parameter was invalid we would return UNSUPPORTED , which is wrong, it should be DENIED --- ArduCopter/GCS_Mavlink.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 8d31a488d4..4720c88c1d 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -739,15 +739,15 @@ 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) { switch(packet.command) { - case MAV_CMD_DO_FOLLOW: #if MODE_FOLLOW_ENABLED == ENABLED + case MAV_CMD_DO_FOLLOW: // param1: sysid of target to follow if ((packet.param1 > 0) && (packet.param1 <= 255)) { copter.g2.follow.set_target_sysid((uint8_t)packet.param1); return MAV_RESULT_ACCEPTED; } + return MAV_RESULT_DENIED; #endif - return MAV_RESULT_UNSUPPORTED; case MAV_CMD_DO_REPOSITION: return handle_command_int_do_reposition(packet);