From 975ad608ebd051a7dbfd300642e0dbb2db9cfd37 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 23 Feb 2018 11:06:04 +1100 Subject: [PATCH] Copter: honour defines for optional feature's log messages --- ArduCopter/Log.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index a3ee099e0f..84eebfc445 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -546,8 +546,10 @@ const struct LogStructure Copter::log_structure[] = { #endif { LOG_PARAMTUNE_MSG, sizeof(log_ParameterTuning), "PTUN", "QBfHHH", "TimeUS,Param,TunVal,CtrlIn,TunLo,TunHi", "s-----", "F-----" }, +#if OPTFLOW == ENABLED { LOG_OPTFLOW_MSG, sizeof(log_Optflow), "OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY", "s-EEEE", "F-0000" }, +#endif { LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning), "CTUN", "Qffffffeccfhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00BBBBBB" }, { LOG_MOTBATT_MSG, sizeof(log_MotBatt), @@ -566,10 +568,14 @@ const struct LogStructure Copter::log_structure[] = { "DFLT", "QBf", "TimeUS,Id,Value", "s--", "F--" }, { LOG_ERROR_MSG, sizeof(log_Error), "ERR", "QBB", "TimeUS,Subsys,ECode", "s--", "F--" }, +#if FRAME_CONFIG == HELI_FRAME { LOG_HELI_MSG, sizeof(log_Heli), "HELI", "Qff", "TimeUS,DRRPM,ERRPM", "s--", "F--" }, +#endif +#if PRECISION_LANDING == ENABLED { LOG_PRECLAND_MSG, sizeof(log_Precland), "PL", "QBBffff", "TimeUS,Heal,TAcq,pX,pY,vX,vY", "s--ddmm","F--00BB" }, +#endif { LOG_GUIDEDTARGET_MSG, sizeof(log_GuidedTarget), "GUID", "QBffffff", "TimeUS,Type,pX,pY,pZ,vX,vY,vZ", "s-mmmnnn", "F-000000" }, #if MODE_THROW_ENABLED == ENABLED