From 73bafa131ef170c1ef8e350979bcbd4bc44bbd88 Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Thu, 21 May 2015 14:33:18 -0400 Subject: [PATCH] AP_MotorsHeli: Overload output() To protect it from future interference from Multirotor code. --- libraries/AP_Motors/AP_MotorsHeli.cpp | 19 +++++++++++++++++++ libraries/AP_Motors/AP_MotorsHeli.h | 3 +++ libraries/AP_Motors/AP_Motors_Class.h | 2 +- 3 files changed, 23 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index 9bf7c2648f..9e42c0c948 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -258,6 +258,25 @@ void AP_MotorsHeli::enable() hal.rcout->enable_ch(AP_MOTORS_HELI_RSC); // output for main rotor esc } +// output - sends commands to the servos +void AP_MotorsHeli::output() +{ + // update throttle filter + update_throttle_filter(); + + if (_flags.armed) { + if (!_flags.interlock) { + output_armed_zero_throttle(); + } else if (_flags.stabilizing) { + output_armed_stabilizing(); + } else { + output_armed_not_stabilizing(); + } + } else { + output_disarmed(); + } +}; + // output_min - sets servos to neutral point void AP_MotorsHeli::output_min() { diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 230901e2d4..f94f92d63b 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -207,6 +207,9 @@ public: // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict virtual uint16_t get_motor_mask(); + // output - sends commands to the motors + void output(); + protected: // output - sends commands to the motors diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index fb1eec72a2..0f343244cd 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -142,7 +142,7 @@ public: void set_throttle_filter_cutoff(float filt_hz) { _throttle_filter.set_cutoff_frequency(filt_hz); } // output - sends commands to the motors - void output(); + virtual void output(); // output_min - sends minimum values out to the motors virtual void output_min() = 0;