mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: Heli: RotorControlState to enum class
This commit is contained in:
parent
a77faaf125
commit
287e9726d7
|
@ -190,7 +190,7 @@ void AP_MotorsHeli::output_min()
|
|||
// move swash to mid
|
||||
move_actuators(0.0f,0.0f,0.5f,0.0f);
|
||||
|
||||
update_motor_control(ROTOR_CONTROL_STOP);
|
||||
update_motor_control(AP_MotorsHeli_RSC::RotorControlState::STOP);
|
||||
|
||||
// override limits flags
|
||||
set_limit_flag_pitch_roll_yaw(true);
|
||||
|
|
|
@ -189,7 +189,7 @@ protected:
|
|||
AP_MotorsHeli_RSC _main_rotor; // main rotor
|
||||
|
||||
// update_motor_controls - sends commands to motor controllers
|
||||
virtual void update_motor_control(RotorControlState state) = 0;
|
||||
virtual void update_motor_control(AP_MotorsHeli_RSC::RotorControlState state) = 0;
|
||||
|
||||
// run spool logic
|
||||
void output_logic();
|
||||
|
|
|
@ -360,12 +360,12 @@ void AP_MotorsHeli_Dual::mix_intermeshing(float pitch_input, float roll_input, f
|
|||
}
|
||||
|
||||
// update_motor_controls - sends commands to motor controllers
|
||||
void AP_MotorsHeli_Dual::update_motor_control(RotorControlState state)
|
||||
void AP_MotorsHeli_Dual::update_motor_control(AP_MotorsHeli_RSC::RotorControlState state)
|
||||
{
|
||||
// Send state update to motors
|
||||
_main_rotor.output(state);
|
||||
|
||||
if (state == ROTOR_CONTROL_STOP) {
|
||||
if (state == AP_MotorsHeli_RSC::RotorControlState::STOP) {
|
||||
// set engine run enable aux output to not run position to kill engine when disarmed
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::Limit::MIN);
|
||||
} else {
|
||||
|
@ -528,20 +528,20 @@ void AP_MotorsHeli_Dual::output_to_motors()
|
|||
switch (_spool_state) {
|
||||
case SpoolState::SHUT_DOWN:
|
||||
// sends minimum values out to the motors
|
||||
update_motor_control(ROTOR_CONTROL_STOP);
|
||||
update_motor_control(AP_MotorsHeli_RSC::RotorControlState::STOP);
|
||||
break;
|
||||
case SpoolState::GROUND_IDLE:
|
||||
// sends idle output to motors when armed. rotor could be static or turning (autorotation)
|
||||
update_motor_control(ROTOR_CONTROL_IDLE);
|
||||
update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE);
|
||||
break;
|
||||
case SpoolState::SPOOLING_UP:
|
||||
case SpoolState::THROTTLE_UNLIMITED:
|
||||
// set motor output based on thrust requests
|
||||
update_motor_control(ROTOR_CONTROL_ACTIVE);
|
||||
update_motor_control(AP_MotorsHeli_RSC::RotorControlState::ACTIVE);
|
||||
break;
|
||||
case SpoolState::SPOOLING_DOWN:
|
||||
// sends idle output to motors and wait for rotor to stop
|
||||
update_motor_control(ROTOR_CONTROL_IDLE);
|
||||
update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -65,7 +65,7 @@ protected:
|
|||
void init_outputs () override;
|
||||
|
||||
// update_motor_controls - sends commands to motor controllers
|
||||
void update_motor_control(RotorControlState state) override;
|
||||
void update_motor_control(AP_MotorsHeli_RSC::RotorControlState state) override;
|
||||
|
||||
// get_swashplate - calculate movement of each swashplate based on configuration
|
||||
float get_swashplate(int8_t swash_num, int8_t swash_axis, float pitch_input, float roll_input, float yaw_input, float coll_input);
|
||||
|
|
|
@ -145,12 +145,12 @@ void AP_MotorsHeli_Quad::calculate_roll_pitch_collective_factors()
|
|||
}
|
||||
|
||||
// update_motor_controls - sends commands to motor controllers
|
||||
void AP_MotorsHeli_Quad::update_motor_control(RotorControlState state)
|
||||
void AP_MotorsHeli_Quad::update_motor_control(AP_MotorsHeli_RSC::RotorControlState state)
|
||||
{
|
||||
// Send state update to motors
|
||||
_main_rotor.output(state);
|
||||
|
||||
if (state == ROTOR_CONTROL_STOP) {
|
||||
if (state == AP_MotorsHeli_RSC::RotorControlState::STOP) {
|
||||
// set engine run enable aux output to not run position to kill engine when disarmed
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::Limit::MIN);
|
||||
} else {
|
||||
|
@ -276,20 +276,20 @@ void AP_MotorsHeli_Quad::output_to_motors()
|
|||
switch (_spool_state) {
|
||||
case SpoolState::SHUT_DOWN:
|
||||
// sends minimum values out to the motors
|
||||
update_motor_control(ROTOR_CONTROL_STOP);
|
||||
update_motor_control(AP_MotorsHeli_RSC::RotorControlState::STOP);
|
||||
break;
|
||||
case SpoolState::GROUND_IDLE:
|
||||
// sends idle output to motors when armed. rotor could be static or turning (autorotation)
|
||||
update_motor_control(ROTOR_CONTROL_IDLE);
|
||||
update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE);
|
||||
break;
|
||||
case SpoolState::SPOOLING_UP:
|
||||
case SpoolState::THROTTLE_UNLIMITED:
|
||||
// set motor output based on thrust requests
|
||||
update_motor_control(ROTOR_CONTROL_ACTIVE);
|
||||
update_motor_control(AP_MotorsHeli_RSC::RotorControlState::ACTIVE);
|
||||
break;
|
||||
case SpoolState::SPOOLING_DOWN:
|
||||
// sends idle output to motors and wait for rotor to stop
|
||||
update_motor_control(ROTOR_CONTROL_IDLE);
|
||||
update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -49,7 +49,7 @@ protected:
|
|||
void init_outputs () override;
|
||||
|
||||
// update_motor_controls - sends commands to motor controllers
|
||||
void update_motor_control(RotorControlState state) override;
|
||||
void update_motor_control(AP_MotorsHeli_RSC::RotorControlState state) override;
|
||||
|
||||
// calculate_roll_pitch_collective_factors - setup rate factors
|
||||
void calculate_roll_pitch_collective_factors ();
|
||||
|
|
|
@ -275,7 +275,7 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
|
|||
}
|
||||
|
||||
switch (state) {
|
||||
case ROTOR_CONTROL_STOP:
|
||||
case RotorControlState::STOP:
|
||||
// set rotor ramp to decrease speed to zero, this happens instantly inside update_rotor_ramp()
|
||||
update_rotor_ramp(0.0f, dt);
|
||||
|
||||
|
@ -296,7 +296,7 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
|
|||
_idle_throttle = get_idle_output();
|
||||
break;
|
||||
|
||||
case ROTOR_CONTROL_IDLE:
|
||||
case RotorControlState::IDLE:
|
||||
// set rotor ramp to decrease speed to zero
|
||||
update_rotor_ramp(0.0f, dt);
|
||||
|
||||
|
@ -348,7 +348,7 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
|
|||
_control_output = _idle_throttle;
|
||||
break;
|
||||
|
||||
case ROTOR_CONTROL_ACTIVE:
|
||||
case RotorControlState::ACTIVE:
|
||||
// set main rotor ramp to increase to full speed
|
||||
update_rotor_ramp(1.0f, dt);
|
||||
|
||||
|
|
|
@ -30,13 +30,6 @@
|
|||
// RSC governor defaults
|
||||
#define AP_MOTORS_HELI_RSC_GOVERNOR_RANGE_DEFAULT 100
|
||||
|
||||
// rotor controller states
|
||||
enum RotorControlState {
|
||||
ROTOR_CONTROL_STOP = 0,
|
||||
ROTOR_CONTROL_IDLE,
|
||||
ROTOR_CONTROL_ACTIVE
|
||||
};
|
||||
|
||||
// rotor control modes
|
||||
enum RotorControlMode {
|
||||
ROTOR_CONTROL_MODE_DISABLED = 0,
|
||||
|
@ -60,6 +53,13 @@ public:
|
|||
AP_Param::setup_object_defaults(this, var_info);
|
||||
};
|
||||
|
||||
// rotor controller states
|
||||
enum class RotorControlState {
|
||||
STOP = 0,
|
||||
IDLE,
|
||||
ACTIVE
|
||||
};
|
||||
|
||||
// init_servo - servo initialization on start-up
|
||||
void init_servo();
|
||||
|
||||
|
|
|
@ -347,13 +347,13 @@ uint32_t AP_MotorsHeli_Single::get_motor_mask()
|
|||
}
|
||||
|
||||
// update_motor_controls - sends commands to motor controllers
|
||||
void AP_MotorsHeli_Single::update_motor_control(RotorControlState state)
|
||||
void AP_MotorsHeli_Single::update_motor_control(AP_MotorsHeli_RSC::RotorControlState state)
|
||||
{
|
||||
// Send state update to motors
|
||||
_tail_rotor.output(state);
|
||||
_main_rotor.output(state);
|
||||
|
||||
if (state == ROTOR_CONTROL_STOP){
|
||||
if (state == AP_MotorsHeli_RSC::RotorControlState::STOP){
|
||||
// set engine run enable aux output to not run position to kill engine when disarmed
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::Limit::MIN);
|
||||
} else {
|
||||
|
@ -504,20 +504,20 @@ void AP_MotorsHeli_Single::output_to_motors()
|
|||
switch (_spool_state) {
|
||||
case SpoolState::SHUT_DOWN:
|
||||
// sends minimum values out to the motors
|
||||
update_motor_control(ROTOR_CONTROL_STOP);
|
||||
update_motor_control(AP_MotorsHeli_RSC::RotorControlState::STOP);
|
||||
break;
|
||||
case SpoolState::GROUND_IDLE:
|
||||
// sends idle output to motors when armed. rotor could be static or turning (autorotation)
|
||||
update_motor_control(ROTOR_CONTROL_IDLE);
|
||||
update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE);
|
||||
break;
|
||||
case SpoolState::SPOOLING_UP:
|
||||
case SpoolState::THROTTLE_UNLIMITED:
|
||||
// set motor output based on thrust requests
|
||||
update_motor_control(ROTOR_CONTROL_ACTIVE);
|
||||
update_motor_control(AP_MotorsHeli_RSC::RotorControlState::ACTIVE);
|
||||
break;
|
||||
case SpoolState::SPOOLING_DOWN:
|
||||
// sends idle output to motors and wait for rotor to stop
|
||||
update_motor_control(ROTOR_CONTROL_IDLE);
|
||||
update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE);
|
||||
break;
|
||||
}
|
||||
|
||||
|
|
|
@ -86,7 +86,7 @@ protected:
|
|||
void init_outputs() override;
|
||||
|
||||
// update_motor_controls - sends commands to motor controllers
|
||||
void update_motor_control(RotorControlState state) override;
|
||||
void update_motor_control(AP_MotorsHeli_RSC::RotorControlState state) override;
|
||||
|
||||
// heli_move_actuators - moves swash plate and tail rotor
|
||||
void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override;
|
||||
|
|
Loading…
Reference in New Issue