mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
RC_Channel: fix flare rc switch action with flight option bit 10 active
This commit is contained in:
parent
151ef760a4
commit
1162d556c6
@ -326,6 +326,15 @@ bool RC_Channel::in_trim_dz() const
|
||||
return is_bounded_int32(radio_in, radio_trim - dead_zone, radio_trim + dead_zone);
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
return trues if input is within deadzone of min
|
||||
*/
|
||||
bool RC_Channel::within_min_dz() const
|
||||
{
|
||||
return radio_in < radio_min + dead_zone;
|
||||
}
|
||||
|
||||
void RC_Channel::set_override(const uint16_t v, const uint32_t timestamp_ms)
|
||||
{
|
||||
if (!rc().gcs_overrides_enabled()) {
|
||||
|
@ -52,6 +52,9 @@ public:
|
||||
// ignores trim and deadzone
|
||||
float norm_input_ignore_trim() const;
|
||||
|
||||
// returns true if input is within deadzone of min
|
||||
bool within_min_dz() 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