mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: tradheli support for turbine start
This commit is contained in:
parent
6b962ae48b
commit
3a67b17142
|
@ -67,6 +67,9 @@ public:
|
||||||
// parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check
|
// parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check
|
||||||
virtual bool parameter_check(bool display_msg) const;
|
virtual bool parameter_check(bool display_msg) const;
|
||||||
|
|
||||||
|
//set turbine start flag on to initiaize starting sequence
|
||||||
|
void set_turb_start(bool turb_start) { _heliflags.start_engine = turb_start; }
|
||||||
|
|
||||||
// has_flybar - returns true if we have a mechical flybar
|
// has_flybar - returns true if we have a mechical flybar
|
||||||
virtual bool has_flybar() const { return AP_MOTORS_HELI_NOFLYBAR; }
|
virtual bool has_flybar() const { return AP_MOTORS_HELI_NOFLYBAR; }
|
||||||
|
|
||||||
|
@ -243,6 +246,7 @@ protected:
|
||||||
uint8_t takeoff_collective : 1; // true if collective is above 30% between H_COL_MID and H_COL_MAX
|
uint8_t takeoff_collective : 1; // true if collective is above 30% between H_COL_MID and H_COL_MAX
|
||||||
uint8_t below_land_min_coll : 1; // true if collective is below H_COL_LAND_MIN
|
uint8_t below_land_min_coll : 1; // true if collective is below H_COL_LAND_MIN
|
||||||
uint8_t rotor_spooldown_complete : 1; // true if the rotors have spooled down completely
|
uint8_t rotor_spooldown_complete : 1; // true if the rotors have spooled down completely
|
||||||
|
uint8_t start_engine : 1;
|
||||||
} _heliflags;
|
} _heliflags;
|
||||||
|
|
||||||
// parameters
|
// parameters
|
||||||
|
|
|
@ -15,6 +15,10 @@
|
||||||
|
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
<<<<<<< HEAD
|
||||||
|
=======
|
||||||
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
>>>>>>> 5faab0ee08... AP_Motors: tradheli support for turbine start
|
||||||
#include "AP_MotorsHeli_RSC.h"
|
#include "AP_MotorsHeli_RSC.h"
|
||||||
#include <AP_RPM/AP_RPM.h>
|
#include <AP_RPM/AP_RPM.h>
|
||||||
|
|
||||||
|
@ -268,6 +272,8 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
|
||||||
governor_reset();
|
governor_reset();
|
||||||
_autothrottle = false;
|
_autothrottle = false;
|
||||||
_governor_fault = false;
|
_governor_fault = false;
|
||||||
|
//turbine start flag on
|
||||||
|
_starting = true;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ROTOR_CONTROL_IDLE:
|
case ROTOR_CONTROL_IDLE:
|
||||||
|
@ -283,6 +289,15 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
|
||||||
_control_output = constrain_float( _rsc_arot_bailout_pct/100.0f , 0.0f, 0.4f);
|
_control_output = constrain_float( _rsc_arot_bailout_pct/100.0f , 0.0f, 0.4f);
|
||||||
} else {
|
} else {
|
||||||
// set rotor control speed to idle speed parameter, this happens instantly and ignores ramping
|
// set rotor control speed to idle speed parameter, this happens instantly and ignores ramping
|
||||||
|
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) {
|
if (_cooldown_time > 0) {
|
||||||
_control_output = get_idle_output() * 1.5f;
|
_control_output = get_idle_output() * 1.5f;
|
||||||
_fast_idle_timer += dt;
|
_fast_idle_timer += dt;
|
||||||
|
@ -293,6 +308,7 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
|
||||||
_control_output = get_idle_output();
|
_control_output = get_idle_output();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ROTOR_CONTROL_ACTIVE:
|
case ROTOR_CONTROL_ACTIVE:
|
||||||
|
|
|
@ -113,6 +113,9 @@ public:
|
||||||
// set the throttle percentage to be sent to external governor to signal that autorotation bailout ramp should be used within this instance of Heli_RSC
|
// set the throttle percentage to be sent to external governor to signal that autorotation bailout ramp should be used within this instance of Heli_RSC
|
||||||
void set_ext_gov_arot_bail(int16_t pct) { _rsc_arot_bailout_pct = pct; }
|
void set_ext_gov_arot_bail(int16_t pct) { _rsc_arot_bailout_pct = pct; }
|
||||||
|
|
||||||
|
// turbine start initialize sequence
|
||||||
|
void set_turbine_start(bool turbine_start) {_turbine_start = (bool)turbine_start; }
|
||||||
|
|
||||||
// output - update value to send to ESC/Servo
|
// output - update value to send to ESC/Servo
|
||||||
void output(RotorControlState state);
|
void output(RotorControlState state);
|
||||||
|
|
||||||
|
@ -145,6 +148,8 @@ private:
|
||||||
float _thrcrv_poly[4][4]; // spline polynomials for throttle curve interpolation
|
float _thrcrv_poly[4][4]; // spline polynomials for throttle curve interpolation
|
||||||
float _collective_in; // collective in for throttle curve calculation, range 0-1.0f
|
float _collective_in; // collective in for throttle curve calculation, range 0-1.0f
|
||||||
float _rotor_rpm; // rotor rpm from speed sensor for governor
|
float _rotor_rpm; // rotor rpm from speed sensor for governor
|
||||||
|
bool _turbine_start;
|
||||||
|
bool _starting;
|
||||||
float _governor_output; // governor output for rotor speed control
|
float _governor_output; // governor output for rotor speed control
|
||||||
bool _governor_engage; // RSC governor status flag
|
bool _governor_engage; // RSC governor status flag
|
||||||
bool _autothrottle; // autothrottle status flag
|
bool _autothrottle; // autothrottle status flag
|
||||||
|
|
|
@ -292,6 +292,12 @@ void AP_MotorsHeli_Single::calculate_armed_scalars()
|
||||||
_main_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
|
_main_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
|
||||||
_tail_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
|
_tail_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
|
||||||
|
|
||||||
|
if (_heliflags.start_engine) {
|
||||||
|
_main_rotor.set_turbine_start(true);
|
||||||
|
} else {
|
||||||
|
_main_rotor.set_turbine_start(false);
|
||||||
|
}
|
||||||
|
|
||||||
// allow use of external governor autorotation bailout
|
// allow use of external governor autorotation bailout
|
||||||
if (_main_rotor._ext_gov_arot_pct.get() > 0) {
|
if (_main_rotor._ext_gov_arot_pct.get() > 0) {
|
||||||
// RSC only needs to know that the vehicle is in an autorotation if using the bailout window on an external governor
|
// RSC only needs to know that the vehicle is in an autorotation if using the bailout window on an external governor
|
||||||
|
|
Loading…
Reference in New Issue