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