forked from Archive/PX4-Autopilot
Merge pull request #1013 from PX4/waypointminpitch
mavlink mission item takeoff: read correct param for minimal pitch
This commit is contained in:
commit
f6eff64d11
|
@ -886,7 +886,7 @@ int Mavlink::map_mavlink_mission_item_to_mission_item(const mavlink_mission_item
|
|||
|
||||
switch (mavlink_mission_item->command) {
|
||||
case MAV_CMD_NAV_TAKEOFF:
|
||||
mission_item->pitch_min = mavlink_mission_item->param2;
|
||||
mission_item->pitch_min = mavlink_mission_item->param1;
|
||||
break;
|
||||
|
||||
default:
|
||||
|
|
Loading…
Reference in New Issue