mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
RC_Channel: added norm_input_dz()
normalised input, taking into account dead zone
This commit is contained in:
parent
ad0e6dccbb
commit
6b0c15b70f
@ -359,6 +359,22 @@ RC_Channel::norm_input()
|
||||
return constrain_float(ret, -1.0f, 1.0f);
|
||||
}
|
||||
|
||||
float
|
||||
RC_Channel::norm_input_dz()
|
||||
{
|
||||
int16_t dz_min = radio_trim - _dead_zone;
|
||||
int16_t dz_max = radio_trim + _dead_zone;
|
||||
float ret;
|
||||
if (radio_in < dz_min && dz_min > radio_min) {
|
||||
ret = _reverse * (float)(radio_in - dz_min) / (float)(dz_min - radio_min);
|
||||
} else if (radio_in > dz_max && radio_max > dz_max) {
|
||||
ret = _reverse * (float)(radio_in - dz_max) / (float)(radio_max - dz_max);
|
||||
} else {
|
||||
ret = 0;
|
||||
}
|
||||
return constrain_float(ret, -1.0f, 1.0f);
|
||||
}
|
||||
|
||||
/*
|
||||
get percentage input from 0 to 100. This ignores the trim value.
|
||||
*/
|
||||
|
@ -102,7 +102,19 @@ public:
|
||||
|
||||
int16_t pwm_to_angle_dz(uint16_t dead_zone);
|
||||
int16_t pwm_to_angle();
|
||||
|
||||
/*
|
||||
return a normalised input for a channel, in range -1 to 1,
|
||||
centered around the channel trim. Ignore deadzone.
|
||||
*/
|
||||
float norm_input();
|
||||
|
||||
/*
|
||||
return a normalised input for a channel, in range -1 to 1,
|
||||
centered around the channel trim. Take into account the deadzone
|
||||
*/
|
||||
float norm_input_dz();
|
||||
|
||||
uint8_t percent_input();
|
||||
float norm_output();
|
||||
int16_t angle_to_pwm();
|
||||
|
Loading…
Reference in New Issue
Block a user