mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
AP_Mission: make cmd.p1 be radius on plane for NAV_WAYPOINT
This commit is contained in:
parent
9de1ae8fbb
commit
c4f84232e2
@ -466,7 +466,18 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
|
|||||||
|
|
||||||
case MAV_CMD_NAV_WAYPOINT: // MAV ID: 16
|
case MAV_CMD_NAV_WAYPOINT: // MAV ID: 16
|
||||||
copy_location = true;
|
copy_location = true;
|
||||||
cmd.p1 = packet.param1; // delay at waypoint in seconds
|
/*
|
||||||
|
the 15 byte limit means we can't fit both delay and radius
|
||||||
|
in the cmd structure. When we expand the mission structure
|
||||||
|
we can do this properly
|
||||||
|
*/
|
||||||
|
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
||||||
|
// acceptance radius in meters
|
||||||
|
cmd.p1 = packet.param2;
|
||||||
|
#else
|
||||||
|
// delay at waypoint in seconds
|
||||||
|
cmd.p1 = packet.param1;
|
||||||
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_CMD_NAV_LOITER_UNLIM: // MAV ID: 17
|
case MAV_CMD_NAV_LOITER_UNLIM: // MAV ID: 17
|
||||||
|
Loading…
Reference in New Issue
Block a user