AP_MotorsHeli: Overload output()

To protect it from future interference from Multirotor code.
This commit is contained in:
Robert Lefebvre 2015-05-21 14:33:18 -04:00 committed by Randy Mackay
parent d3ce68a8ca
commit 73bafa131e
3 changed files with 23 additions and 1 deletions

View File

@ -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()
{

View File

@ -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

View File

@ -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;