From ee6508d5a7fa2ebbec60461b60f7548e14167e24 Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Thu, 18 Jun 2015 19:39:58 -0400 Subject: [PATCH] Copter: Event Log rotor speed going below critical --- ArduCopter/defines.h | 1 + ArduCopter/heli.cpp | 2 ++ 2 files changed, 3 insertions(+) diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 17e9b687fb..2feb75b663 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -314,6 +314,7 @@ enum FlipState { #define DATA_MOTORS_INTERLOCK_DISABLED 56 #define DATA_MOTORS_INTERLOCK_ENABLED 57 #define DATA_ROTOR_RUNUP_COMPLETE 58 // Heli only +#define DATA_ROTOR_SPEED_BELOW_CRITICAL 59 // Heli only // Centi-degrees to radians #define DEGX100 5729.57795f diff --git a/ArduCopter/heli.cpp b/ArduCopter/heli.cpp index 804e5f8f31..94e114da2d 100644 --- a/ArduCopter/heli.cpp +++ b/ArduCopter/heli.cpp @@ -160,6 +160,8 @@ 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()){ 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(); }