mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
RC_Channel: add norm_input_ignore_trim
same as norm_input but ignores the trim value
This commit is contained in:
parent
7750c5573e
commit
60238ec040
@ -305,6 +305,18 @@ RC_Channel::norm_input_dz() const
|
||||
return constrain_float(ret, -1.0f, 1.0f);
|
||||
}
|
||||
|
||||
// return a normalised input for a channel, in range -1 to 1,
|
||||
// ignores trim and deadzone
|
||||
float RC_Channel::norm_input_ignore_trim() const
|
||||
{
|
||||
// sanity check min and max to avoid divide by zero
|
||||
if (radio_max <= radio_min) {
|
||||
return 0.0f;
|
||||
}
|
||||
const float ret = (reversed ? -2.0f : 2.0f) * (((float)(radio_in - radio_min) / (float)(radio_max - radio_min)) - 0.5f);
|
||||
return constrain_float(ret, -1.0f, 1.0f);
|
||||
}
|
||||
|
||||
/*
|
||||
get percentage input from 0 to 100. This ignores the trim value.
|
||||
*/
|
||||
|
@ -52,6 +52,10 @@ public:
|
||||
*/
|
||||
float norm_input_dz() const;
|
||||
|
||||
// return a normalised input for a channel, in range -1 to 1,
|
||||
// ignores trim and deadzone
|
||||
float norm_input_ignore_trim() const;
|
||||
|
||||
uint8_t percent_input() const;
|
||||
int16_t pwm_to_range() const;
|
||||
int16_t pwm_to_range_dz(uint16_t dead_zone) const;
|
||||
|
Loading…
Reference in New Issue
Block a user