@ -18,7 +18,7 @@
@@ -18,7 +18,7 @@
# include "MsgHandler.h"
# include "Replay.h"
# define DEBUG 0
# define DEBUG 1
# if DEBUG
# define debug(fmt, args...) printf(fmt "\n", ##args)
# else
@ -29,12 +29,19 @@
@@ -29,12 +29,19 @@
extern const AP_HAL : : HAL & hal ;
const struct LogStructure log_structure [ ] = {
const struct LogStructure running_codes_ log_structure[ ] = {
LOG_COMMON_STRUCTURES ,
} ;
LogReader : : LogReader ( AP_AHRS & _ahrs , AP_InertialSensor & _ins , Compass & _compass , AP_GPS & _gps ,
AP_Airspeed & _airspeed , DataFlash_Class & _dataflash , const char * * & _nottypes ) :
LogReader : : LogReader ( AP_AHRS & _ahrs ,
AP_InertialSensor & _ins ,
Compass & _compass ,
AP_GPS & _gps ,
AP_Airspeed & _airspeed ,
DataFlash_Class & _dataflash ,
struct LogStructure * log_structure ,
uint8_t log_structure_count ,
const char * * & _nottypes ) :
DataFlashFileReader ( ) ,
vehicle ( VehicleType : : VEHICLE_UNKNOWN ) ,
ahrs ( _ahrs ) ,
@ -47,8 +54,15 @@ LogReader::LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, Compass &_compass,
@@ -47,8 +54,15 @@ LogReader::LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, Compass &_compass,
gyro_mask ( 7 ) ,
last_timestamp_usec ( 0 ) ,
installed_vehicle_specific_parsers ( false ) ,
_log_structure ( log_structure ) ,
nottypes ( _nottypes )
{
if ( log_structure_count ! = 0 ) {
: : fprintf ( stderr , " Do NOT put anything in the log_structure before passing it in here " ) ;
abort ( ) ; // so there.
}
initialise_fmt_map ( ) ;
}
struct log_Format deferred_formats [ LOGREADER_MAX_FORMATS ] ;
@ -83,17 +97,53 @@ void LogReader::maybe_install_vehicle_specific_parsers() {
@@ -83,17 +97,53 @@ void LogReader::maybe_install_vehicle_specific_parsers() {
}
/*
messages which we will be generating , so should be discarded
messages which we will be generating , so should be discarded .
Additionally , FMT messages for messages NOT in this list will be
passed straight through to the output file , whereas FMT messages for
messages IN this list must come from LOG_BASE_STRUCTURES in
LogStructure . h
Note that there is an existing with FMTU messages , as these are
emitted both from the common structures at log startup and also when
Log_Write ( . . . ) is called for the first time for a particular format
name . Since we include it in generated_names FMTU messages will not
be passed through from the source logs - but since the Replay code
does call Log_Write ( . . . ) you will end up with a small selection of
FMTU messages from that .
*/
static const char * generated_names [ ] = { " EKF1 " , " EKF2 " , " EKF3 " , " EKF4 " , " EKF5 " ,
" NKF1 " , " NKF2 " , " NKF3 " , " NKF4 " , " NKF5 " ,
" NKF6 " , " NKF7 " , " NKF8 " , " NKF9 " , " NKF10 " ,
" AHR2 " , " POS " , " CHEK " ,
" IMT " , " IMT2 " ,
" MAG " , " MAG2 " ,
" BARO " , " BAR2 " ,
" GPS " , " GPA " ,
" NKA " , " NKV " , NULL } ;
static const char * generated_names [ ] = {
" FMT " ,
" FMTU " ,
" NKF1 " , " NKF2 " , " NKF3 " , " NKF4 " , " NKF5 " , " NKF6 " , " NKF7 " , " NKF8 " , " NKF9 " , " NKF0 " ,
" NKQ1 " , " NKQ2 " ,
" XKF1 " , " XKF2 " , " XKF3 " , " XKF4 " , " XKF5 " , " XKF6 " , " XKF7 " , " XKF8 " , " XKF9 " , " XKF0 " ,
" XKQ1 " , " XKQ2 " , " XKFD " , " XKV1 " , " XKV2 " ,
" AHR2 " ,
" ORGN " ,
" POS " ,
" CHEK " ,
" IMT " , " IMT2 " , " IMT3 " ,
" MAG " , " MAG2 " ,
" BARO " , " BAR2 " ,
" GPS " , " GPA " ,
NULL ,
} ;
// these names we emit from the code as normal, but are emitted using
// Log_Write. Thus they are not present in LOG_COMMON_STRUCTURES. A
// format will be written for this by the code itself the first time
// the message is emitted to the log. However, we must not write the
// messages from the old log to the new log, so we need to keep a map
// of IDs to prune out...
static const char * log_write_names [ ] = {
" NKA " ,
" NKV " ,
" NKT1 " ,
" NKT2 " ,
nullptr
} ;
/*
see if a type is in a list of types
@ -111,30 +161,78 @@ bool LogReader::in_list(const char *type, const char *list[])
@@ -111,30 +161,78 @@ bool LogReader::in_list(const char *type, const char *list[])
return false ;
}
void LogReader : : initialise_fmt_map ( )
{
for ( const char * * name = generated_names ;
* name ! = nullptr ;
name + + ) {
bool found = false ;
for ( uint8_t n = 0 ; n < ARRAY_SIZE ( running_codes_log_structure ) ; n + + ) {
if ( streq ( * name , running_codes_log_structure [ n ] . name ) ) {
const uint8_t t = running_codes_log_structure [ n ] . msg_type ;
mapped_msgid [ t ] = t ;
found = true ;
break ;
}
}
if ( ! found ) {
if ( streq ( * name , " CHEK " ) ) {
// HACK: CHEK is emitted using Log_Write, so doesn't
// have a fixed address to pre-populate the fmt-map
// with....
continue ;
}
: : fprintf ( stderr , " Failed to find apparently-generated-name (%s) in COMMON_LOG_STRUCTURES \n " , * name ) ;
abort ( ) ;
}
}
}
/*
map from an incoming format type to an outgoing format type
*/
uint8_t LogReader : : map_fmt_type ( const char * name , uint8_t intype )
{
if ( intype = = 128 ) {
// everybody's favourite FMT message...
return 128 ;
}
if ( mapped_msgid [ intype ] ! = 0 ) {
// already mapped
return mapped_msgid [ intype ] ;
}
// see if it is in our structure list
for ( uint8_t i = 0 ; i < ARRAY_SIZE ( log_structure ) ; i + + ) {
if ( strcmp ( name , log_structure [ i ] . name ) = = 0 ) {
mapped_msgid [ intype ] = log_structure [ i ] . msg_type ;
return mapped_msgid [ intype ] ;
for ( uint8_t n = next_msgid ; n < 255 ; n + + ) {
: : fprintf ( stderr , " next_msgid=%u \n " , next_msgid ) ;
bool already_mapped = false ;
for ( uint16_t i = 0 ; i < sizeof ( mapped_msgid ) ; i + + ) {
if ( mapped_msgid [ i ] = = n ) {
// already mapped - must be one of our generated names
already_mapped = true ;
break ;
}
}
if ( already_mapped ) {
continue ;
}
if ( DataFlash_Class : : instance ( ) - > msg_type_in_use ( n ) ) {
continue ;
}
mapped_msgid [ intype ] = n ;
next_msgid = n + 1 ;
break ;
}
// it is a new one, allocate an ID
mapped_msgid [ intype ] = next_msgid + + ;
if ( mapped_msgid [ intype ] = = 0 ) {
: : fprintf ( stderr , " mapping failed \n " ) ;
abort ( ) ;
}
return mapped_msgid [ intype ] ;
}
bool LogReader : : save_message_type ( const char * name )
{
bool save_message = ! in_list ( name , generated_names ) ;
save_message = save_message & & ! in_list ( name , log_write_names ) ;
if ( save_chek_messages & & strcmp ( name , " CHEK " ) = = 0 ) {
save_message = true ;
}
@ -148,22 +246,54 @@ bool LogReader::handle_log_format_msg(const struct log_Format &f)
@@ -148,22 +246,54 @@ bool LogReader::handle_log_format_msg(const struct log_Format &f)
memcpy ( name , f . name , 4 ) ;
debug ( " Defining log format for type (%d) (%s) \n " , f . type , name ) ;
if ( save_message_type ( name ) ) {
/*
any messages which we won ' t be generating internally in
replay should get the original FMT header
We need to remap the type in the FMT header to avoid
conflicts with our current table
*/
struct log_Format f_mapped = f ;
f_mapped . type = map_fmt_type ( name , f . type ) ;
dataflash . WriteBlock ( & f_mapped , sizeof ( f_mapped ) ) ;
}
struct LogStructure s = _log_structure [ _log_structure_count + + ] ;
dataflash . set_num_types ( _log_structure_count ) ;
if ( msgparser [ f . type ] ! = NULL ) {
return true ;
if ( in_list ( name , log_write_names ) ) {
debug ( " %s is a Log_Write-written message \n " , name ) ;
} else {
if ( in_list ( name , generated_names ) ) {
debug ( " Log format for type (%d) (%s) taken from running code \n " ,
f . type , name ) ;
bool found = false ;
for ( uint8_t n = 0 ; n < ARRAY_SIZE ( running_codes_log_structure ) ; n + + ) {
if ( streq ( name , running_codes_log_structure [ n ] . name ) ) {
found = true ;
memcpy ( & s , & running_codes_log_structure [ n ] , sizeof ( LogStructure ) ) ;
break ;
}
}
if ( ! found ) {
: : fprintf ( stderr , " Expected to be able to emit an FMT for (%s), but no FMT message found in running code \n " , name ) ;
abort ( ) ;
}
} else {
debug ( " Log format for type (%d) (%s) taken from log \n " , f . type , name ) ;
// generate a LogStructure entry for this FMT
s . msg_type = map_fmt_type ( name , f . type ) ;
s . msg_len = f . length ;
s . name = f . name ;
s . format = f . format ;
s . labels = f . labels ;
}
// emit the FMT to DataFlash:
struct log_Format pkt { } ;
pkt . head1 = HEAD_BYTE1 ;
pkt . head2 = HEAD_BYTE2 ;
pkt . msgid = LOG_FORMAT_MSG ;
pkt . type = s . msg_type ;
pkt . length = s . msg_len ;
strncpy ( pkt . name , s . name , sizeof ( pkt . name ) ) ;
strncpy ( pkt . format , s . format , sizeof ( pkt . format ) ) ;
strncpy ( pkt . labels , s . labels , sizeof ( pkt . labels ) ) ;
dataflash . WriteCriticalBlock ( & pkt , sizeof ( pkt ) ) ;
}
if ( msgparser [ f . type ] ! = NULL ) {
return true ;
}
// map from format name to a parser subclass:
if ( streq ( name , " PARM " ) ) {
msgparser [ f . type ] = new LR_MsgHandler_PARM
@ -281,6 +411,9 @@ bool LogReader::handle_msg(const struct log_Format &f, uint8_t *msg) {
@@ -281,6 +411,9 @@ bool LogReader::handle_msg(const struct log_Format &f, uint8_t *msg) {
memcpy ( name , f . name , 4 ) ;
if ( save_message_type ( name ) ) {
// write this message through to output log, changing the ID
// present in the input log to that used for the same message
// name in the output log
if ( mapped_msgid [ msg [ 2 ] ] = = 0 ) {
printf ( " Unknown msgid %u \n " , ( unsigned ) msg [ 2 ] ) ;
exit ( 1 ) ;
@ -350,28 +483,3 @@ bool LogReader::set_parameter(const char *name, float value)
@@ -350,28 +483,3 @@ bool LogReader::set_parameter(const char *name, float value)
}
return true ;
}
/*
called when the last FMT message has been processed
*/
void LogReader : : end_format_msgs ( void )
{
// write out any formats we will be producing
for ( uint8_t i = 0 ; generated_names [ i ] ; i + + ) {
for ( uint8_t n = 0 ; n < ARRAY_SIZE ( log_structure ) ; n + + ) {
if ( strcmp ( generated_names [ i ] , log_structure [ n ] . name ) = = 0 ) {
const struct LogStructure * s = & log_structure [ n ] ;
struct log_Format pkt { } ;
pkt . head1 = HEAD_BYTE1 ;
pkt . head2 = HEAD_BYTE2 ;
pkt . msgid = LOG_FORMAT_MSG ;
pkt . type = s - > msg_type ;
pkt . length = s - > msg_len ;
strncpy ( pkt . name , s - > name , sizeof ( pkt . name ) ) ;
strncpy ( pkt . format , s - > format , sizeof ( pkt . format ) ) ;
strncpy ( pkt . labels , s - > labels , sizeof ( pkt . labels ) ) ;
dataflash . WriteCriticalBlock ( & pkt , sizeof ( pkt ) ) ;
}
}
}
}