4 changed files with 254 additions and 208 deletions
@ -0,0 +1,104 @@
@@ -0,0 +1,104 @@
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
/*
|
||||
This program is free software: you can redistribute it and/or modify |
||||
it under the terms of the GNU General Public License as published by |
||||
the Free Software Foundation, either version 3 of the License, or |
||||
(at your option) any later version. |
||||
|
||||
This program is distributed in the hope that it will be useful, |
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of |
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
||||
GNU General Public License for more details. |
||||
|
||||
You should have received a copy of the GNU General Public License |
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/ |
||||
|
||||
#include <stdlib.h> |
||||
#include <AP_HAL.h> |
||||
|
||||
#include "AP_MotorsHeli_RSC.h" |
||||
|
||||
extern const AP_HAL::HAL& hal; |
||||
|
||||
// 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() |
||||
{ |
||||
// recalculate rotor ramp up increment
|
||||
if (_ramp_time <= 0) { |
||||
_ramp_time = 1; |
||||
} |
||||
|
||||
_ramp_increment = 1000.0f / (_ramp_time * _loop_rate); |
||||
|
||||
// recalculate rotor runup increment
|
||||
if (_runup_time <= 0 ) { |
||||
_runup_time = 1; |
||||
} |
||||
|
||||
if (_runup_time < _ramp_time) { |
||||
_runup_time = _ramp_time; |
||||
} |
||||
|
||||
_runup_increment = 1000.0f / (_runup_time * _loop_rate); |
||||
} |
||||
|
||||
void AP_MotorsHeli_RSC::output_armed() |
||||
{ |
||||
// ramp rotor esc output towards target
|
||||
if (_speed_out < _desired_speed) { |
||||
// allow rotor out to jump to rotor's current speed
|
||||
if (_speed_out < _estimated_speed) { |
||||
_speed_out = _estimated_speed; |
||||
} |
||||
|
||||
// ramp up slowly to target
|
||||
_speed_out += _ramp_increment; |
||||
if (_speed_out > _desired_speed) { |
||||
_speed_out = _desired_speed; |
||||
} |
||||
} else { |
||||
// ramping down happens instantly
|
||||
_speed_out = _desired_speed; |
||||
} |
||||
|
||||
// ramp rotor speed estimate towards speed out
|
||||
if (_estimated_speed < _speed_out) { |
||||
_estimated_speed += _runup_increment; |
||||
if (_estimated_speed > _speed_out) { |
||||
_estimated_speed = _speed_out; |
||||
} |
||||
} else { |
||||
_estimated_speed -= _runup_increment; |
||||
if (_estimated_speed < _speed_out) { |
||||
_estimated_speed = _speed_out; |
||||
} |
||||
} |
||||
|
||||
// set runup complete flag
|
||||
if (!_runup_complete && _desired_speed > 0 && _estimated_speed >= _desired_speed) { |
||||
_runup_complete = true; |
||||
} |
||||
|
||||
if (_runup_complete && _estimated_speed <= _critical_speed) { |
||||
_runup_complete = false; |
||||
} |
||||
|
||||
// output to rsc servo
|
||||
write_rsc(_speed_out); |
||||
} |
||||
|
||||
void AP_MotorsHeli_RSC::output_disarmed() |
||||
{ |
||||
write_rsc(0); |
||||
} |
||||
|
||||
// write_rsc - outputs pwm onto output rsc channel
|
||||
// servo_out parameter is of the range 0 ~ 1000
|
||||
void AP_MotorsHeli_RSC::write_rsc(int16_t servo_out) |
||||
{ |
||||
_servo_output.servo_out = servo_out; |
||||
_servo_output.calc_pwm(); |
||||
|
||||
hal.rcout->write(_servo_output_channel, _servo_output.radio_out); |
||||
} |
@ -0,0 +1,76 @@
@@ -0,0 +1,76 @@
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#ifndef __AP_MOTORS_HELI_RSC_H__ |
||||
#define __AP_MOTORS_HELI_RSC_H__ |
||||
|
||||
#include <inttypes.h> |
||||
#include <AP_Common.h> |
||||
#include <AP_Math.h> |
||||
#include <RC_Channel.h> |
||||
|
||||
class AP_MotorsHeli_RSC { |
||||
public: |
||||
AP_MotorsHeli_RSC(RC_Channel& servo_output, |
||||
int8_t servo_output_channel, |
||||
uint16_t loop_rate) : |
||||
_servo_output(servo_output), |
||||
_servo_output_channel(servo_output_channel), |
||||
_loop_rate(loop_rate) |
||||
{}; |
||||
|
||||
// set_critical_speed
|
||||
void set_critical_speed(int16_t critical_speed) { _critical_speed = critical_speed; } |
||||
|
||||
// get_critical_speed
|
||||
int16_t get_critical_speed() const { return _critical_speed; } |
||||
|
||||
// get_desired_speed
|
||||
int16_t get_desired_speed() const { return _desired_speed; } |
||||
|
||||
// set_desired_speed
|
||||
void set_desired_speed(int16_t desired_speed) { _desired_speed = desired_speed; } |
||||
|
||||
// get_estimated_speed
|
||||
int16_t get_estimated_speed() const { return _estimated_speed; } |
||||
|
||||
// is_runup_complete
|
||||
bool is_runup_complete() const { return _runup_complete; } |
||||
|
||||
// set_ramp_time
|
||||
void set_ramp_time (int8_t ramp_time) { _ramp_time = ramp_time; } |
||||
|
||||
// set_runup_time
|
||||
void set_runup_time (int8_t runup_time) { _runup_time = runup_time; } |
||||
|
||||
// recalc_scalers
|
||||
void recalc_scalers(); |
||||
|
||||
// output_armed
|
||||
void output_armed (); |
||||
|
||||
// output_disarmed
|
||||
void output_disarmed (); |
||||
|
||||
private: |
||||
|
||||
// external variables
|
||||
RC_Channel& _servo_output; |
||||
int8_t _servo_output_channel; // output channel to rotor esc
|
||||
float _loop_rate; // main loop rate
|
||||
|
||||
// internal variables
|
||||
int16_t _critical_speed = 0; // rotor speed below which flight is not possible
|
||||
int16_t _desired_speed = 0; // latest desired rotor speed from pilot
|
||||
float _speed_out = 0; // latest output sent to the main rotor or an estimate of the rotors actual speed (whichever is higher) (0 ~ 1000)
|
||||
float _estimated_speed = 0; // estimated speed of the main rotor (0~1000)
|
||||
float _ramp_increment = 0; // the amount we can increase the rotor output during each 100hz iteration
|
||||
int8_t _ramp_time = 0; // time in seconds for the output to the main rotor's ESC to reach full speed
|
||||
int8_t _runup_time = 0; // time in seconds for the main rotor to reach full speed. Must be longer than _rsc_ramp_time
|
||||
float _runup_increment = 0; // the amount we can increase the rotor's estimated speed during each 100hz iteration
|
||||
bool _runup_complete = false; // flag for determining if runup is complete
|
||||
|
||||
// write_rsc - outputs pwm onto output rsc channel. servo_out parameter is of the range 0 ~ 1000
|
||||
void write_rsc(int16_t servo_out); |
||||
}; |
||||
|
||||
#endif // AP_MOTORS_HELI_RSC_H
|
Loading…
Reference in new issue