ardupilot/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp

179 lines
6.3 KiB
C++

// -*- 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/AP_HAL.h>
#include "AP_MotorsHeli_RSC.h"
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()
{
// recalculate rotor ramp up increment
if (_ramp_time <= 0) {
_ramp_time = 1;
}
_ramp_increment = 1.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 = 1.0f / (_runup_time * _loop_rate);
}
// set_power_output_range
void AP_MotorsHeli_RSC::set_power_output_range(uint16_t power_low, uint16_t power_high)
{
_power_output_low = power_low;
_power_output_high = power_high;
_power_output_range = _power_output_high - _power_output_low;
}
// output - update value to send to ESC/Servo
void AP_MotorsHeli_RSC::output(RotorControlState state)
{
switch (state){
case ROTOR_CONTROL_STOP:
// set rotor ramp to decrease speed to zero, this happens instantly inside update_rotor_ramp()
update_rotor_ramp(0.0f);
// control output forced to zero
_control_output = 0;
break;
case ROTOR_CONTROL_IDLE:
// set rotor ramp to decrease speed to zero
update_rotor_ramp(0.0f);
// set rotor control speed to idle speed parameter, this happens instantly and ignore ramping
_control_output = _idle_output;
break;
case ROTOR_CONTROL_ACTIVE:
// set main rotor ramp to increase to full speed
update_rotor_ramp(1.0f);
if ((_control_mode == ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH) || (_control_mode == ROTOR_CONTROL_MODE_SPEED_SETPOINT)) {
// set control rotor speed to ramp slewed value between idle and desired speed
_control_output = _idle_output + (_rotor_ramp_output * (_desired_speed - _idle_output));
} else if (_control_mode == ROTOR_CONTROL_MODE_OPEN_LOOP_POWER_OUTPUT) {
// throttle output depending on estimated power demand. Output is ramped up from idle speed during rotor runup.
_control_output = _idle_output + (_rotor_ramp_output * ((_power_output_low - _idle_output) + (_power_output_range * _load_feedforward)));
}
break;
}
// update rotor speed run-up estimate
update_rotor_runup();
// output to rsc servo
write_rsc(_control_output);
}
// update_rotor_ramp - slews rotor output scalar between 0 and 1, outputs float scalar to _rotor_ramp_output
void AP_MotorsHeli_RSC::update_rotor_ramp(float rotor_ramp_input)
{
// ramp output upwards towards target
if (_rotor_ramp_output < rotor_ramp_input) {
// allow control output to jump to estimated speed
if (_rotor_ramp_output < _rotor_runup_output) {
_rotor_ramp_output = _rotor_runup_output;
}
// ramp up slowly to target
_rotor_ramp_output += _ramp_increment;
if (_rotor_ramp_output > rotor_ramp_input) {
_rotor_ramp_output = rotor_ramp_input;
}
}else{
// ramping down happens instantly
_rotor_ramp_output = rotor_ramp_input;
}
}
// update_rotor_runup - function to slew rotor runup scalar, outputs float scalar to _rotor_runup_ouptut
void AP_MotorsHeli_RSC::update_rotor_runup()
{
// ramp speed estimate towards control out
if (_rotor_runup_output < _rotor_ramp_output) {
_rotor_runup_output += _runup_increment;
if (_rotor_runup_output > _rotor_ramp_output) {
_rotor_runup_output = _rotor_ramp_output;
}
}else{
_rotor_runup_output -= _runup_increment;
if (_rotor_runup_output < _rotor_ramp_output) {
_rotor_runup_output = _rotor_ramp_output;
}
}
// update run-up complete flag
// if control mode is disabled, then run-up complete always returns true
if ( _control_mode == ROTOR_CONTROL_MODE_DISABLED ){
_runup_complete = true;
return;
}
// if rotor ramp and runup are both at full speed, then run-up has been completed
if (!_runup_complete && (_rotor_ramp_output >= 1.0f) && (_rotor_runup_output >= 1.0f)) {
_runup_complete = true;
}
// if rotor speed is less than critical speed, then run-up is not complete
// this will prevent the case where the target rotor speed is less than critical speed
if (_runup_complete && (get_rotor_speed() <= _critical_speed)) {
_runup_complete = false;
}
}
// get_rotor_speed - gets rotor speed either as an estimate, or (ToDO) a measured value
int16_t AP_MotorsHeli_RSC::get_rotor_speed() const
{
// if no actual measured rotor speed is available, estimate speed based on rotor runup scalar.
return (_rotor_runup_output * _max_speed);
}
// 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)
{
if (_control_mode == ROTOR_CONTROL_MODE_DISABLED){
// do not do servo output to avoid conflicting with other output on the channel
// ToDo: We should probably use RC_Channel_Aux to avoid this problem
return;
} else {
_servo_output.servo_out = servo_out;
_servo_output.calc_pwm();
hal.rcout->write(_servo_output_channel, _servo_output.radio_out);
}
}