From 6f480c98cc0db539b824c56b6449658714cf49a4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 12 Oct 2018 10:44:00 +1100 Subject: [PATCH] AP_SBusOut: fixed build warnings --- libraries/AP_SBusOut/AP_SBusOut.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_SBusOut/AP_SBusOut.cpp b/libraries/AP_SBusOut/AP_SBusOut.cpp index efd69bcd74..1d66585d5c 100644 --- a/libraries/AP_SBusOut/AP_SBusOut.cpp +++ b/libraries/AP_SBusOut/AP_SBusOut.cpp @@ -103,12 +103,12 @@ AP_SBusOut::update() /* construct sbus frame representing channels 1 through 16 (max) */ uint8_t nchan = MIN(NUM_SERVO_CHANNELS, SBUS_CHANNELS); for (unsigned i = 0; i < nchan; ++i) { - SRV_Channel *ch = SRV_Channels::srv_channel(i); - if (ch == nullptr) { + SRV_Channel *c = SRV_Channels::srv_channel(i); + if (c == nullptr) { continue; } /*protect from out of bounds values and limit to 11 bits*/ - uint16_t pwmval = MAX(ch->get_output_pwm(), SBUS_MIN); + uint16_t pwmval = MAX(c->get_output_pwm(), SBUS_MIN); value = (uint16_t)((pwmval - SBUS_MIN) * SBUS_SCALE); if (value > 0x07ff) { value = 0x07ff;