Plane: rely on conversion from long to int for DO_FOLLOW

we have code which tries to handle commands coming in as command long as command int.

Change to rely on that code working, rather than handling both command-long and command-int variants
This commit is contained in:
Peter Barker 2023-07-28 09:44:49 +10:00 committed by Andrew Tridgell
parent 459ea697d9
commit 354e3fa5bf
1 changed files with 0 additions and 10 deletions

View File

@ -1102,16 +1102,6 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
return MAV_RESULT_ACCEPTED;
#endif
#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_FAILED;
#endif
default:
return GCS_MAVLINK::handle_command_long_packet(packet);
}