Skip to content

Commit cb73e0c

Browse files
committed
Sub: Update set_throttle_out() when disarmed in all modes.
Extends commit 56df6b to apply to other modes besides Manual.
1 parent 56df6ba commit cb73e0c

File tree

6 files changed

+11
-11
lines changed

6 files changed

+11
-11
lines changed

ArduSub/mode_acro.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ void ModeAcro::run()
1919
// if not armed set throttle to zero and exit immediately
2020
if (!motors.armed()) {
2121
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
22-
attitude_control->set_throttle_out(0,true,g.throttle_filt);
22+
attitude_control->set_throttle_out(0.5,true,g.throttle_filt);
2323
attitude_control->relax_attitude_controllers();
2424
return;
2525
}

ArduSub/mode_auto.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -111,7 +111,7 @@ void ModeAuto::auto_wp_run()
111111
// call attitude controller
112112
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
113113
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
114-
attitude_control->set_throttle_out(0,true,g.throttle_filt);
114+
attitude_control->set_throttle_out(0.5,true,g.throttle_filt);
115115
attitude_control->relax_attitude_controllers();
116116
sub.wp_nav.wp_and_spline_init_m(); // Reset xy target
117117
return;
@@ -302,7 +302,7 @@ void ModeAuto::auto_loiter_run()
302302
if (!motors.armed()) {
303303
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
304304
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
305-
attitude_control->set_throttle_out(0,true,g.throttle_filt);
305+
attitude_control->set_throttle_out(0.5,true,g.throttle_filt);
306306
attitude_control->relax_attitude_controllers();
307307

308308
sub.wp_nav.wp_and_spline_init_m(); // Reset xy target
@@ -479,7 +479,7 @@ void ModeAuto::auto_terrain_recover_run()
479479
// if not armed set throttle to zero and exit immediately
480480
if (!motors.armed()) {
481481
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
482-
attitude_control->set_throttle_out(0,true,g.throttle_filt);
482+
attitude_control->set_throttle_out(0.5,true,g.throttle_filt);
483483
attitude_control->relax_attitude_controllers();
484484

485485
sub.loiter_nav.init_target(); // Reset xy target

ArduSub/mode_circle.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ void ModeCircle::run()
4646
// To-Do: add some initialisation of position controllers
4747
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
4848
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
49-
attitude_control->set_throttle_out(0,true,g.throttle_filt);
49+
attitude_control->set_throttle_out(0.5,true,g.throttle_filt);
5050
attitude_control->relax_attitude_controllers();
5151
sub.circle_nav.init();
5252
return;

ArduSub/mode_guided.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -464,7 +464,7 @@ void ModeGuided::guided_pos_control_run()
464464
if (!motors.armed()) {
465465
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
466466
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
467-
attitude_control->set_throttle_out(0,true,g.throttle_filt);
467+
attitude_control->set_throttle_out(0.5,true,g.throttle_filt);
468468
attitude_control->relax_attitude_controllers();
469469
sub.wp_nav.wp_and_spline_init_m();
470470
return;
@@ -529,7 +529,7 @@ void ModeGuided::guided_vel_control_run()
529529
if (!motors.armed()) {
530530
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
531531
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
532-
attitude_control->set_throttle_out(0,true,g.throttle_filt);
532+
attitude_control->set_throttle_out(0.5,true,g.throttle_filt);
533533
attitude_control->relax_attitude_controllers();
534534
// initialise velocity controller
535535
position_control->D_init_controller();
@@ -602,7 +602,7 @@ void ModeGuided::guided_posvel_control_run()
602602
if (!motors.armed()) {
603603
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
604604
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
605-
attitude_control->set_throttle_out(0,true,g.throttle_filt);
605+
attitude_control->set_throttle_out(0.5,true,g.throttle_filt);
606606
attitude_control->relax_attitude_controllers();
607607
// initialise velocity controller
608608
position_control->D_init_controller();
@@ -682,7 +682,7 @@ void ModeGuided::guided_angle_control_run()
682682
if (!motors.armed()) {
683683
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
684684
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
685-
attitude_control->set_throttle_out(0.0f,true,g.throttle_filt);
685+
attitude_control->set_throttle_out(0.5f,true,g.throttle_filt);
686686
attitude_control->relax_attitude_controllers();
687687
// initialise velocity controller
688688
position_control->D_init_controller();

ArduSub/mode_stabilize.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@ void ModeStabilize::run()
1818
// if not armed set throttle to zero and exit immediately
1919
if (!motors.armed()) {
2020
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
21-
attitude_control->set_throttle_out(0,true,g.throttle_filt);
21+
attitude_control->set_throttle_out(0.5,true,g.throttle_filt);
2222
attitude_control->relax_attitude_controllers();
2323
sub.last_pilot_heading_rad = ahrs.get_yaw_rad();
2424
return;

ArduSub/mode_surface.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@ void ModeSurface::run()
2525
if (!motors.armed()) {
2626
motors.output_min();
2727
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
28-
attitude_control->set_throttle_out(0,true,g.throttle_filt);
28+
attitude_control->set_throttle_out(0.5,true,g.throttle_filt);
2929
attitude_control->relax_attitude_controllers();
3030
position_control->D_init_controller();
3131
return;

0 commit comments

Comments
 (0)