Copter: Implementation of autorotation condition at RSC level

enables faster re-spool(user settable timer) after power engagement
This commit is contained in:
Ferruccio1984 2022-03-24 08:39:41 -07:00 committed by Bill Geyer
parent e935913f95
commit da4a2ec85d
3 changed files with 7 additions and 27 deletions

View File

@ -796,10 +796,8 @@ private:
float get_pilot_desired_rotor_speed() const;
void heli_update_rotor_speed_targets();
void heli_update_autorotation();
#if MODE_AUTOROTATE_ENABLED == ENABLED
void heli_set_autorotation(bool autotrotation);
#endif
void update_collective_low_flag(int16_t throttle_control);
// inertia.cpp
void read_inertia();

View File

@ -288,17 +288,14 @@
//////////////////////////////////////////////////////////////////////////////
// Autorotate - autonomous auto-rotation - helicopters only
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#if FRAME_CONFIG == HELI_FRAME
#if FRAME_CONFIG == HELI_FRAME
#ifndef MODE_AUTOROTATE_ENABLED
# define MODE_AUTOROTATE_ENABLED !HAL_MINIMIZE_FEATURES
#endif
#else
# define MODE_AUTOROTATE_ENABLED DISABLED
#endif
#else
# define MODE_AUTOROTATE_ENABLED DISABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Beacon support - support for local positioning systems

View File

@ -185,7 +185,7 @@ void Copter::heli_update_rotor_speed_targets()
// when rotor_runup_complete changes to true, log event
if (!rotor_runup_complete_last && motors->rotor_runup_complete()){
AP::logger().Write_Event(LogEvent::ROTOR_RUNUP_COMPLETE);
} else if (rotor_runup_complete_last && !motors->rotor_runup_complete()){
} else if (rotor_runup_complete_last && !motors->rotor_runup_complete() && !heli_flags.in_autorotation){
AP::logger().Write_Event(LogEvent::ROTOR_SPEED_BELOW_CRITICAL);
}
rotor_runup_complete_last = motors->rotor_runup_complete();
@ -205,31 +205,16 @@ void Copter::heli_update_autorotation()
}
// set flag to facilitate both auto and manual autorotations
heli_flags.in_autorotation = true;
} else {
heli_flags.in_autorotation = false;
}
// sets autorotation flags through out libraries
heli_set_autorotation(heli_flags.in_autorotation);
if (!ap.land_complete && g2.arot.is_enable()) {
motors->set_in_autorotation(heli_flags.in_autorotation);
motors->set_enable_bailout(true);
} else {
heli_flags.in_autorotation = false;
motors->set_in_autorotation(heli_flags.in_autorotation);
motors->set_enable_bailout(false);
}
#else
heli_flags.in_autorotation = false;
motors->set_enable_bailout(false);
#endif
}
#if MODE_AUTOROTATE_ENABLED == ENABLED
// heli_set_autorotation - set the autorotation flag throughout libraries
void Copter::heli_set_autorotation(bool autorotation)
{
motors->set_in_autorotation(autorotation);
}
#endif
// update collective low flag. Use a debounce time of 400 milliseconds.
void Copter::update_collective_low_flag(int16_t throttle_control)
{