mirror of https://github.com/ArduPilot/ardupilot
Copter: make code work for manual autorotations outside SITL
This commit is contained in:
parent
da4a2ec85d
commit
562050a800
|
@ -288,12 +288,16 @@
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Autorotate - autonomous auto-rotation - helicopters only
|
// Autorotate - autonomous auto-rotation - helicopters only
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
#ifndef MODE_AUTOROTATE_ENABLED
|
#ifndef MODE_AUTOROTATE_ENABLED
|
||||||
# define MODE_AUTOROTATE_ENABLED !HAL_MINIMIZE_FEATURES
|
# define MODE_AUTOROTATE_ENABLED !HAL_MINIMIZE_FEATURES
|
||||||
#endif
|
#endif
|
||||||
#else
|
#else
|
||||||
# define MODE_AUTOROTATE_ENABLED DISABLED
|
# define MODE_AUTOROTATE_ENABLED DISABLED
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
# define MODE_AUTOROTATE_ENABLED DISABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
|
@ -196,23 +196,32 @@ void Copter::heli_update_rotor_speed_targets()
|
||||||
// to autorotation flight mode if manual collective is not being used.
|
// to autorotation flight mode if manual collective is not being used.
|
||||||
void Copter::heli_update_autorotation()
|
void Copter::heli_update_autorotation()
|
||||||
{
|
{
|
||||||
#if MODE_AUTOROTATE_ENABLED == ENABLED
|
|
||||||
// check if flying and interlock disengaged
|
// check if flying and interlock disengaged
|
||||||
if (!ap.land_complete && !motors->get_interlock() && g2.arot.is_enable()) {
|
if (!ap.land_complete && !motors->get_interlock()) {
|
||||||
if (!flightmode->has_manual_throttle()) {
|
#if MODE_AUTOROTATE_ENABLED == ENABLED
|
||||||
// set autonomous autorotation flight mode
|
if (g2.arot.is_enable()) {
|
||||||
set_mode(Mode::Number::AUTOROTATE, ModeReason::AUTOROTATION_START);
|
if (!flightmode->has_manual_throttle()) {
|
||||||
|
// set autonomous autorotation flight mode
|
||||||
|
set_mode(Mode::Number::AUTOROTATE, ModeReason::AUTOROTATION_START);
|
||||||
|
}
|
||||||
|
// set flag to facilitate both auto and manual autorotations
|
||||||
|
heli_flags.in_autorotation = true;
|
||||||
|
motors->set_in_autorotation(heli_flags.in_autorotation);
|
||||||
|
motors->set_enable_bailout(true);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
if (flightmode->has_manual_throttle() && motors->arot_man_enabled()) {
|
||||||
|
// set flag to facilitate both auto and manual autorotations
|
||||||
|
heli_flags.in_autorotation = true;
|
||||||
|
motors->set_in_autorotation(heli_flags.in_autorotation);
|
||||||
|
motors->set_enable_bailout(true);
|
||||||
}
|
}
|
||||||
// set flag to facilitate both auto and manual autorotations
|
|
||||||
heli_flags.in_autorotation = true;
|
|
||||||
motors->set_in_autorotation(heli_flags.in_autorotation);
|
|
||||||
motors->set_enable_bailout(true);
|
|
||||||
} else {
|
} else {
|
||||||
heli_flags.in_autorotation = false;
|
heli_flags.in_autorotation = false;
|
||||||
motors->set_in_autorotation(heli_flags.in_autorotation);
|
motors->set_in_autorotation(heli_flags.in_autorotation);
|
||||||
motors->set_enable_bailout(false);
|
motors->set_enable_bailout(false);
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// update collective low flag. Use a debounce time of 400 milliseconds.
|
// update collective low flag. Use a debounce time of 400 milliseconds.
|
||||||
|
|
Loading…
Reference in New Issue