mirror of https://github.com/ArduPilot/ardupilot
Copter: Change from enum to class
This commit is contained in:
parent
e5a2ba3ebc
commit
07a5f61782
|
@ -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;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -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);
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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);
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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);
|
||||
|
||||
|
|
Loading…
Reference in New Issue