mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: add spool down complete flag
This commit is contained in:
parent
f8cde71389
commit
814c52fbb7
|
@ -414,7 +414,7 @@ void AP_MotorsHeli::output_logic()
|
|||
_spool_state = SpoolState::SPOOLING_UP;
|
||||
break;
|
||||
}
|
||||
if (!rotor_speed_above_critical()){
|
||||
if (_heliflags.rotor_spooldown_complete){
|
||||
_spool_state = SpoolState::GROUND_IDLE;
|
||||
}
|
||||
break;
|
||||
|
|
|
@ -247,6 +247,7 @@ protected:
|
|||
uint8_t land_complete : 1; // true if aircraft is landed
|
||||
uint8_t takeoff_collective : 1; // true if collective is above 30% between H_COL_MID and H_COL_MAX
|
||||
uint8_t below_mid_collective : 1; // true if collective is below H_COL_MID
|
||||
uint8_t rotor_spooldown_complete : 1; // true if the rotors have spooled down completely
|
||||
} _heliflags;
|
||||
|
||||
// parameters
|
||||
|
|
|
@ -514,6 +514,8 @@ void AP_MotorsHeli_Dual::update_motor_control(RotorControlState state)
|
|||
|
||||
// Check if rotors are run-up
|
||||
_heliflags.rotor_runup_complete = _main_rotor.is_runup_complete();
|
||||
// Check if rotors are spooled down
|
||||
_heliflags.rotor_spooldown_complete = _main_rotor.is_spooldown_complete();
|
||||
}
|
||||
|
||||
//
|
||||
|
|
|
@ -210,6 +210,8 @@ void AP_MotorsHeli_Quad::update_motor_control(RotorControlState state)
|
|||
|
||||
// Check if rotors are run-up
|
||||
_heliflags.rotor_runup_complete = _main_rotor.is_runup_complete();
|
||||
// Check if rotors are spooled down
|
||||
_heliflags.rotor_spooldown_complete = _main_rotor.is_spooldown_complete();
|
||||
}
|
||||
|
||||
//
|
||||
|
|
|
@ -382,6 +382,8 @@ void AP_MotorsHeli_RSC::update_rotor_runup(float dt)
|
|||
if (_runup_complete && (get_rotor_speed() <= get_critical_speed())) {
|
||||
_runup_complete = false;
|
||||
}
|
||||
// if rotor estimated speed is zero, then spooldown has been completed
|
||||
if (get_rotor_speed() <= 0.0f) { _spooldown_complete = true; } else { _spooldown_complete = false; }
|
||||
}
|
||||
|
||||
// get_rotor_speed - gets rotor speed either as an estimate, or (ToDO) a measured value
|
||||
|
|
|
@ -105,6 +105,9 @@ public:
|
|||
// is_runup_complete
|
||||
bool is_runup_complete() const { return _runup_complete; }
|
||||
|
||||
// is_spooldown_complete
|
||||
bool is_spooldown_complete() const { return _spooldown_complete; }
|
||||
|
||||
// set_ramp_time
|
||||
void set_ramp_time(int8_t ramp_time) { _ramp_time = ramp_time; }
|
||||
|
||||
|
@ -163,6 +166,7 @@ private:
|
|||
bool _use_bailout_ramp; // true if allowing RSC to quickly ramp up engine
|
||||
bool _in_autorotation; // true if vehicle is currently in an autorotation
|
||||
int16_t _rsc_arot_bailout_pct; // the throttle percentage sent to the external governor to signal that autorotation bailout ramp should be used
|
||||
bool _spooldown_complete; // flag for determining if spooldown is complete
|
||||
|
||||
// update_rotor_ramp - slews rotor output scalar between 0 and 1, outputs float scalar to _rotor_ramp_output
|
||||
void update_rotor_ramp(float rotor_ramp_input, float dt);
|
||||
|
|
|
@ -393,6 +393,9 @@ void AP_MotorsHeli_Single::update_motor_control(RotorControlState state)
|
|||
|
||||
// Check if both rotors are run-up, tail rotor controller always returns true if not enabled
|
||||
_heliflags.rotor_runup_complete = ( _main_rotor.is_runup_complete() && _tail_rotor.is_runup_complete() );
|
||||
|
||||
// Check if both rotors are spooled down, tail rotor controller always returns true if not enabled
|
||||
_heliflags.rotor_spooldown_complete = ( _main_rotor.is_spooldown_complete() );
|
||||
}
|
||||
|
||||
//
|
||||
|
|
Loading…
Reference in New Issue