diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 11d1ab7efe..c4e8068982 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -973,19 +973,19 @@ Mode::AltHoldModeState Mode::get_alt_hold_state(float target_climb_rate_cms) switch (motors->get_spool_state()) { case AP_Motors::SpoolState::SHUT_DOWN: - return AltHold_MotorStopped; + return AltHoldModeState::MotorStopped; case AP_Motors::SpoolState::GROUND_IDLE: - return AltHold_Landed_Ground_Idle; + return AltHoldModeState::Landed_Ground_Idle; default: - return AltHold_Landed_Pre_Takeoff; + return AltHoldModeState::Landed_Pre_Takeoff; } } else if (takeoff.running() || takeoff.triggered(target_climb_rate_cms)) { // the aircraft is currently landed or taking off, asking for a positive climb rate and in THROTTLE_UNLIMITED // the aircraft should progress through the take off procedure - return AltHold_Takeoff; + return AltHoldModeState::Takeoff; } else if (!copter.ap.auto_armed || copter.ap.land_complete) { // the aircraft is armed and landed @@ -1000,17 +1000,17 @@ Mode::AltHoldModeState Mode::get_alt_hold_state(float target_climb_rate_cms) if (motors->get_spool_state() == AP_Motors::SpoolState::GROUND_IDLE) { // the aircraft is waiting in ground idle - return AltHold_Landed_Ground_Idle; + return AltHoldModeState::Landed_Ground_Idle; } else { // the aircraft can leave the ground at any time - return AltHold_Landed_Pre_Takeoff; + return AltHoldModeState::Landed_Pre_Takeoff; } } else { // the aircraft is in a flying state motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); - return AltHold_Flying; + return AltHoldModeState::Flying; } } diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index bb045a2c28..5ac4d97c79 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -231,12 +231,12 @@ protected: virtual float throttle_hover() const; // Alt_Hold based flight mode states used in Alt_Hold, Loiter, and Sport - enum AltHoldModeState { - AltHold_MotorStopped, - AltHold_Takeoff, - AltHold_Landed_Ground_Idle, - AltHold_Landed_Pre_Takeoff, - AltHold_Flying + enum class AltHoldModeState { + MotorStopped, + Takeoff, + Landed_Ground_Idle, + Landed_Pre_Takeoff, + Flying }; AltHoldModeState get_alt_hold_state(float target_climb_rate_cms); diff --git a/ArduCopter/mode_althold.cpp b/ArduCopter/mode_althold.cpp index 36c7a60143..91c7943867 100644 --- a/ArduCopter/mode_althold.cpp +++ b/ArduCopter/mode_althold.cpp @@ -48,22 +48,22 @@ void ModeAltHold::run() // Alt Hold State Machine switch (althold_state) { - case AltHold_MotorStopped: + case AltHoldModeState::MotorStopped: attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_yaw_target_and_rate(false); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: attitude_control->reset_yaw_target_and_rate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // initiate take-off if (!takeoff.running()) { takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); @@ -76,7 +76,7 @@ void ModeAltHold::run() takeoff.do_pilot_takeoff(target_climb_rate); break; - case AltHold_Flying: + case AltHoldModeState::Flying: motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); #if AP_AVOIDANCE_ENABLED diff --git a/ArduCopter/mode_flowhold.cpp b/ArduCopter/mode_flowhold.cpp index f5414e9dac..24ab8806be 100644 --- a/ArduCopter/mode_flowhold.cpp +++ b/ArduCopter/mode_flowhold.cpp @@ -263,7 +263,7 @@ void ModeFlowHold::run() // Flow Hold State Machine switch (flowhold_state) { - case AltHold_MotorStopped: + 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(); @@ -271,7 +271,7 @@ void ModeFlowHold::run() flow_pi_xy.reset_I(); break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // set motors to full range copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); @@ -287,16 +287,16 @@ void ModeFlowHold::run() takeoff.do_pilot_takeoff(target_climb_rate); break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: attitude_control->reset_yaw_target_and_rate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Flying: + case AltHoldModeState::Flying: copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); // get avoidance adjusted climb rate diff --git a/ArduCopter/mode_loiter.cpp b/ArduCopter/mode_loiter.cpp index 602aa52859..1b76c41430 100644 --- a/ArduCopter/mode_loiter.cpp +++ b/ArduCopter/mode_loiter.cpp @@ -123,7 +123,7 @@ void ModeLoiter::run() // Loiter State Machine switch (loiter_state) { - case AltHold_MotorStopped: + case AltHoldModeState::MotorStopped: attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_yaw_target_and_rate(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero @@ -131,18 +131,18 @@ void ModeLoiter::run() attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false); break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: attitude_control->reset_yaw_target_and_rate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); loiter_nav->init_target(); attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // initiate take-off if (!takeoff.running()) { takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); @@ -161,7 +161,7 @@ void ModeLoiter::run() attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false); break; - case AltHold_Flying: + case AltHoldModeState::Flying: // set motors to full range motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); diff --git a/ArduCopter/mode_poshold.cpp b/ArduCopter/mode_poshold.cpp index 7b47eeb7c3..c90e36a18e 100644 --- a/ArduCopter/mode_poshold.cpp +++ b/ArduCopter/mode_poshold.cpp @@ -100,7 +100,7 @@ void ModePosHold::run() // state machine switch (poshold_state) { - case AltHold_MotorStopped: + case AltHoldModeState::MotorStopped: attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_yaw_target_and_rate(false); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero @@ -115,14 +115,14 @@ void ModePosHold::run() init_wind_comp_estimate(); break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: loiter_nav->clear_pilot_desired_acceleration(); loiter_nav->init_target(); attitude_control->reset_yaw_target_and_rate(); init_wind_comp_estimate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero @@ -131,7 +131,7 @@ void ModePosHold::run() pitch_mode = RPMode::PILOT_OVERRIDE; break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // initiate take-off if (!takeoff.running()) { takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); @@ -152,7 +152,7 @@ void ModePosHold::run() pitch_mode = RPMode::PILOT_OVERRIDE; break; - case AltHold_Flying: + case AltHoldModeState::Flying: motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); // get avoidance adjusted climb rate diff --git a/ArduCopter/mode_sport.cpp b/ArduCopter/mode_sport.cpp index 954a5a2b98..7647e4973c 100644 --- a/ArduCopter/mode_sport.cpp +++ b/ArduCopter/mode_sport.cpp @@ -74,22 +74,22 @@ void ModeSport::run() // State Machine switch (sport_state) { - case AltHold_MotorStopped: + case AltHoldModeState::MotorStopped: attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_yaw_target_and_rate(false); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: attitude_control->reset_yaw_target_and_rate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // initiate take-off if (!takeoff.running()) { takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); @@ -102,7 +102,7 @@ void ModeSport::run() takeoff.do_pilot_takeoff(target_climb_rate); break; - case AltHold_Flying: + case AltHoldModeState::Flying: motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); // get avoidance adjusted climb rate diff --git a/ArduCopter/mode_zigzag.cpp b/ArduCopter/mode_zigzag.cpp index 6847126f36..3887f1bd52 100644 --- a/ArduCopter/mode_zigzag.cpp +++ b/ArduCopter/mode_zigzag.cpp @@ -326,7 +326,7 @@ void ModeZigZag::manual_control() // althold state machine switch (althold_state) { - case AltHold_MotorStopped: + case AltHoldModeState::MotorStopped: attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_yaw_target_and_rate(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero @@ -334,7 +334,7 @@ void ModeZigZag::manual_control() attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(loiter_nav->get_roll(), loiter_nav->get_pitch(), target_yaw_rate); break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // initiate take-off if (!takeoff.running()) { takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); @@ -353,18 +353,18 @@ void ModeZigZag::manual_control() takeoff.do_pilot_takeoff(target_climb_rate); break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: attitude_control->reset_yaw_target_and_rate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); loiter_nav->init_target(); attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Flying: + case AltHoldModeState::Flying: // set motors to full range motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);