mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
RC: set dead zone only if parameter has not been set by user
This commit is contained in:
parent
f300df5fd1
commit
47437b9ddf
@ -95,9 +95,11 @@ RC_Channel::set_angle(int16_t angle)
|
||||
}
|
||||
|
||||
void
|
||||
RC_Channel::set_dead_zone(int16_t dzone)
|
||||
RC_Channel::set_default_dead_zone(int16_t dzone)
|
||||
{
|
||||
_dead_zone.set_and_save(abs(dzone >>1));
|
||||
if (!_dead_zone.load()) {
|
||||
_dead_zone.set(abs(dzone));
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
|
@ -49,7 +49,7 @@ public:
|
||||
void set_angle(int16_t angle);
|
||||
void set_reverse(bool reverse);
|
||||
bool get_reverse(void);
|
||||
void set_dead_zone(int16_t dzone);
|
||||
void set_default_dead_zone(int16_t dzone);
|
||||
|
||||
// read input from APM_RC - create a control_in value
|
||||
void set_pwm(int16_t pwm);
|
||||
|
Loading…
Reference in New Issue
Block a user