From 00757fb77fa302036c73a694b9320fcae0be9859 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 17 Aug 2020 11:08:42 +0900 Subject: [PATCH] SRV_Channel: fix get_output_norm comment also minor formatting fix --- libraries/SRV_Channel/SRV_Channel.cpp | 2 +- libraries/SRV_Channel/SRV_Channel.h | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/SRV_Channel/SRV_Channel.cpp b/libraries/SRV_Channel/SRV_Channel.cpp index 1102b5f4d2..f5a9595496 100644 --- a/libraries/SRV_Channel/SRV_Channel.cpp +++ b/libraries/SRV_Channel/SRV_Channel.cpp @@ -171,7 +171,7 @@ float SRV_Channel::get_output_norm(void) ret = 0; } if (get_reversed()) { - ret = -ret; + ret = -ret; } return ret; } diff --git a/libraries/SRV_Channel/SRV_Channel.h b/libraries/SRV_Channel/SRV_Channel.h index 51e1cd5f05..c04bec2b60 100644 --- a/libraries/SRV_Channel/SRV_Channel.h +++ b/libraries/SRV_Channel/SRV_Channel.h @@ -277,7 +277,7 @@ private: // return PWM for a given limit value uint16_t get_limit_pwm(Limit limit) const; - // get normalised output from -1 to 1 + // get normalised output from -1 to 1, assuming 0 at mid point of servo_min/servo_max float get_output_norm(void); // a bitmask type wide enough for NUM_SERVO_CHANNELS @@ -337,8 +337,8 @@ public: // get pwm output for the first channel of the given function type. static bool get_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t &value); - // get normalised output (-1 to 1 for angle, 0 to 1 for range). Value is taken from pwm value - // return zero on error. + // get normalised output (-1 to 1 with 0 at mid point of servo_min/servo_max) + // Value is taken from pwm value. Returns zero on error. static float get_output_norm(SRV_Channel::Aux_servo_function_t function); // get output channel mask for a function