AP_Motors:Heli - new rotor speed control modes for autothrottle governor

This commit is contained in:
MidwestAire 2021-01-20 15:09:07 -06:00 committed by Bill Geyer
parent fb6db5e564
commit 42a131522b
6 changed files with 13 additions and 13 deletions

View File

@ -454,7 +454,7 @@ void AP_MotorsHeli::output_logic()
bool AP_MotorsHeli::parameter_check(bool display_msg) const
{
// returns false if RSC Mode is not set to a valid control mode
if (_main_rotor._rsc_mode.get() <= (int8_t)ROTOR_CONTROL_MODE_DISABLED || _main_rotor._rsc_mode.get() > (int8_t)ROTOR_CONTROL_MODE_CLOSED_LOOP_POWER_OUTPUT) {
if (_main_rotor._rsc_mode.get() <= (int8_t)ROTOR_CONTROL_MODE_DISABLED || _main_rotor._rsc_mode.get() > (int8_t)ROTOR_CONTROL_MODE_AUTOTHROTTLE) {
if (display_msg) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_MODE invalid");
}

View File

@ -334,7 +334,7 @@ void AP_MotorsHeli_Dual::set_rpm(float rotor_rpm)
void AP_MotorsHeli_Dual::calculate_armed_scalars()
{
// Set rsc mode specific parameters
if (_main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_OPEN_LOOP_POWER_OUTPUT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_CLOSED_LOOP_POWER_OUTPUT) {
if (_main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_THROTTLECURVE || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_AUTOTHROTTLE) {
_main_rotor.set_throttle_curve();
}
// keeps user from changing RSC mode while armed

View File

@ -113,7 +113,7 @@ void AP_MotorsHeli_Quad::set_rpm(float rotor_rpm)
void AP_MotorsHeli_Quad::calculate_armed_scalars()
{
// Set rsc mode specific parameters
if (_main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_OPEN_LOOP_POWER_OUTPUT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_CLOSED_LOOP_POWER_OUTPUT) {
if (_main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_THROTTLECURVE || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_AUTOTHROTTLE) {
_main_rotor.set_throttle_curve();
}
// keeps user from changing RSC mode while armed

View File

@ -36,7 +36,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
// @Description: Selects the type of rotor speed control used to determine throttle output to the HeliRSC servo channel when motor interlock is enabled (throttle hold off). RC Passthrough sends the input from the RC Motor Interlock channel as throttle output. External Gov SetPoint sends the RSC SetPoint parameter value as throttle output. Throttle Curve uses the 5 point throttle curve to determine throttle output based on the collective output. Governor is ArduCopter's built-in governor that uses the throttle curve for a feed forward throttle command to determine throttle output.
// @Values: 1:RC Passthrough, 2:External Gov SetPoint, 3:Throttle Curve, 4:Governor
// @User: Standard
AP_GROUPINFO("MODE", 2, AP_MotorsHeli_RSC, _rsc_mode, (int8_t)ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH),
AP_GROUPINFO("MODE", 2, AP_MotorsHeli_RSC, _rsc_mode, (int8_t)ROTOR_CONTROL_MODE_PASSTHROUGH),
// @Param: RAMP_TIME
// @DisplayName: Throttle Ramp Time
@ -250,14 +250,14 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
// set main rotor ramp to increase to full speed
update_rotor_ramp(1.0f, dt);
if ((_control_mode == ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH) || (_control_mode == ROTOR_CONTROL_MODE_SPEED_SETPOINT)) {
if ((_control_mode == ROTOR_CONTROL_MODE_PASSTHROUGH) || (_control_mode == ROTOR_CONTROL_MODE_SETPOINT)) {
// set control rotor speed to ramp slewed value between idle and desired speed
_control_output = get_idle_output() + (_rotor_ramp_output * (_desired_speed - get_idle_output()));
} else if (_control_mode == ROTOR_CONTROL_MODE_OPEN_LOOP_POWER_OUTPUT) {
} else if (_control_mode == ROTOR_CONTROL_MODE_THROTTLECURVE) {
// throttle output from throttle curve based on collective position
float desired_throttle = calculate_desired_throttle(_collective_in);
_control_output = get_idle_output() + (_rotor_ramp_output * (desired_throttle - get_idle_output()));
} else if (_control_mode == ROTOR_CONTROL_MODE_CLOSED_LOOP_POWER_OUTPUT) {
} else if (_control_mode == ROTOR_CONTROL_MODE_AUTOTHROTTLE) {
// governor provides two modes of throttle control - governor engaged
// or throttle curve if governor is out of range or sensor failed
float desired_throttle = calculate_desired_throttle(_collective_in);

View File

@ -43,10 +43,10 @@ enum RotorControlState {
// rotor control modes
enum RotorControlMode {
ROTOR_CONTROL_MODE_DISABLED = 0,
ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH,
ROTOR_CONTROL_MODE_SPEED_SETPOINT,
ROTOR_CONTROL_MODE_OPEN_LOOP_POWER_OUTPUT,
ROTOR_CONTROL_MODE_CLOSED_LOOP_POWER_OUTPUT
ROTOR_CONTROL_MODE_PASSTHROUGH,
ROTOR_CONTROL_MODE_SETPOINT,
ROTOR_CONTROL_MODE_THROTTLECURVE,
ROTOR_CONTROL_MODE_AUTOTHROTTLE
};
class AP_MotorsHeli_RSC {

View File

@ -284,7 +284,7 @@ void AP_MotorsHeli_Single::set_rpm(float rotor_rpm)
void AP_MotorsHeli_Single::calculate_armed_scalars()
{
// Set rsc mode specific parameters
if (_main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_OPEN_LOOP_POWER_OUTPUT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_CLOSED_LOOP_POWER_OUTPUT) {
if (_main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_THROTTLECURVE || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_AUTOTHROTTLE) {
_main_rotor.set_throttle_curve();
}
// keeps user from changing RSC mode while armed
@ -350,7 +350,7 @@ void AP_MotorsHeli_Single::calculate_scalars()
// send setpoints to DDVP rotor controller and trigger recalculation of scalars
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) {
_tail_rotor.set_control_mode(ROTOR_CONTROL_MODE_SPEED_SETPOINT);
_tail_rotor.set_control_mode(ROTOR_CONTROL_MODE_SETPOINT);
_tail_rotor.set_ramp_time(_main_rotor._ramp_time.get());
_tail_rotor.set_runup_time(_main_rotor._runup_time.get());
_tail_rotor.set_critical_speed(_main_rotor._critical_speed.get());