Browse Source

RC: set dead zone only if parameter has not been set by user

mission-4.1.18
Randy Mackay 12 years ago
parent
commit
47437b9ddf
  1. 6
      libraries/RC_Channel/RC_Channel.cpp
  2. 2
      libraries/RC_Channel/RC_Channel.h

6
libraries/RC_Channel/RC_Channel.cpp

@ -95,9 +95,11 @@ RC_Channel::set_angle(int16_t angle) @@ -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

2
libraries/RC_Channel/RC_Channel.h

@ -49,7 +49,7 @@ public: @@ -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…
Cancel
Save