@@ -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 ();
0 commit comments