forked from Archive/PX4-Autopilot
mission: for vtol takeoff don't use next waypoint as target during transition
- this caused the navigator to use the next waypoint (after the vtol takeoff item) to be used as target during the transition. If the altitude of that waypoint was much higher than the takeoff altitude then there were FOH effects after the transition which caused the vehicle to first descend before climbing again. Signed-off-by: RomanBapst <bapstroman@gmail.com>
This commit is contained in:
parent
a1b81df445
commit
d502292d07
|
@ -798,17 +798,10 @@ Mission::set_mission_items()
|
|||
}
|
||||
|
||||
set_vtol_transition_item(&_mission_item, vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW);
|
||||
_mission_item.yaw = _navigator->get_local_position()->heading;
|
||||
|
||||
if (has_next_position_item) {
|
||||
/* got next mission item, update setpoint triplet */
|
||||
mission_item_to_position_setpoint(mission_item_next_position, &pos_sp_triplet->current);
|
||||
|
||||
} else {
|
||||
_mission_item.yaw = _navigator->get_local_position()->heading;
|
||||
|
||||
/* set position setpoint to target during the transition */
|
||||
generate_waypoint_from_heading(&pos_sp_triplet->current, _mission_item.yaw);
|
||||
}
|
||||
/* set position setpoint to target during the transition */
|
||||
generate_waypoint_from_heading(&pos_sp_triplet->current, _mission_item.yaw);
|
||||
}
|
||||
|
||||
/* takeoff completed and transitioned, move to takeoff wp as fixed wing */
|
||||
|
|
Loading…
Reference in New Issue