Skip to content

Commit

Permalink
Copter: Change from enum to class
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura authored and rmackay9 committed May 7, 2024
1 parent e5a2ba3 commit 07a5f61
Show file tree
Hide file tree
Showing 8 changed files with 43 additions and 43 deletions.
14 changes: 7 additions & 7 deletions ArduCopter/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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;
}
}

Expand Down
12 changes: 6 additions & 6 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -231,12 +231,12 @@ class Mode {
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);

Expand Down
10 changes: 5 additions & 5 deletions ArduCopter/mode_althold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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));
Expand All @@ -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
Expand Down
10 changes: 5 additions & 5 deletions ArduCopter/mode_flowhold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -263,15 +263,15 @@ 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();
copter.pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
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);

Expand All @@ -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
Expand Down
10 changes: 5 additions & 5 deletions ArduCopter/mode_loiter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,26 +123,26 @@ 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
loiter_nav->init_target();
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));
Expand All @@ -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);

Expand Down
10 changes: 5 additions & 5 deletions ArduCopter/mode_poshold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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

Expand All @@ -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));
Expand All @@ -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
Expand Down
10 changes: 5 additions & 5 deletions ArduCopter/mode_sport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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));
Expand All @@ -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
Expand Down
10 changes: 5 additions & 5 deletions ArduCopter/mode_zigzag.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -326,15 +326,15 @@ 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
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);
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));
Expand All @@ -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);

Expand Down

0 comments on commit 07a5f61

Please sign in to comment.