mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: 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 FAILED, which is wrong, it should be DENIED
This commit is contained in:
parent
d41e677c08
commit
5c7e22debb
|
@ -963,15 +963,15 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
|
|||
case MAV_CMD_GUIDED_CHANGE_HEADING:
|
||||
return handle_command_int_guided_slew_commands(packet);
|
||||
|
||||
case MAV_CMD_DO_FOLLOW:
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
case MAV_CMD_DO_FOLLOW:
|
||||
// param1: sysid of target to follow
|
||||
if ((packet.param1 > 0) && (packet.param1 <= 255)) {
|
||||
plane.g2.follow.set_target_sysid((uint8_t)packet.param1);
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
return MAV_RESULT_DENIED;
|
||||
#endif
|
||||
return MAV_RESULT_FAILED;
|
||||
|
||||
default:
|
||||
return GCS_MAVLINK::handle_command_int_packet(packet);
|
||||
|
|
Loading…
Reference in New Issue