mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: simplify channel check in get_pwm()
This commit is contained in:
parent
b69afff6a7
commit
750718bdd3
|
@ -208,10 +208,10 @@ void RC_Channels::read_mode_switch()
|
||||||
*/
|
*/
|
||||||
bool RC_Channels::get_pwm(uint8_t c, uint16_t &pwm) const
|
bool RC_Channels::get_pwm(uint8_t c, uint16_t &pwm) const
|
||||||
{
|
{
|
||||||
if (c < 1 || c > NUM_RC_CHANNELS) {
|
RC_Channel *chan = rc_channel(c-1);
|
||||||
|
if (chan == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
RC_Channel *chan = rc_channel(c-1);
|
|
||||||
int16_t pwm_signed = chan->get_radio_in();
|
int16_t pwm_signed = chan->get_radio_in();
|
||||||
if (pwm_signed < 0) {
|
if (pwm_signed < 0) {
|
||||||
return false;
|
return false;
|
||||||
|
|
|
@ -29,7 +29,7 @@ public:
|
||||||
RC_Channel_Example obj_channels[NUM_RC_CHANNELS];
|
RC_Channel_Example obj_channels[NUM_RC_CHANNELS];
|
||||||
|
|
||||||
RC_Channel_Example *channel(const uint8_t chan) override {
|
RC_Channel_Example *channel(const uint8_t chan) override {
|
||||||
if (chan > NUM_RC_CHANNELS) {
|
if (chan >= NUM_RC_CHANNELS) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
return &obj_channels[chan];
|
return &obj_channels[chan];
|
||||||
|
|
Loading…
Reference in New Issue