From b1c7ec9aacdec0dbeaec2abbb6467059794a681e Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Tue, 11 Aug 2015 15:12:16 -0400 Subject: [PATCH] AP_MotorsHeli: run RSC Control function in Output Min function Move Output_Min() function into Heli_Single class as it will eventually be overloaded by other helicopter class types. --- libraries/AP_Motors/AP_MotorsHeli.cpp | 13 ------------- libraries/AP_Motors/AP_MotorsHeli.h | 2 +- libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 16 ++++++++++++++++ libraries/AP_Motors/AP_MotorsHeli_Single.h | 3 +++ 4 files changed, 20 insertions(+), 14 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index b37fe011c3..31ebb87c31 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -178,19 +178,6 @@ void AP_MotorsHeli::output() } }; -// output_min - sets servos to neutral point -void AP_MotorsHeli::output_min() -{ - // move swash to mid - move_swash(0,0,500,0); - - // override limits flags - limit.roll_pitch = true; - limit.yaw = true; - limit.throttle_lower = true; - limit.throttle_upper = false; -} - // parameter_check - check if helicopter specific parameters are sensible bool AP_MotorsHeli::parameter_check() const { diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index f9cb8055b1..e7ee7bd654 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -88,7 +88,7 @@ public: virtual void enable() = 0; // output_min - sets servos to neutral point - void output_min(); + virtual void output_min() = 0; // output_test - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index 7d79bd095e..5fdff974bd 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -250,6 +250,22 @@ uint16_t AP_MotorsHeli_Single::get_motor_mask() return (1U << 0 | 1U << 1 | 1U << 2 | 1U << 3 | 1U << AP_MOTORS_HELI_SINGLE_AUX | 1U << AP_MOTORS_HELI_SINGLE_RSC); } +// output_min - sets servos to neutral point +void AP_MotorsHeli_Single::output_min() +{ + // move swash to mid + move_swash(0,0,500,0); + + _main_rotor.output(ROTOR_CONTROL_STOP); + _tail_rotor.output(ROTOR_CONTROL_STOP); + + // override limits flags + limit.roll_pitch = true; + limit.yaw = true; + limit.throttle_lower = true; + limit.throttle_upper = false; +} + // sends commands to the motors void AP_MotorsHeli_Single::output_armed_stabilizing() { diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.h b/libraries/AP_Motors/AP_MotorsHeli_Single.h index 645ddecc7a..edcc4d265c 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.h @@ -81,6 +81,9 @@ public: // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 void output_test(uint8_t motor_seq, int16_t pwm); + // output_min - sets servos to neutral point + void output_min(); + // allow_arming - returns true if main rotor is spinning and it is ok to arm bool allow_arming() const;