From 93dbcf88b88a6cfb47b1f367c373f2b0239b2af9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 12 Oct 2018 10:44:00 +1100 Subject: [PATCH] AP_Volz_Protocol: fixed build warnings --- libraries/AP_Volz_Protocol/AP_Volz_Protocol.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Volz_Protocol/AP_Volz_Protocol.cpp b/libraries/AP_Volz_Protocol/AP_Volz_Protocol.cpp index ee0812c6a3..ca72c958de 100644 --- a/libraries/AP_Volz_Protocol/AP_Volz_Protocol.cpp +++ b/libraries/AP_Volz_Protocol/AP_Volz_Protocol.cpp @@ -67,21 +67,21 @@ void AP_Volz_Protocol::update() // check if current channel is needed for Volz protocol if (last_used_bitmask & (1U<get_output_pwm() < ch->get_output_min()) { + if (c->get_output_pwm() < c->get_output_min()) { value = 0; } else { - value = ch->get_output_pwm() - ch->get_output_min(); + value = c->get_output_pwm() - c->get_output_min(); } // scale the PWM value to Volz value value = value + VOLZ_EXTENDED_POSITION_MIN; - value = value * VOLZ_SCALE_VALUE / (ch->get_output_max() - ch->get_output_min()); + value = value * VOLZ_SCALE_VALUE / (c->get_output_max() - c->get_output_min()); // make sure value stays in range if (value > VOLZ_EXTENDED_POSITION_MAX) {