mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_Motors: added H_RSC_POWER_NEGC and H_RSC_SLEWRATE
this gives more control over throttle for petrol helis. H_RSC_POWER_NEGC allows for a asymmetric V-curve, which allows for less power being put into the head when landing or when sitting on the ground. That can lead to significantly less vibration and chance of ground oscillation. A heli not being flown with aerobatics does not need to use high throttle at negative collective pitch. The H_RSC_SLEWRATE allows for a maximum throttle slew rate to be set. Some petrol motors can cut if the throttle is moved too quickly. We had this happen at a height of 6m when switching from ALT_HOLD to STABILIZE mode. It also lowers the chance of the blades skewing in their holders with the sudden change of power when the heli is disarmed. In general it is a bad idea to do instantaneous large movements of a IC engine throttle.
This commit is contained in:
parent
918c41b1e4
commit
11975223dd
@ -125,7 +125,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
|
||||
|
||||
// @Param: RSC_POWER_LOW
|
||||
// @DisplayName: Throttle Servo Low Power Position
|
||||
// @Description: Throttle output at zero collective pitch.
|
||||
// @Description: Throttle output at zero collective pitch. This is on a scale from 0 to 1000, where 1000 is full throttle and 0 is zero throttle. Actual PWM values are controlled by H_RSC_PWM_MIN and H_RSC_PWM_MAX. Zero collective pitch is defined by H_COL_MID.
|
||||
// @Range: 0 1000
|
||||
// @Increment: 10
|
||||
// @User: Standard
|
||||
@ -133,7 +133,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
|
||||
|
||||
// @Param: RSC_POWER_HIGH
|
||||
// @DisplayName: Throttle Servo High Power Position
|
||||
// @Description: Throttle output at max collective pitch.
|
||||
// @Description: Throttle output at maximum collective pitch. This is on a scale from 0 to 1000, where 1000 is full throttle and 0 is zero throttle. Actual PWM values are controlled by H_RSC_PWM_MIN and H_RSC_PWM_MAX.
|
||||
// @Range: 0 1000
|
||||
// @Increment: 10
|
||||
// @User: Standard
|
||||
@ -156,6 +156,22 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("SV_TEST", 17, AP_MotorsHeli, _servo_test, 0),
|
||||
|
||||
// @Param: RSC_POWER_NEGC
|
||||
// @DisplayName: Throttle servo negative collective power position
|
||||
// @Description: Throttle output at full negative collective pitch. This is on a scale from 0 to 1000, where 1000 is full throttle and 0 is zero throttle. Actual PWM values are controlled by H_RSC_PWM_MIN and H_RSC_PWM_MAX. If this is equal to H_RSC_POWER_HIGH then you will have a symmetric V-curve for the throttle response.
|
||||
// @Range: 1 1000
|
||||
// @Increment: 10
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("RSC_POWER_NEGC", 18, AP_MotorsHeli, _rsc_power_negc, AP_MOTORS_HELI_RSC_POWER_HIGH_DEFAULT),
|
||||
|
||||
// @Param: RSC_SLEWRATE
|
||||
// @DisplayName: Throttle servo slew rate
|
||||
// @Description: This controls the maximum rate at which the throttle output can change, as a percentage per second. A value of 100 means the throttle can change over its full range in one second. A value of zero gives unlimited slew rate.
|
||||
// @Range: 0 500
|
||||
// @Increment: 10
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("RSC_SLEWRATE", 19, AP_MotorsHeli, _rsc_slewrate, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -199,6 +199,8 @@ protected:
|
||||
AP_Int16 _rsc_idle_output; // Rotor control output while at idle
|
||||
AP_Int16 _rsc_power_low; // throttle value sent to throttle servo at zero collective pitch
|
||||
AP_Int16 _rsc_power_high; // throttle value sent to throttle servo at maximum collective pitch
|
||||
AP_Int16 _rsc_power_negc; // throttle value sent to throttle servo at full negative collective pitch
|
||||
AP_Int16 _rsc_slewrate; // throttle slew rate (percentage per second)
|
||||
AP_Int8 _servo_test; // sets number of cycles to test servo movement on bootup
|
||||
|
||||
// internal variables
|
||||
|
@ -29,11 +29,12 @@ void AP_MotorsHeli_RSC::init_servo()
|
||||
}
|
||||
|
||||
// set_power_output_range
|
||||
void AP_MotorsHeli_RSC::set_power_output_range(float power_low, float power_high)
|
||||
void AP_MotorsHeli_RSC::set_power_output_range(float power_low, float power_high, float power_negc, uint16_t slewrate)
|
||||
{
|
||||
_power_output_low = power_low;
|
||||
_power_output_high = power_high;
|
||||
_power_output_range = _power_output_high - _power_output_low;
|
||||
_power_output_negc = power_negc;
|
||||
_power_slewrate = slewrate;
|
||||
}
|
||||
|
||||
// output - update value to send to ESC/Servo
|
||||
@ -41,6 +42,7 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
|
||||
{
|
||||
float dt;
|
||||
uint64_t now = AP_HAL::micros64();
|
||||
float last_control_output = _control_output;
|
||||
|
||||
if (_last_update_us == 0) {
|
||||
_last_update_us = now;
|
||||
@ -75,8 +77,15 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
|
||||
// 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)));
|
||||
// throttle output depending on estimated power demand. Output is ramped up from idle speed during rotor runup. A negative load
|
||||
// is for the left side of the V-curve (-ve collective) A positive load is for the right side (+ve collective)
|
||||
if (_load_feedforward >= 0) {
|
||||
float range = _power_output_high - _power_output_low;
|
||||
_control_output = _idle_output + (_rotor_ramp_output * ((_power_output_low - _idle_output) + (range * _load_feedforward)));
|
||||
} else {
|
||||
float range = _power_output_negc - _power_output_low;
|
||||
_control_output = _idle_output + (_rotor_ramp_output * ((_power_output_low - _idle_output) - (range * _load_feedforward)));
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
@ -84,6 +93,12 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
|
||||
// update rotor speed run-up estimate
|
||||
update_rotor_runup(dt);
|
||||
|
||||
if (_power_slewrate > 0) {
|
||||
// implement slew rate for throttle
|
||||
float max_delta = dt * _power_slewrate * 0.01f;
|
||||
_control_output = constrain_float(_control_output, last_control_output-max_delta, last_control_output+max_delta);
|
||||
}
|
||||
|
||||
// output to rsc servo
|
||||
write_rsc(_control_output);
|
||||
}
|
||||
|
@ -69,9 +69,9 @@ public:
|
||||
void set_runup_time(int8_t runup_time) { _runup_time = runup_time; }
|
||||
|
||||
// set_power_output_range
|
||||
void set_power_output_range(float power_low, float power_high);
|
||||
void set_power_output_range(float power_low, float power_high, float power_negc, uint16_t slewrate);
|
||||
|
||||
// set_motor_load
|
||||
// set_motor_load. +ve numbers for +ve collective. -ve numbers for negative collective
|
||||
void set_motor_load(float load) { _load_feedforward = load; }
|
||||
|
||||
// output - update value to send to ESC/Servo
|
||||
@ -97,7 +97,8 @@ private:
|
||||
bool _runup_complete = false; // flag for determining if runup is complete
|
||||
float _power_output_low = 0.0f; // setpoint for power output at minimum rotor power
|
||||
float _power_output_high = 0.0f; // setpoint for power output at maximum rotor power
|
||||
float _power_output_range = 0.0f; // maximum range of output power
|
||||
float _power_output_negc = 0.0f; // setpoint for power output at full negative collective
|
||||
uint16_t _power_slewrate = 0; // slewrate for throttle (percentage per second)
|
||||
float _load_feedforward = 0.0f; // estimate of motor load, range 0-1.0f
|
||||
|
||||
AP_Int16 _pwm_min;
|
||||
|
@ -261,7 +261,7 @@ void AP_MotorsHeli_Single::calculate_armed_scalars()
|
||||
_main_rotor.set_runup_time(_rsc_runup_time);
|
||||
_main_rotor.set_critical_speed(_rsc_critical/1000.0f);
|
||||
_main_rotor.set_idle_output(_rsc_idle_output/1000.0f);
|
||||
_main_rotor.set_power_output_range(_rsc_power_low/1000.0f, _rsc_power_high/1000.0f);
|
||||
_main_rotor.set_power_output_range(_rsc_power_low/1000.0f, _rsc_power_high/1000.0f, _rsc_power_negc/1000.0f, (uint16_t)_rsc_slewrate.get());
|
||||
}
|
||||
|
||||
|
||||
@ -433,9 +433,11 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float
|
||||
// ToDo: include tail rotor power?
|
||||
// ToDo: add main rotor cyclic power?
|
||||
if (collective_out > _collective_mid_pct) {
|
||||
// +ve motor load for +ve collective
|
||||
_main_rotor.set_motor_load((collective_out - _collective_mid_pct) / (1.0f - _collective_mid_pct));
|
||||
} else {
|
||||
_main_rotor.set_motor_load((_collective_mid_pct - collective_out) / _collective_mid_pct);
|
||||
// -ve motor load for -ve collective
|
||||
_main_rotor.set_motor_load((collective_out - _collective_mid_pct) / _collective_mid_pct);
|
||||
}
|
||||
|
||||
// swashplate servos
|
||||
|
Loading…
Reference in New Issue
Block a user