From 5ca3c4baf686d61dcfc425d9c2efcdf12421eeb2 Mon Sep 17 00:00:00 2001 From: Randy Mackay <rmackay9@yahoo.com> Date: Fri, 26 Sep 2014 23:23:04 +0900 Subject: [PATCH] Mission: fix CHANGE_ALT to store climb rate in lat param The slightly confusing storage of climb rate in the lat field led to a bug fix a few months ago that actually created a bug. --- libraries/AP_Mission/AP_Mission.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 1072b644e4..613c273173 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -809,7 +809,7 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd, case MAV_CMD_CONDITION_CHANGE_ALT: // MAV ID: 113 copy_alt = true; // only altitude is used - packet.param1 = cmd.content.location.alt / 100.0f; // climb/descent rate converted from cm/s to m/s. To-Do: store in proper climb_rate structure + packet.param1 = cmd.content.location.lat / 100.0f; // climb/descent rate converted from cm/s to m/s. To-Do: store in proper climb_rate structure break; case MAV_CMD_CONDITION_DISTANCE: // MAV ID: 114