mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
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.
This commit is contained in:
parent
ef0e37b478
commit
5ca3c4baf6
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user