mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_MotorsHeli: move rotor_speed_above_critical to RSC so that it is actually used
This commit is contained in:
parent
d3f2309eac
commit
4b2c1368bd
@ -102,9 +102,6 @@ public:
|
||||
// return true if the main rotor is up to speed
|
||||
bool rotor_runup_complete() const { return _heliflags.rotor_runup_complete; }
|
||||
|
||||
// rotor_speed_above_critical - return true if rotor speed is above that critical for flight
|
||||
virtual bool rotor_speed_above_critical() const = 0;
|
||||
|
||||
//get rotor governor output
|
||||
virtual float get_governor_output() const = 0;
|
||||
|
||||
|
@ -61,9 +61,6 @@ public:
|
||||
// get_desired_rotor_speed - gets target rotor speed as a number from 0 ~ 1000
|
||||
float get_desired_rotor_speed() const override { return _main_rotor.get_rotor_speed(); }
|
||||
|
||||
// rotor_speed_above_critical - return true if rotor speed is above that critical for flight
|
||||
bool rotor_speed_above_critical() const override { return _main_rotor.get_rotor_speed() > _main_rotor.get_critical_speed(); }
|
||||
|
||||
// get_governor_output
|
||||
float get_governor_output() const override { return _main_rotor.get_governor_output(); }
|
||||
|
||||
|
@ -40,9 +40,6 @@ public:
|
||||
// get_desired_rotor_speed - gets target rotor speed as a number from 0 ~ 1000
|
||||
float get_desired_rotor_speed() const override { return _main_rotor.get_rotor_speed(); }
|
||||
|
||||
// rotor_speed_above_critical - return true if rotor speed is above that critical for flight
|
||||
bool rotor_speed_above_critical() const override { return _main_rotor.get_rotor_speed() > _main_rotor.get_critical_speed(); }
|
||||
|
||||
// get_governor_output
|
||||
float get_governor_output() const override { return _main_rotor.get_governor_output(); }
|
||||
|
||||
|
@ -461,7 +461,7 @@ void AP_MotorsHeli_RSC::update_rotor_runup(float dt)
|
||||
}
|
||||
// if in autorotation, don't let rotor_runup_output go less than critical speed to keep
|
||||
// runup complete flag from being set to false
|
||||
if (_autorotating && _rotor_runup_output < get_critical_speed()) {
|
||||
if (_autorotating && !rotor_speed_above_critical()) {
|
||||
_rotor_runup_output = get_critical_speed();
|
||||
}
|
||||
|
||||
@ -479,7 +479,7 @@ void AP_MotorsHeli_RSC::update_rotor_runup(float dt)
|
||||
}
|
||||
// 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
|
||||
if (_runup_complete && (get_rotor_speed() < get_critical_speed())) {
|
||||
if (_runup_complete && !rotor_speed_above_critical()) {
|
||||
_runup_complete = false;
|
||||
}
|
||||
// if rotor estimated speed is zero, then spooldown has been completed
|
||||
|
@ -128,6 +128,9 @@ public:
|
||||
// Return mask of output channels which the RSC is outputting on
|
||||
uint32_t get_output_mask() const;
|
||||
|
||||
// rotor_speed_above_critical - return true if rotor speed is above that critical for flight
|
||||
bool rotor_speed_above_critical(void) const { return get_rotor_speed() > get_critical_speed(); }
|
||||
|
||||
// var_info for holding Parameter information
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
@ -61,9 +61,6 @@ public:
|
||||
// get_desired_rotor_speed - gets target rotor speed as a number from 0 ~ 1
|
||||
float get_desired_rotor_speed() const override { return _main_rotor.get_desired_speed(); }
|
||||
|
||||
// rotor_speed_above_critical - return true if rotor speed is above that critical for flight
|
||||
bool rotor_speed_above_critical() const override { return _main_rotor.get_rotor_speed() > _main_rotor.get_critical_speed(); }
|
||||
|
||||
// get_governor_output
|
||||
float get_governor_output() const override { return _main_rotor.get_governor_output(); }
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user