123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200 |
- #include "AP_Logger.h"
- #include "AP_Logger_Backend.h"
- #include "AP_Logger_File.h"
- #include "AP_Logger_SITL.h"
- #include "AP_Logger_DataFlash.h"
- #include "AP_Logger_MAVLink.h"
- #include <AP_InternalError/AP_InternalError.h>
- #include <GCS_MAVLink/GCS.h>
- AP_Logger *AP_Logger::_singleton;
- extern const AP_HAL::HAL& hal;
- #ifndef HAL_LOGGING_FILE_BUFSIZE
- #if HAL_MEM_CLASS >= HAL_MEM_CLASS_300
- #define HAL_LOGGING_FILE_BUFSIZE 50
- #else
- #define HAL_LOGGING_FILE_BUFSIZE 16
- #endif
- #endif
- #ifndef HAL_LOGGING_MAV_BUFSIZE
- #define HAL_LOGGING_MAV_BUFSIZE 8
- #endif
- #ifndef HAL_LOGGING_FILE_TIMEOUT
- #define HAL_LOGGING_FILE_TIMEOUT 5
- #endif
- #ifndef HAL_LOGGER_ARM_PERSIST
- #define HAL_LOGGER_ARM_PERSIST 15
- #endif
- #ifndef HAL_LOGGING_BACKENDS_DEFAULT
- # ifdef HAL_LOGGING_DATAFLASH
- # define HAL_LOGGING_BACKENDS_DEFAULT Backend_Type::BLOCK
- # else
- # define HAL_LOGGING_BACKENDS_DEFAULT Backend_Type::FILESYSTEM
- # endif
- #endif
- const AP_Param::GroupInfo AP_Logger::var_info[] = {
-
-
-
-
-
-
- AP_GROUPINFO("_BACKEND_TYPE", 0, AP_Logger, _params.backend_types, uint8_t(HAL_LOGGING_BACKENDS_DEFAULT)),
-
-
-
-
- AP_GROUPINFO("_FILE_BUFSIZE", 1, AP_Logger, _params.file_bufsize, HAL_LOGGING_FILE_BUFSIZE),
-
-
-
-
-
- AP_GROUPINFO("_DISARMED", 2, AP_Logger, _params.log_disarmed, 0),
-
-
-
-
-
- AP_GROUPINFO("_REPLAY", 3, AP_Logger, _params.log_replay, 0),
-
-
-
-
-
- AP_GROUPINFO("_FILE_DSRMROT", 4, AP_Logger, _params.file_disarm_rot, 0),
-
-
-
-
-
- AP_GROUPINFO("_MAV_BUFSIZE", 5, AP_Logger, _params.mav_bufsize, HAL_LOGGING_MAV_BUFSIZE),
-
-
-
-
-
- AP_GROUPINFO("_FILE_TIMEOUT", 6, AP_Logger, _params.file_timeout, HAL_LOGGING_FILE_TIMEOUT),
-
- AP_GROUPEND
- };
- #define streq(x, y) (!strcmp(x, y))
- AP_Logger::AP_Logger(const AP_Int32 &log_bitmask)
- : _log_bitmask(log_bitmask)
- {
- AP_Param::setup_object_defaults(this, var_info);
- if (_singleton != nullptr) {
- AP_HAL::panic("AP_Logger must be singleton");
- }
- _singleton = this;
- }
- void AP_Logger::Init(const struct LogStructure *structures, uint8_t num_types)
- {
- gcs().send_text(MAV_SEVERITY_INFO, "Preparing log system");
- if (hal.util->was_watchdog_armed()) {
- gcs().send_text(MAV_SEVERITY_INFO, "Forcing logging for watchdog reset");
- _params.log_disarmed.set(1);
- }
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- validate_structures(structures, num_types);
- dump_structures(structures, num_types);
- #endif
- if (_next_backend == LOGGER_MAX_BACKENDS) {
- AP_HAL::panic("Too many backends");
- return;
- }
- _num_types = num_types;
- _structures = structures;
- #if defined(HAL_BOARD_LOG_DIRECTORY) && HAVE_FILESYSTEM_SUPPORT
- if (_params.backend_types & uint8_t(Backend_Type::FILESYSTEM)) {
- LoggerMessageWriter_DFLogStart *message_writer =
- new LoggerMessageWriter_DFLogStart();
- if (message_writer != nullptr) {
- backends[_next_backend] = new AP_Logger_File(*this,
- message_writer,
- HAL_BOARD_LOG_DIRECTORY);
- }
- if (backends[_next_backend] == nullptr) {
- hal.console->printf("Unable to open AP_Logger_File");
- } else {
- _next_backend++;
- }
- }
- #endif
- #if LOGGER_MAVLINK_SUPPORT
- if (_params.backend_types & uint8_t(Backend_Type::MAVLINK)) {
- if (_next_backend == LOGGER_MAX_BACKENDS) {
- AP_HAL::panic("Too many backends");
- return;
- }
- LoggerMessageWriter_DFLogStart *message_writer =
- new LoggerMessageWriter_DFLogStart();
- if (message_writer != nullptr) {
- backends[_next_backend] = new AP_Logger_MAVLink(*this,
- message_writer);
- }
- if (backends[_next_backend] == nullptr) {
- hal.console->printf("Unable to open AP_Logger_MAVLink");
- } else {
- _next_backend++;
- }
- }
- #endif
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- if (_params.backend_types & uint8_t(Backend_Type::BLOCK)) {
- if (_next_backend == LOGGER_MAX_BACKENDS) {
- AP_HAL::panic("Too many backends");
- return;
- }
- LoggerMessageWriter_DFLogStart *message_writer =
- new LoggerMessageWriter_DFLogStart();
- if (message_writer != nullptr) {
- backends[_next_backend] = new AP_Logger_SITL(*this, message_writer);
- }
- if (backends[_next_backend] == nullptr) {
- hal.console->printf("Unable to open AP_Logger_SITL");
- } else {
- _next_backend++;
- }
- }
- #endif
- #ifdef HAL_LOGGING_DATAFLASH
- if (_params.backend_types & uint8_t(Backend_Type::BLOCK)) {
- if (_next_backend == LOGGER_MAX_BACKENDS) {
- AP_HAL::panic("Too many backends");
- return;
- }
- LoggerMessageWriter_DFLogStart *message_writer =
- new LoggerMessageWriter_DFLogStart();
- if (message_writer != nullptr) {
- backends[_next_backend] = new AP_Logger_DataFlash(*this, message_writer);
- }
- if (backends[_next_backend] == nullptr) {
- hal.console->printf("Unable to open AP_Logger_DataFlash");
- } else {
- _next_backend++;
- }
- }
- #endif
-
- for (uint8_t i=0; i<_next_backend; i++) {
- backends[i]->Init();
- }
- Prep();
- EnableWrites(true);
- gcs().send_text(MAV_SEVERITY_INFO, "Prepared log system");
- }
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- #include <stdio.h>
- #define DEBUG_LOG_STRUCTURES 0
- extern const AP_HAL::HAL& hal;
- #define Debug(fmt, args ...) do {::fprintf(stderr, "%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
- static uint8_t count_commas(const char *string)
- {
- uint8_t ret = 0;
- for (uint8_t i=0; i<strlen(string); i++) {
- if (string[i] == ',') {
- ret++;
- }
- }
- return ret;
- }
- const char* AP_Logger::unit_name(const uint8_t unit_id)
- {
- for(uint8_t i=0; i<unit_id; i++) {
- if (_units[i].ID == unit_id) {
- return _units[i].unit;
- }
- }
- return NULL;
- }
- double AP_Logger::multiplier_name(const uint8_t multiplier_id)
- {
- for(uint8_t i=0; i<multiplier_id; i++) {
- if (_multipliers[i].ID == multiplier_id) {
- return _multipliers[i].multiplier;
- }
- }
-
- return 1.0f;
- }
- void AP_Logger::dump_structure_field(const struct LogStructure *logstructure, const char *label, const uint8_t fieldnum)
- {
- ::fprintf(stderr, " %s (%s)*(%f)\n", label, unit_name(logstructure->units[fieldnum]), multiplier_name(logstructure->multipliers[fieldnum]));
- }
- void AP_Logger::dump_structures(const struct LogStructure *logstructures, const uint8_t num_types)
- {
- #if DEBUG_LOG_STRUCTURES
- for (uint16_t i=0; i<num_types; i++) {
- const struct LogStructure *logstructure = &logstructures[i];
- ::fprintf(stderr, "%s\n", logstructure->name);
- char label[32] = { };
- uint8_t labeloffset = 0;
- int8_t fieldnum = 0;
- for (uint8_t j=0; j<strlen(logstructure->labels); j++) {
- char labelchar = logstructure->labels[j];
- if (labelchar == '\0') {
- break;
- }
- if (labelchar == ',') {
- dump_structure_field(logstructure, label, fieldnum);
- fieldnum++;
- labeloffset = 0;
- memset(label, '\0', 32);
- } else {
- label[labeloffset++] = labelchar;
- }
- }
- dump_structure_field(logstructure, label, fieldnum);
- ::fprintf(stderr, "\n");
- }
- #endif
- }
- bool AP_Logger::validate_structure(const struct LogStructure *logstructure, const int16_t offset)
- {
- bool passed = true;
- #if DEBUG_LOG_STRUCTURES
- Debug("offset=%d ID=%d NAME=%s", offset, logstructure->msg_type, logstructure->name);
- #endif
-
- #define CHECK_ENTRY(fieldname,fieldname_s,fieldlen) \
- do { \
- if (strnlen(logstructure->fieldname, fieldlen) > fieldlen-1) { \
- Debug(" Message " fieldname_s " not NULL-terminated or too long"); \
- passed = false; \
- } \
- } while (false)
- CHECK_ENTRY(name, "name", LS_NAME_SIZE);
- CHECK_ENTRY(format, "format", LS_FORMAT_SIZE);
- CHECK_ENTRY(labels, "labels", LS_LABELS_SIZE);
- CHECK_ENTRY(units, "units", LS_UNITS_SIZE);
- CHECK_ENTRY(multipliers, "multipliers", LS_MULTIPLIERS_SIZE);
- #undef CHECK_ENTRY
-
- if (seen_ids[logstructure->msg_type]) {
- Debug(" ID %d used twice (LogStructure offset=%d)", logstructure->msg_type, offset);
- passed = false;
- }
- seen_ids[logstructure->msg_type] = true;
-
- uint8_t fieldcount = strlen(logstructure->format);
- uint8_t labelcount = count_commas(logstructure->labels)+1;
- if (fieldcount != labelcount) {
- Debug(" fieldcount=%u does not match labelcount=%u",
- fieldcount, labelcount);
- passed = false;
- }
-
- const int16_t msg_len = Write_calc_msg_len(logstructure->format);
- if (msg_len != logstructure->msg_len) {
- 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);
- passed = false;
- }
-
- if (strlen(logstructure->units) != fieldcount) {
- Debug(" fieldcount=%u does not match unitcount=%u",
- (unsigned)fieldcount, (unsigned)strlen(logstructure->units));
- passed = false;
- }
-
- if (strlen(logstructure->multipliers) != fieldcount) {
- Debug(" fieldcount=%u does not match multipliercount=%u",
- (unsigned)fieldcount, (unsigned)strlen(logstructure->multipliers));
- passed = false;
- }
-
- for (uint8_t j=0; j<strlen(logstructure->units); j++) {
- char logunit = logstructure->units[j];
- uint8_t k;
- for (k=0; k<_num_units; k++) {
- if (logunit == _units[k].ID) {
-
- break;
- }
- }
- if (k == _num_units) {
- Debug(" invalid unit=%c", logunit);
- passed = false;
- }
- }
-
- for (uint8_t j=0; j<strlen(logstructure->multipliers); j++) {
- char logmultiplier = logstructure->multipliers[j];
- uint8_t k;
- for (k=0; k<_num_multipliers; k++) {
- if (logmultiplier == _multipliers[k].ID) {
-
- break;
- }
- }
- if (k == _num_multipliers) {
- Debug(" invalid multiplier=%c", logmultiplier);
- passed = false;
- }
- }
-
- if (false && passed) {
- for (uint8_t j=0; j<strlen(logstructure->multipliers); j++) {
- const char fmt = logstructure->format[j];
- if (fmt != 'f') {
- continue;
- }
- const char logmultiplier = logstructure->multipliers[j];
- if (logmultiplier == '0' ||
- logmultiplier == '?' ||
- logmultiplier == '-') {
- continue;
- }
- Debug(" %s[%u] float with non-zero multiplier=%c",
- logstructure->name,
- j,
- logmultiplier);
- passed = false;
- }
- }
- return passed;
- }
- void AP_Logger::validate_structures(const struct LogStructure *logstructures, const uint8_t num_types)
- {
- Debug("Validating structures");
- bool passed = true;
- for (uint16_t i=0; i<num_types; i++) {
- const struct LogStructure *logstructure = &logstructures[i];
- passed = validate_structure(logstructure, i) && passed;
- }
-
- for (uint16_t i=0; i<ARRAY_SIZE(log_Units); i++) {
- const struct UnitStructure &a = log_Units[i];
- for (uint16_t j=i+1; j<ARRAY_SIZE(log_Units); j++) {
- const struct UnitStructure &b = log_Units[j];
- if (a.ID == b.ID) {
- Debug("duplicate unit id=%c (%s/%s)", a.ID, a.unit, b.unit);
- passed = false;
- }
- if (streq(a.unit, b.unit)) {
- Debug("duplicate unit=%s (%c/%c)", a.unit, a.ID, b.ID);
- passed = false;
- }
- }
- }
-
- for (uint16_t i=0; i<ARRAY_SIZE(log_Multipliers); i++) {
- const struct MultiplierStructure &a = log_Multipliers[i];
- for (uint16_t j=i+1; j<ARRAY_SIZE(log_Multipliers); j++) {
- const struct MultiplierStructure &b = log_Multipliers[j];
- if (a.ID == b.ID) {
- Debug("duplicate multiplier id=%c (%f/%f)",
- a.ID, a.multiplier, b.multiplier);
- passed = false;
- }
- if (is_equal(a.multiplier, b.multiplier)) {
- if (a.ID == '?' && b.ID == '0') {
-
- continue;
- }
- Debug("duplicate multiplier=%f (%c/%c)",
- a.multiplier, a.ID, b.ID);
- passed = false;
- }
- }
- }
- if (!passed) {
- Debug("Log structures are invalid");
- abort();
- }
- }
- #endif
- const struct LogStructure *AP_Logger::structure(uint16_t num) const
- {
- return &_structures[num];
- }
- bool AP_Logger::logging_present() const
- {
- return _next_backend != 0;
- }
- bool AP_Logger::logging_enabled() const
- {
- if (_next_backend == 0) {
- return false;
- }
- for (uint8_t i=0; i<_next_backend; i++) {
- if (backends[i]->logging_enabled()) {
- return true;
- }
- }
- return false;
- }
- bool AP_Logger::logging_failed() const
- {
- if (_next_backend < 1) {
-
- return true;
- }
- for (uint8_t i=0; i<_next_backend; i++) {
- if (backends[i]->logging_failed()) {
- return true;
- }
- }
- return false;
- }
- void AP_Logger::Write_MessageF(const char *fmt, ...)
- {
- char msg[65] {};
- va_list ap;
- va_start(ap, fmt);
- hal.util->vsnprintf(msg, sizeof(msg), fmt, ap);
- va_end(ap);
- Write_Message(msg);
- }
- void AP_Logger::backend_starting_new_log(const AP_Logger_Backend *backend)
- {
- for (uint8_t i=0; i<_next_backend; i++) {
- if (backends[i] == backend) {
-
- for (struct log_write_fmt *f = log_write_fmts; f; f=f->next) {
- f->sent_mask &= ~(1<<i);
- }
- break;
- }
- }
- }
- bool AP_Logger::should_log(const uint32_t mask) const
- {
- bool armed = vehicle_is_armed();
- if (!(mask & _log_bitmask)) {
- return false;
- }
- if (!armed && !log_while_disarmed()) {
- return false;
- }
- if (in_log_download()) {
- return false;
- }
- if (_next_backend == 0) {
- return false;
- }
- return true;
- }
- const struct UnitStructure *AP_Logger::unit(uint16_t num) const
- {
- return &_units[num];
- }
- const struct MultiplierStructure *AP_Logger::multiplier(uint16_t num) const
- {
- return &log_Multipliers[num];
- }
- #define FOR_EACH_BACKEND(methodcall) \
- do { \
- for (uint8_t i=0; i<_next_backend; i++) { \
- backends[i]->methodcall; \
- } \
- } while (0)
- void AP_Logger::PrepForArming()
- {
- FOR_EACH_BACKEND(PrepForArming());
- }
- void AP_Logger::setVehicle_Startup_Writer(vehicle_startup_message_Writer writer)
- {
- _vehicle_messages = writer;
- }
- void AP_Logger::set_vehicle_armed(const bool armed_state)
- {
- if (armed_state == _armed) {
-
- return;
- }
- _armed = armed_state;
- if (!_armed) {
-
- FOR_EACH_BACKEND(vehicle_was_disarmed());
- }
- }
- void AP_Logger::WriteBlock(const void *pBuffer, uint16_t size) {
- FOR_EACH_BACKEND(WriteBlock(pBuffer, size));
- }
- void AP_Logger::WriteCriticalBlock(const void *pBuffer, uint16_t size) {
- FOR_EACH_BACKEND(WriteCriticalBlock(pBuffer, size));
- }
- void AP_Logger::WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) {
- FOR_EACH_BACKEND(WritePrioritisedBlock(pBuffer, size, is_critical));
- }
- void AP_Logger::EraseAll() {
- FOR_EACH_BACKEND(EraseAll());
- }
- bool AP_Logger::CardInserted(void) {
- for (uint8_t i=0; i< _next_backend; i++) {
- if (backends[i]->CardInserted()) {
- return true;
- }
- }
- return false;
- }
- void AP_Logger::Prep() {
- FOR_EACH_BACKEND(Prep());
- }
- void AP_Logger::StopLogging()
- {
- FOR_EACH_BACKEND(stop_logging());
- }
- uint16_t AP_Logger::find_last_log() const {
- if (_next_backend == 0) {
- return 0;
- }
- return backends[0]->find_last_log();
- }
- void AP_Logger::get_log_boundaries(uint16_t log_num, uint32_t & start_page, uint32_t & end_page) {
- if (_next_backend == 0) {
- return;
- }
- backends[0]->get_log_boundaries(log_num, start_page, end_page);
- }
- void AP_Logger::get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) {
- if (_next_backend == 0) {
- return;
- }
- backends[0]->get_log_info(log_num, size, time_utc);
- }
- int16_t AP_Logger::get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) {
- if (_next_backend == 0) {
- return 0;
- }
- return backends[0]->get_log_data(log_num, page, offset, len, data);
- }
- uint16_t AP_Logger::get_num_logs(void) {
- if (_next_backend == 0) {
- return 0;
- }
- return backends[0]->get_num_logs();
- }
- bool AP_Logger::logging_started(void) {
- for (uint8_t i=0; i< _next_backend; i++) {
- if (backends[i]->logging_started()) {
- return true;
- }
- }
- return false;
- }
- void AP_Logger::handle_mavlink_msg(GCS_MAVLINK &link, const mavlink_message_t &msg)
- {
- switch (msg.msgid) {
- case MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS:
- FOR_EACH_BACKEND(remote_log_block_status_msg(link.get_chan(), msg));
- break;
- case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
- FALLTHROUGH;
- case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
- FALLTHROUGH;
- case MAVLINK_MSG_ID_LOG_ERASE:
- FALLTHROUGH;
- case MAVLINK_MSG_ID_LOG_REQUEST_END:
- handle_log_message(link, msg);
- break;
- }
- }
- void AP_Logger::periodic_tasks() {
- handle_log_send();
- FOR_EACH_BACKEND(periodic_tasks());
- }
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
-
- void AP_Logger::flush(void) {
- FOR_EACH_BACKEND(flush());
- }
- #endif
- void AP_Logger::Write_EntireMission()
- {
- FOR_EACH_BACKEND(Write_EntireMission());
- }
- void AP_Logger::Write_Message(const char *message)
- {
- FOR_EACH_BACKEND(Write_Message(message));
- }
- void AP_Logger::Write_Mode(uint8_t mode, uint8_t reason)
- {
- FOR_EACH_BACKEND(Write_Mode(mode, reason));
- }
- void AP_Logger::Write_Parameter(const char *name, float value)
- {
- FOR_EACH_BACKEND(Write_Parameter(name, value));
- }
- void AP_Logger::Write_Mission_Cmd(const AP_Mission &mission,
- const AP_Mission::Mission_Command &cmd)
- {
- FOR_EACH_BACKEND(Write_Mission_Cmd(mission, cmd));
- }
- void AP_Logger::Write_RallyPoint(uint8_t total,
- uint8_t sequence,
- const RallyLocation &rally_point)
- {
- FOR_EACH_BACKEND(Write_RallyPoint(total, sequence, rally_point));
- }
- void AP_Logger::Write_Rally()
- {
- FOR_EACH_BACKEND(Write_Rally());
- }
- uint32_t AP_Logger::num_dropped() const
- {
- if (_next_backend == 0) {
- return 0;
- }
- return backends[0]->num_dropped();
- }
- void AP_Logger::Write(const char *name, const char *labels, const char *fmt, ...)
- {
- va_list arg_list;
- va_start(arg_list, fmt);
- WriteV(name, labels, nullptr, nullptr, fmt, arg_list);
- va_end(arg_list);
- }
- void AP_Logger::Write(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...)
- {
- va_list arg_list;
- va_start(arg_list, fmt);
- WriteV(name, labels, units, mults, fmt, arg_list);
- va_end(arg_list);
- }
- void AP_Logger::WriteCritical(const char *name, const char *labels, const char *fmt, ...)
- {
- va_list arg_list;
- va_start(arg_list, fmt);
- WriteV(name, labels, nullptr, nullptr, fmt, arg_list, true);
- va_end(arg_list);
- }
- void AP_Logger::WriteCritical(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...)
- {
- va_list arg_list;
- va_start(arg_list, fmt);
- WriteV(name, labels, units, mults, fmt, arg_list, true);
- va_end(arg_list);
- }
- void AP_Logger::WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list, bool is_critical)
- {
- struct log_write_fmt *f = msg_fmt_for_name(name, labels, units, mults, fmt);
- if (f == nullptr) {
-
-
- AP::internalerror().error(AP_InternalError::error_t::logger_mapfailure);
- return;
- }
- for (uint8_t i=0; i<_next_backend; i++) {
- if (!(f->sent_mask & (1U<<i))) {
- if (!backends[i]->Write_Emit_FMT(f->msg_type)) {
- continue;
- }
- f->sent_mask |= (1U<<i);
- }
- va_list arg_copy;
- va_copy(arg_copy, arg_list);
- backends[i]->Write(f->msg_type, arg_copy, is_critical);
- va_end(arg_copy);
- }
- }
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- void AP_Logger::assert_same_fmt_for_name(const AP_Logger::log_write_fmt *f,
- const char *name,
- const char *labels,
- const char *units,
- const char *mults,
- const char *fmt) const
- {
- bool passed = true;
- if (!streq(f->name, name)) {
-
- Debug("format names differ (%s) != (%s)", f->name, name);
- passed = false;
- }
- if (!streq(f->labels, labels)) {
- Debug("format labels differ (%s) vs (%s)", f->labels, labels);
- passed = false;
- }
- if ((f->units != nullptr && units == nullptr) ||
- (f->units == nullptr && units != nullptr) ||
- (units !=nullptr && !streq(f->units, units))) {
- Debug("format units differ (%s) vs (%s)",
- (f->units ? f->units : "nullptr"),
- (units ? units : "nullptr"));
- passed = false;
- }
- if ((f->mults != nullptr && mults == nullptr) ||
- (f->mults == nullptr && mults != nullptr) ||
- (mults != nullptr && !streq(f->mults, mults))) {
- Debug("format mults differ (%s) vs (%s)",
- (f->mults ? f->mults : "nullptr"),
- (mults ? mults : "nullptr"));
- passed = false;
- }
- if (!streq(f->fmt, fmt)) {
- Debug("format fmt differ (%s) vs (%s)",
- (f->fmt ? f->fmt : "nullptr"),
- (fmt ? fmt : "nullptr"));
- passed = false;
- }
- if (!passed) {
- Debug("Format definition must be consistent for every call of Write");
- abort();
- }
- }
- #endif
- AP_Logger::log_write_fmt *AP_Logger::msg_fmt_for_name(const char *name, const char *labels, const char *units, const char *mults, const char *fmt)
- {
- struct log_write_fmt *f;
- for (f = log_write_fmts; f; f=f->next) {
- if (f->name == name) {
-
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- assert_same_fmt_for_name(f, name, labels, units, mults, fmt);
- #endif
- return f;
- }
- }
- f = (struct log_write_fmt *)calloc(1, sizeof(*f));
- if (f == nullptr) {
-
- return nullptr;
- }
-
- int16_t msg_type = find_free_msg_type();
- if (msg_type == -1) {
- free(f);
- return nullptr;
- }
- f->msg_type = msg_type;
- f->name = name;
- f->fmt = fmt;
- f->labels = labels;
- f->units = units;
- f->mults = mults;
- int16_t tmp = Write_calc_msg_len(fmt);
- if (tmp == -1) {
- free(f);
- return nullptr;
- }
- f->msg_len = tmp;
-
- f->next = log_write_fmts;
- log_write_fmts = f;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- char ls_name[LS_NAME_SIZE] = {};
- char ls_format[LS_FORMAT_SIZE] = {};
- char ls_labels[LS_LABELS_SIZE] = {};
- char ls_units[LS_UNITS_SIZE] = {};
- char ls_multipliers[LS_MULTIPLIERS_SIZE] = {};
- struct LogStructure ls = {
- f->msg_type,
- f->msg_len,
- ls_name,
- ls_format,
- ls_labels,
- ls_units,
- ls_multipliers
- };
- memcpy((char*)ls_name, f->name, MIN(sizeof(ls_name), strlen(f->name)));
- memcpy((char*)ls_format, f->fmt, MIN(sizeof(ls_format), strlen(f->fmt)));
- memcpy((char*)ls_labels, f->labels, MIN(sizeof(ls_labels), strlen(f->labels)));
- if (f->units != nullptr) {
- memcpy((char*)ls_units, f->units, MIN(sizeof(ls_units), strlen(f->units)));
- } else {
- memset((char*)ls_units, '?', MIN(sizeof(ls_format), strlen(f->fmt)));
- }
- if (f->mults != nullptr) {
- memcpy((char*)ls_multipliers, f->mults, MIN(sizeof(ls_multipliers), strlen(f->mults)));
- } else {
- memset((char*)ls_multipliers, '?', MIN(sizeof(ls_format), strlen(f->fmt)));
- }
- if (!validate_structure(&ls, (int16_t)-1)) {
- Debug("Log structure invalid");
- abort();
- }
- #endif
- return f;
- }
- const struct LogStructure *AP_Logger::structure_for_msg_type(const uint8_t msg_type)
- {
- for (uint16_t i=0; i<_num_types;i++) {
- const struct LogStructure *s = structure(i);
- if (s->msg_type == msg_type) {
-
- return s;
- }
- }
- return nullptr;
- }
- const struct AP_Logger::log_write_fmt *AP_Logger::log_write_fmt_for_msg_type(const uint8_t msg_type) const
- {
- struct log_write_fmt *f;
- for (f = log_write_fmts; f; f=f->next) {
- if (f->msg_type == msg_type) {
- return f;
- }
- }
- return nullptr;
- }
- bool AP_Logger::msg_type_in_use(const uint8_t msg_type) const
- {
-
-
- for (uint16_t i=0; i<_num_types;i++) {
- if (structure(i)->msg_type == msg_type) {
-
- return true;
- }
- }
- struct log_write_fmt *f;
- for (f = log_write_fmts; f; f=f->next) {
- if (f->msg_type == msg_type) {
- return true;
- }
- }
- return false;
- }
- int16_t AP_Logger::find_free_msg_type() const
- {
-
- for (uint16_t msg_type=254; msg_type>0; msg_type--) {
- if (! msg_type_in_use(msg_type)) {
- return msg_type;
- }
- }
- return -1;
- }
- bool AP_Logger::fill_log_write_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const
- {
-
- struct log_write_fmt *f;
- for (f = log_write_fmts; f; f=f->next) {
- if(f->msg_type == msg_type) {
- break;
- }
- }
- if (!f) {
- return false;
- }
- logstruct.msg_type = msg_type;
- strncpy((char*)logstruct.name, f->name, LS_NAME_SIZE);
- strncpy((char*)logstruct.format, f->fmt, LS_FORMAT_SIZE);
- strncpy((char*)logstruct.labels, f->labels, LS_LABELS_SIZE);
- if (f->units != nullptr) {
- strncpy((char*)logstruct.units, f->units, LS_UNITS_SIZE);
- } else {
- memset((char*)logstruct.units, '\0', LS_UNITS_SIZE);
- memset((char*)logstruct.units, '?', MIN(LS_UNITS_SIZE,strlen(logstruct.format)));
- }
- if (f->mults != nullptr) {
- strncpy((char*)logstruct.multipliers, f->mults, LS_MULTIPLIERS_SIZE);
- } else {
- memset((char*)logstruct.multipliers, '\0', LS_MULTIPLIERS_SIZE);
- memset((char*)logstruct.multipliers, '?', MIN(LS_MULTIPLIERS_SIZE, strlen(logstruct.format)));
-
-
- if (!strncmp(logstruct.labels, "TimeUS,", MIN(LS_LABELS_SIZE, strlen("TimeUS,")))) {
- ((char*)(logstruct.units))[0] = 's';
- ((char*)(logstruct.multipliers))[0] = 'F';
- }
- }
- logstruct.msg_len = f->msg_len;
- return true;
- }
- int16_t AP_Logger::Write_calc_msg_len(const char *fmt) const
- {
- uint8_t len = LOG_PACKET_HEADER_LEN;
- for (uint8_t i=0; i<strlen(fmt); i++) {
- switch(fmt[i]) {
- case 'a' : len += sizeof(int16_t[32]); break;
- case 'b' : len += sizeof(int8_t); break;
- case 'c' : len += sizeof(int16_t); break;
- case 'd' : len += sizeof(double); break;
- case 'e' : len += sizeof(int32_t); break;
- case 'f' : len += sizeof(float); break;
- case 'h' : len += sizeof(int16_t); break;
- case 'i' : len += sizeof(int32_t); break;
- case 'n' : len += sizeof(char[4]); break;
- case 'B' : len += sizeof(uint8_t); break;
- case 'C' : len += sizeof(uint16_t); break;
- case 'E' : len += sizeof(uint32_t); break;
- case 'H' : len += sizeof(uint16_t); break;
- case 'I' : len += sizeof(uint32_t); break;
- case 'L' : len += sizeof(int32_t); break;
- case 'M' : len += sizeof(uint8_t); break;
- case 'N' : len += sizeof(char[16]); break;
- case 'Z' : len += sizeof(char[64]); break;
- case 'q' : len += sizeof(int64_t); break;
- case 'Q' : len += sizeof(uint64_t); break;
- default:
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- AP_HAL::panic("Unknown format specifier (%c)", fmt[i]);
- #endif
- return -1;
- }
- }
- return len;
- }
- #undef FOR_EACH_BACKEND
- bool AP_Logger::Write_ISBH(const uint16_t seqno,
- const AP_InertialSensor::IMU_SENSOR_TYPE sensor_type,
- const uint8_t sensor_instance,
- const uint16_t mult,
- const uint16_t sample_count,
- const uint64_t sample_us,
- const float sample_rate_hz)
- {
- if (_next_backend == 0) {
- return false;
- }
- const struct log_ISBH pkt{
- LOG_PACKET_HEADER_INIT(LOG_ISBH_MSG),
- time_us : AP_HAL::micros64(),
- seqno : seqno,
- sensor_type : (uint8_t)sensor_type,
- instance : sensor_instance,
- multiplier : mult,
- sample_count : sample_count,
- sample_us : sample_us,
- sample_rate_hz : sample_rate_hz,
- };
-
- for (uint8_t i=1; i<_next_backend; i++) {
- backends[i]->WriteBlock(&pkt, sizeof(pkt));
- }
- return backends[0]->WriteBlock(&pkt, sizeof(pkt));
- }
- bool AP_Logger::Write_ISBD(const uint16_t isb_seqno,
- const uint16_t seqno,
- const int16_t x[32],
- const int16_t y[32],
- const int16_t z[32])
- {
- if (_next_backend == 0) {
- return false;
- }
- struct log_ISBD pkt = {
- LOG_PACKET_HEADER_INIT(LOG_ISBD_MSG),
- time_us : AP_HAL::micros64(),
- isb_seqno : isb_seqno,
- seqno : seqno
- };
- memcpy(pkt.x, x, sizeof(pkt.x));
- memcpy(pkt.y, y, sizeof(pkt.y));
- memcpy(pkt.z, z, sizeof(pkt.z));
-
- for (uint8_t i=1; i<_next_backend; i++) {
- backends[i]->WriteBlock(&pkt, sizeof(pkt));
- }
- return backends[0]->WriteBlock(&pkt, sizeof(pkt));
- }
- void AP_Logger::Write_Event(Log_Event id)
- {
- const struct log_Event pkt{
- LOG_PACKET_HEADER_INIT(LOG_EVENT_MSG),
- time_us : AP_HAL::micros64(),
- id : id
- };
- WriteCriticalBlock(&pkt, sizeof(pkt));
- }
- void AP_Logger::Write_Error(LogErrorSubsystem sub_system,
- LogErrorCode error_code)
- {
- const struct log_Error pkt{
- LOG_PACKET_HEADER_INIT(LOG_ERROR_MSG),
- time_us : AP_HAL::micros64(),
- sub_system : uint8_t(sub_system),
- error_code : uint8_t(error_code),
- };
- WriteCriticalBlock(&pkt, sizeof(pkt));
- }
- bool AP_Logger::log_while_disarmed(void) const
- {
- if (_force_log_disarmed) {
- return true;
- }
- if (_params.log_disarmed != 0) {
- return true;
- }
- uint32_t now = AP_HAL::millis();
- uint32_t persist_ms = HAL_LOGGER_ARM_PERSIST*1000U;
-
- const uint32_t arm_change_ms = hal.util->get_last_armed_change();
- if (!hal.util->get_soft_armed() && arm_change_ms != 0 && now - arm_change_ms < persist_ms) {
- return true;
- }
-
- if (_last_arming_failure_ms && now - _last_arming_failure_ms < persist_ms) {
- return true;
- }
- return false;
- }
- namespace AP {
- AP_Logger &logger()
- {
- return *AP_Logger::get_singleton();
- }
- };
|