mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: 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:
parent
354e3fa5bf
commit
a79a8ca659
|
@ -826,16 +826,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
|||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
|
||||
#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_FAILED;
|
||||
#endif
|
||||
|
||||
case MAV_CMD_CONDITION_YAW:
|
||||
// param1 : target angle [0-360]
|
||||
// param2 : speed during change [deg per second]
|
||||
|
|
Loading…
Reference in New Issue