Skip to content

Commit

Permalink
Copter: remove unnecessary true statements
Browse files Browse the repository at this point in the history
  • Loading branch information
bnsgeyer committed Dec 3, 2024
1 parent 40a2c31 commit 13efb77
Show file tree
Hide file tree
Showing 9 changed files with 9 additions and 9 deletions.
2 changes: 1 addition & 1 deletion ArduCopter/mode_acro_heli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ void ModeAcro_Heli::run()
switch (motors->get_spool_state()) {
case AP_Motors::SpoolState::SHUT_DOWN:
// Motors Stopped
attitude_control->reset_target_and_rate(true);
attitude_control->reset_target_and_rate();
attitude_control->reset_rate_controller_I_terms();
break;
case AP_Motors::SpoolState::GROUND_IDLE:
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_althold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ void ModeAltHold::run()

case AltHoldModeState::MotorStopped:
attitude_control->reset_rate_controller_I_terms();
attitude_control->reset_yaw_target_and_rate(true);
attitude_control->reset_yaw_target_and_rate();
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
break;

Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_drift.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ void ModeDrift::run()
switch (motors->get_spool_state()) {
case AP_Motors::SpoolState::SHUT_DOWN:
// Motors Stopped
attitude_control->reset_yaw_target_and_rate(true);
attitude_control->reset_yaw_target_and_rate();
attitude_control->reset_rate_controller_I_terms();
break;

Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_flowhold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -266,7 +266,7 @@ void ModeFlowHold::run()
case AltHoldModeState::MotorStopped:
copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
copter.attitude_control->reset_rate_controller_I_terms();
copter.attitude_control->reset_yaw_target_and_rate(true);
copter.attitude_control->reset_yaw_target_and_rate();
copter.pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
flow_pi_xy.reset_I();
break;
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_loiter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ void ModeLoiter::run()

case AltHoldModeState::MotorStopped:
attitude_control->reset_rate_controller_I_terms();
attitude_control->reset_yaw_target_and_rate(true);
attitude_control->reset_yaw_target_and_rate();
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
loiter_nav->init_target();
attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false);
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_poshold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ void ModePosHold::run()

case AltHoldModeState::MotorStopped:
attitude_control->reset_rate_controller_I_terms();
attitude_control->reset_yaw_target_and_rate(true);
attitude_control->reset_yaw_target_and_rate();
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
loiter_nav->clear_pilot_desired_acceleration();
loiter_nav->init_target();
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_sport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ void ModeSport::run()

case AltHoldModeState::MotorStopped:
attitude_control->reset_rate_controller_I_terms();
attitude_control->reset_yaw_target_and_rate(true);
attitude_control->reset_yaw_target_and_rate();
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
break;

Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_stabilize_heli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ void ModeStabilize_Heli::run()
switch (motors->get_spool_state()) {
case AP_Motors::SpoolState::SHUT_DOWN:
// Motors Stopped
attitude_control->reset_yaw_target_and_rate(true);
attitude_control->reset_yaw_target_and_rate();
attitude_control->reset_rate_controller_I_terms();
break;
case AP_Motors::SpoolState::GROUND_IDLE:
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_zigzag.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -330,7 +330,7 @@ void ModeZigZag::manual_control()

case AltHoldModeState::MotorStopped:
attitude_control->reset_rate_controller_I_terms();
attitude_control->reset_yaw_target_and_rate(true);
attitude_control->reset_yaw_target_and_rate();
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
loiter_nav->init_target();
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(loiter_nav->get_roll(), loiter_nav->get_pitch(), target_yaw_rate);
Expand Down

0 comments on commit 13efb77

Please sign in to comment.