mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Sub: Enabled control modes to operate at zero throttle
This commit is contained in:
parent
fc6f793aab
commit
c6b3f46e04
@ -27,7 +27,7 @@ void Sub::acro_run()
|
||||
int16_t pilot_throttle_scaled;
|
||||
|
||||
// if motors not running reset angle targets
|
||||
if(!motors.armed() || ap.throttle_zero) {
|
||||
if(!motors.armed()) {
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
// slow start if landed
|
||||
if (ap.land_complete) {
|
||||
|
@ -28,7 +28,7 @@ void Sub::rov_run()
|
||||
int16_t pilot_throttle_scaled;
|
||||
|
||||
// if not armed or throttle at zero, set throttle to zero and exit immediately
|
||||
if(!motors.armed() || ap.throttle_zero) {
|
||||
if(!motors.armed()) {
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
// slow start if landed
|
||||
if (ap.land_complete) {
|
||||
|
@ -33,7 +33,7 @@ void Sub::sport_run()
|
||||
pos_control.set_accel_z(g.pilot_accel_z);
|
||||
|
||||
// if not armed or throttle at zero, set throttle to zero and exit immediately
|
||||
if(!motors.armed() || ap.throttle_zero) {
|
||||
if(!motors.armed()) {
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average);
|
||||
return;
|
||||
|
@ -28,7 +28,7 @@ void Sub::stabilize_run()
|
||||
int16_t pilot_throttle_scaled;
|
||||
|
||||
// if not armed or throttle at zero, set throttle to zero and exit immediately
|
||||
if(!motors.armed() || ap.throttle_zero) {
|
||||
if(!motors.armed()) {
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
// slow start if landed
|
||||
if (ap.land_complete) {
|
||||
|
Loading…
Reference in New Issue
Block a user