diff --git a/Tools/Replay/LR_MsgHandler.cpp b/Tools/Replay/LR_MsgHandler.cpp index 5bbf27d9df..9f9bdc0f50 100644 --- a/Tools/Replay/LR_MsgHandler.cpp +++ b/Tools/Replay/LR_MsgHandler.cpp @@ -5,9 +5,9 @@ extern const AP_HAL::HAL& hal; LR_MsgHandler::LR_MsgHandler(struct log_Format &_f, - AP_Logger &_dataflash, + AP_Logger &_logger, uint64_t &_last_timestamp_usec) : - dataflash(_dataflash), last_timestamp_usec(_last_timestamp_usec), + logger(_logger), last_timestamp_usec(_last_timestamp_usec), MsgHandler(_f) { } diff --git a/Tools/Replay/LR_MsgHandler.h b/Tools/Replay/LR_MsgHandler.h index 013f5bd6fc..1f34a53897 100644 --- a/Tools/Replay/LR_MsgHandler.h +++ b/Tools/Replay/LR_MsgHandler.h @@ -7,7 +7,7 @@ class LR_MsgHandler : public MsgHandler { public: LR_MsgHandler(struct log_Format &f, - AP_Logger &_dataflash, + AP_Logger &_logger, uint64_t &last_timestamp_usec); virtual void process_message(uint8_t *msg) = 0; @@ -20,7 +20,7 @@ public: }; protected: - AP_Logger &dataflash; + AP_Logger &logger; void wait_timestamp(uint32_t timestamp); void wait_timestamp_usec(uint64_t timestamp); void wait_timestamp_from_msg(uint8_t *msg); @@ -34,9 +34,9 @@ protected: class LR_MsgHandler_AHR2 : public LR_MsgHandler { 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) - : LR_MsgHandler(_f, _dataflash,_last_timestamp_usec), + : LR_MsgHandler(_f, _logger,_last_timestamp_usec), ahr2_attitude(_ahr2_attitude) { }; virtual void process_message(uint8_t *msg); @@ -49,9 +49,9 @@ private: class LR_MsgHandler_ARM : public LR_MsgHandler { public: - LR_MsgHandler_ARM(log_Format &_f, AP_Logger &_dataflash, + LR_MsgHandler_ARM(log_Format &_f, AP_Logger &_logger, 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); }; @@ -60,9 +60,9 @@ public: class LR_MsgHandler_ARSP : public LR_MsgHandler { 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) : - 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); @@ -73,9 +73,9 @@ private: class LR_MsgHandler_NKF1 : public LR_MsgHandler { public: - LR_MsgHandler_NKF1(log_Format &_f, AP_Logger &_dataflash, + LR_MsgHandler_NKF1(log_Format &_f, AP_Logger &_logger, 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); }; @@ -84,9 +84,9 @@ public: class LR_MsgHandler_ATT : public LR_MsgHandler { 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) - : 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); @@ -98,9 +98,9 @@ private: class LR_MsgHandler_CHEK : public LR_MsgHandler { 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) - : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), + : LR_MsgHandler(_f, _logger, _last_timestamp_usec), check_state(_check_state) { }; virtual void process_message(uint8_t *msg); @@ -112,9 +112,9 @@ private: class LR_MsgHandler_BARO : public LR_MsgHandler { public: - LR_MsgHandler_BARO(log_Format &_f, AP_Logger &_dataflash, + LR_MsgHandler_BARO(log_Format &_f, AP_Logger &_logger, 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); @@ -125,9 +125,9 @@ public: class LR_MsgHandler_Event : public LR_MsgHandler { public: - LR_MsgHandler_Event(log_Format &_f, AP_Logger &_dataflash, + LR_MsgHandler_Event(log_Format &_f, AP_Logger &_logger, 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); }; @@ -139,10 +139,10 @@ class LR_MsgHandler_GPS_Base : public LR_MsgHandler { 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, 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) { }; protected: @@ -156,10 +156,10 @@ private: class LR_MsgHandler_GPS : public LR_MsgHandler_GPS_Base { 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, 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), ground_alt_cm(_ground_alt_cm) { }; @@ -177,10 +177,10 @@ private: class LR_MsgHandler_GPS2 : public LR_MsgHandler_GPS_Base { 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, 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), ground_alt_cm(_ground_alt_cm) { }; virtual void process_message(uint8_t *msg); @@ -193,9 +193,9 @@ class LR_MsgHandler_GPA_Base : public LR_MsgHandler { 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) - : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), gps(_gps) { }; + : LR_MsgHandler(_f, _logger, _last_timestamp_usec), gps(_gps) { }; protected: 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 { 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) - : LR_MsgHandler_GPA_Base(_f, _dataflash,_last_timestamp_usec, + : LR_MsgHandler_GPA_Base(_f, _logger,_last_timestamp_usec, _gps), gps(_gps) { }; void process_message(uint8_t *msg); @@ -222,9 +222,9 @@ private: class LR_MsgHandler_GPA2 : public LR_MsgHandler_GPA_Base { 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) - : LR_MsgHandler_GPA_Base(_f, _dataflash, _last_timestamp_usec, + : LR_MsgHandler_GPA_Base(_f, _logger, _last_timestamp_usec, _gps), gps(_gps) { }; virtual void process_message(uint8_t *msg); private: @@ -238,11 +238,11 @@ private: class LR_MsgHandler_IMU_Base : public LR_MsgHandler { 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, uint8_t &_accel_mask, uint8_t &_gyro_mask, AP_InertialSensor &_ins) : - LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), + LR_MsgHandler(_f, _logger, _last_timestamp_usec), accel_mask(_accel_mask), gyro_mask(_gyro_mask), ins(_ins) { }; @@ -257,11 +257,11 @@ private: class LR_MsgHandler_IMU : public LR_MsgHandler_IMU_Base { public: - LR_MsgHandler_IMU(log_Format &_f, AP_Logger &_dataflash, + LR_MsgHandler_IMU(log_Format &_f, AP_Logger &_logger, uint64_t &_last_timestamp_usec, uint8_t &_accel_mask, uint8_t &_gyro_mask, 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) { }; void process_message(uint8_t *msg); @@ -270,11 +270,11 @@ public: class LR_MsgHandler_IMU2 : public LR_MsgHandler_IMU_Base { public: - LR_MsgHandler_IMU2(log_Format &_f, AP_Logger &_dataflash, + LR_MsgHandler_IMU2(log_Format &_f, AP_Logger &_logger, uint64_t &_last_timestamp_usec, uint8_t &_accel_mask, uint8_t &_gyro_mask, 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) {}; virtual void process_message(uint8_t *msg); @@ -283,11 +283,11 @@ public: class LR_MsgHandler_IMU3 : public LR_MsgHandler_IMU_Base { public: - LR_MsgHandler_IMU3(log_Format &_f, AP_Logger &_dataflash, + LR_MsgHandler_IMU3(log_Format &_f, AP_Logger &_logger, uint64_t &_last_timestamp_usec, uint8_t &_accel_mask, uint8_t &_gyro_mask, 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) {}; virtual void process_message(uint8_t *msg); @@ -297,12 +297,12 @@ public: class LR_MsgHandler_IMT_Base : public LR_MsgHandler { 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, uint8_t &_accel_mask, uint8_t &_gyro_mask, bool &_use_imt, AP_InertialSensor &_ins) : - LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), + LR_MsgHandler(_f, _logger, _last_timestamp_usec), accel_mask(_accel_mask), gyro_mask(_gyro_mask), use_imt(_use_imt), @@ -319,12 +319,12 @@ private: class LR_MsgHandler_IMT : public LR_MsgHandler_IMT_Base { public: - LR_MsgHandler_IMT(log_Format &_f, AP_Logger &_dataflash, + LR_MsgHandler_IMT(log_Format &_f, AP_Logger &_logger, uint64_t &_last_timestamp_usec, uint8_t &_accel_mask, uint8_t &_gyro_mask, bool &_use_imt, 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) { }; void process_message(uint8_t *msg); @@ -333,12 +333,12 @@ public: class LR_MsgHandler_IMT2 : public LR_MsgHandler_IMT_Base { public: - LR_MsgHandler_IMT2(log_Format &_f, AP_Logger &_dataflash, + LR_MsgHandler_IMT2(log_Format &_f, AP_Logger &_logger, uint64_t &_last_timestamp_usec, uint8_t &_accel_mask, uint8_t &_gyro_mask, bool &_use_imt, 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) { }; void process_message(uint8_t *msg); @@ -347,12 +347,12 @@ public: class LR_MsgHandler_IMT3 : public LR_MsgHandler_IMT_Base { public: - LR_MsgHandler_IMT3(log_Format &_f, AP_Logger &_dataflash, + LR_MsgHandler_IMT3(log_Format &_f, AP_Logger &_logger, uint64_t &_last_timestamp_usec, uint8_t &_accel_mask, uint8_t &_gyro_mask, bool &_use_imt, 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) { }; void process_message(uint8_t *msg); @@ -362,9 +362,9 @@ public: class LR_MsgHandler_MAG_Base : public LR_MsgHandler { 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) - : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), compass(_compass) { }; + : LR_MsgHandler(_f, _logger, _last_timestamp_usec), compass(_compass) { }; protected: 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 { 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) - : 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); }; @@ -386,9 +386,9 @@ public: class LR_MsgHandler_MAG2 : public LR_MsgHandler_MAG_Base { 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) - : 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); }; @@ -398,10 +398,10 @@ public: class LR_MsgHandler_MSG : public LR_MsgHandler { public: - LR_MsgHandler_MSG(log_Format &_f, AP_Logger &_dataflash, + LR_MsgHandler_MSG(log_Format &_f, AP_Logger &_logger, uint64_t &_last_timestamp_usec, 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) { } @@ -416,9 +416,9 @@ private: class LR_MsgHandler_NTUN_Copter : public LR_MsgHandler { 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) - : 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); @@ -430,10 +430,10 @@ private: class LR_MsgHandler_PARM : public LR_MsgHandler { public: - LR_MsgHandler_PARM(log_Format &_f, AP_Logger &_dataflash, + LR_MsgHandler_PARM(log_Format &_f, AP_Logger &_logger, uint64_t &_last_timestamp_usec, const std::function&set_parameter_callback) : - LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), + LR_MsgHandler(_f, _logger, _last_timestamp_usec), _set_parameter_callback(set_parameter_callback) {}; @@ -447,9 +447,9 @@ private: class LR_MsgHandler_PM : public LR_MsgHandler { public: - LR_MsgHandler_PM(log_Format &_f, AP_Logger &_dataflash, + LR_MsgHandler_PM(log_Format &_f, AP_Logger &_logger, 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); @@ -460,10 +460,10 @@ private: class LR_MsgHandler_SIM : public LR_MsgHandler { public: - LR_MsgHandler_SIM(log_Format &_f, AP_Logger &_dataflash, + LR_MsgHandler_SIM(log_Format &_f, AP_Logger &_logger, uint64_t &_last_timestamp_usec, Vector3f &_sim_attitude) - : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), + : LR_MsgHandler(_f, _logger, _last_timestamp_usec), sim_attitude(_sim_attitude) { }; diff --git a/Tools/Replay/LogReader.cpp b/Tools/Replay/LogReader.cpp index a27fe3df80..b5ac05ac25 100644 --- a/Tools/Replay/LogReader.cpp +++ b/Tools/Replay/LogReader.cpp @@ -38,7 +38,7 @@ LogReader::LogReader(AP_AHRS &_ahrs, Compass &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed, - AP_Logger &_dataflash, + AP_Logger &_logger, struct LogStructure *log_structure, uint8_t log_structure_count, const char **&_nottypes): @@ -49,7 +49,7 @@ LogReader::LogReader(AP_AHRS &_ahrs, compass(_compass), gps(_gps), airspeed(_airspeed), - dataflash(_dataflash), + logger(_logger), accel_mask(7), gyro_mask(7), last_timestamp_usec(0), @@ -80,7 +80,7 @@ void LogReader::maybe_install_vehicle_specific_parsers() { for (uint8_t i = 0; istop_clock(last_timestamp_usec); } diff --git a/Tools/Replay/LogReader.h b/Tools/Replay/LogReader.h index 795460dea2..c806402eb2 100644 --- a/Tools/Replay/LogReader.h +++ b/Tools/Replay/LogReader.h @@ -11,7 +11,7 @@ public: Compass &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed, - AP_Logger &_dataflash, + AP_Logger &_logger, struct LogStructure *log_structure, uint8_t log_structure_count, const char **¬types); @@ -47,7 +47,7 @@ private: Compass &compass; AP_GPS &gps; AP_Airspeed &airspeed; - AP_Logger &dataflash; + AP_Logger &logger; struct LogStructure *_log_structure; uint8_t _log_structure_count; diff --git a/Tools/Replay/Parameters.h b/Tools/Replay/Parameters.h index af4c263d88..e5df26dc93 100644 --- a/Tools/Replay/Parameters.h +++ b/Tools/Replay/Parameters.h @@ -14,7 +14,7 @@ public: k_param_airspeed, k_param_NavEKF2, k_param_compass, - k_param_dataflash, + k_param_logger, k_param_NavEKF3 }; AP_Int8 dummy; diff --git a/Tools/Replay/Replay.cpp b/Tools/Replay/Replay.cpp index 8e1e46dba4..fc105f4ec9 100644 --- a/Tools/Replay/Replay.cpp +++ b/Tools/Replay/Replay.cpp @@ -75,7 +75,7 @@ const AP_Param::Info ReplayVehicle::var_info[] = { // @Group: LOG // @Path: ../libraries/AP_Logger/AP_Logger.cpp - GOBJECT(dataflash, "LOG", AP_Logger), + GOBJECT(logger, "LOG", AP_Logger), // @Group: EK3_ // @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 // the current code (if we do emit the message in the normal // places in the EKF, for example) - dataflash.Init(log_structure, 0); + logger.Init(log_structure, 0); ahrs.set_compass(&compass); ahrs.set_fly_forward(true); @@ -169,8 +169,8 @@ enum { OPT_PACKET_COUNTS, }; -void Replay::flush_dataflash(void) { - _vehicle.dataflash.flush(); +void Replay::flush_logger(void) { + _vehicle.logger.flush(); } /* @@ -474,8 +474,8 @@ bool Replay::find_log_info(struct log_information &info) // catch floating point exceptions static void _replay_sig_fpe(int signum) { - fprintf(stderr, "ERROR: Floating point exception - flushing dataflash...\n"); - replay.flush_dataflash(); + fprintf(stderr, "ERROR: Floating point exception - flushing logger...\n"); + replay.flush_logger(); fprintf(stderr, "ERROR: ... and aborting.\n"); if (replay.check_solution) { FILE *f = fopen("replay_results.txt","a"); @@ -614,13 +614,13 @@ void Replay::set_signal_handlers(void) void Replay::write_ekf_logs(void) { if (!LogReader::in_list("EKF", nottypes)) { - _vehicle.dataflash.Write_EKF(_vehicle.ahrs); + _vehicle.logger.Write_EKF(_vehicle.ahrs); } if (!LogReader::in_list("AHRS2", nottypes)) { - _vehicle.dataflash.Write_AHRS2(_vehicle.ahrs); + _vehicle.logger.Write_AHRS2(_vehicle.ahrs); } 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.getLLH(loc); - _vehicle.dataflash.Write( + _vehicle.logger.Write( "CHEK", "TimeUS,Roll,Pitch,Yaw,Lat,Lng,Alt,VN,VE,VD", "sdddDUmnnn", @@ -779,7 +779,7 @@ void Replay::log_check_solution(void) void Replay::flush_and_exit() { - flush_dataflash(); + flush_logger(); if (check_solution) { report_checks(); diff --git a/Tools/Replay/Replay.h b/Tools/Replay/Replay.h index 2a201c64c3..11624b7c88 100644 --- a/Tools/Replay/Replay.h +++ b/Tools/Replay/Replay.h @@ -69,7 +69,7 @@ public: AP_Int32 unused; // logging is magic for Replay; this is unused struct LogStructure log_structure[256] = { }; - AP_Logger dataflash{unused}; + AP_Logger logger{unused}; private: Parameters g; @@ -91,7 +91,7 @@ public: void setup() override; void loop() override; - void flush_dataflash(void); + void flush_logger(void); void show_packet_counts(); bool check_solution = false; @@ -124,7 +124,7 @@ private: _vehicle.compass, _vehicle.gps, _vehicle.airspeed, - _vehicle.dataflash, + _vehicle.logger, _vehicle.log_structure, 0, nottypes};