mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Plane: provide target velocity in QPOS descent
This commit is contained in:
parent
74da3c74ac
commit
5857e750ce
@ -2659,7 +2659,7 @@ void QuadPlane::vtol_position_controller(void)
|
|||||||
for final land repositioning and descent we run the position controller
|
for final land repositioning and descent we run the position controller
|
||||||
*/
|
*/
|
||||||
Vector3f zero;
|
Vector3f zero;
|
||||||
pos_control->input_pos_vel_accel_xy(poscontrol.target_cm, zero, zero);
|
pos_control->input_pos_vel_accel_xy(poscontrol.target_cm, poscontrol.target_vel_cms, zero);
|
||||||
|
|
||||||
// also run fixed wing navigation
|
// also run fixed wing navigation
|
||||||
plane.nav_controller->update_waypoint(plane.prev_WP_loc, loc);
|
plane.nav_controller->update_waypoint(plane.prev_WP_loc, loc);
|
||||||
|
Loading…
Reference in New Issue
Block a user