diff --git a/ArduSub/control_acro.cpp b/ArduSub/control_acro.cpp index 5da2e81d66..4884d5cc81 100644 --- a/ArduSub/control_acro.cpp +++ b/ArduSub/control_acro.cpp @@ -27,7 +27,8 @@ void Sub::acro_run() // if not armed set throttle to zero and exit immediately if (!motors.armed()) { motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); - attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); + attitude_control.set_throttle_out(0,true,g.throttle_filt); + attitude_control.relax_attitude_controllers(); return; } diff --git a/ArduSub/control_althold.cpp b/ArduSub/control_althold.cpp index a8121eeff8..a5e14a477b 100644 --- a/ArduSub/control_althold.cpp +++ b/ArduSub/control_althold.cpp @@ -39,7 +39,8 @@ void Sub::althold_run() if (!motors.armed()) { motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); // Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle) - attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); + attitude_control.set_throttle_out(0,true,g.throttle_filt); + attitude_control.relax_attitude_controllers(); pos_control.relax_alt_hold_controllers(motors.get_throttle_hover()); last_pilot_heading = ahrs.yaw_sensor; return; diff --git a/ArduSub/control_auto.cpp b/ArduSub/control_auto.cpp index 81356a6c98..d12b05c657 100644 --- a/ArduSub/control_auto.cpp +++ b/ArduSub/control_auto.cpp @@ -118,8 +118,8 @@ void Sub::auto_wp_run() // call attitude controller // Sub vehicles do not stabilize roll/pitch/yaw when disarmed motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); - attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); - + attitude_control.set_throttle_out(0,true,g.throttle_filt); + attitude_control.relax_attitude_controllers(); return; } @@ -203,9 +203,9 @@ void Sub::auto_spline_run() // To-Do: reset waypoint origin to current location because vehicle is probably on the ground so we don't want it lurching left or right on take-off // (of course it would be better if people just used take-off) // Sub vehicles do not stabilize roll/pitch/yaw when disarmed - attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); - + attitude_control.set_throttle_out(0,true,g.throttle_filt); + attitude_control.relax_attitude_controllers(); return; } @@ -391,7 +391,8 @@ void Sub::auto_loiter_run() if (!motors.armed()) { motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); // Sub vehicles do not stabilize roll/pitch/yaw when disarmed - attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); + attitude_control.set_throttle_out(0,true,g.throttle_filt); + attitude_control.relax_attitude_controllers(); return; } @@ -675,7 +676,8 @@ void Sub::auto_terrain_recover_run() // if not armed set throttle to zero and exit immediately if (!motors.armed()) { motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); - attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); + attitude_control.set_throttle_out(0,true,g.throttle_filt); + attitude_control.relax_attitude_controllers(); return; } diff --git a/ArduSub/control_circle.cpp b/ArduSub/control_circle.cpp index 7650ad0f05..07cf4d7597 100644 --- a/ArduSub/control_circle.cpp +++ b/ArduSub/control_circle.cpp @@ -43,8 +43,8 @@ void Sub::circle_run() // To-Do: add some initialisation of position controllers motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); // Sub vehicles do not stabilize roll/pitch/yaw when disarmed - attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); - + attitude_control.set_throttle_out(0,true,g.throttle_filt); + attitude_control.relax_attitude_controllers(); pos_control.set_alt_target_to_current_alt(); return; } diff --git a/ArduSub/control_guided.cpp b/ArduSub/control_guided.cpp index 095a1d95b2..17ee7e5876 100644 --- a/ArduSub/control_guided.cpp +++ b/ArduSub/control_guided.cpp @@ -293,8 +293,8 @@ void Sub::guided_pos_control_run() if (!motors.armed()) { motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); // Sub vehicles do not stabilize roll/pitch/yaw when disarmed - attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); - + attitude_control.set_throttle_out(0,true,g.throttle_filt); + attitude_control.relax_attitude_controllers(); return; } @@ -344,8 +344,8 @@ void Sub::guided_vel_control_run() pos_control.init_vel_controller_xyz(); motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); // Sub vehicles do not stabilize roll/pitch/yaw when disarmed - attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); - + attitude_control.set_throttle_out(0,true,g.throttle_filt); + attitude_control.relax_attitude_controllers(); return; } @@ -399,8 +399,8 @@ void Sub::guided_posvel_control_run() pos_control.set_desired_velocity(Vector3f(0,0,0)); motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); // Sub vehicles do not stabilize roll/pitch/yaw when disarmed - attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); - + attitude_control.set_throttle_out(0,true,g.throttle_filt); + attitude_control.relax_attitude_controllers(); return; } @@ -469,8 +469,8 @@ void Sub::guided_angle_control_run() if (!motors.armed()) { motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); // Sub vehicles do not stabilize roll/pitch/yaw when disarmed - attitude_control.set_throttle_out_unstabilized(0.0f,true,g.throttle_filt); - + attitude_control.set_throttle_out(0.0f,true,g.throttle_filt); + attitude_control.relax_attitude_controllers(); pos_control.relax_alt_hold_controllers(motors.get_throttle_hover()); return; } diff --git a/ArduSub/control_manual.cpp b/ArduSub/control_manual.cpp index 4cf757d3e4..baeb646cd8 100644 --- a/ArduSub/control_manual.cpp +++ b/ArduSub/control_manual.cpp @@ -20,7 +20,8 @@ void Sub::manual_run() // if not armed set throttle to zero and exit immediately if (!motors.armed()) { motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); - attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); + attitude_control.set_throttle_out(0,true,g.throttle_filt); + attitude_control.relax_attitude_controllers(); return; } diff --git a/ArduSub/control_poshold.cpp b/ArduSub/control_poshold.cpp index fe82c638b9..45d7dae2f8 100644 --- a/ArduSub/control_poshold.cpp +++ b/ArduSub/control_poshold.cpp @@ -43,7 +43,8 @@ void Sub::poshold_run() motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); loiter_nav.clear_pilot_desired_acceleration(); loiter_nav.init_target(); - attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); + attitude_control.set_throttle_out(0,true,g.throttle_filt); + attitude_control.relax_attitude_controllers(); pos_control.relax_alt_hold_controllers(motors.get_throttle_hover()); return; } diff --git a/ArduSub/control_stabilize.cpp b/ArduSub/control_stabilize.cpp index 7d2ca51fe6..7963cf674b 100644 --- a/ArduSub/control_stabilize.cpp +++ b/ArduSub/control_stabilize.cpp @@ -21,7 +21,8 @@ void Sub::stabilize_run() // if not armed set throttle to zero and exit immediately if (!motors.armed()) { motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); - attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); + attitude_control.set_throttle_out(0,true,g.throttle_filt); + attitude_control.relax_attitude_controllers(); last_pilot_heading = ahrs.yaw_sensor; return; } diff --git a/ArduSub/control_surface.cpp b/ArduSub/control_surface.cpp index d0f9863924..924a0fbf06 100644 --- a/ArduSub/control_surface.cpp +++ b/ArduSub/control_surface.cpp @@ -28,7 +28,8 @@ void Sub::surface_run() if (!motors.armed()) { motors.output_min(); motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); - attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); + attitude_control.set_throttle_out(0,true,g.throttle_filt); + attitude_control.relax_attitude_controllers(); return; }