Copter: Event Log rotor speed going below critical

This commit is contained in:
Robert Lefebvre 2015-06-18 19:39:58 -04:00 committed by Randy Mackay
parent 0c92565d23
commit ee6508d5a7
2 changed files with 3 additions and 0 deletions

View File

@ -314,6 +314,7 @@ enum FlipState {
#define DATA_MOTORS_INTERLOCK_DISABLED 56 #define DATA_MOTORS_INTERLOCK_DISABLED 56
#define DATA_MOTORS_INTERLOCK_ENABLED 57 #define DATA_MOTORS_INTERLOCK_ENABLED 57
#define DATA_ROTOR_RUNUP_COMPLETE 58 // Heli only #define DATA_ROTOR_RUNUP_COMPLETE 58 // Heli only
#define DATA_ROTOR_SPEED_BELOW_CRITICAL 59 // Heli only
// Centi-degrees to radians // Centi-degrees to radians
#define DEGX100 5729.57795f #define DEGX100 5729.57795f

View File

@ -160,6 +160,8 @@ void Copter::heli_update_rotor_speed_targets()
// when rotor_runup_complete changes to true, log event // when rotor_runup_complete changes to true, log event
if (!rotor_runup_complete_last && motors.rotor_runup_complete()){ if (!rotor_runup_complete_last && motors.rotor_runup_complete()){
Log_Write_Event(DATA_ROTOR_RUNUP_COMPLETE); Log_Write_Event(DATA_ROTOR_RUNUP_COMPLETE);
} else if (rotor_runup_complete_last && !motors.rotor_runup_complete()){
Log_Write_Event(DATA_ROTOR_SPEED_BELOW_CRITICAL);
} }
rotor_runup_complete_last = motors.rotor_runup_complete(); rotor_runup_complete_last = motors.rotor_runup_complete();
} }