mirror of https://github.com/ArduPilot/ardupilot
Plane: On vtol landings if from a mission perform crosstracking
This commit is contained in:
parent
f70c1e96c7
commit
a8102d6662
|
@ -2407,7 +2407,7 @@ void QuadPlane::vtol_position_controller(void)
|
|||
const float aspeed_threshold = MAX(plane.aparm.airspeed_min-2, assist_speed);
|
||||
|
||||
// run fixed wing navigation
|
||||
plane.nav_controller->update_waypoint(plane.current_loc, loc);
|
||||
plane.nav_controller->update_waypoint(plane.auto_state.crosstrack ? plane.prev_WP_loc : plane.current_loc, loc);
|
||||
|
||||
// use TECS for throttle
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.TECS_controller.get_throttle_demand());
|
||||
|
@ -3240,7 +3240,8 @@ bool QuadPlane::do_vtol_land(const AP_Mission::Mission_Command& cmd)
|
|||
plane.crash_state.is_crashed = false;
|
||||
|
||||
// also update nav_controller for status output
|
||||
plane.nav_controller->update_waypoint(plane.current_loc, plane.next_WP_loc);
|
||||
plane.nav_controller->update_waypoint(plane.auto_state.crosstrack ? plane.prev_WP_loc : plane.current_loc,
|
||||
plane.next_WP_loc);
|
||||
|
||||
poscontrol_init_approach();
|
||||
return true;
|
||||
|
|
Loading…
Reference in New Issue