|
|
|
@ -293,8 +293,8 @@ void Sub::guided_pos_control_run()
@@ -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()
@@ -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()
@@ -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()
@@ -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; |
|
|
|
|
} |
|
|
|
|