mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/RC_Channel/RC_Channel.h
This commit is contained in:
parent
fb2df43984
commit
5564e0c440
|
@ -11,97 +11,98 @@
|
|||
|
||||
/// @class RC_Channel
|
||||
/// @brief Object managing one RC channel
|
||||
class RC_Channel{
|
||||
public:
|
||||
/// Constructor
|
||||
///
|
||||
/// @param key EEPROM storage key for the channel trim parameters.
|
||||
/// @param name Optional name for the group.
|
||||
///
|
||||
RC_Channel(uint8_t ch_out) :
|
||||
scale_output(1.0),
|
||||
_filter(false),
|
||||
_high(1),
|
||||
_ch_out(ch_out) {}
|
||||
class RC_Channel {
|
||||
public:
|
||||
/// Constructor
|
||||
///
|
||||
/// @param key EEPROM storage key for the channel trim parameters.
|
||||
/// @param name Optional name for the group.
|
||||
///
|
||||
RC_Channel(uint8_t ch_out) :
|
||||
scale_output(1.0),
|
||||
_filter(false),
|
||||
_high(1),
|
||||
_ch_out(ch_out) {
|
||||
}
|
||||
|
||||
// setup min and max radio values in CLI
|
||||
void update_min_max();
|
||||
void zero_min_max();
|
||||
// setup min and max radio values in CLI
|
||||
void update_min_max();
|
||||
void zero_min_max();
|
||||
|
||||
// startup
|
||||
void load_eeprom(void);
|
||||
void save_eeprom(void);
|
||||
void save_trim(void);
|
||||
void set_filter(bool filter);
|
||||
void set_type(uint8_t t);
|
||||
// startup
|
||||
void load_eeprom(void);
|
||||
void save_eeprom(void);
|
||||
void save_trim(void);
|
||||
void set_filter(bool filter);
|
||||
void set_type(uint8_t t);
|
||||
|
||||
// setup the control preferences
|
||||
void set_range(int16_t low, int16_t high);
|
||||
void set_range_out(int16_t low, int16_t high);
|
||||
void set_angle(int16_t angle);
|
||||
void set_reverse(bool reverse);
|
||||
bool get_reverse(void);
|
||||
void set_dead_zone(int16_t dzone);
|
||||
// setup the control preferences
|
||||
void set_range(int16_t low, int16_t high);
|
||||
void set_range_out(int16_t low, int16_t high);
|
||||
void set_angle(int16_t angle);
|
||||
void set_reverse(bool reverse);
|
||||
bool get_reverse(void);
|
||||
void set_dead_zone(int16_t dzone);
|
||||
|
||||
// read input from APM_RC - create a control_in value
|
||||
void set_pwm(int16_t pwm);
|
||||
// read input from APM_RC - create a control_in value
|
||||
void set_pwm(int16_t pwm);
|
||||
|
||||
// pwm is stored here
|
||||
int16_t radio_in;
|
||||
// pwm is stored here
|
||||
int16_t radio_in;
|
||||
|
||||
// call after first set_pwm
|
||||
void trim();
|
||||
// call after first set_pwm
|
||||
void trim();
|
||||
|
||||
// did our read come in 50µs below the min?
|
||||
bool get_failsafe(void);
|
||||
// did our read come in 50µs below the min?
|
||||
bool get_failsafe(void);
|
||||
|
||||
// value generated from PWM
|
||||
int16_t control_in;
|
||||
// value generated from PWM
|
||||
int16_t control_in;
|
||||
|
||||
int16_t control_mix(float value);
|
||||
int16_t control_mix(float value);
|
||||
|
||||
// current values to the servos - degrees * 100 (approx assuming servo is -45 to 45 degrees except [3] is 0 to 100
|
||||
int16_t servo_out;
|
||||
// current values to the servos - degrees * 100 (approx assuming servo is -45 to 45 degrees except [3] is 0 to 100
|
||||
int16_t servo_out;
|
||||
|
||||
// generate PWM from servo_out value
|
||||
void calc_pwm(void);
|
||||
// generate PWM from servo_out value
|
||||
void calc_pwm(void);
|
||||
|
||||
// PWM is without the offset from radio_min
|
||||
int16_t pwm_out;
|
||||
int16_t radio_out;
|
||||
// PWM is without the offset from radio_min
|
||||
int16_t pwm_out;
|
||||
int16_t radio_out;
|
||||
|
||||
AP_Int16 radio_min;
|
||||
AP_Int16 radio_trim;
|
||||
AP_Int16 radio_max;
|
||||
AP_Int16 radio_min;
|
||||
AP_Int16 radio_trim;
|
||||
AP_Int16 radio_max;
|
||||
|
||||
// includes offset from PWM
|
||||
//int16_t get_radio_out(void);
|
||||
// includes offset from PWM
|
||||
//int16_t get_radio_out(void);
|
||||
|
||||
int16_t pwm_to_angle();
|
||||
float norm_input();
|
||||
float norm_output();
|
||||
int16_t angle_to_pwm();
|
||||
int16_t pwm_to_range();
|
||||
int16_t range_to_pwm();
|
||||
int16_t pwm_to_angle();
|
||||
float norm_input();
|
||||
float norm_output();
|
||||
int16_t angle_to_pwm();
|
||||
int16_t pwm_to_range();
|
||||
int16_t range_to_pwm();
|
||||
|
||||
float scale_output;
|
||||
static void set_apm_rc(APM_RC_Class * apm_rc);
|
||||
void output();
|
||||
void enable_out();
|
||||
static APM_RC_Class *_apm_rc;
|
||||
float scale_output;
|
||||
static void set_apm_rc(APM_RC_Class * apm_rc);
|
||||
void output();
|
||||
void enable_out();
|
||||
static APM_RC_Class * _apm_rc;
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
bool _filter;
|
||||
AP_Int8 _reverse;
|
||||
AP_Int16 _dead_zone;
|
||||
uint8_t _type;
|
||||
int16_t _high;
|
||||
int16_t _low;
|
||||
int16_t _high_out;
|
||||
int16_t _low_out;
|
||||
uint8_t _ch_out;
|
||||
private:
|
||||
bool _filter;
|
||||
AP_Int8 _reverse;
|
||||
AP_Int16 _dead_zone;
|
||||
uint8_t _type;
|
||||
int16_t _high;
|
||||
int16_t _low;
|
||||
int16_t _high_out;
|
||||
int16_t _low_out;
|
||||
uint8_t _ch_out;
|
||||
};
|
||||
|
||||
// This is ugly, but it fixes compilation on arduino
|
||||
|
|
Loading…
Reference in New Issue