Browse Source

DataFlash: added TRIGGER message to Logs

DataFlash.h: added support for Trigger MSG, supressed TAB separations
and file reorganized LogFile.cpp: included Trigger packet
master
Jaime Machuca 9 years ago committed by Andrew Tridgell
parent
commit
1001e53140
  1. 3
      libraries/DataFlash/DataFlash.h
  2. 30
      libraries/DataFlash/LogFile.cpp
  3. 21
      libraries/DataFlash/LogStructure.h

3
libraries/DataFlash/DataFlash.h

@ -110,6 +110,7 @@ public: @@ -110,6 +110,7 @@ public:
void Log_Write_Radio(const mavlink_radio_t &packet);
void Log_Write_Message(const char *message);
void Log_Write_Camera(const AP_AHRS &ahrs, const AP_GPS &gps, const Location &current_loc);
void Log_Write_Trigger(const AP_AHRS &ahrs, const AP_GPS &gps, const Location &current_loc);
void Log_Write_ESC(void);
void Log_Write_Airspeed(AP_Airspeed &airspeed);
void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets);
@ -178,4 +179,4 @@ private: @@ -178,4 +179,4 @@ private:
const char *_firmware_string;
};
#endif
#endif

30
libraries/DataFlash/LogFile.cpp

@ -1565,6 +1565,34 @@ void DataFlash_Class::Log_Write_Camera(const AP_AHRS &ahrs, const AP_GPS &gps, c @@ -1565,6 +1565,34 @@ void DataFlash_Class::Log_Write_Camera(const AP_AHRS &ahrs, const AP_GPS &gps, c
WriteCriticalBlock(&pkt, sizeof(pkt));
}
// Write a Trigger packet
void DataFlash_Class::Log_Write_Trigger(const AP_AHRS &ahrs, const AP_GPS &gps, const Location &current_loc)
{
int32_t altitude, altitude_rel;
if (current_loc.flags.relative_alt) {
altitude = current_loc.alt+ahrs.get_home().alt;
altitude_rel = current_loc.alt;
} else {
altitude = current_loc.alt;
altitude_rel = current_loc.alt - ahrs.get_home().alt;
}
struct log_Trigger pkt = {
LOG_PACKET_HEADER_INIT(LOG_TRIGGER_MSG),
time_us : AP_HAL::micros64(),
gps_time : gps.time_week_ms(),
gps_week : gps.time_week(),
latitude : current_loc.lat,
longitude : current_loc.lng,
altitude : altitude,
altitude_rel: altitude_rel,
roll : (int16_t)ahrs.roll_sensor,
pitch : (int16_t)ahrs.pitch_sensor,
yaw : (uint16_t)ahrs.yaw_sensor
};
WriteBlock(&pkt, sizeof(pkt));
}
// Write an attitude packet
void DataFlash_Class::Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets)
{
@ -1776,4 +1804,4 @@ void DataFlash_Class::Log_Write_RPM(const AP_RPM &rpm_sensor) @@ -1776,4 +1804,4 @@ void DataFlash_Class::Log_Write_RPM(const AP_RPM &rpm_sensor)
rpm2 : rpm_sensor.get_rpm(1)
};
WriteBlock(&pkt, sizeof(pkt));
}
}

21
libraries/DataFlash/LogStructure.h

@ -390,6 +390,20 @@ struct PACKED log_Camera { @@ -390,6 +390,20 @@ struct PACKED log_Camera {
uint16_t yaw;
};
struct PACKED log_Trigger {
LOG_PACKET_HEADER;
uint64_t time_us;
uint32_t gps_time;
uint16_t gps_week;
int32_t latitude;
int32_t longitude;
int32_t altitude;
int32_t altitude_rel;
int16_t roll;
int16_t pitch;
uint16_t yaw;
};
struct PACKED log_Attitude {
LOG_PACKET_HEADER;
uint64_t time_us;
@ -733,9 +747,11 @@ Format characters in the format string for binary log messages @@ -733,9 +747,11 @@ Format characters in the format string for binary log messages
{ LOG_MODE_MSG, sizeof(log_Mode), \
"MODE", "QMB", "TimeUS,Mode,ModeNum" }, \
{ LOG_RFND_MSG, sizeof(log_RFND), \
"RFND", "QCC", "TimeUS,Dist1,Dist2" }, \
"RFND", "QCC", "TimeUS,Dist1,Dist2" }, \
{ LOG_DF_MAV_STATS, sizeof(log_DF_MAV_Stats), \
"DMS", "IIIIIBBBBBBBBBB", "TimeMS,N,Dp,RT,RS,Er,Fa,Fmn,Fmx,Pa,Pmn,Pmx,Sa,Smn,Smx" }
"DMS", "IIIIIBBBBBBBBBB", "TimeMS,N,Dp,RT,RS,Er,Fa,Fmn,Fmx,Pa,Pmn,Pmx,Sa,Smn,Smx" }, \
{ LOG_TRIGGER_MSG, sizeof(log_Trigger), \
"TRIG", "QIHLLeeccC","TimeUS,GPSTime,GPSWeek,Lat,Lng,Alt,RelAlt,Roll,Pitch,Yaw" }
// messages for more advanced boards
#define LOG_EXTRA_STRUCTURES \
@ -966,6 +982,7 @@ enum LogMessages { @@ -966,6 +982,7 @@ enum LogMessages {
LOG_MSG_SBPRAW1,
LOG_MSG_SBPRAW2,
LOG_MSG_SBPRAWx,
LOG_TRIGGER_MSG,
LOG_GIMBAL1_MSG,
LOG_GIMBAL2_MSG,

Loading…
Cancel
Save