mirror of https://github.com/ArduPilot/ardupilot
AP_Mission: Give CONINTUE_AND_CHANGE_ALT a parameter: climb/descend
Param 1 denotes which direction the user expects the plane to travel when changing altitude: 0 = no expectation, command completes when within 5 m of altitude. 1 = climb expected, command completes at or above altitude. 2 = descent expected, command completes at or below altitude.
This commit is contained in:
parent
66d7fbfbc1
commit
7e8e3698ae
|
@ -531,6 +531,10 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
|
|||
|
||||
case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT: // MAV ID: 30
|
||||
copy_location = true; // only using alt
|
||||
cmd.p1 = packet.param1; // Climb/Descend
|
||||
// 0 = Neutral, cmd complete at +/- 5 of indicated alt.
|
||||
// 1 = Climb, cmd complete at or above indicated alt.
|
||||
// 2 = Descend, cmd complete at or below indicated alt.
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_LOITER_TO_ALT: // MAV ID: 31
|
||||
|
@ -849,7 +853,11 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd,
|
|||
break;
|
||||
|
||||
case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT: // MAV ID: 30
|
||||
copy_location = true; //only using alt.
|
||||
copy_location = true; //only using alt
|
||||
packet.param1 = cmd.p1; // Climb/Descend
|
||||
// 0 = Neutral, cmd complete at +/- 5 of indicated alt.
|
||||
// 1 = Climb, cmd complete at or above indicated alt.
|
||||
// 2 = Descend, cmd complete at or below indicated alt.
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_LOITER_TO_ALT: // MAV ID: 31
|
||||
|
|
Loading…
Reference in New Issue