From 2c612e5f8ed5105223d9442f9fb9d4a75c939506 Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Thu, 12 Nov 2015 20:37:43 -0500 Subject: [PATCH] AP_MotorsHeli: Add parameter checks to Single class --- libraries/AP_Motors/AP_MotorsHeli.h | 2 +- libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 17 +++++++++++++++++ libraries/AP_Motors/AP_MotorsHeli_Single.h | 3 +++ 3 files changed, 21 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 936f49a377..423d41b8c0 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -107,7 +107,7 @@ public: virtual bool allow_arming() const = 0; // parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check - bool parameter_check() const; + virtual bool parameter_check() const; // has_flybar - returns true if we have a mechical flybar virtual bool has_flybar() const { return AP_MOTORS_HELI_NOFLYBAR; } diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index 3df1e286fc..d7883cdeda 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -518,3 +518,20 @@ void AP_MotorsHeli_Single::servo_test() _pitch_control_input = _pitch_test; _yaw_control_input = _yaw_test; } + +// parameter_check - check if helicopter specific parameters are sensible +bool AP_MotorsHeli_Single::parameter_check() const +{ + // returns false if Phase Angle is outside of range + if ((_phase_angle > 90) || (_phase_angle < -90)){ + return false; + } + + // returns false if External Gyro Gain is outside of range + if ((_ext_gyro_gain < 0) || (_ext_gyro_gain > 1000)){ + return false; + } + + // check parent class parameters + return AP_MotorsHeli::parameter_check(); +} diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.h b/libraries/AP_Motors/AP_MotorsHeli_Single.h index 49d59b402e..1dbaeb12a1 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.h @@ -83,6 +83,9 @@ public: // allow_arming - returns true if main rotor is spinning and it is ok to arm bool allow_arming() const; + // parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check + bool parameter_check() const; + // set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1000 void set_desired_rotor_speed(int16_t desired_speed);