From 91c7663ca2973ecd130bb28b263f6079b357b3b5 Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Tue, 11 Aug 2015 11:01:11 -0400 Subject: [PATCH] AP_MotorsHeli: Set range of new RSC Servo object. --- libraries/AP_Motors/AP_MotorsHeli_RSC.cpp | 7 +++++++ libraries/AP_Motors/AP_MotorsHeli_RSC.h | 3 +++ libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 4 ++++ 3 files changed, 14 insertions(+) diff --git a/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp b/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp index fe195aade5..20f3de3715 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp @@ -21,6 +21,13 @@ extern const AP_HAL::HAL& hal; +// init_servo - servo initialization on start-up +void AP_MotorsHeli_RSC::init_servo() +{ + // set servo range + _servo_output.set_range(0,1000); +} + // recalc_scalers - recalculates various scalers used. Should be called at about 1hz to allow users to see effect of changing parameters void AP_MotorsHeli_RSC::recalc_scalers() { diff --git a/libraries/AP_Motors/AP_MotorsHeli_RSC.h b/libraries/AP_Motors/AP_MotorsHeli_RSC.h index 4d8a605683..f06c4eddf2 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_RSC.h +++ b/libraries/AP_Motors/AP_MotorsHeli_RSC.h @@ -22,6 +22,9 @@ public: _loop_rate(loop_rate) {}; + // init_servo - servo initialization on start-up + void init_servo(); + // set_critical_speed void set_critical_speed(int16_t critical_speed) { _critical_speed = critical_speed; } diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index e721333e2e..241d851a70 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -367,6 +367,10 @@ void AP_MotorsHeli_Single::init_servos() init_swash_servo (_swash_servo_3); _yaw_servo.set_angle(4500); + + // set main rotor servo range + // tail rotor servo use range as set in vehicle code for rc7 + _main_rotor.init_servo(); } // calculate_roll_pitch_collective_factors - calculate factors based on swash type and servo position