mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
DataFlash: save some flash space on APM2
don't include log message headers that are not used on APM2
This commit is contained in:
parent
166c1fd530
commit
fd87f28a07
@ -368,21 +368,16 @@ struct PACKED log_Camera {
|
|||||||
uint16_t yaw;
|
uint16_t yaw;
|
||||||
};
|
};
|
||||||
|
|
||||||
#define LOG_COMMON_STRUCTURES \
|
// messages for all boards
|
||||||
|
#define LOG_BASE_STRUCTURES \
|
||||||
{ LOG_FORMAT_MSG, sizeof(log_Format), \
|
{ LOG_FORMAT_MSG, sizeof(log_Format), \
|
||||||
"FMT", "BBnNZ", "Type,Length,Name,Format,Columns" }, \
|
"FMT", "BBnNZ", "Type,Length,Name,Format,Columns" }, \
|
||||||
{ LOG_PARAMETER_MSG, sizeof(log_Parameter), \
|
{ LOG_PARAMETER_MSG, sizeof(log_Parameter), \
|
||||||
"PARM", "Nf", "Name,Value" }, \
|
"PARM", "Nf", "Name,Value" }, \
|
||||||
{ LOG_GPS_MSG, sizeof(log_GPS), \
|
{ LOG_GPS_MSG, sizeof(log_GPS), \
|
||||||
"GPS", "BIHBcLLeeEefI", "Status,TimeMS,Week,NSats,HDop,Lat,Lng,RelAlt,Alt,Spd,GCrs,VZ,T" }, \
|
"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), \
|
{ LOG_IMU_MSG, sizeof(log_IMU), \
|
||||||
"IMU", "Iffffff", "TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ" }, \
|
"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), \
|
{ LOG_MESSAGE_MSG, sizeof(log_Message), \
|
||||||
"MSG", "Z", "Message"}, \
|
"MSG", "Z", "Message"}, \
|
||||||
{ LOG_RCIN_MSG, sizeof(log_RCIN), \
|
{ LOG_RCIN_MSG, sizeof(log_RCIN), \
|
||||||
@ -393,6 +388,21 @@ struct PACKED log_Camera {
|
|||||||
"BARO", "Iffc", "TimeMS,Alt,Press,Temp" }, \
|
"BARO", "Iffc", "TimeMS,Alt,Press,Temp" }, \
|
||||||
{ LOG_POWR_MSG, sizeof(log_POWR), \
|
{ LOG_POWR_MSG, sizeof(log_POWR), \
|
||||||
"POWR","ICCH","TimeMS,Vcc,VServo,Flags" }, \
|
"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), \
|
{ LOG_AHR2_MSG, sizeof(log_AHRS), \
|
||||||
"AHR2","IccCfLL","TimeMS,Roll,Pitch,Yaw,Alt,Lat,Lng" }, \
|
"AHR2","IccCfLL","TimeMS,Roll,Pitch,Yaw,Alt,Lat,Lng" }, \
|
||||||
{ LOG_SIMSTATE_MSG, sizeof(log_AHRS), \
|
{ LOG_SIMSTATE_MSG, sizeof(log_AHRS), \
|
||||||
@ -404,13 +414,13 @@ struct PACKED log_Camera {
|
|||||||
{ LOG_EKF3_MSG, sizeof(log_EKF3), \
|
{ LOG_EKF3_MSG, sizeof(log_EKF3), \
|
||||||
"EKF3","Icccccchhhc","TimeMS,IVN,IVE,IVD,IPN,IPE,IPD,IMX,IMY,IMZ,IVT" }, \
|
"EKF3","Icccccchhhc","TimeMS,IVN,IVE,IVD,IPN,IPE,IPD,IMX,IMY,IMZ,IVT" }, \
|
||||||
{ LOG_EKF4_MSG, sizeof(log_EKF4), \
|
{ LOG_EKF4_MSG, sizeof(log_EKF4), \
|
||||||
"EKF4","IcccccccbbBB","TimeMS,SV,SP,SH,SMX,SMY,SMZ,SVT,OFN,EFE,FS,DS" }, \
|
"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" }, \
|
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||||
{ LOG_RADIO_MSG, sizeof(log_Radio), \
|
#define LOG_COMMON_STRUCTURES LOG_BASE_STRUCTURES, LOG_EXTRA_STRUCTURES
|
||||||
"RAD", "IBBBBBHH", "TimeMS,RSSI,RemRSSI,TxBuf,Noise,RemNoise,RxErrors,Fixed" }, \
|
#else
|
||||||
{ LOG_CAMERA_MSG, sizeof(log_Camera), \
|
#define LOG_COMMON_STRUCTURES LOG_BASE_STRUCTURES
|
||||||
"CAM", "IHLLeeccC","GPSTime,GPSWeek,Lat,Lng,Alt,RelAlt,Roll,Pitch,Yaw" }
|
#endif
|
||||||
|
|
||||||
// message types 0 to 100 reversed for vehicle specific use
|
// message types 0 to 100 reversed for vehicle specific use
|
||||||
|
|
||||||
|
@ -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) {
|
if (ins.get_gyro_count() < 2 && ins.get_accel_count() < 2) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
#if INS_MAX_INSTANCES > 1
|
||||||
const Vector3f &gyro2 = ins.get_gyro(1);
|
const Vector3f &gyro2 = ins.get_gyro(1);
|
||||||
const Vector3f &accel2 = ins.get_accel(1);
|
const Vector3f &accel2 = ins.get_accel(1);
|
||||||
struct log_IMU pkt2 = {
|
struct log_IMU pkt2 = {
|
||||||
@ -814,6 +815,7 @@ void DataFlash_Class::Log_Write_IMU(const AP_InertialSensor &ins)
|
|||||||
accel_z : accel3.z
|
accel_z : accel3.z
|
||||||
};
|
};
|
||||||
WriteBlock(&pkt3, sizeof(pkt3));
|
WriteBlock(&pkt3, sizeof(pkt3));
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
// Write a text message to the log
|
// Write a text message to the log
|
||||||
|
Loading…
Reference in New Issue
Block a user