9 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT 63 #define streq(x, y) (!strcmp(x, y)) 66 : _firmware_string(firmware_string)
67 , _log_bitmask(log_bitmask)
79 gcs().
send_text(MAV_SEVERITY_INFO,
"Preparing log system");
80 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 91 #if defined(HAL_BOARD_LOG_DIRECTORY) 92 #if HAL_OS_POSIX_IO || HAL_OS_FATFS_IO 97 if (message_writer !=
nullptr) {
108 #elif CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT 115 if (message_writer !=
nullptr) {
117 #if defined(BOARD_SDCARD_NAME) || defined(BOARD_DATAFLASH_FATFS) 125 printf(
"Unable to open DataFlash_Revo");
131 #endif // HAL_BOARD_LOG_DIRECTORY 133 #if DATAFLASH_MAVLINK_SUPPORT 142 if (message_writer !=
nullptr) {
162 gcs().
send_text(MAV_SEVERITY_INFO,
"Prepared log system");
165 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 168 #define DEBUG_LOG_STRUCTURES 0 171 #define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0) 177 for (uint8_t i=0; i<strlen(
string); i++) {
178 if (
string[i] ==
',') {
188 for(uint8_t i=0; i<unit_id; i++) {
189 if (
_units[i].ID == unit_id) {
199 for(uint8_t i=0; i<multiplier_id; i++) {
218 #if DEBUG_LOG_STRUCTURES 219 for (uint16_t i=0; i<num_types; i++) {
220 const struct LogStructure *logstructure = &logstructures[i];
222 char label[32] = { };
223 uint8_t labeloffset = 0;
225 for (uint8_t j=0; j<strlen(logstructure->
labels); j++) {
226 char labelchar = logstructure->
labels[j];
227 if (labelchar ==
'\0') {
230 if (labelchar ==
',') {
234 memset(label,
'\0', 32);
236 label[labeloffset++] = labelchar;
249 #if DEBUG_LOG_STRUCTURES 250 Debug(
"offset=%d ID=%d NAME=%s\n", offset, logstructure->
msg_type, logstructure->
name);
254 #define CHECK_ENTRY(fieldname,fieldname_s,fieldlen) \ 256 if (strnlen(logstructure->fieldname, fieldlen) > fieldlen-1) { \ 257 Debug("Message " fieldname_s " not NULL-terminated or too long"); \ 270 Debug(
"ID %d used twice (LogStructure offset=%d)", logstructure->
msg_type, offset);
276 uint8_t fieldcount = strlen(logstructure->
format);
278 if (fieldcount != labelcount) {
279 Debug(
"fieldcount=%u does not match labelcount=%u",
280 fieldcount, labelcount);
286 if (msg_len != logstructure->
msg_len) {
287 Debug(
"Calculated message length for (%s) based on format field (%s) does not match structure size (%d != %u)", logstructure->
name, logstructure->
format, msg_len, logstructure->
msg_len);
292 if (strlen(logstructure->
units) != fieldcount) {
293 Debug(
"fieldcount=%u does not match unitcount=%lu",
294 fieldcount, strlen(logstructure->
units));
299 if (strlen(logstructure->
multipliers) != fieldcount) {
300 Debug(
"fieldcount=%u does not match multipliercount=%lu",
306 for (uint8_t j=0; j<strlen(logstructure->
units); j++) {
307 char logunit = logstructure->
units[j];
310 if (logunit ==
_units[k].ID) {
315 if (k == _num_units) {
316 Debug(
"invalid unit=%c", logunit);
322 for (uint8_t j=0; j<strlen(logstructure->
multipliers); j++) {
331 if (k == _num_multipliers) {
332 Debug(
"invalid multiplier=%c", logmultiplier);
341 Debug(
"Validating structures");
344 for (uint16_t i=0; i<num_types; i++) {
345 const struct LogStructure *logstructure = &logstructures[i];
349 Debug(
"Log structures are invalid");
354 #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL 409 f->sent_mask &= ~(1<<i);
443 #define FOR_EACH_BACKEND(methodcall) \ 445 for (uint8_t i=0; i<_next_backend; i++) { \ 446 backends[i]->methodcall; \ 462 if (armed_state ==
_armed) {
559 switch (msg->msgid) {
560 case MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS:
563 case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
565 case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
567 case MAVLINK_MSG_ID_LOG_ERASE:
569 case MAVLINK_MSG_ID_LOG_REQUEST_END:
580 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX 626 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 636 va_start(arg_list, fmt);
637 Log_WriteV(name, labels,
nullptr,
nullptr, fmt, arg_list);
645 va_start(arg_list, fmt);
646 Log_WriteV(name, labels, units, mults, fmt, arg_list);
668 va_copy(arg_copy, arg_list);
675 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 681 const char *
fmt)
const 686 Debug(
"format names differ (%s) != (%s)", f->
name, name);
690 Debug(
"format labels differ (%s) vs (%s)", f->
labels, labels);
693 if ((f->
units !=
nullptr && units ==
nullptr) ||
694 (f->
units ==
nullptr && units !=
nullptr) ||
695 (units !=
nullptr && !
streq(f->
units, units))) {
696 Debug(
"format units differ (%s) vs (%s)",
698 (units ? units :
"nullptr"));
701 if ((f->
mults !=
nullptr && mults ==
nullptr) ||
702 (f->
mults ==
nullptr && mults !=
nullptr) ||
703 (mults !=
nullptr && !
streq(f->
mults, mults))) {
704 Debug(
"format mults differ (%s) vs (%s)",
706 (mults ? mults :
"nullptr"));
710 Debug(
"format fmt differ (%s) vs (%s)",
711 (f->
fmt ? f->
fmt :
"nullptr"),
712 (fmt ? fmt :
"nullptr"));
716 Debug(
"Format definition must be consistent for every call of Log_Write");
726 if (f->
name == name) {
728 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 741 if (msg_type == -1) {
764 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 779 memcpy((
char*)ls_name, f->
name,
MIN(
sizeof(ls_name), strlen(f->
name)));
780 memcpy((
char*)ls_format, f->
fmt,
MIN(
sizeof(ls_format), strlen(f->
fmt)));
781 memcpy((
char*)ls_labels, f->
labels,
MIN(
sizeof(ls_labels), strlen(f->
labels)));
782 if (f->
units !=
nullptr) {
783 memcpy((
char*)ls_units, f->
units,
MIN(
sizeof(ls_units), strlen(f->
units)));
785 memset((
char*)ls_units,
'?',
MIN(
sizeof(ls_format), strlen(f->
fmt)));
787 if (f->
mults !=
nullptr) {
788 memcpy((
char*)ls_multipliers, f->
mults,
MIN(
sizeof(ls_multipliers), strlen(f->
mults)));
790 memset((
char*)ls_multipliers,
'?',
MIN(
sizeof(ls_format), strlen(f->
fmt)));
804 if (
structure(i)->msg_type == msg_type) {
823 for (uint16_t msg_type=254; msg_type>0; msg_type--) {
853 if (f->
units !=
nullptr) {
859 if (f->
mults !=
nullptr) {
867 ((
char*)(logstruct.
units))[0] =
's';
882 for (uint8_t i=0; i<strlen(fmt); i++) {
884 case 'a' : len +=
sizeof(int16_t[32]);
break;
885 case 'b' : len +=
sizeof(int8_t);
break;
886 case 'c' : len +=
sizeof(int16_t);
break;
887 case 'd' : len +=
sizeof(double);
break;
888 case 'e' : len +=
sizeof(int32_t);
break;
889 case 'f' : len +=
sizeof(float);
break;
890 case 'h' : len +=
sizeof(int16_t);
break;
891 case 'i' : len +=
sizeof(int32_t);
break;
892 case 'n' : len +=
sizeof(
char[4]);
break;
893 case 'B' : len +=
sizeof(uint8_t);
break;
894 case 'C' : len +=
sizeof(uint16_t);
break;
895 case 'E' : len +=
sizeof(uint32_t);
break;
896 case 'H' : len +=
sizeof(uint16_t);
break;
897 case 'I' : len +=
sizeof(uint32_t);
break;
898 case 'L' : len +=
sizeof(int32_t);
break;
899 case 'M' : len +=
sizeof(uint8_t);
break;
900 case 'N' : len +=
sizeof(
char[16]);
break;
901 case 'Z' : len +=
sizeof(
char[64]);
break;
902 case 'q' : len +=
sizeof(int64_t);
break;
903 case 'Q' : len +=
sizeof(uint64_t);
break;
905 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 916 #undef FOR_EACH_BACKEND 921 const uint8_t sensor_instance,
923 const uint16_t sample_count,
924 const uint64_t sample_us,
925 const float sample_rate_hz)
937 sample_count : sample_count,
938 sample_us : sample_us,
939 sample_rate_hz : sample_rate_hz,
953 const uint16_t
seqno,
967 memcpy(pkt.
x, x,
sizeof(pkt.
x));
968 memcpy(pkt.
y, y,
sizeof(pkt.
y));
969 memcpy(pkt.
z, z,
sizeof(pkt.
z));
int printf(const char *fmt,...)
void handle_mavlink_msg(class GCS_MAVLINK &, mavlink_message_t *msg)
void Log_Write_MessageF(const char *fmt,...)
static const uint8_t LS_NAME_SIZE
void dump_structure_field(const struct LogStructure *logstructure, const char *label, const uint8_t fieldnum)
pretty-print field information from a log structure
static DataFlash_Class * _instance
uint32_t num_dropped(void) const
int16_t find_free_msg_type() const
bool logging_enabled() const
struct log_write_fmt * next
struct log_write_fmt * msg_fmt_for_name(const char *name, const char *labels, const char *units, const char *mults, const char *fmt)
const uint8_t _num_multipliers
void internal_error() const
MAVLink transport control class.
static const uint8_t LS_MULTIPLIERS_SIZE
AP_HAL::UARTDriver * console
#define HAL_BOARD_LOG_DIRECTORY
Interface definition for the various Ground Control System.
bool logging_started(void)
#define CHECK_ENTRY(fieldname, fieldname_s, fieldlen)
bool should_log(uint32_t mask) const
#define AP_GROUPINFO(name, idx, clazz, element, def)
void Log_Write_Mode(uint8_t mode, uint8_t reason)
struct DataFlash_Class::@194 _params
void Log_Write_Message(const char *message)
virtual void get_log_boundaries(uint16_t log_num, uint16_t &start_page, uint16_t &end_page)=0
void Log_Write_Parameter(const char *name, float value)
void handle_log_message(class GCS_MAVLINK &, mavlink_message_t *msg)
#define DATAFLASH_MAX_BACKENDS
void WriteBlock(const void *pBuffer, uint16_t size)
const struct LogStructure * structure(uint16_t num) const
void WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
const struct MultiplierStructure log_Multipliers[]
void * calloc(size_t nmemb, size_t size)
mavlink_channel_t get_chan() const
bool in_log_download() const
bool Log_Write_ISBH(uint16_t seqno, AP_InertialSensor::IMU_SENSOR_TYPE sensor_type, uint8_t instance, uint16_t multiplier, uint16_t sample_count, uint64_t sample_us, float sample_rate_hz)
void get_log_boundaries(uint16_t log_num, uint16_t &start_page, uint16_t &end_page)
virtual int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)=0
void backend_starting_new_log(const DataFlash_Backend *backend)
bool fill_log_write_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const
int vsnprintf(char *str, size_t size, const char *format, va_list ap)
virtual void printf(const char *,...) FMT_PRINTF(2
void set_vehicle_armed(bool armed_state)
void Init(const struct LogStructure *structure, uint8_t num_types)
void dump_structures(const struct LogStructure *logstructures, const uint8_t num_types)
static const struct AP_Param::GroupInfo var_info[]
void Log_Write(const char *name, const char *labels, const char *fmt,...)
virtual uint16_t find_last_log()=0
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)
void Log_WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list)
static uint8_t count_commas(const char *string)
return the number of commas present in string
void validate_structures(const struct LogStructure *logstructures, const uint8_t num_types)
const struct MultiplierStructure * _multipliers
void set_mission(const AP_Mission *mission)
bool msg_type_in_use(uint8_t msg_type) const
double multiplier_name(const uint8_t multiplier_id)
return a multiplier value given its ID
const AP_Int32 & _log_bitmask
bool log_while_disarmed(void) const
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static DataFlash_Class * instance(void)
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc)
static const uint8_t LS_LABELS_SIZE
uint16_t find_last_log() const
const struct MultiplierStructure * multiplier(uint16_t num) const
void send_text(MAV_SEVERITY severity, const char *fmt,...)
void setVehicle_Startup_Log_Writer(vehicle_startup_message_Log_Writer writer)
bool validate_structure(const struct LogStructure *logstructure, int16_t offset)
bool logging_failed() const
void WriteCriticalBlock(const void *pBuffer, uint16_t size)
void Log_Write_Mission_Cmd(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd)
virtual uint16_t get_num_logs()=0
bool logging_present() const
const struct UnitStructure * _units
const char * unit_name(const uint8_t unit_id)
return a unit name given its ID
bool Log_Write_ISBD(uint16_t isb_seqno, uint16_t seqno, const int16_t x[32], const int16_t y[32], const int16_t z[32])
#define Debug(fmt, args ...)
DataFlash_Class(const char *firmware_string, const AP_Int32 &log_bitmask)
void assert_same_fmt_for_name(const log_write_fmt *f, const char *name, const char *labels, const char *units, const char *mults, const char *fmt) const
static const uint8_t LS_FORMAT_SIZE
void EnableWrites(bool enable)
const struct UnitStructure * unit(uint16_t num) const
const char * _firmware_string
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
void Log_Write_EntireMission(const AP_Mission &mission)
void panic(const char *errormsg,...) FMT_PRINTF(1
bool Log_Write(uint8_t msg_type, va_list arg_list, bool is_critical=false)
bool WriteBlock(const void *pBuffer, uint16_t size)
vehicle_startup_message_Log_Writer _vehicle_messages
#define LOG_PACKET_HEADER_LEN
#define LOG_PACKET_HEADER_INIT(id)
virtual void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc)=0
static const uint8_t LS_UNITS_SIZE
const struct LogStructure * _structures
int16_t Log_Write_calc_msg_len(const char *fmt) const
bool vehicle_is_armed() const
uint16_t get_num_logs(void)
#define FOR_EACH_BACKEND(methodcall)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
uint32_t num_dropped(void) const
DataFlash_Backend * backends[DATAFLASH_MAX_BACKENDS]
struct DataFlash_Class::log_write_fmt * log_write_fmts