mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Mission: bug fix to condition-change-alt
Fix contributed by oniondream, thanks!
This commit is contained in:
parent
24b481ac0d
commit
621cc2b953
@ -777,7 +777,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.lat / 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.alt / 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