AP_Motors: move turbine start to update_turbine_start and style cleanup

This commit is contained in:
Bill Geyer 2022-02-20 22:59:18 -05:00 committed by Randy Mackay
parent 2fa54f0df4
commit f7b420f131
5 changed files with 43 additions and 35 deletions

View File

@ -232,6 +232,8 @@ void AP_MotorsHeli::output()
output_disarmed(); output_disarmed();
} }
update_turbine_start();
output_to_motors(); output_to_motors();
}; };
@ -597,3 +599,13 @@ bool AP_MotorsHeli::heli_option(HeliOption opt) const
return (_heli_options & (uint8_t)opt); return (_heli_options & (uint8_t)opt);
} }
// updates the turbine start flag
void AP_MotorsHeli::update_turbine_start()
{
if (_heliflags.start_engine) {
_main_rotor.set_turbine_start(true);
} else {
_main_rotor.set_turbine_start(false);
}
}

View File

@ -67,8 +67,8 @@ 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 //set turbine start flag on to initiaize starting sequence
void set_turb_start(bool turb_start) { _heliflags.start_engine = turb_start; } 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; }
@ -225,6 +225,9 @@ protected:
const char* _get_frame_string() const override { return "HELI"; } const char* _get_frame_string() const override { return "HELI"; }
// update turbine start flag
void update_turbine_start();
// enum values for HOVER_LEARN parameter // enum values for HOVER_LEARN parameter
enum HoverLearn { enum HoverLearn {
HOVER_LEARN_DISABLED = 0, HOVER_LEARN_DISABLED = 0,
@ -246,7 +249,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; uint8_t start_engine : 1; // true if turbine start RC option is initiated
} _heliflags; } _heliflags;
// parameters // parameters

View File

@ -15,10 +15,7 @@
#include <stdlib.h> #include <stdlib.h>
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
<<<<<<< HEAD
=======
#include <GCS_MAVLink/GCS.h> #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>
@ -272,8 +269,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 //turbine start flag on
_starting = true; _starting = true;
break; break;
case ROTOR_CONTROL_IDLE: case ROTOR_CONTROL_IDLE:
@ -289,25 +286,24 @@ 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 ) { if (_turbine_start && _starting == true ) {
_control_output += 0.001f; _control_output += 0.001f;
if (_control_output >= 1.0f) {
if(_control_output >= 1.0f) { _control_output = get_idle_output();
_control_output = get_idle_output(); gcs().send_text(MAV_SEVERITY_INFO, "Turbine startup");
gcs().send_text(MAV_SEVERITY_INFO, "Turbine startup"); _starting = false;
_starting = false; }
} } else{
} 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; if (_fast_idle_timer > (float)_cooldown_time) {
if (_fast_idle_timer > (float)_cooldown_time) { _fast_idle_timer = 0.0f;
_fast_idle_timer = 0.0f; }
} else {
_control_output = get_idle_output();
} }
} else {
_control_output = get_idle_output();
} }
}
} }
break; break;
@ -315,6 +311,9 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
// set main rotor ramp to increase to full speed // set main rotor ramp to increase to full speed
update_rotor_ramp(1.0f, dt); update_rotor_ramp(1.0f, dt);
// 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;
if ((_control_mode == ROTOR_CONTROL_MODE_PASSTHROUGH) || (_control_mode == ROTOR_CONTROL_MODE_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 // 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())); _control_output = get_idle_output() + (_rotor_ramp_output * (_desired_speed - get_idle_output()));

View File

@ -113,8 +113,8 @@ 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 // turbine start initialize sequence
void set_turbine_start(bool turbine_start) {_turbine_start = (bool)turbine_start; } void set_turbine_start(bool turbine_start) {_turbine_start = 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);
@ -148,8 +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 _turbine_start; // initiates starting sequence
bool _starting; bool _starting; // tracks if starting sequence has been used
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

View File

@ -291,12 +291,6 @@ void AP_MotorsHeli_Single::calculate_armed_scalars()
// set bailout ramp time // set bailout ramp time
_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) {