mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: Heli: add helper to log runup event
This commit is contained in:
parent
6c44869c82
commit
1766bfe45a
|
@ -17,6 +17,7 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_MotorsHeli.h"
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
@ -598,3 +599,16 @@ AP_MotorsHeli_RSC::RotorControlState AP_MotorsHeli::get_rotor_control_state() co
|
|||
// Should be unreachable, but needed to keep the compiler happy
|
||||
return AP_MotorsHeli_RSC::RotorControlState::STOP;
|
||||
}
|
||||
|
||||
// Update _heliflags.rotor_runup_complete value writing log event on state change
|
||||
void AP_MotorsHeli::set_rotor_runup_complete(bool new_value)
|
||||
{
|
||||
#if HAL_LOGGING_ENABLED
|
||||
if (!_heliflags.rotor_runup_complete && new_value) {
|
||||
LOGGER_WRITE_EVENT(LogEvent::ROTOR_RUNUP_COMPLETE);
|
||||
} else if (_heliflags.rotor_runup_complete && !new_value && !_heliflags.in_autorotation) {
|
||||
LOGGER_WRITE_EVENT(LogEvent::ROTOR_SPEED_BELOW_CRITICAL);
|
||||
}
|
||||
#endif
|
||||
_heliflags.rotor_runup_complete = new_value;
|
||||
}
|
||||
|
|
|
@ -233,6 +233,9 @@ protected:
|
|||
// update turbine start flag
|
||||
void update_turbine_start();
|
||||
|
||||
// Update _heliflags.rotor_runup_complete value writing log event on state change
|
||||
void set_rotor_runup_complete(bool new_value);
|
||||
|
||||
// enum values for HOVER_LEARN parameter
|
||||
enum HoverLearn {
|
||||
HOVER_LEARN_DISABLED = 0,
|
||||
|
|
|
@ -374,7 +374,8 @@ void AP_MotorsHeli_Dual::update_motor_control(AP_MotorsHeli_RSC::RotorControlSta
|
|||
}
|
||||
|
||||
// Check if rotors are run-up
|
||||
_heliflags.rotor_runup_complete = _main_rotor.is_runup_complete();
|
||||
set_rotor_runup_complete(_main_rotor.is_runup_complete());
|
||||
|
||||
// Check if rotors are spooled down
|
||||
_heliflags.rotor_spooldown_complete = _main_rotor.is_spooldown_complete();
|
||||
}
|
||||
|
|
|
@ -159,7 +159,8 @@ void AP_MotorsHeli_Quad::update_motor_control(AP_MotorsHeli_RSC::RotorControlSta
|
|||
}
|
||||
|
||||
// Check if rotors are run-up
|
||||
_heliflags.rotor_runup_complete = _main_rotor.is_runup_complete();
|
||||
set_rotor_runup_complete(_main_rotor.is_runup_complete());
|
||||
|
||||
// Check if rotors are spooled down
|
||||
_heliflags.rotor_spooldown_complete = _main_rotor.is_spooldown_complete();
|
||||
}
|
||||
|
|
|
@ -362,7 +362,7 @@ void AP_MotorsHeli_Single::update_motor_control(AP_MotorsHeli_RSC::RotorControlS
|
|||
}
|
||||
|
||||
// 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() );
|
||||
set_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