mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Sub: stop position control when in velocity mode
This commit is contained in:
parent
61d854035c
commit
431ee46133
@ -364,6 +364,7 @@ void Sub::guided_vel_control_run()
|
|||||||
pos_control.set_vel_desired_cms(Vector3f(0,0,0));
|
pos_control.set_vel_desired_cms(Vector3f(0,0,0));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
pos_control.stop_pos_xy_stabilisation();
|
||||||
// call velocity controller which includes z axis controller
|
// call velocity controller which includes z axis controller
|
||||||
pos_control.update_xy_controller();
|
pos_control.update_xy_controller();
|
||||||
pos_control.update_z_controller();
|
pos_control.update_z_controller();
|
||||||
|
Loading…
Reference in New Issue
Block a user