From c4f84232e20e4aa99d724c5f1671a484ad373aff Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 3 Sep 2014 11:23:08 +1000 Subject: [PATCH] AP_Mission: make cmd.p1 be radius on plane for NAV_WAYPOINT --- libraries/AP_Mission/AP_Mission.cpp | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 2c6cb1625d..bb62a0695e 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -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 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; case MAV_CMD_NAV_LOITER_UNLIM: // MAV ID: 17