MotorsHeli_RSC: RotorControlState enum
This commit is contained in:
parent
d99bb66f8a
commit
72efc85ee8
@ -59,7 +59,7 @@ void AP_MotorsHeli_RSC::set_power_output_range(uint16_t power_low, uint16_t powe
|
||||
}
|
||||
|
||||
// output - update value to send to ESC/Servo
|
||||
void AP_MotorsHeli_RSC::output(uint8_t state)
|
||||
void AP_MotorsHeli_RSC::output(RotorControlState state)
|
||||
{
|
||||
switch (state){
|
||||
case ROTOR_CONTROL_STOP:
|
||||
@ -175,4 +175,4 @@ void AP_MotorsHeli_RSC::write_rsc(int16_t servo_out)
|
||||
|
||||
hal.rcout->write(_servo_output_channel, _servo_output.radio_out);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -8,9 +8,11 @@
|
||||
#include <RC_Channel/RC_Channel.h> // RC Channel Library
|
||||
|
||||
// rotor controller states
|
||||
#define ROTOR_CONTROL_STOP 0
|
||||
#define ROTOR_CONTROL_IDLE 1
|
||||
#define ROTOR_CONTROL_ACTIVE 2
|
||||
enum RotorControlState {
|
||||
ROTOR_CONTROL_STOP = 0,
|
||||
ROTOR_CONTROL_IDLE,
|
||||
ROTOR_CONTROL_ACTIVE
|
||||
};
|
||||
|
||||
// rotor control modes
|
||||
#define ROTOR_CONTROL_MODE_DISABLED 0
|
||||
@ -75,7 +77,7 @@ public:
|
||||
void recalc_scalers();
|
||||
|
||||
// output - update value to send to ESC/Servo
|
||||
void output(uint8_t state);
|
||||
void output(RotorControlState state);
|
||||
|
||||
private:
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user