mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
RC_Channel: use set_default for runtime param defaults
This commit is contained in:
parent
39246c13ad
commit
21e7d46944
@ -114,9 +114,7 @@ RC_Channel::set_angle(int16_t angle)
|
||||
void
|
||||
RC_Channel::set_default_dead_zone(int16_t dzone)
|
||||
{
|
||||
if (!_dead_zone.load()) {
|
||||
_dead_zone.set(abs(dzone));
|
||||
}
|
||||
_dead_zone.set_default(abs(dzone));
|
||||
}
|
||||
|
||||
void
|
||||
|
Loading…
Reference in New Issue
Block a user