mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: remove twin paths for writing FMT messages
This stops us tracking formats-written in two places. The Write() method will now emit formats as required and set the relevant bit in the backend-owned bitmask of formats sent.
This commit is contained in:
parent
64e859ecc5
commit
3208491983
|
@ -614,16 +614,6 @@ void AP_Logger::Write_MessageF(const char *fmt, ...)
|
|||
void AP_Logger::backend_starting_new_log(const AP_Logger_Backend *backend)
|
||||
{
|
||||
_log_start_count++;
|
||||
|
||||
for (uint8_t i=0; i<_next_backend; i++) {
|
||||
if (backends[i] == backend) { // pointer comparison!
|
||||
// reset sent masks
|
||||
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
|
||||
|
@ -950,12 +940,7 @@ void AP_Logger::Write_NamedValueFloat(const char *name, float value)
|
|||
void AP_Logger::Safe_Write_Emit_FMT(log_write_fmt *f)
|
||||
{
|
||||
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);
|
||||
}
|
||||
backends[i]->Safe_Write_Emit_FMT(f->msg_type);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1041,12 +1026,6 @@ void AP_Logger::WriteV(const char *name, const char *labels, const char *units,
|
|||
}
|
||||
|
||||
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, is_streaming);
|
||||
|
@ -1313,8 +1292,15 @@ int16_t AP_Logger::find_free_msg_type() const
|
|||
* It is assumed that logstruct's char* variables are valid strings of
|
||||
* maximum lengths for those fields (given in LogStructure.h e.g. LS_NAME_SIZE)
|
||||
*/
|
||||
bool AP_Logger::fill_log_write_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const
|
||||
bool AP_Logger::fill_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const
|
||||
{
|
||||
// check the static lists first...
|
||||
const LogStructure *found = structure_for_msg_type(msg_type);
|
||||
if (found != nullptr) {
|
||||
logstruct = *found;
|
||||
return true;
|
||||
}
|
||||
|
||||
// find log structure information corresponding to msg_type:
|
||||
struct log_write_fmt *f;
|
||||
for (f = log_write_fmts; f; f=f->next) {
|
||||
|
|
|
@ -382,7 +382,6 @@ public:
|
|||
struct log_write_fmt *next;
|
||||
uint8_t msg_type;
|
||||
uint8_t msg_len;
|
||||
uint8_t sent_mask; // bitmask of backends sent to
|
||||
const char *name;
|
||||
const char *fmt;
|
||||
const char *labels;
|
||||
|
@ -452,7 +451,7 @@ private:
|
|||
int16_t find_free_msg_type() const;
|
||||
|
||||
// fill LogStructure with information about msg_type
|
||||
bool fill_log_write_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const;
|
||||
bool fill_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const;
|
||||
|
||||
bool _armed;
|
||||
|
||||
|
|
|
@ -145,6 +145,15 @@ void AP_Logger_Backend::WriteMoreStartupMessages()
|
|||
*/
|
||||
|
||||
|
||||
// output a FMT message if not already done so
|
||||
void AP_Logger_Backend::Safe_Write_Emit_FMT(uint8_t msg_type)
|
||||
{
|
||||
if (have_emitted_format_for_type(LogMessages(msg_type))) {
|
||||
return;
|
||||
}
|
||||
Write_Emit_FMT(msg_type);
|
||||
}
|
||||
|
||||
bool AP_Logger_Backend::Write_Emit_FMT(uint8_t msg_type)
|
||||
{
|
||||
#if APM_BUILD_TYPE(APM_BUILD_Replay)
|
||||
|
@ -166,7 +175,7 @@ bool AP_Logger_Backend::Write_Emit_FMT(uint8_t msg_type)
|
|||
ls.units,
|
||||
ls.multipliers
|
||||
};
|
||||
if (!_front.fill_log_write_logstructure(logstruct, msg_type)) {
|
||||
if (!_front.fill_logstructure(logstruct, msg_type)) {
|
||||
// this is a bug; we've been asked to write out the FMT
|
||||
// message for a msg_type, but the frontend can't supply the
|
||||
// required information
|
||||
|
@ -393,28 +402,6 @@ void AP_Logger_Backend::validate_WritePrioritisedBlock(const void *pBuffer,
|
|||
}
|
||||
#endif
|
||||
|
||||
bool AP_Logger_Backend::emit_format_for_type(LogMessages a_type)
|
||||
{
|
||||
// linearly scan the formats structure to find the format for the type:
|
||||
for (uint8_t i=0; i< num_types(); i++) {
|
||||
const auto &s { structure(i) };
|
||||
if (s == nullptr) {
|
||||
continue;
|
||||
}
|
||||
if (s->msg_type != a_type) {
|
||||
continue;
|
||||
}
|
||||
// found the relevant structure. Attempt to write it:
|
||||
if (!Write_Format(s)) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
// didn't find the structure. That's probably bad...
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
|
||||
return false;
|
||||
}
|
||||
|
||||
bool AP_Logger_Backend::ensure_format_emitted(const void *pBuffer, uint16_t size)
|
||||
{
|
||||
#if APM_BUILD_TYPE(APM_BUILD_Replay)
|
||||
|
@ -437,11 +424,11 @@ bool AP_Logger_Backend::ensure_format_emitted(const void *pBuffer, uint16_t size
|
|||
return true;
|
||||
}
|
||||
if (!have_emitted_format_for_type(LOG_FORMAT_MSG) &&
|
||||
!emit_format_for_type(LOG_FORMAT_MSG)) {
|
||||
!Write_Emit_FMT(LOG_FORMAT_MSG)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return emit_format_for_type(type);
|
||||
return Write_Emit_FMT(type);
|
||||
}
|
||||
|
||||
bool AP_Logger_Backend::WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical, bool writev_streaming)
|
||||
|
|
|
@ -159,6 +159,9 @@ public:
|
|||
// Returns true if the FMT message has ever been written.
|
||||
bool Write_Emit_FMT(uint8_t msg_type);
|
||||
|
||||
// output a FMT message if not already done so
|
||||
void Safe_Write_Emit_FMT(uint8_t msg_type);
|
||||
|
||||
// write a log message out to the log of msg_type type, with
|
||||
// values contained in arg_list:
|
||||
bool Write(uint8_t msg_type, va_list arg_list, bool is_critical=false, bool is_streaming=false);
|
||||
|
|
Loading…
Reference in New Issue