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
This commit is contained in:
Peter Barker 2023-07-28 09:52:04 +10:00 committed by Andrew Tridgell
parent a79a8ca659
commit d41e677c08
1 changed files with 2 additions and 2 deletions

View File

@ -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);