mirror of https://github.com/ArduPilot/ardupilot
Tools/Replay: rename datalogger to logger
This commit is contained in:
parent
c39cc7dbb8
commit
a8908e3c57
|
@ -5,9 +5,9 @@
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
LR_MsgHandler::LR_MsgHandler(struct log_Format &_f,
|
LR_MsgHandler::LR_MsgHandler(struct log_Format &_f,
|
||||||
AP_Logger &_dataflash,
|
AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec) :
|
uint64_t &_last_timestamp_usec) :
|
||||||
dataflash(_dataflash), last_timestamp_usec(_last_timestamp_usec),
|
logger(_logger), last_timestamp_usec(_last_timestamp_usec),
|
||||||
MsgHandler(_f) {
|
MsgHandler(_f) {
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -7,7 +7,7 @@
|
||||||
class LR_MsgHandler : public MsgHandler {
|
class LR_MsgHandler : public MsgHandler {
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler(struct log_Format &f,
|
LR_MsgHandler(struct log_Format &f,
|
||||||
AP_Logger &_dataflash,
|
AP_Logger &_logger,
|
||||||
uint64_t &last_timestamp_usec);
|
uint64_t &last_timestamp_usec);
|
||||||
virtual void process_message(uint8_t *msg) = 0;
|
virtual void process_message(uint8_t *msg) = 0;
|
||||||
|
|
||||||
|
@ -20,7 +20,7 @@ public:
|
||||||
};
|
};
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
AP_Logger &dataflash;
|
AP_Logger &logger;
|
||||||
void wait_timestamp(uint32_t timestamp);
|
void wait_timestamp(uint32_t timestamp);
|
||||||
void wait_timestamp_usec(uint64_t timestamp);
|
void wait_timestamp_usec(uint64_t timestamp);
|
||||||
void wait_timestamp_from_msg(uint8_t *msg);
|
void wait_timestamp_from_msg(uint8_t *msg);
|
||||||
|
@ -34,9 +34,9 @@ protected:
|
||||||
class LR_MsgHandler_AHR2 : public LR_MsgHandler
|
class LR_MsgHandler_AHR2 : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_AHR2(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_AHR2(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec, Vector3f &_ahr2_attitude)
|
uint64_t &_last_timestamp_usec, Vector3f &_ahr2_attitude)
|
||||||
: LR_MsgHandler(_f, _dataflash,_last_timestamp_usec),
|
: LR_MsgHandler(_f, _logger,_last_timestamp_usec),
|
||||||
ahr2_attitude(_ahr2_attitude) { };
|
ahr2_attitude(_ahr2_attitude) { };
|
||||||
|
|
||||||
virtual void process_message(uint8_t *msg);
|
virtual void process_message(uint8_t *msg);
|
||||||
|
@ -49,9 +49,9 @@ private:
|
||||||
class LR_MsgHandler_ARM : public LR_MsgHandler
|
class LR_MsgHandler_ARM : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_ARM(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_ARM(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec)
|
uint64_t &_last_timestamp_usec)
|
||||||
: LR_MsgHandler(_f, _dataflash, _last_timestamp_usec) { };
|
: LR_MsgHandler(_f, _logger, _last_timestamp_usec) { };
|
||||||
|
|
||||||
virtual void process_message(uint8_t *msg);
|
virtual void process_message(uint8_t *msg);
|
||||||
};
|
};
|
||||||
|
@ -60,9 +60,9 @@ public:
|
||||||
class LR_MsgHandler_ARSP : public LR_MsgHandler
|
class LR_MsgHandler_ARSP : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_ARSP(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_ARSP(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec, AP_Airspeed &_airspeed) :
|
uint64_t &_last_timestamp_usec, AP_Airspeed &_airspeed) :
|
||||||
LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), airspeed(_airspeed) { };
|
LR_MsgHandler(_f, _logger, _last_timestamp_usec), airspeed(_airspeed) { };
|
||||||
|
|
||||||
virtual void process_message(uint8_t *msg);
|
virtual void process_message(uint8_t *msg);
|
||||||
|
|
||||||
|
@ -73,9 +73,9 @@ private:
|
||||||
class LR_MsgHandler_NKF1 : public LR_MsgHandler
|
class LR_MsgHandler_NKF1 : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_NKF1(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_NKF1(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec) :
|
uint64_t &_last_timestamp_usec) :
|
||||||
LR_MsgHandler(_f, _dataflash, _last_timestamp_usec) { };
|
LR_MsgHandler(_f, _logger, _last_timestamp_usec) { };
|
||||||
|
|
||||||
virtual void process_message(uint8_t *msg);
|
virtual void process_message(uint8_t *msg);
|
||||||
};
|
};
|
||||||
|
@ -84,9 +84,9 @@ public:
|
||||||
class LR_MsgHandler_ATT : public LR_MsgHandler
|
class LR_MsgHandler_ATT : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_ATT(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_ATT(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec, Vector3f &_attitude)
|
uint64_t &_last_timestamp_usec, Vector3f &_attitude)
|
||||||
: LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), attitude(_attitude)
|
: LR_MsgHandler(_f, _logger, _last_timestamp_usec), attitude(_attitude)
|
||||||
{ };
|
{ };
|
||||||
virtual void process_message(uint8_t *msg);
|
virtual void process_message(uint8_t *msg);
|
||||||
|
|
||||||
|
@ -98,9 +98,9 @@ private:
|
||||||
class LR_MsgHandler_CHEK : public LR_MsgHandler
|
class LR_MsgHandler_CHEK : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_CHEK(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_CHEK(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec, CheckState &_check_state)
|
uint64_t &_last_timestamp_usec, CheckState &_check_state)
|
||||||
: LR_MsgHandler(_f, _dataflash, _last_timestamp_usec),
|
: LR_MsgHandler(_f, _logger, _last_timestamp_usec),
|
||||||
check_state(_check_state)
|
check_state(_check_state)
|
||||||
{ };
|
{ };
|
||||||
virtual void process_message(uint8_t *msg);
|
virtual void process_message(uint8_t *msg);
|
||||||
|
@ -112,9 +112,9 @@ private:
|
||||||
class LR_MsgHandler_BARO : public LR_MsgHandler
|
class LR_MsgHandler_BARO : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_BARO(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_BARO(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec)
|
uint64_t &_last_timestamp_usec)
|
||||||
: LR_MsgHandler(_f, _dataflash, _last_timestamp_usec)
|
: LR_MsgHandler(_f, _logger, _last_timestamp_usec)
|
||||||
{ };
|
{ };
|
||||||
|
|
||||||
virtual void process_message(uint8_t *msg);
|
virtual void process_message(uint8_t *msg);
|
||||||
|
@ -125,9 +125,9 @@ public:
|
||||||
class LR_MsgHandler_Event : public LR_MsgHandler
|
class LR_MsgHandler_Event : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_Event(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_Event(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec)
|
uint64_t &_last_timestamp_usec)
|
||||||
: LR_MsgHandler(_f, _dataflash, _last_timestamp_usec) { };
|
: LR_MsgHandler(_f, _logger, _last_timestamp_usec) { };
|
||||||
|
|
||||||
virtual void process_message(uint8_t *msg);
|
virtual void process_message(uint8_t *msg);
|
||||||
};
|
};
|
||||||
|
@ -139,10 +139,10 @@ class LR_MsgHandler_GPS_Base : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
|
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_GPS_Base(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_GPS_Base(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec, AP_GPS &_gps,
|
uint64_t &_last_timestamp_usec, AP_GPS &_gps,
|
||||||
uint32_t &_ground_alt_cm)
|
uint32_t &_ground_alt_cm)
|
||||||
: LR_MsgHandler(_f, _dataflash, _last_timestamp_usec),
|
: LR_MsgHandler(_f, _logger, _last_timestamp_usec),
|
||||||
gps(_gps), ground_alt_cm(_ground_alt_cm) { };
|
gps(_gps), ground_alt_cm(_ground_alt_cm) { };
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
@ -156,10 +156,10 @@ private:
|
||||||
class LR_MsgHandler_GPS : public LR_MsgHandler_GPS_Base
|
class LR_MsgHandler_GPS : public LR_MsgHandler_GPS_Base
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_GPS(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_GPS(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec, AP_GPS &_gps,
|
uint64_t &_last_timestamp_usec, AP_GPS &_gps,
|
||||||
uint32_t &_ground_alt_cm)
|
uint32_t &_ground_alt_cm)
|
||||||
: LR_MsgHandler_GPS_Base(_f, _dataflash,_last_timestamp_usec,
|
: LR_MsgHandler_GPS_Base(_f, _logger,_last_timestamp_usec,
|
||||||
_gps, _ground_alt_cm),
|
_gps, _ground_alt_cm),
|
||||||
gps(_gps), ground_alt_cm(_ground_alt_cm) { };
|
gps(_gps), ground_alt_cm(_ground_alt_cm) { };
|
||||||
|
|
||||||
|
@ -177,10 +177,10 @@ private:
|
||||||
class LR_MsgHandler_GPS2 : public LR_MsgHandler_GPS_Base
|
class LR_MsgHandler_GPS2 : public LR_MsgHandler_GPS_Base
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_GPS2(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_GPS2(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec, AP_GPS &_gps,
|
uint64_t &_last_timestamp_usec, AP_GPS &_gps,
|
||||||
uint32_t &_ground_alt_cm)
|
uint32_t &_ground_alt_cm)
|
||||||
: LR_MsgHandler_GPS_Base(_f, _dataflash, _last_timestamp_usec,
|
: LR_MsgHandler_GPS_Base(_f, _logger, _last_timestamp_usec,
|
||||||
_gps, _ground_alt_cm), gps(_gps),
|
_gps, _ground_alt_cm), gps(_gps),
|
||||||
ground_alt_cm(_ground_alt_cm) { };
|
ground_alt_cm(_ground_alt_cm) { };
|
||||||
virtual void process_message(uint8_t *msg);
|
virtual void process_message(uint8_t *msg);
|
||||||
|
@ -193,9 +193,9 @@ class LR_MsgHandler_GPA_Base : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
|
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_GPA_Base(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_GPA_Base(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec, AP_GPS &_gps)
|
uint64_t &_last_timestamp_usec, AP_GPS &_gps)
|
||||||
: LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), gps(_gps) { };
|
: LR_MsgHandler(_f, _logger, _last_timestamp_usec), gps(_gps) { };
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
void update_from_msg_gpa(uint8_t imu_offset, uint8_t *data);
|
void update_from_msg_gpa(uint8_t imu_offset, uint8_t *data);
|
||||||
|
@ -208,9 +208,9 @@ private:
|
||||||
class LR_MsgHandler_GPA : public LR_MsgHandler_GPA_Base
|
class LR_MsgHandler_GPA : public LR_MsgHandler_GPA_Base
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_GPA(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_GPA(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec, AP_GPS &_gps)
|
uint64_t &_last_timestamp_usec, AP_GPS &_gps)
|
||||||
: LR_MsgHandler_GPA_Base(_f, _dataflash,_last_timestamp_usec,
|
: LR_MsgHandler_GPA_Base(_f, _logger,_last_timestamp_usec,
|
||||||
_gps), gps(_gps) { };
|
_gps), gps(_gps) { };
|
||||||
|
|
||||||
void process_message(uint8_t *msg);
|
void process_message(uint8_t *msg);
|
||||||
|
@ -222,9 +222,9 @@ private:
|
||||||
class LR_MsgHandler_GPA2 : public LR_MsgHandler_GPA_Base
|
class LR_MsgHandler_GPA2 : public LR_MsgHandler_GPA_Base
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_GPA2(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_GPA2(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec, AP_GPS &_gps)
|
uint64_t &_last_timestamp_usec, AP_GPS &_gps)
|
||||||
: LR_MsgHandler_GPA_Base(_f, _dataflash, _last_timestamp_usec,
|
: LR_MsgHandler_GPA_Base(_f, _logger, _last_timestamp_usec,
|
||||||
_gps), gps(_gps) { };
|
_gps), gps(_gps) { };
|
||||||
virtual void process_message(uint8_t *msg);
|
virtual void process_message(uint8_t *msg);
|
||||||
private:
|
private:
|
||||||
|
@ -238,11 +238,11 @@ private:
|
||||||
class LR_MsgHandler_IMU_Base : public LR_MsgHandler
|
class LR_MsgHandler_IMU_Base : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_IMU_Base(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_IMU_Base(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec,
|
uint64_t &_last_timestamp_usec,
|
||||||
uint8_t &_accel_mask, uint8_t &_gyro_mask,
|
uint8_t &_accel_mask, uint8_t &_gyro_mask,
|
||||||
AP_InertialSensor &_ins) :
|
AP_InertialSensor &_ins) :
|
||||||
LR_MsgHandler(_f, _dataflash, _last_timestamp_usec),
|
LR_MsgHandler(_f, _logger, _last_timestamp_usec),
|
||||||
accel_mask(_accel_mask),
|
accel_mask(_accel_mask),
|
||||||
gyro_mask(_gyro_mask),
|
gyro_mask(_gyro_mask),
|
||||||
ins(_ins) { };
|
ins(_ins) { };
|
||||||
|
@ -257,11 +257,11 @@ private:
|
||||||
class LR_MsgHandler_IMU : public LR_MsgHandler_IMU_Base
|
class LR_MsgHandler_IMU : public LR_MsgHandler_IMU_Base
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_IMU(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_IMU(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec,
|
uint64_t &_last_timestamp_usec,
|
||||||
uint8_t &_accel_mask, uint8_t &_gyro_mask,
|
uint8_t &_accel_mask, uint8_t &_gyro_mask,
|
||||||
AP_InertialSensor &_ins)
|
AP_InertialSensor &_ins)
|
||||||
: LR_MsgHandler_IMU_Base(_f, _dataflash, _last_timestamp_usec,
|
: LR_MsgHandler_IMU_Base(_f, _logger, _last_timestamp_usec,
|
||||||
_accel_mask, _gyro_mask, _ins) { };
|
_accel_mask, _gyro_mask, _ins) { };
|
||||||
|
|
||||||
void process_message(uint8_t *msg);
|
void process_message(uint8_t *msg);
|
||||||
|
@ -270,11 +270,11 @@ public:
|
||||||
class LR_MsgHandler_IMU2 : public LR_MsgHandler_IMU_Base
|
class LR_MsgHandler_IMU2 : public LR_MsgHandler_IMU_Base
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_IMU2(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_IMU2(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec,
|
uint64_t &_last_timestamp_usec,
|
||||||
uint8_t &_accel_mask, uint8_t &_gyro_mask,
|
uint8_t &_accel_mask, uint8_t &_gyro_mask,
|
||||||
AP_InertialSensor &_ins)
|
AP_InertialSensor &_ins)
|
||||||
: LR_MsgHandler_IMU_Base(_f, _dataflash, _last_timestamp_usec,
|
: LR_MsgHandler_IMU_Base(_f, _logger, _last_timestamp_usec,
|
||||||
_accel_mask, _gyro_mask, _ins) {};
|
_accel_mask, _gyro_mask, _ins) {};
|
||||||
|
|
||||||
virtual void process_message(uint8_t *msg);
|
virtual void process_message(uint8_t *msg);
|
||||||
|
@ -283,11 +283,11 @@ public:
|
||||||
class LR_MsgHandler_IMU3 : public LR_MsgHandler_IMU_Base
|
class LR_MsgHandler_IMU3 : public LR_MsgHandler_IMU_Base
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_IMU3(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_IMU3(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec,
|
uint64_t &_last_timestamp_usec,
|
||||||
uint8_t &_accel_mask, uint8_t &_gyro_mask,
|
uint8_t &_accel_mask, uint8_t &_gyro_mask,
|
||||||
AP_InertialSensor &_ins)
|
AP_InertialSensor &_ins)
|
||||||
: LR_MsgHandler_IMU_Base(_f, _dataflash, _last_timestamp_usec,
|
: LR_MsgHandler_IMU_Base(_f, _logger, _last_timestamp_usec,
|
||||||
_accel_mask, _gyro_mask, _ins) {};
|
_accel_mask, _gyro_mask, _ins) {};
|
||||||
|
|
||||||
virtual void process_message(uint8_t *msg);
|
virtual void process_message(uint8_t *msg);
|
||||||
|
@ -297,12 +297,12 @@ public:
|
||||||
class LR_MsgHandler_IMT_Base : public LR_MsgHandler
|
class LR_MsgHandler_IMT_Base : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_IMT_Base(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_IMT_Base(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec,
|
uint64_t &_last_timestamp_usec,
|
||||||
uint8_t &_accel_mask, uint8_t &_gyro_mask,
|
uint8_t &_accel_mask, uint8_t &_gyro_mask,
|
||||||
bool &_use_imt,
|
bool &_use_imt,
|
||||||
AP_InertialSensor &_ins) :
|
AP_InertialSensor &_ins) :
|
||||||
LR_MsgHandler(_f, _dataflash, _last_timestamp_usec),
|
LR_MsgHandler(_f, _logger, _last_timestamp_usec),
|
||||||
accel_mask(_accel_mask),
|
accel_mask(_accel_mask),
|
||||||
gyro_mask(_gyro_mask),
|
gyro_mask(_gyro_mask),
|
||||||
use_imt(_use_imt),
|
use_imt(_use_imt),
|
||||||
|
@ -319,12 +319,12 @@ private:
|
||||||
class LR_MsgHandler_IMT : public LR_MsgHandler_IMT_Base
|
class LR_MsgHandler_IMT : public LR_MsgHandler_IMT_Base
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_IMT(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_IMT(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec,
|
uint64_t &_last_timestamp_usec,
|
||||||
uint8_t &_accel_mask, uint8_t &_gyro_mask,
|
uint8_t &_accel_mask, uint8_t &_gyro_mask,
|
||||||
bool &_use_imt,
|
bool &_use_imt,
|
||||||
AP_InertialSensor &_ins)
|
AP_InertialSensor &_ins)
|
||||||
: LR_MsgHandler_IMT_Base(_f, _dataflash, _last_timestamp_usec,
|
: LR_MsgHandler_IMT_Base(_f, _logger, _last_timestamp_usec,
|
||||||
_accel_mask, _gyro_mask, _use_imt, _ins) { };
|
_accel_mask, _gyro_mask, _use_imt, _ins) { };
|
||||||
|
|
||||||
void process_message(uint8_t *msg);
|
void process_message(uint8_t *msg);
|
||||||
|
@ -333,12 +333,12 @@ public:
|
||||||
class LR_MsgHandler_IMT2 : public LR_MsgHandler_IMT_Base
|
class LR_MsgHandler_IMT2 : public LR_MsgHandler_IMT_Base
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_IMT2(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_IMT2(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec,
|
uint64_t &_last_timestamp_usec,
|
||||||
uint8_t &_accel_mask, uint8_t &_gyro_mask,
|
uint8_t &_accel_mask, uint8_t &_gyro_mask,
|
||||||
bool &_use_imt,
|
bool &_use_imt,
|
||||||
AP_InertialSensor &_ins)
|
AP_InertialSensor &_ins)
|
||||||
: LR_MsgHandler_IMT_Base(_f, _dataflash, _last_timestamp_usec,
|
: LR_MsgHandler_IMT_Base(_f, _logger, _last_timestamp_usec,
|
||||||
_accel_mask, _gyro_mask, _use_imt, _ins) { };
|
_accel_mask, _gyro_mask, _use_imt, _ins) { };
|
||||||
|
|
||||||
void process_message(uint8_t *msg);
|
void process_message(uint8_t *msg);
|
||||||
|
@ -347,12 +347,12 @@ public:
|
||||||
class LR_MsgHandler_IMT3 : public LR_MsgHandler_IMT_Base
|
class LR_MsgHandler_IMT3 : public LR_MsgHandler_IMT_Base
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_IMT3(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_IMT3(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec,
|
uint64_t &_last_timestamp_usec,
|
||||||
uint8_t &_accel_mask, uint8_t &_gyro_mask,
|
uint8_t &_accel_mask, uint8_t &_gyro_mask,
|
||||||
bool &_use_imt,
|
bool &_use_imt,
|
||||||
AP_InertialSensor &_ins)
|
AP_InertialSensor &_ins)
|
||||||
: LR_MsgHandler_IMT_Base(_f, _dataflash, _last_timestamp_usec,
|
: LR_MsgHandler_IMT_Base(_f, _logger, _last_timestamp_usec,
|
||||||
_accel_mask, _gyro_mask, _use_imt, _ins) { };
|
_accel_mask, _gyro_mask, _use_imt, _ins) { };
|
||||||
|
|
||||||
void process_message(uint8_t *msg);
|
void process_message(uint8_t *msg);
|
||||||
|
@ -362,9 +362,9 @@ public:
|
||||||
class LR_MsgHandler_MAG_Base : public LR_MsgHandler
|
class LR_MsgHandler_MAG_Base : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_MAG_Base(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_MAG_Base(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec, Compass &_compass)
|
uint64_t &_last_timestamp_usec, Compass &_compass)
|
||||||
: LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), compass(_compass) { };
|
: LR_MsgHandler(_f, _logger, _last_timestamp_usec), compass(_compass) { };
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
void update_from_msg_compass(uint8_t compass_offset, uint8_t *msg);
|
void update_from_msg_compass(uint8_t compass_offset, uint8_t *msg);
|
||||||
|
@ -376,9 +376,9 @@ private:
|
||||||
class LR_MsgHandler_MAG : public LR_MsgHandler_MAG_Base
|
class LR_MsgHandler_MAG : public LR_MsgHandler_MAG_Base
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_MAG(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_MAG(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec, Compass &_compass)
|
uint64_t &_last_timestamp_usec, Compass &_compass)
|
||||||
: LR_MsgHandler_MAG_Base(_f, _dataflash, _last_timestamp_usec,_compass) {};
|
: LR_MsgHandler_MAG_Base(_f, _logger, _last_timestamp_usec,_compass) {};
|
||||||
|
|
||||||
virtual void process_message(uint8_t *msg);
|
virtual void process_message(uint8_t *msg);
|
||||||
};
|
};
|
||||||
|
@ -386,9 +386,9 @@ public:
|
||||||
class LR_MsgHandler_MAG2 : public LR_MsgHandler_MAG_Base
|
class LR_MsgHandler_MAG2 : public LR_MsgHandler_MAG_Base
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_MAG2(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_MAG2(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec, Compass &_compass)
|
uint64_t &_last_timestamp_usec, Compass &_compass)
|
||||||
: LR_MsgHandler_MAG_Base(_f, _dataflash, _last_timestamp_usec,_compass) {};
|
: LR_MsgHandler_MAG_Base(_f, _logger, _last_timestamp_usec,_compass) {};
|
||||||
|
|
||||||
virtual void process_message(uint8_t *msg);
|
virtual void process_message(uint8_t *msg);
|
||||||
};
|
};
|
||||||
|
@ -398,10 +398,10 @@ public:
|
||||||
class LR_MsgHandler_MSG : public LR_MsgHandler
|
class LR_MsgHandler_MSG : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_MSG(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_MSG(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec,
|
uint64_t &_last_timestamp_usec,
|
||||||
VehicleType::vehicle_type &_vehicle, AP_AHRS &_ahrs) :
|
VehicleType::vehicle_type &_vehicle, AP_AHRS &_ahrs) :
|
||||||
LR_MsgHandler(_f, _dataflash, _last_timestamp_usec),
|
LR_MsgHandler(_f, _logger, _last_timestamp_usec),
|
||||||
vehicle(_vehicle), ahrs(_ahrs) { }
|
vehicle(_vehicle), ahrs(_ahrs) { }
|
||||||
|
|
||||||
|
|
||||||
|
@ -416,9 +416,9 @@ private:
|
||||||
class LR_MsgHandler_NTUN_Copter : public LR_MsgHandler
|
class LR_MsgHandler_NTUN_Copter : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_NTUN_Copter(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_NTUN_Copter(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec, Vector3f &_inavpos)
|
uint64_t &_last_timestamp_usec, Vector3f &_inavpos)
|
||||||
: LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), inavpos(_inavpos) {};
|
: LR_MsgHandler(_f, _logger, _last_timestamp_usec), inavpos(_inavpos) {};
|
||||||
|
|
||||||
virtual void process_message(uint8_t *msg);
|
virtual void process_message(uint8_t *msg);
|
||||||
|
|
||||||
|
@ -430,10 +430,10 @@ private:
|
||||||
class LR_MsgHandler_PARM : public LR_MsgHandler
|
class LR_MsgHandler_PARM : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_PARM(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_PARM(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec,
|
uint64_t &_last_timestamp_usec,
|
||||||
const std::function<bool(const char *name, const float)>&set_parameter_callback) :
|
const std::function<bool(const char *name, const float)>&set_parameter_callback) :
|
||||||
LR_MsgHandler(_f, _dataflash, _last_timestamp_usec),
|
LR_MsgHandler(_f, _logger, _last_timestamp_usec),
|
||||||
_set_parameter_callback(set_parameter_callback)
|
_set_parameter_callback(set_parameter_callback)
|
||||||
{};
|
{};
|
||||||
|
|
||||||
|
@ -447,9 +447,9 @@ private:
|
||||||
class LR_MsgHandler_PM : public LR_MsgHandler
|
class LR_MsgHandler_PM : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_PM(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_PM(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec)
|
uint64_t &_last_timestamp_usec)
|
||||||
: LR_MsgHandler(_f, _dataflash, _last_timestamp_usec) { };
|
: LR_MsgHandler(_f, _logger, _last_timestamp_usec) { };
|
||||||
|
|
||||||
virtual void process_message(uint8_t *msg);
|
virtual void process_message(uint8_t *msg);
|
||||||
|
|
||||||
|
@ -460,10 +460,10 @@ private:
|
||||||
class LR_MsgHandler_SIM : public LR_MsgHandler
|
class LR_MsgHandler_SIM : public LR_MsgHandler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LR_MsgHandler_SIM(log_Format &_f, AP_Logger &_dataflash,
|
LR_MsgHandler_SIM(log_Format &_f, AP_Logger &_logger,
|
||||||
uint64_t &_last_timestamp_usec,
|
uint64_t &_last_timestamp_usec,
|
||||||
Vector3f &_sim_attitude)
|
Vector3f &_sim_attitude)
|
||||||
: LR_MsgHandler(_f, _dataflash, _last_timestamp_usec),
|
: LR_MsgHandler(_f, _logger, _last_timestamp_usec),
|
||||||
sim_attitude(_sim_attitude)
|
sim_attitude(_sim_attitude)
|
||||||
{ };
|
{ };
|
||||||
|
|
||||||
|
|
|
@ -38,7 +38,7 @@ LogReader::LogReader(AP_AHRS &_ahrs,
|
||||||
Compass &_compass,
|
Compass &_compass,
|
||||||
AP_GPS &_gps,
|
AP_GPS &_gps,
|
||||||
AP_Airspeed &_airspeed,
|
AP_Airspeed &_airspeed,
|
||||||
AP_Logger &_dataflash,
|
AP_Logger &_logger,
|
||||||
struct LogStructure *log_structure,
|
struct LogStructure *log_structure,
|
||||||
uint8_t log_structure_count,
|
uint8_t log_structure_count,
|
||||||
const char **&_nottypes):
|
const char **&_nottypes):
|
||||||
|
@ -49,7 +49,7 @@ LogReader::LogReader(AP_AHRS &_ahrs,
|
||||||
compass(_compass),
|
compass(_compass),
|
||||||
gps(_gps),
|
gps(_gps),
|
||||||
airspeed(_airspeed),
|
airspeed(_airspeed),
|
||||||
dataflash(_dataflash),
|
logger(_logger),
|
||||||
accel_mask(7),
|
accel_mask(7),
|
||||||
gyro_mask(7),
|
gyro_mask(7),
|
||||||
last_timestamp_usec(0),
|
last_timestamp_usec(0),
|
||||||
|
@ -80,7 +80,7 @@ void LogReader::maybe_install_vehicle_specific_parsers() {
|
||||||
for (uint8_t i = 0; i<LOGREADER_MAX_FORMATS; i++) {
|
for (uint8_t i = 0; i<LOGREADER_MAX_FORMATS; i++) {
|
||||||
if (deferred_formats[i].type != 0) {
|
if (deferred_formats[i].type != 0) {
|
||||||
msgparser[i] = new LR_MsgHandler_NTUN_Copter
|
msgparser[i] = new LR_MsgHandler_NTUN_Copter
|
||||||
(deferred_formats[i], dataflash, last_timestamp_usec,
|
(deferred_formats[i], logger, last_timestamp_usec,
|
||||||
inavpos);
|
inavpos);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -247,7 +247,7 @@ bool LogReader::handle_log_format_msg(const struct log_Format &f)
|
||||||
debug("Defining log format for type (%d) (%s)\n", f.type, name);
|
debug("Defining log format for type (%d) (%s)\n", f.type, name);
|
||||||
|
|
||||||
struct LogStructure s = _log_structure[_log_structure_count++];
|
struct LogStructure s = _log_structure[_log_structure_count++];
|
||||||
dataflash.set_num_types(_log_structure_count);
|
logger.set_num_types(_log_structure_count);
|
||||||
|
|
||||||
if (in_list(name, log_write_names)) {
|
if (in_list(name, log_write_names)) {
|
||||||
debug("%s is a Log_Write-written message\n", name);
|
debug("%s is a Log_Write-written message\n", name);
|
||||||
|
@ -287,7 +287,7 @@ bool LogReader::handle_log_format_msg(const struct log_Format &f)
|
||||||
strncpy(pkt.name, s.name, sizeof(pkt.name));
|
strncpy(pkt.name, s.name, sizeof(pkt.name));
|
||||||
strncpy(pkt.format, s.format, sizeof(pkt.format));
|
strncpy(pkt.format, s.format, sizeof(pkt.format));
|
||||||
strncpy(pkt.labels, s.labels, sizeof(pkt.labels));
|
strncpy(pkt.labels, s.labels, sizeof(pkt.labels));
|
||||||
dataflash.WriteCriticalBlock(&pkt, sizeof(pkt));
|
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
|
||||||
if (msgparser[f.type] != NULL) {
|
if (msgparser[f.type] != NULL) {
|
||||||
|
@ -297,85 +297,85 @@ bool LogReader::handle_log_format_msg(const struct log_Format &f)
|
||||||
// map from format name to a parser subclass:
|
// map from format name to a parser subclass:
|
||||||
if (streq(name, "PARM")) {
|
if (streq(name, "PARM")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_PARM
|
msgparser[f.type] = new LR_MsgHandler_PARM
|
||||||
(formats[f.type], dataflash,
|
(formats[f.type], logger,
|
||||||
last_timestamp_usec,
|
last_timestamp_usec,
|
||||||
[this](const char *xname, const float xvalue) {
|
[this](const char *xname, const float xvalue) {
|
||||||
return set_parameter(xname, xvalue);
|
return set_parameter(xname, xvalue);
|
||||||
});
|
});
|
||||||
} else if (streq(name, "GPS")) {
|
} else if (streq(name, "GPS")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_GPS(formats[f.type],
|
msgparser[f.type] = new LR_MsgHandler_GPS(formats[f.type],
|
||||||
dataflash,
|
logger,
|
||||||
last_timestamp_usec,
|
last_timestamp_usec,
|
||||||
gps, ground_alt_cm);
|
gps, ground_alt_cm);
|
||||||
} else if (streq(name, "GPS2")) {
|
} else if (streq(name, "GPS2")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_GPS2(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_GPS2(formats[f.type], logger,
|
||||||
last_timestamp_usec,
|
last_timestamp_usec,
|
||||||
gps, ground_alt_cm);
|
gps, ground_alt_cm);
|
||||||
} else if (streq(name, "GPA")) {
|
} else if (streq(name, "GPA")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_GPA(formats[f.type],
|
msgparser[f.type] = new LR_MsgHandler_GPA(formats[f.type],
|
||||||
dataflash,
|
logger,
|
||||||
last_timestamp_usec,
|
last_timestamp_usec,
|
||||||
gps);
|
gps);
|
||||||
} else if (streq(name, "GPA2")) {
|
} else if (streq(name, "GPA2")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_GPA2(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_GPA2(formats[f.type], logger,
|
||||||
last_timestamp_usec,
|
last_timestamp_usec,
|
||||||
gps);
|
gps);
|
||||||
} else if (streq(name, "MSG")) {
|
} else if (streq(name, "MSG")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_MSG(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_MSG(formats[f.type], logger,
|
||||||
last_timestamp_usec,
|
last_timestamp_usec,
|
||||||
vehicle, ahrs);
|
vehicle, ahrs);
|
||||||
} else if (streq(name, "IMU")) {
|
} else if (streq(name, "IMU")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_IMU(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_IMU(formats[f.type], logger,
|
||||||
last_timestamp_usec,
|
last_timestamp_usec,
|
||||||
accel_mask, gyro_mask, ins);
|
accel_mask, gyro_mask, ins);
|
||||||
} else if (streq(name, "IMU2")) {
|
} else if (streq(name, "IMU2")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_IMU2(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_IMU2(formats[f.type], logger,
|
||||||
last_timestamp_usec,
|
last_timestamp_usec,
|
||||||
accel_mask, gyro_mask, ins);
|
accel_mask, gyro_mask, ins);
|
||||||
} else if (streq(name, "IMU3")) {
|
} else if (streq(name, "IMU3")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_IMU3(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_IMU3(formats[f.type], logger,
|
||||||
last_timestamp_usec,
|
last_timestamp_usec,
|
||||||
accel_mask, gyro_mask, ins);
|
accel_mask, gyro_mask, ins);
|
||||||
} else if (streq(name, "IMT")) {
|
} else if (streq(name, "IMT")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_IMT(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_IMT(formats[f.type], logger,
|
||||||
last_timestamp_usec,
|
last_timestamp_usec,
|
||||||
accel_mask, gyro_mask, use_imt, ins);
|
accel_mask, gyro_mask, use_imt, ins);
|
||||||
} else if (streq(name, "IMT2")) {
|
} else if (streq(name, "IMT2")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_IMT2(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_IMT2(formats[f.type], logger,
|
||||||
last_timestamp_usec,
|
last_timestamp_usec,
|
||||||
accel_mask, gyro_mask, use_imt, ins);
|
accel_mask, gyro_mask, use_imt, ins);
|
||||||
} else if (streq(name, "IMT3")) {
|
} else if (streq(name, "IMT3")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_IMT3(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_IMT3(formats[f.type], logger,
|
||||||
last_timestamp_usec,
|
last_timestamp_usec,
|
||||||
accel_mask, gyro_mask, use_imt, ins);
|
accel_mask, gyro_mask, use_imt, ins);
|
||||||
} else if (streq(name, "SIM")) {
|
} else if (streq(name, "SIM")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_SIM(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_SIM(formats[f.type], logger,
|
||||||
last_timestamp_usec,
|
last_timestamp_usec,
|
||||||
sim_attitude);
|
sim_attitude);
|
||||||
} else if (streq(name, "BARO")) {
|
} else if (streq(name, "BARO")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_BARO(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_BARO(formats[f.type], logger,
|
||||||
last_timestamp_usec);
|
last_timestamp_usec);
|
||||||
} else if (streq(name, "ARM")) {
|
} else if (streq(name, "ARM")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_ARM(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_ARM(formats[f.type], logger,
|
||||||
last_timestamp_usec);
|
last_timestamp_usec);
|
||||||
} else if (streq(name, "EV")) {
|
} else if (streq(name, "EV")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_Event(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_Event(formats[f.type], logger,
|
||||||
last_timestamp_usec);
|
last_timestamp_usec);
|
||||||
} else if (streq(name, "AHR2")) {
|
} else if (streq(name, "AHR2")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_AHR2(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_AHR2(formats[f.type], logger,
|
||||||
last_timestamp_usec,
|
last_timestamp_usec,
|
||||||
ahr2_attitude);
|
ahr2_attitude);
|
||||||
} else if (streq(name, "ATT")) {
|
} else if (streq(name, "ATT")) {
|
||||||
// this parser handles *all* attitude messages - the common one,
|
// this parser handles *all* attitude messages - the common one,
|
||||||
// and also the rover/copter/plane-specific (old) messages
|
// and also the rover/copter/plane-specific (old) messages
|
||||||
msgparser[f.type] = new LR_MsgHandler_ATT(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_ATT(formats[f.type], logger,
|
||||||
last_timestamp_usec,
|
last_timestamp_usec,
|
||||||
attitude);
|
attitude);
|
||||||
} else if (streq(name, "MAG")) {
|
} else if (streq(name, "MAG")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_MAG(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_MAG(formats[f.type], logger,
|
||||||
last_timestamp_usec, compass);
|
last_timestamp_usec, compass);
|
||||||
} else if (streq(name, "MAG2")) {
|
} else if (streq(name, "MAG2")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_MAG2(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_MAG2(formats[f.type], logger,
|
||||||
last_timestamp_usec, compass);
|
last_timestamp_usec, compass);
|
||||||
} else if (streq(name, "NTUN")) {
|
} else if (streq(name, "NTUN")) {
|
||||||
// the label "NTUN" is used by rover, copter and plane -
|
// the label "NTUN" is used by rover, copter and plane -
|
||||||
|
@ -385,18 +385,18 @@ bool LogReader::handle_log_format_msg(const struct log_Format &f)
|
||||||
memcpy(&deferred_formats[f.type], &formats[f.type],
|
memcpy(&deferred_formats[f.type], &formats[f.type],
|
||||||
sizeof(struct log_Format));
|
sizeof(struct log_Format));
|
||||||
} else if (streq(name, "ARSP")) { // plane-specific(?!)
|
} else if (streq(name, "ARSP")) { // plane-specific(?!)
|
||||||
msgparser[f.type] = new LR_MsgHandler_ARSP(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_ARSP(formats[f.type], logger,
|
||||||
last_timestamp_usec,
|
last_timestamp_usec,
|
||||||
airspeed);
|
airspeed);
|
||||||
} else if (streq(name, "NKF1")) {
|
} else if (streq(name, "NKF1")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_NKF1(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_NKF1(formats[f.type], logger,
|
||||||
last_timestamp_usec);
|
last_timestamp_usec);
|
||||||
} else if (streq(name, "CHEK")) {
|
} else if (streq(name, "CHEK")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_CHEK(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_CHEK(formats[f.type], logger,
|
||||||
last_timestamp_usec,
|
last_timestamp_usec,
|
||||||
check_state);
|
check_state);
|
||||||
} else if (streq(name, "PM")) {
|
} else if (streq(name, "PM")) {
|
||||||
msgparser[f.type] = new LR_MsgHandler_PM(formats[f.type], dataflash,
|
msgparser[f.type] = new LR_MsgHandler_PM(formats[f.type], logger,
|
||||||
last_timestamp_usec);
|
last_timestamp_usec);
|
||||||
} else {
|
} else {
|
||||||
debug(" No parser for (%s)\n", name);
|
debug(" No parser for (%s)\n", name);
|
||||||
|
@ -420,10 +420,10 @@ bool LogReader::handle_msg(const struct log_Format &f, uint8_t *msg) {
|
||||||
}
|
}
|
||||||
msg[2] = mapped_msgid[msg[2]];
|
msg[2] = mapped_msgid[msg[2]];
|
||||||
if (!in_list(name, nottypes)) {
|
if (!in_list(name, nottypes)) {
|
||||||
dataflash.WriteBlock(msg, f.length);
|
logger.WriteBlock(msg, f.length);
|
||||||
}
|
}
|
||||||
// a MsgHandler would probably have found a timestamp and
|
// a MsgHandler would probably have found a timestamp and
|
||||||
// caled stop_clock. This runs IO, clearing dataflash's
|
// caled stop_clock. This runs IO, clearing logger's
|
||||||
// buffer.
|
// buffer.
|
||||||
hal.scheduler->stop_clock(last_timestamp_usec);
|
hal.scheduler->stop_clock(last_timestamp_usec);
|
||||||
}
|
}
|
||||||
|
|
|
@ -11,7 +11,7 @@ public:
|
||||||
Compass &_compass,
|
Compass &_compass,
|
||||||
AP_GPS &_gps,
|
AP_GPS &_gps,
|
||||||
AP_Airspeed &_airspeed,
|
AP_Airspeed &_airspeed,
|
||||||
AP_Logger &_dataflash,
|
AP_Logger &_logger,
|
||||||
struct LogStructure *log_structure,
|
struct LogStructure *log_structure,
|
||||||
uint8_t log_structure_count,
|
uint8_t log_structure_count,
|
||||||
const char **¬types);
|
const char **¬types);
|
||||||
|
@ -47,7 +47,7 @@ private:
|
||||||
Compass &compass;
|
Compass &compass;
|
||||||
AP_GPS &gps;
|
AP_GPS &gps;
|
||||||
AP_Airspeed &airspeed;
|
AP_Airspeed &airspeed;
|
||||||
AP_Logger &dataflash;
|
AP_Logger &logger;
|
||||||
struct LogStructure *_log_structure;
|
struct LogStructure *_log_structure;
|
||||||
uint8_t _log_structure_count;
|
uint8_t _log_structure_count;
|
||||||
|
|
||||||
|
|
|
@ -14,7 +14,7 @@ public:
|
||||||
k_param_airspeed,
|
k_param_airspeed,
|
||||||
k_param_NavEKF2,
|
k_param_NavEKF2,
|
||||||
k_param_compass,
|
k_param_compass,
|
||||||
k_param_dataflash,
|
k_param_logger,
|
||||||
k_param_NavEKF3
|
k_param_NavEKF3
|
||||||
};
|
};
|
||||||
AP_Int8 dummy;
|
AP_Int8 dummy;
|
||||||
|
|
|
@ -75,7 +75,7 @@ const AP_Param::Info ReplayVehicle::var_info[] = {
|
||||||
|
|
||||||
// @Group: LOG
|
// @Group: LOG
|
||||||
// @Path: ../libraries/AP_Logger/AP_Logger.cpp
|
// @Path: ../libraries/AP_Logger/AP_Logger.cpp
|
||||||
GOBJECT(dataflash, "LOG", AP_Logger),
|
GOBJECT(logger, "LOG", AP_Logger),
|
||||||
|
|
||||||
// @Group: EK3_
|
// @Group: EK3_
|
||||||
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
|
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
|
||||||
|
@ -109,7 +109,7 @@ void ReplayVehicle::setup(void)
|
||||||
// message as a product of Replay), or the format understood in
|
// message as a product of Replay), or the format understood in
|
||||||
// the current code (if we do emit the message in the normal
|
// the current code (if we do emit the message in the normal
|
||||||
// places in the EKF, for example)
|
// places in the EKF, for example)
|
||||||
dataflash.Init(log_structure, 0);
|
logger.Init(log_structure, 0);
|
||||||
|
|
||||||
ahrs.set_compass(&compass);
|
ahrs.set_compass(&compass);
|
||||||
ahrs.set_fly_forward(true);
|
ahrs.set_fly_forward(true);
|
||||||
|
@ -169,8 +169,8 @@ enum {
|
||||||
OPT_PACKET_COUNTS,
|
OPT_PACKET_COUNTS,
|
||||||
};
|
};
|
||||||
|
|
||||||
void Replay::flush_dataflash(void) {
|
void Replay::flush_logger(void) {
|
||||||
_vehicle.dataflash.flush();
|
_vehicle.logger.flush();
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -474,8 +474,8 @@ bool Replay::find_log_info(struct log_information &info)
|
||||||
// catch floating point exceptions
|
// catch floating point exceptions
|
||||||
static void _replay_sig_fpe(int signum)
|
static void _replay_sig_fpe(int signum)
|
||||||
{
|
{
|
||||||
fprintf(stderr, "ERROR: Floating point exception - flushing dataflash...\n");
|
fprintf(stderr, "ERROR: Floating point exception - flushing logger...\n");
|
||||||
replay.flush_dataflash();
|
replay.flush_logger();
|
||||||
fprintf(stderr, "ERROR: ... and aborting.\n");
|
fprintf(stderr, "ERROR: ... and aborting.\n");
|
||||||
if (replay.check_solution) {
|
if (replay.check_solution) {
|
||||||
FILE *f = fopen("replay_results.txt","a");
|
FILE *f = fopen("replay_results.txt","a");
|
||||||
|
@ -614,13 +614,13 @@ void Replay::set_signal_handlers(void)
|
||||||
void Replay::write_ekf_logs(void)
|
void Replay::write_ekf_logs(void)
|
||||||
{
|
{
|
||||||
if (!LogReader::in_list("EKF", nottypes)) {
|
if (!LogReader::in_list("EKF", nottypes)) {
|
||||||
_vehicle.dataflash.Write_EKF(_vehicle.ahrs);
|
_vehicle.logger.Write_EKF(_vehicle.ahrs);
|
||||||
}
|
}
|
||||||
if (!LogReader::in_list("AHRS2", nottypes)) {
|
if (!LogReader::in_list("AHRS2", nottypes)) {
|
||||||
_vehicle.dataflash.Write_AHRS2(_vehicle.ahrs);
|
_vehicle.logger.Write_AHRS2(_vehicle.ahrs);
|
||||||
}
|
}
|
||||||
if (!LogReader::in_list("POS", nottypes)) {
|
if (!LogReader::in_list("POS", nottypes)) {
|
||||||
_vehicle.dataflash.Write_POS(_vehicle.ahrs);
|
_vehicle.logger.Write_POS(_vehicle.ahrs);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -730,7 +730,7 @@ void Replay::log_check_generate(void)
|
||||||
_vehicle.EKF2.getVelNED(-1,velocity);
|
_vehicle.EKF2.getVelNED(-1,velocity);
|
||||||
_vehicle.EKF2.getLLH(loc);
|
_vehicle.EKF2.getLLH(loc);
|
||||||
|
|
||||||
_vehicle.dataflash.Write(
|
_vehicle.logger.Write(
|
||||||
"CHEK",
|
"CHEK",
|
||||||
"TimeUS,Roll,Pitch,Yaw,Lat,Lng,Alt,VN,VE,VD",
|
"TimeUS,Roll,Pitch,Yaw,Lat,Lng,Alt,VN,VE,VD",
|
||||||
"sdddDUmnnn",
|
"sdddDUmnnn",
|
||||||
|
@ -779,7 +779,7 @@ void Replay::log_check_solution(void)
|
||||||
|
|
||||||
void Replay::flush_and_exit()
|
void Replay::flush_and_exit()
|
||||||
{
|
{
|
||||||
flush_dataflash();
|
flush_logger();
|
||||||
|
|
||||||
if (check_solution) {
|
if (check_solution) {
|
||||||
report_checks();
|
report_checks();
|
||||||
|
|
|
@ -69,7 +69,7 @@ public:
|
||||||
AP_Int32 unused; // logging is magic for Replay; this is unused
|
AP_Int32 unused; // logging is magic for Replay; this is unused
|
||||||
struct LogStructure log_structure[256] = {
|
struct LogStructure log_structure[256] = {
|
||||||
};
|
};
|
||||||
AP_Logger dataflash{unused};
|
AP_Logger logger{unused};
|
||||||
|
|
||||||
private:
|
private:
|
||||||
Parameters g;
|
Parameters g;
|
||||||
|
@ -91,7 +91,7 @@ public:
|
||||||
void setup() override;
|
void setup() override;
|
||||||
void loop() override;
|
void loop() override;
|
||||||
|
|
||||||
void flush_dataflash(void);
|
void flush_logger(void);
|
||||||
void show_packet_counts();
|
void show_packet_counts();
|
||||||
|
|
||||||
bool check_solution = false;
|
bool check_solution = false;
|
||||||
|
@ -124,7 +124,7 @@ private:
|
||||||
_vehicle.compass,
|
_vehicle.compass,
|
||||||
_vehicle.gps,
|
_vehicle.gps,
|
||||||
_vehicle.airspeed,
|
_vehicle.airspeed,
|
||||||
_vehicle.dataflash,
|
_vehicle.logger,
|
||||||
_vehicle.log_structure,
|
_vehicle.log_structure,
|
||||||
0,
|
0,
|
||||||
nottypes};
|
nottypes};
|
||||||
|
|
Loading…
Reference in New Issue