From effccacf464233edc7faafd9d784b07c21ffccca Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 3 Sep 2014 21:15:41 +1000 Subject: [PATCH] AP_Mission: fixed acceptance radius outgoing this needs to match incoming --- libraries/AP_Mission/AP_Mission.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index bb62a0695e..22a2933992 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -725,7 +725,13 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd, case MAV_CMD_NAV_WAYPOINT: // MAV ID: 16 copy_location = true; - packet.param1 = cmd.p1; // delay at waypoint in seconds +#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) + // acceptance radius in meters + packet.param2 = cmd.p1; +#else + // delay at waypoint in seconds + packet.param1 = cmd.p1; +#endif break; case MAV_CMD_NAV_LOITER_UNLIM: // MAV ID: 17