2015-07-21 07:07:54 -03:00
/*
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>
2015-08-15 13:42:46 -03:00
# include <AP_HAL/AP_HAL.h>
2021-10-27 10:06:23 -03:00
# include <GCS_MAVLink/GCS.h>
2015-07-21 07:07:54 -03:00
# include "AP_MotorsHeli_RSC.h"
2021-02-06 00:54:43 -04:00
# include <AP_RPM/AP_RPM.h>
2015-07-21 07:07:54 -03:00
extern const AP_HAL : : HAL & hal ;
2019-08-07 23:52:17 -03:00
const AP_Param : : GroupInfo AP_MotorsHeli_RSC : : var_info [ ] = {
// @Param: SETPOINT
// @DisplayName: External Motor Governor Setpoint
// @Description: Throttle (HeliRSC Servo) output in percent to the external motor governor when motor interlock enabled (throttle hold off).
2019-02-14 20:28:48 -04:00
// @Range: 0 100
2019-08-07 23:52:17 -03:00
// @Units: %
2019-02-14 20:28:48 -04:00
// @Increment: 1
// @User: Standard
2019-08-07 23:52:17 -03:00
AP_GROUPINFO ( " SETPOINT " , 1 , AP_MotorsHeli_RSC , _rsc_setpoint , AP_MOTORS_HELI_RSC_SETPOINT ) ,
// @Param: MODE
// @DisplayName: Rotor Speed Control Mode
2021-02-06 00:54:43 -04:00
// @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. AutoThrottle requires a rotor speed sensor, contains an advanced autothrottle governor and is primarily for piston and turbine engines. WARNING: Throttle ramp time and throttle curve MUST be tuned properly using Throttle Curve mode before using AutoThrottle
2021-01-21 07:02:11 -04:00
// @Values: 1:RC Passthrough, 2:External Gov SetPoint, 3:Throttle Curve, 4:AutoThrottle
2019-08-07 23:52:17 -03:00
// @User: Standard
2021-01-20 17:09:07 -04:00
AP_GROUPINFO ( " MODE " , 2 , AP_MotorsHeli_RSC , _rsc_mode , ( int8_t ) ROTOR_CONTROL_MODE_PASSTHROUGH ) ,
2019-08-07 23:52:17 -03:00
// @Param: RAMP_TIME
2019-12-07 18:50:33 -04:00
// @DisplayName: Throttle Ramp Time
2019-08-07 23:52:17 -03:00
// @Description: Time in seconds for throttle output (HeliRSC servo) to ramp from ground idle (RSC_IDLE) to flight idle throttle setting when motor interlock is enabled (throttle hold off).
// @Range: 0 60
// @Units: s
// @User: Standard
AP_GROUPINFO ( " RAMP_TIME " , 3 , AP_MotorsHeli_RSC , _ramp_time , AP_MOTORS_HELI_RSC_RAMP_TIME ) ,
// @Param: RUNUP_TIME
// @DisplayName: Rotor Runup Time
2021-01-21 07:02:11 -04:00
// @Description: Actual time in seconds for the main rotor to reach full speed after motor interlock is enabled (throttle hold off). Must be at least one second longer than the Throttle Ramp Time that is set with RSC_RAMP_TIME. WARNING: For AutoThrottle users with piston and turbine engines it is VERY important to know how long it takes to warm up your engine and reach full rotor speed when throttle switch is turned ON. This timer should be set for at least the amount of time it takes to get your helicopter to full flight power, ready for takeoff. Failure to heed this warning could result in the auto-takeoff mode attempting to lift up into hover before the engine has reached full power, and subsequent loss of control
2019-08-07 23:52:17 -03:00
// @Range: 0 60
// @Units: s
// @User: Standard
AP_GROUPINFO ( " RUNUP_TIME " , 4 , AP_MotorsHeli_RSC , _runup_time , AP_MOTORS_HELI_RSC_RUNUP_TIME ) ,
2019-02-14 20:28:48 -04:00
2019-08-07 23:52:17 -03:00
// @Param: CRITICAL
// @DisplayName: Critical Rotor Speed
// @Description: Percentage of normal rotor speed where flight is no longer possible. However currently the rotor runup/rundown is estimated using the RSC_RUNUP_TIME parameter. Estimated rotor speed increases/decreases between 0 (rotor stopped) to 1 (rotor at normal speed) in the RSC_RUNUP_TIME in seconds. This parameter should be set so that the estimated rotor speed goes below critical in approximately 3 seconds. So if you had a 10 second runup time then set RSC_CRITICAL to 70%.
2019-02-14 20:28:48 -04:00
// @Range: 0 100
2019-08-07 23:52:17 -03:00
// @Units: %
2019-02-14 20:28:48 -04:00
// @Increment: 1
// @User: Standard
2019-08-07 23:52:17 -03:00
AP_GROUPINFO ( " CRITICAL " , 5 , AP_MotorsHeli_RSC , _critical_speed , AP_MOTORS_HELI_RSC_CRITICAL ) ,
2019-02-14 20:28:48 -04:00
2019-08-07 23:52:17 -03:00
// @Param: IDLE
2019-12-07 18:50:33 -04:00
// @DisplayName: Throttle Output at Idle
2019-08-07 23:52:17 -03:00
// @Description: Throttle output (HeliRSC Servo) in percent while armed but motor interlock is disabled (throttle hold on). FOR COMBUSTION ENGINES. Sets the engine ground idle throttle percentage with clutch disengaged. This must be set to zero for electric helicopters under most situations. If the ESC has an autorotation window this can be set to keep the autorotation window open in the ESC. Consult the operating manual for your ESC to set it properly for this purpose
// @Range: 0 50
// @Units: %
2019-02-14 20:28:48 -04:00
// @Increment: 1
// @User: Standard
2019-08-07 23:52:17 -03:00
AP_GROUPINFO ( " IDLE " , 6 , AP_MotorsHeli_RSC , _idle_output , AP_MOTORS_HELI_RSC_IDLE_DEFAULT ) ,
// @Param: SLEWRATE
2019-12-07 18:50:33 -04:00
// @DisplayName: Throttle Slew Rate
2019-08-07 23:52:17 -03:00
// @Description: This controls the maximum rate at which the throttle output (HeliRSC servo) 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 ( " SLEWRATE " , 7 , AP_MotorsHeli_RSC , _power_slewrate , 0 ) ,
2019-02-14 20:28:48 -04:00
2019-08-07 23:52:17 -03:00
// @Param: THRCRV_0
2019-12-07 18:50:33 -04:00
// @DisplayName: Throttle Curve at 0% Coll
2019-08-07 23:52:17 -03:00
// @Description: Sets the throttle output (HeliRSC servo) in percent for the throttle curve at the minimum collective pitch position. The 0 percent collective is defined by H_COL_MIN. Example: if the setup has -2 degree to +10 degree collective pitch setup, this setting would correspond to -2 degree of pitch.
2019-02-14 20:28:48 -04:00
// @Range: 0 100
2019-08-07 23:52:17 -03:00
// @Units: %
2019-02-14 20:28:48 -04:00
// @Increment: 1
// @User: Standard
2019-08-07 23:52:17 -03:00
AP_GROUPINFO ( " THRCRV_0 " , 8 , AP_MotorsHeli_RSC , _thrcrv [ 0 ] , AP_MOTORS_HELI_RSC_THRCRV_0_DEFAULT ) ,
2019-02-14 20:28:48 -04:00
2019-08-07 23:52:17 -03:00
// @Param: THRCRV_25
2019-12-07 18:50:33 -04:00
// @DisplayName: Throttle Curve at 25% Coll
2019-08-07 23:52:17 -03:00
// @Description: Sets the throttle output (HeliRSC servo) in percent for the throttle curve at 25% of full collective travel where he 0 percent collective is defined by H_COL_MIN and 100 percent collective is defined by H_COL_MAX. Example: if the setup has -2 degree to +10 degree collective pitch setup, the total range is 12 degrees. 25% of 12 degrees is 3 degrees, so this setting would correspond to +1 degree of pitch.
2019-02-14 20:28:48 -04:00
// @Range: 0 100
2019-08-07 23:52:17 -03:00
// @Units: %
2019-02-14 20:28:48 -04:00
// @Increment: 1
// @User: Standard
2019-08-07 23:52:17 -03:00
AP_GROUPINFO ( " THRCRV_25 " , 9 , AP_MotorsHeli_RSC , _thrcrv [ 1 ] , AP_MOTORS_HELI_RSC_THRCRV_25_DEFAULT ) ,
2019-02-14 20:28:48 -04:00
2019-08-07 23:52:17 -03:00
// @Param: THRCRV_50
2019-12-07 18:50:33 -04:00
// @DisplayName: Throttle Curve at 50% Coll
2019-08-07 23:52:17 -03:00
// @Description: Sets the throttle output (HeliRSC servo) in percent for the throttle curve at 50% of full collective travel where he 0 percent collective is defined by H_COL_MIN and 100 percent collective is defined by H_COL_MAX. Example: if the setup has -2 degree to +10 degree collective pitch setup, the total range is 12 degrees. 50% of 12 degrees is 6 degrees, so this setting would correspond to +4 degree of pitch.
// @Range: 0 100
// @Units: %
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " THRCRV_50 " , 10 , AP_MotorsHeli_RSC , _thrcrv [ 2 ] , AP_MOTORS_HELI_RSC_THRCRV_50_DEFAULT ) ,
2019-02-14 20:28:48 -04:00
2019-08-07 23:52:17 -03:00
// @Param: THRCRV_75
2019-12-07 18:50:33 -04:00
// @DisplayName: Throttle Curve at 75% Coll
2019-08-07 23:52:17 -03:00
// @Description: Sets the throttle output (HeliRSC servo) in percent for the throttle curve at 75% of full collective travel where he 0 percent collective is defined by H_COL_MIN and 100 percent collective is defined by H_COL_MAX. Example: if the setup has -2 degree to +10 degree collective pitch setup, the total range is 12 degrees. 75% of 12 degrees is 9 degrees, so this setting would correspond to +7 degree of pitch.
// @Range: 0 100
// @Units: %
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " THRCRV_75 " , 11 , AP_MotorsHeli_RSC , _thrcrv [ 3 ] , AP_MOTORS_HELI_RSC_THRCRV_75_DEFAULT ) ,
2019-02-14 20:28:48 -04:00
2019-08-07 23:52:17 -03:00
// @Param: THRCRV_100
2019-12-07 18:50:33 -04:00
// @DisplayName: Throttle Curve at 100% Coll
2019-08-07 23:52:17 -03:00
// @Description: Sets the throttle output (HeliRSC servo) in percent for the throttle curve at the minimum collective pitch position. The 100 percent collective is defined by H_COL_MAX. Example: if the setup has -2 degree to +10 degree collective pitch setup, this setting would correspond to +10 degree of pitch.
// @Range: 0 100
// @Units: %
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " THRCRV_100 " , 12 , AP_MotorsHeli_RSC , _thrcrv [ 4 ] , AP_MOTORS_HELI_RSC_THRCRV_100_DEFAULT ) ,
2019-02-14 20:28:48 -04:00
2021-11-11 13:09:26 -04:00
// Indices 13 thru 16 have been re-assigned and should not be used in the future
// @Param: GOV_RANGE
// @DisplayName: Governor Operational Range
// @Description: RPM range +/- governor rpm reference setting where governor is operational. If speed sensor fails or rpm falls outside of this range, the governor will disengage and return to throttle curve. Recommended range is 100
// @Range: 50 200
// @Units: RPM
// @Increment: 10
// @User: Standard
AP_GROUPINFO ( " GOV_RANGE " , 17 , AP_MotorsHeli_RSC , _governor_range , AP_MOTORS_HELI_RSC_GOVERNOR_RANGE_DEFAULT ) ,
2019-02-14 20:28:48 -04:00
2021-02-06 08:49:11 -04:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
// @Param: AROT_PCT
// @DisplayName: Autorotation Throttle Percentage for External Governor
// @Description: The throttle percentage sent to external governors, signaling to enable fast spool-up, when bailing out of an autorotation. Set 0 to disable. If also using a tail rotor of type DDVP with external governor then this value must lie within the autorotation window of both governors.
// @Range: 0 40
// @Units: %
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " AROT_PCT " , 18 , AP_MotorsHeli_RSC , _ext_gov_arot_pct , 0 ) ,
# endif
2021-11-11 13:09:26 -04:00
// @Param: CLDWN_TIME
// @DisplayName: Cooldown Time
// @Description: Will provide a fast idle for engine cooldown by raising the Ground Idle speed setting by 50% for the number of seconds the timer is set for. A setting of zero disables the fast idle. This feature will only apply after the runup complete has been declared. This will not extend the time before ground idle is declared, which triggers engine shutdown for autonomous landings.
2021-02-10 16:45:07 -04:00
// @Range: 0 120
// @Units: s
2021-01-21 07:02:11 -04:00
// @Increment: 1
// @User: Standard
2021-11-11 13:09:26 -04:00
AP_GROUPINFO ( " CLDWN_TIME " , 19 , AP_MotorsHeli_RSC , _cooldown_time , 0 ) ,
2021-02-07 14:30:05 -04:00
2021-01-21 07:02:11 -04:00
// @Param: GOV_COMP
// @DisplayName: Governor Torque Compensator
2021-11-11 13:09:26 -04:00
// @Description: Adjusts the autothrottle governor torque compensator that determines how fast the governor will adjust the base torque reference to compensate for changes in density altitude. If RPM is low or high by more than 2-5 RPM, increase this setting by 1% at a time until the governor speed matches your RPM setting. Setting the compensator too high can result in surging and throttle "hunting". Do not make large adjustments at one time
2021-02-06 00:54:43 -04:00
// @Range: 0 70
2019-08-07 23:52:17 -03:00
// @Units: %
2021-11-11 13:09:26 -04:00
// @Increment: 0.1
2019-02-14 20:28:48 -04:00
// @User: Standard
2021-02-06 08:49:11 -04:00
AP_GROUPINFO ( " GOV_COMP " , 20 , AP_MotorsHeli_RSC , _governor_compensator , 25 ) ,
2019-02-14 20:28:48 -04:00
2019-08-07 23:52:17 -03:00
// @Param: GOV_DROOP
2021-01-21 07:02:11 -04:00
// @DisplayName: Governor Droop Compensator
2021-11-11 13:09:26 -04:00
// @Description: AutoThrottle governor droop response under load, normal settings of 0-50%. Higher value is quicker response to large speed changes due to load but may cause surging. Adjust this to be as aggressive as possible without getting surging or RPM over-run when the governor responds to large load changes on the rotor system
2021-02-06 00:54:43 -04:00
// @Range: 0 100
2019-08-07 23:52:17 -03:00
// @Units: %
2021-11-11 13:09:26 -04:00
// @Increment: 0.1
2019-02-14 20:28:48 -04:00
// @User: Standard
2021-02-10 16:45:07 -04:00
AP_GROUPINFO ( " GOV_DROOP " , 21 , AP_MotorsHeli_RSC , _governor_droop_response , 25 ) ,
2019-02-14 20:28:48 -04:00
2021-01-21 07:02:11 -04:00
// @Param: GOV_FF
// @DisplayName: Governor Feedforward
2021-11-11 13:09:26 -04:00
// @Description: Feedforward governor gain to throttle response during sudden loading/unloading of the rotor system. If RPM drops excessively during full collective climb with the droop response set correctly, increase the governor feedforward.
2021-01-21 07:02:11 -04:00
// @Range: 0 100
2019-08-07 23:52:17 -03:00
// @Units: %
2021-11-11 13:09:26 -04:00
// @Increment: 0.1
2019-02-14 20:28:48 -04:00
// @User: Standard
2021-02-10 16:45:07 -04:00
AP_GROUPINFO ( " GOV_FF " , 22 , AP_MotorsHeli_RSC , _governor_ff , 50 ) ,
2021-02-07 14:30:05 -04:00
2021-02-10 16:45:07 -04:00
// @Param: GOV_RPM
// @DisplayName: Rotor RPM Setting
// @Description: Main rotor RPM that governor maintains when engaged
// @Range: 800 3500
// @Units: RPM
// @Increment: 10
// @User: Standard
AP_GROUPINFO ( " GOV_RPM " , 23 , AP_MotorsHeli_RSC , _governor_rpm , 1500 ) ,
// @Param: GOV_TORQUE
// @DisplayName: Governor Torque Limiter
2021-11-11 13:09:26 -04:00
// @Description: Adjusts the engine's percentage of torque rise on autothrottle during ramp-up to governor speed. The torque rise will determine how fast the rotor speed will ramp up when rotor speed reaches 50% of the rotor RPM setting. The sequence of events engaging the governor is as follows: Throttle ramp time will engage the clutch and start the main rotor turning. The collective should be at flat pitch and the throttle curve set to provide at least 50% of normal RPM at flat pitch. The autothrottle torque limiter will automatically activate and start accelerating the main rotor. If the autothrottle consistently fails to accelerate the main rotor during ramp-in due to engine tune or other factors, then increase the torque limiter setting. NOTE: throttle ramp time and throttle curve should be tuned using RSC_MODE Throttle Curve before using RSC_MODE AutoThrottle
2021-02-10 16:45:07 -04:00
// @Range: 10 60
// @Units: %
2021-01-21 07:02:11 -04:00
// @Increment: 1
2019-02-28 21:43:03 -04:00
// @User: Standard
2021-02-10 16:45:07 -04:00
AP_GROUPINFO ( " GOV_TORQUE " , 24 , AP_MotorsHeli_RSC , _governor_torque , 30 ) ,
2020-04-01 11:40:53 -03:00
2019-02-14 20:28:48 -04:00
AP_GROUPEND
} ;
2015-08-11 12:01:11 -03:00
// init_servo - servo initialization on start-up
void AP_MotorsHeli_RSC : : init_servo ( )
{
2015-12-05 06:10:52 -04:00
// setup RSC on specified channel by default
2017-01-03 05:56:57 -04:00
SRV_Channels : : set_aux_channel_default ( _aux_fn , _default_channel ) ;
2018-07-11 16:33:00 -03:00
2021-02-07 14:30:05 -04:00
// set servo range
2018-07-11 16:33:00 -03:00
SRV_Channels : : set_range ( SRV_Channels : : get_motor_function ( _aux_fn ) , 1000 ) ;
2015-08-11 12:01:11 -03:00
}
2015-08-11 21:20:28 -03:00
// set_power_output_range
2018-03-23 01:09:14 -03:00
// TODO: Look at possibly calling this at a slower rate. Doesn't need to be called every cycle.
2019-08-07 23:52:17 -03:00
void AP_MotorsHeli_RSC : : set_throttle_curve ( )
2015-08-11 21:20:28 -03:00
{
2019-08-07 23:52:17 -03:00
float thrcrv [ 5 ] ;
2018-03-23 01:09:14 -03:00
// Ensure user inputs are within parameter limits
2019-08-07 23:52:17 -03:00
// Scale throttle curve parameters
2018-03-23 01:09:14 -03:00
for ( uint8_t i = 0 ; i < 5 ; i + + ) {
2019-08-07 23:52:17 -03:00
thrcrv [ i ] = constrain_float ( _thrcrv [ i ] * 0.01f , 0.0f , 1.0f ) ;
2018-03-23 01:09:14 -03:00
}
// Calculate the spline polynomials for the throttle curve
splinterp5 ( thrcrv , _thrcrv_poly ) ;
2015-08-11 21:20:28 -03:00
}
2015-08-07 22:14:45 -03:00
// output - update value to send to ESC/Servo
2015-08-28 03:20:42 -03:00
void AP_MotorsHeli_RSC : : output ( RotorControlState state )
2015-07-21 07:07:54 -03:00
{
2021-11-11 13:09:26 -04:00
// _rotor_RPM available to the RSC output
2022-07-15 08:53:41 -03:00
# if AP_RPM_ENABLED
2021-02-06 00:54:43 -04:00
const AP_RPM * rpm = AP_RPM : : get_singleton ( ) ;
2021-11-11 13:09:26 -04:00
if ( rpm ! = nullptr ) {
if ( ! rpm - > get_rpm ( 0 , _rotor_rpm ) ) {
// No valid RPM data
_rotor_rpm = - 1 ;
}
} else {
// No RPM because pointer is null
2021-02-06 00:54:43 -04:00
_rotor_rpm = - 1 ;
}
2022-07-15 08:53:41 -03:00
# else
_rotor_rpm = - 1 ;
# endif
2021-02-07 14:30:05 -04:00
2016-06-04 22:20:58 -03:00
float dt ;
uint64_t now = AP_HAL : : micros64 ( ) ;
2016-06-29 23:28:34 -03:00
float last_control_output = _control_output ;
2018-03-23 01:09:14 -03:00
2016-06-04 22:20:58 -03:00
if ( _last_update_us = = 0 ) {
_last_update_us = now ;
dt = 0.001f ;
} else {
dt = 1.0e-6 f * ( now - _last_update_us ) ;
_last_update_us = now ;
}
2018-03-23 01:09:14 -03:00
2015-08-07 20:52:22 -03:00
switch ( state ) {
2015-08-07 22:14:45 -03:00
case ROTOR_CONTROL_STOP :
2015-08-11 15:31:20 -03:00
// set rotor ramp to decrease speed to zero, this happens instantly inside update_rotor_ramp()
2016-06-04 22:20:58 -03:00
update_rotor_ramp ( 0.0f , dt ) ;
2015-08-11 15:31:20 -03:00
// control output forced to zero
2016-02-03 04:53:34 -04:00
_control_output = 0.0f ;
2021-02-07 14:30:05 -04:00
2021-02-10 16:45:07 -04:00
// governor is forced to disengage status and reset outputs
governor_reset ( ) ;
2021-01-21 07:02:11 -04:00
_autothrottle = false ;
_governor_fault = false ;
2022-02-20 23:59:18 -04:00
//turbine start flag on
_starting = true ;
2015-08-07 22:14:45 -03:00
break ;
case ROTOR_CONTROL_IDLE :
2015-08-11 15:31:20 -03:00
// set rotor ramp to decrease speed to zero
2016-06-04 22:20:58 -03:00
update_rotor_ramp ( 0.0f , dt ) ;
2015-08-11 15:31:20 -03:00
2021-02-10 16:45:07 -04:00
// set rotor control speed to engine idle and ensure governor is reset, if used
governor_reset ( ) ;
2021-11-11 13:09:26 -04:00
_autothrottle = false ;
2021-01-21 07:02:11 -04:00
_governor_fault = false ;
2021-11-11 13:09:26 -04:00
if ( _in_autorotation ) {
// if in autorotation and using an external governor, set the output to tell the governor to use bailout ramp
_control_output = constrain_float ( _rsc_arot_bailout_pct / 100.0f , 0.0f , 0.4f ) ;
} else {
// set rotor control speed to idle speed parameter, this happens instantly and ignores ramping
2022-02-20 23:59:18 -04:00
if ( _turbine_start & & _starting = = true ) {
_control_output + = 0.001f ;
if ( _control_output > = 1.0f ) {
_control_output = get_idle_output ( ) ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Turbine startup " ) ;
_starting = false ;
}
} else {
if ( _cooldown_time > 0 ) {
_control_output = get_idle_output ( ) * 1.5f ;
_fast_idle_timer + = dt ;
if ( _fast_idle_timer > ( float ) _cooldown_time ) {
_fast_idle_timer = 0.0f ;
}
} else {
_control_output = get_idle_output ( ) ;
2021-11-11 13:09:26 -04:00
}
2021-01-21 07:02:11 -04:00
}
2020-04-01 11:40:53 -03:00
}
2015-08-07 22:14:45 -03:00
break ;
2015-08-07 20:52:22 -03:00
2015-08-07 22:14:45 -03:00
case ROTOR_CONTROL_ACTIVE :
2015-08-11 15:31:20 -03:00
// set main rotor ramp to increase to full speed
2016-06-04 22:20:58 -03:00
update_rotor_ramp ( 1.0f , dt ) ;
2015-08-11 15:31:20 -03:00
2022-02-20 23:59:18 -04:00
// if turbine engine started without using start sequence, set starting flag just to be sure it can't be triggered when back in idle
_starting = false ;
2021-01-20 17:09:07 -04:00
if ( ( _control_mode = = ROTOR_CONTROL_MODE_PASSTHROUGH ) | | ( _control_mode = = ROTOR_CONTROL_MODE_SETPOINT ) ) {
2015-08-11 15:31:20 -03:00
// set control rotor speed to ramp slewed value between idle and desired speed
2019-08-07 23:52:17 -03:00
_control_output = get_idle_output ( ) + ( _rotor_ramp_output * ( _desired_speed - get_idle_output ( ) ) ) ;
2021-01-20 17:09:07 -04:00
} else if ( _control_mode = = ROTOR_CONTROL_MODE_THROTTLECURVE ) {
2018-03-23 01:09:14 -03:00
// throttle output from throttle curve based on collective position
2021-01-21 07:02:11 -04:00
float throttlecurve = calculate_throttlecurve ( _collective_in ) ;
_control_output = get_idle_output ( ) + ( _rotor_ramp_output * ( throttlecurve - get_idle_output ( ) ) ) ;
2021-01-20 17:09:07 -04:00
} else if ( _control_mode = = ROTOR_CONTROL_MODE_AUTOTHROTTLE ) {
2021-01-21 07:02:11 -04:00
autothrottle_run ( ) ;
2021-02-07 14:30:05 -04:00
}
2015-08-07 22:14:45 -03:00
break ;
}
2015-07-21 07:07:54 -03:00
2015-08-11 15:31:20 -03:00
// update rotor speed run-up estimate
2016-06-04 22:20:58 -03:00
update_rotor_runup ( dt ) ;
2015-08-10 18:24:57 -03:00
2016-06-29 23:28:34 -03:00
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 ) ;
}
2018-03-23 01:09:14 -03:00
2015-08-07 22:14:45 -03:00
// output to rsc servo
2015-08-11 21:20:28 -03:00
write_rsc ( _control_output ) ;
2015-08-07 22:14:45 -03:00
}
2015-08-07 20:52:22 -03:00
2015-08-11 15:31:20 -03:00
// update_rotor_ramp - slews rotor output scalar between 0 and 1, outputs float scalar to _rotor_ramp_output
2016-06-04 22:20:58 -03:00
void AP_MotorsHeli_RSC : : update_rotor_ramp ( float rotor_ramp_input , float dt )
2015-08-07 22:14:45 -03:00
{
2019-11-28 16:23:47 -04:00
int8_t ramp_time ;
// sanity check ramp time and enable bailout if set
if ( _use_bailout_ramp | | _ramp_time < = 0 ) {
ramp_time = 1 ;
} else {
ramp_time = _ramp_time ;
2016-02-03 04:53:34 -04:00
}
2015-08-07 22:14:45 -03:00
// ramp output upwards towards target
2015-08-11 15:31:20 -03:00
if ( _rotor_ramp_output < rotor_ramp_input ) {
2015-08-07 22:14:45 -03:00
// allow control output to jump to estimated speed
2015-08-11 15:31:20 -03:00
if ( _rotor_ramp_output < _rotor_runup_output ) {
_rotor_ramp_output = _rotor_runup_output ;
2015-07-21 07:07:54 -03:00
}
2015-08-07 22:14:45 -03:00
// ramp up slowly to target
2019-11-28 16:23:47 -04:00
_rotor_ramp_output + = ( dt / ramp_time ) ;
2015-08-11 15:31:20 -03:00
if ( _rotor_ramp_output > rotor_ramp_input ) {
_rotor_ramp_output = rotor_ramp_input ;
2015-07-21 07:07:54 -03:00
}
2015-08-07 22:14:45 -03:00
} else {
// ramping down happens instantly
2015-08-11 15:31:20 -03:00
_rotor_ramp_output = rotor_ramp_input ;
2015-08-07 22:14:45 -03:00
}
2015-08-10 18:24:57 -03:00
}
2015-08-11 15:31:20 -03:00
// update_rotor_runup - function to slew rotor runup scalar, outputs float scalar to _rotor_runup_ouptut
2016-06-04 22:20:58 -03:00
void AP_MotorsHeli_RSC : : update_rotor_runup ( float dt )
2015-08-10 18:24:57 -03:00
{
2020-04-04 05:58:46 -03:00
int8_t runup_time = _runup_time ;
2016-02-03 04:53:34 -04:00
// sanity check runup time
2020-04-04 05:58:46 -03:00
runup_time = MAX ( _ramp_time + 1 , runup_time ) ;
// adjust rotor runup when bailing out
if ( _use_bailout_ramp ) {
// maintain same delta as set in parameters
runup_time = _runup_time - _ramp_time + 1 ;
2016-02-03 04:53:34 -04:00
}
2020-04-04 05:58:46 -03:00
// protect against divide by zero
runup_time = MAX ( 1 , runup_time ) ;
2015-08-07 22:14:45 -03:00
// ramp speed estimate towards control out
2020-04-04 05:58:46 -03:00
float runup_increment = dt / runup_time ;
2015-08-11 15:31:20 -03:00
if ( _rotor_runup_output < _rotor_ramp_output ) {
2016-02-03 04:53:34 -04:00
_rotor_runup_output + = runup_increment ;
2015-08-11 15:31:20 -03:00
if ( _rotor_runup_output > _rotor_ramp_output ) {
_rotor_runup_output = _rotor_ramp_output ;
2015-08-07 20:52:22 -03:00
}
2015-08-07 22:14:45 -03:00
} else {
2016-02-03 04:53:34 -04:00
_rotor_runup_output - = runup_increment ;
2015-08-11 15:31:20 -03:00
if ( _rotor_runup_output < _rotor_ramp_output ) {
_rotor_runup_output = _rotor_ramp_output ;
2015-08-07 20:52:22 -03:00
}
2015-08-07 22:14:45 -03:00
}
2015-07-21 07:07:54 -03:00
2015-08-10 18:24:57 -03:00
// update run-up complete flag
2015-08-11 15:31:20 -03:00
// if control mode is disabled, then run-up complete always returns true
if ( _control_mode = = ROTOR_CONTROL_MODE_DISABLED ) {
2015-08-07 22:14:45 -03:00
_runup_complete = true ;
2015-08-11 15:31:20 -03:00
return ;
2015-08-07 22:14:45 -03:00
}
2015-08-11 15:31:20 -03:00
// 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
2019-08-07 23:52:17 -03:00
if ( _runup_complete & & ( get_rotor_speed ( ) < = get_critical_speed ( ) ) ) {
2015-08-07 22:14:45 -03:00
_runup_complete = false ;
2015-08-07 20:52:22 -03:00
}
2021-12-05 19:57:05 -04:00
// if rotor estimated speed is zero, then spooldown has been completed
if ( get_rotor_speed ( ) < = 0.0f ) { _spooldown_complete = true ; } else { _spooldown_complete = false ; }
2015-07-21 07:07:54 -03:00
}
2015-08-11 15:31:20 -03:00
// get_rotor_speed - gets rotor speed either as an estimate, or (ToDO) a measured value
2016-02-03 04:53:34 -04:00
float AP_MotorsHeli_RSC : : get_rotor_speed ( ) const
2015-08-11 15:31:20 -03:00
{
// if no actual measured rotor speed is available, estimate speed based on rotor runup scalar.
2016-02-03 04:53:34 -04:00
return _rotor_runup_output ;
2015-08-11 15:31:20 -03:00
}
2015-07-21 07:07:54 -03:00
// write_rsc - outputs pwm onto output rsc channel
2016-02-03 04:53:34 -04:00
// servo_out parameter is of the range 0 ~ 1
void AP_MotorsHeli_RSC : : write_rsc ( float servo_out )
2015-07-21 07:07:54 -03:00
{
2015-08-11 15:31:20 -03:00
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 {
2021-09-18 15:06:41 -03:00
SRV_Channels : : set_output_scaled ( _aux_fn , servo_out * 1000 ) ;
2015-08-11 15:31:20 -03:00
}
2015-08-28 03:20:42 -03:00
}
2018-03-23 01:09:14 -03:00
2021-01-21 07:02:11 -04:00
// calculate_throttlecurve - uses throttle curve and collective input to determine throttle setting
float AP_MotorsHeli_RSC : : calculate_throttlecurve ( float collective_in )
2018-03-23 01:09:14 -03:00
{
const float inpt = collective_in * 4.0f + 1.0f ;
uint8_t idx = constrain_int16 ( int8_t ( collective_in * 4 ) , 0 , 3 ) ;
const float a = inpt - ( idx + 1.0f ) ;
const float b = ( idx + 1.0f ) - inpt + 1.0f ;
float throttle = _thrcrv_poly [ idx ] [ 0 ] * a + _thrcrv_poly [ idx ] [ 1 ] * b + _thrcrv_poly [ idx ] [ 2 ] * ( powf ( a , 3.0f ) - a ) / 6.0f + _thrcrv_poly [ idx ] [ 3 ] * ( powf ( b , 3.0f ) - b ) / 6.0f ;
throttle = constrain_float ( throttle , 0.0f , 1.0f ) ;
return throttle ;
}
2021-01-21 07:02:11 -04:00
// autothrottle_run - calculate throttle output for governor controlled throttle
void AP_MotorsHeli_RSC : : autothrottle_run ( )
{
float throttlecurve = calculate_throttlecurve ( _collective_in ) ;
2021-11-11 13:09:26 -04:00
float const torque_ref_error_rpm = 2.0f ;
// if the desired governor RPM is zero, use the throttle curve only and exit
if ( _governor_rpm = = 0 ) {
_control_output = get_idle_output ( ) + ( _rotor_ramp_output * ( throttlecurve - get_idle_output ( ) ) ) ;
return ;
}
2021-02-07 14:30:05 -04:00
2021-02-06 00:54:43 -04:00
// autothrottle main power loop with governor
2021-01-21 07:02:11 -04:00
if ( _governor_engage & & ! _governor_fault ) {
2021-02-06 00:54:43 -04:00
// calculate droop - difference between actual and desired speed
2021-11-11 13:09:26 -04:00
float governor_droop = ( ( float ) _governor_rpm - _rotor_rpm ) * _governor_droop_response * 0.0001f ;
_governor_output = governor_droop + ( ( throttlecurve - _governor_torque_reference ) * _governor_ff * 0.01 ) ;
if ( _rotor_rpm < ( ( float ) _governor_rpm - torque_ref_error_rpm ) ) {
2021-02-06 00:54:43 -04:00
_governor_torque_reference + = get_governor_compensator ( ) ; // torque compensator
2021-11-11 13:09:26 -04:00
} else if ( _rotor_rpm > ( ( float ) _governor_rpm + torque_ref_error_rpm ) ) {
2021-01-21 07:02:11 -04:00
_governor_torque_reference - = get_governor_compensator ( ) ;
}
2021-11-11 13:09:26 -04:00
// throttle output uses droop + torque compensation to maintain proper rotor speed
_control_output = constrain_float ( ( _governor_torque_reference + _governor_output ) , ( get_idle_output ( ) * 1.5f ) , 1.0f ) ;
// governor and speed sensor fault detection - must maintain RPM within governor range
2021-02-06 00:54:43 -04:00
// speed fault detector will allow a fault to persist for 200 contiguous governor updates
// this is failsafe for bad speed sensor or severely mis-adjusted governor
2021-11-11 13:09:26 -04:00
if ( ( _rotor_rpm < = ( _governor_rpm - _governor_range ) ) | | ( _rotor_rpm > = ( _governor_rpm + _governor_range ) ) ) {
_governor_fault_count + + ;
if ( _governor_fault_count > 200 ) {
2021-02-10 16:45:07 -04:00
governor_reset ( ) ;
2021-01-21 07:02:11 -04:00
_governor_fault = true ;
2021-11-11 13:09:26 -04:00
if ( _rotor_rpm > = ( _governor_rpm + _governor_range ) ) {
2021-02-06 00:54:43 -04:00
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Governor Fault: Rotor Overspeed " ) ;
} else {
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Governor Fault: Rotor Underspeed " ) ;
}
2021-01-21 07:02:11 -04:00
}
} else {
2021-11-11 13:09:26 -04:00
_governor_fault_count = 0 ; // reset fault count if the fault doesn't persist
2021-02-07 14:30:05 -04:00
}
2021-01-21 07:02:11 -04:00
} else if ( ! _governor_engage & & ! _governor_fault ) {
2021-11-11 13:09:26 -04:00
// if governor is not engaged and rotor is overspeeding by more than 2% due to misconfigured
// throttle curve or stuck throttle, set a fault and governor will not operate
if ( _rotor_rpm > ( _governor_rpm + _governor_range ) ) {
_governor_fault = true ;
governor_reset ( ) ;
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Governor Fault: Rotor Overspeed " ) ;
_governor_output = 0.0f ;
2021-02-06 00:54:43 -04:00
// torque rise limiter accelerates rotor to the reference speed
// this limits the max torque rise the governor could call for from the main power loop
2021-11-11 13:09:26 -04:00
} else if ( _rotor_rpm > = ( _governor_rpm * 0.5f ) ) {
2021-01-21 07:02:11 -04:00
float torque_limit = ( get_governor_torque ( ) * get_governor_torque ( ) ) ;
2021-11-11 13:09:26 -04:00
_governor_output = ( _rotor_rpm / ( float ) _governor_rpm ) * torque_limit ;
if ( _rotor_rpm > = ( ( float ) _governor_rpm - torque_ref_error_rpm ) ) {
2021-01-21 07:02:11 -04:00
_governor_engage = true ;
_autothrottle = true ;
2021-11-11 13:09:26 -04:00
gcs ( ) . send_text ( MAV_SEVERITY_NOTICE , " Governor Engaged " ) ;
2021-01-21 07:02:11 -04:00
}
} else {
2021-02-06 00:54:43 -04:00
// temporary use of throttle curve and ramp timer to accelerate rotor to governor min torque rise speed
2021-11-11 13:09:26 -04:00
_governor_output = 0.0f ;
2021-01-21 07:02:11 -04:00
}
2021-11-11 13:09:26 -04:00
_control_output = constrain_float ( get_idle_output ( ) + ( _rotor_ramp_output * ( throttlecurve + _governor_output - get_idle_output ( ) ) ) , 0.0f , 1.0f ) ;
_governor_torque_reference = _control_output ; // increment torque setting to be passed to main power loop
2021-01-21 07:02:11 -04:00
} else {
2021-02-06 00:54:43 -04:00
// failsafe - if governor has faulted use throttle curve
2021-02-10 16:45:07 -04:00
_control_output = get_idle_output ( ) + ( _rotor_ramp_output * ( throttlecurve - get_idle_output ( ) ) ) ;
2021-01-21 07:02:11 -04:00
}
}
2021-02-10 16:45:07 -04:00
// governor_reset - disengages governor and resets outputs
void AP_MotorsHeli_RSC : : governor_reset ( )
{
_governor_output = 0.0f ;
_governor_torque_reference = 0.0f ;
_governor_engage = false ;
2021-11-11 13:09:26 -04:00
_governor_fault_count = 0 ; // reset fault count when governor reset
2021-02-10 16:45:07 -04:00
}