From fd87f28a07aa4a3d248201c956311ce58172bdfd Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 27 Jun 2014 10:28:21 +1000 Subject: [PATCH] DataFlash: save some flash space on APM2 don't include log message headers that are not used on APM2 --- libraries/DataFlash/DataFlash.h | 38 +++++++++++++++++++++------------ libraries/DataFlash/LogFile.cpp | 2 ++ 2 files changed, 26 insertions(+), 14 deletions(-) diff --git a/libraries/DataFlash/DataFlash.h b/libraries/DataFlash/DataFlash.h index aa3d229d16..769fa9e1da 100644 --- a/libraries/DataFlash/DataFlash.h +++ b/libraries/DataFlash/DataFlash.h @@ -368,21 +368,16 @@ struct PACKED log_Camera { uint16_t yaw; }; -#define LOG_COMMON_STRUCTURES \ +// messages for all boards +#define LOG_BASE_STRUCTURES \ { LOG_FORMAT_MSG, sizeof(log_Format), \ "FMT", "BBnNZ", "Type,Length,Name,Format,Columns" }, \ { LOG_PARAMETER_MSG, sizeof(log_Parameter), \ "PARM", "Nf", "Name,Value" }, \ { LOG_GPS_MSG, sizeof(log_GPS), \ "GPS", "BIHBcLLeeEefI", "Status,TimeMS,Week,NSats,HDop,Lat,Lng,RelAlt,Alt,Spd,GCrs,VZ,T" }, \ - { LOG_GPS2_MSG, sizeof(log_GPS2), \ - "GPS2", "BIHBcLLeEefIBI", "Status,TimeMS,Week,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,T,DSc,DAg" }, \ { LOG_IMU_MSG, sizeof(log_IMU), \ "IMU", "Iffffff", "TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ" }, \ - { LOG_IMU2_MSG, sizeof(log_IMU), \ - "IMU2", "Iffffff", "TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ" }, \ - { LOG_IMU3_MSG, sizeof(log_IMU), \ - "IMU3", "Iffffff", "TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ" }, \ { LOG_MESSAGE_MSG, sizeof(log_Message), \ "MSG", "Z", "Message"}, \ { LOG_RCIN_MSG, sizeof(log_RCIN), \ @@ -393,6 +388,21 @@ struct PACKED log_Camera { "BARO", "Iffc", "TimeMS,Alt,Press,Temp" }, \ { LOG_POWR_MSG, sizeof(log_POWR), \ "POWR","ICCH","TimeMS,Vcc,VServo,Flags" }, \ + { LOG_CMD_MSG, sizeof(log_Cmd), \ + "CMD", "IHHHfffffff","TimeMS,CTot,CNum,CId,Prm1,Prm2,Prm3,Prm4,Lat,Lng,Alt" }, \ + { LOG_RADIO_MSG, sizeof(log_Radio), \ + "RAD", "IBBBBBHH", "TimeMS,RSSI,RemRSSI,TxBuf,Noise,RemNoise,RxErrors,Fixed" }, \ + { LOG_CAMERA_MSG, sizeof(log_Camera), \ + "CAM", "IHLLeeccC","GPSTime,GPSWeek,Lat,Lng,Alt,RelAlt,Roll,Pitch,Yaw" } + +// messages for more advanced boards +#define LOG_EXTRA_STRUCTURES \ + { LOG_GPS2_MSG, sizeof(log_GPS2), \ + "GPS2", "BIHBcLLeEefIBI", "Status,TimeMS,Week,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,T,DSc,DAg" }, \ + { LOG_IMU2_MSG, sizeof(log_IMU), \ + "IMU2", "Iffffff", "TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ" }, \ + { LOG_IMU3_MSG, sizeof(log_IMU), \ + "IMU3", "Iffffff", "TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ" }, \ { LOG_AHR2_MSG, sizeof(log_AHRS), \ "AHR2","IccCfLL","TimeMS,Roll,Pitch,Yaw,Alt,Lat,Lng" }, \ { LOG_SIMSTATE_MSG, sizeof(log_AHRS), \ @@ -404,13 +414,13 @@ struct PACKED log_Camera { { LOG_EKF3_MSG, sizeof(log_EKF3), \ "EKF3","Icccccchhhc","TimeMS,IVN,IVE,IVD,IPN,IPE,IPD,IMX,IMY,IMZ,IVT" }, \ { LOG_EKF4_MSG, sizeof(log_EKF4), \ - "EKF4","IcccccccbbBB","TimeMS,SV,SP,SH,SMX,SMY,SMZ,SVT,OFN,EFE,FS,DS" }, \ - { LOG_CMD_MSG, sizeof(log_Cmd), \ - "CMD", "IHHHfffffff","TimeMS,CTot,CNum,CId,Prm1,Prm2,Prm3,Prm4,Lat,Lng,Alt" }, \ - { LOG_RADIO_MSG, sizeof(log_Radio), \ - "RAD", "IBBBBBHH", "TimeMS,RSSI,RemRSSI,TxBuf,Noise,RemNoise,RxErrors,Fixed" }, \ - { LOG_CAMERA_MSG, sizeof(log_Camera), \ - "CAM", "IHLLeeccC","GPSTime,GPSWeek,Lat,Lng,Alt,RelAlt,Roll,Pitch,Yaw" } + "EKF4","IcccccccbbBB","TimeMS,SV,SP,SH,SMX,SMY,SMZ,SVT,OFN,EFE,FS,DS" } + +#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75 +#define LOG_COMMON_STRUCTURES LOG_BASE_STRUCTURES, LOG_EXTRA_STRUCTURES +#else +#define LOG_COMMON_STRUCTURES LOG_BASE_STRUCTURES +#endif // message types 0 to 100 reversed for vehicle specific use diff --git a/libraries/DataFlash/LogFile.cpp b/libraries/DataFlash/LogFile.cpp index c4adc426af..6dc0d0e901 100644 --- a/libraries/DataFlash/LogFile.cpp +++ b/libraries/DataFlash/LogFile.cpp @@ -785,6 +785,7 @@ void DataFlash_Class::Log_Write_IMU(const AP_InertialSensor &ins) if (ins.get_gyro_count() < 2 && ins.get_accel_count() < 2) { return; } +#if INS_MAX_INSTANCES > 1 const Vector3f &gyro2 = ins.get_gyro(1); const Vector3f &accel2 = ins.get_accel(1); struct log_IMU pkt2 = { @@ -814,6 +815,7 @@ void DataFlash_Class::Log_Write_IMU(const AP_InertialSensor &ins) accel_z : accel3.z }; WriteBlock(&pkt3, sizeof(pkt3)); +#endif } // Write a text message to the log