mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: removed set_filter() and scale_output
these unused options were costing 5 bytes per channel, for a total of 50 bytes on ArduCopter
This commit is contained in:
parent
6a24bdec05
commit
d57566ad0e
|
@ -116,12 +116,6 @@ RC_Channel::get_reverse(void)
|
|||
else return 0;
|
||||
}
|
||||
|
||||
void
|
||||
RC_Channel::set_filter(bool filter)
|
||||
{
|
||||
_filter = filter;
|
||||
}
|
||||
|
||||
void
|
||||
RC_Channel::set_type(uint8_t t)
|
||||
{
|
||||
|
@ -139,16 +133,6 @@ RC_Channel::trim()
|
|||
void
|
||||
RC_Channel::set_pwm(int16_t pwm)
|
||||
{
|
||||
|
||||
/*if(_filter){
|
||||
* if(radio_in == 0)
|
||||
* radio_in = pwm;
|
||||
* else
|
||||
* radio_in = (pwm + radio_in) >> 1; // Small filtering
|
||||
* }else{
|
||||
* radio_in = pwm;
|
||||
* }*/
|
||||
|
||||
radio_in = pwm;
|
||||
|
||||
if(_type == RC_CHANNEL_RANGE) {
|
||||
|
@ -157,27 +141,9 @@ RC_Channel::set_pwm(int16_t pwm)
|
|||
//control_in = min(control_in, _high);
|
||||
control_in = (control_in < _dead_zone) ? 0 : control_in;
|
||||
|
||||
if (fabs(scale_output) != 1) {
|
||||
control_in *= scale_output;
|
||||
}
|
||||
|
||||
}else{
|
||||
|
||||
} else {
|
||||
//RC_CHANNEL_ANGLE, RC_CHANNEL_ANGLE_RAW
|
||||
control_in = pwm_to_angle();
|
||||
|
||||
|
||||
if (fabs(scale_output) != 1) {
|
||||
control_in *= scale_output;
|
||||
}
|
||||
|
||||
/*
|
||||
* // coming soon ??
|
||||
* if(expo) {
|
||||
* long temp = control_in;
|
||||
* temp = (temp * temp) / (long)_high;
|
||||
* control_in = (int16_t)((control_in >= 0) ? temp : -temp);
|
||||
* }*/
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -19,8 +19,6 @@ public:
|
|||
/// @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) {
|
||||
if (_reverse == 0) {
|
||||
|
@ -36,7 +34,6 @@ public:
|
|||
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
|
||||
|
@ -88,7 +85,6 @@ public:
|
|||
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();
|
||||
|
@ -97,7 +93,6 @@ public:
|
|||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
bool _filter;
|
||||
AP_Int8 _reverse;
|
||||
AP_Int16 _dead_zone;
|
||||
uint8_t _type;
|
||||
|
|
|
@ -85,7 +85,6 @@ void setup()
|
|||
rc_2.set_dead_zone(80);
|
||||
rc_3.set_range(0,1000);
|
||||
rc_3.set_dead_zone(20);
|
||||
rc_3.scale_output = .8; // gives more dynamic range to quads
|
||||
rc_4.set_angle(6000);
|
||||
rc_4.set_dead_zone(500);
|
||||
rc_5.set_range(0,1000);
|
||||
|
|
|
@ -87,7 +87,6 @@ void setup()
|
|||
rc_2.dead_zone = 80;
|
||||
rc_3.set_range(0,1000);
|
||||
rc_3.dead_zone = 20;
|
||||
rc_3.scale_output = .8; // gives more dynamic range to quads
|
||||
rc_4.set_angle(6000);
|
||||
rc_4.dead_zone = 500;
|
||||
rc_5.set_range(0,1000);
|
||||
|
@ -206,4 +205,4 @@ setup_radio()
|
|||
}
|
||||
}
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue