diff --git a/APMrover2/APMrover2.cpp b/APMrover2/APMrover2.cpp index cda5e12ce7..0a67f975c8 100644 --- a/APMrover2/APMrover2.cpp +++ b/APMrover2/APMrover2.cpp @@ -83,7 +83,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { SCHED_TASK(compass_save, 0.1, 200), SCHED_TASK(accel_cal_update, 10, 200), #if LOGGING_ENABLED == ENABLED - SCHED_TASK_CLASS(DataFlash_Class, &rover.DataFlash, periodic_tasks, 50, 300), + SCHED_TASK_CLASS(AP_Logger, &rover.logger, periodic_tasks, 50, 300), #endif SCHED_TASK_CLASS(AP_InertialSensor, &rover.ins, periodic, 400, 200), SCHED_TASK_CLASS(AP_Scheduler, &rover.scheduler, update_logging, 0.1, 200), @@ -139,7 +139,7 @@ void Rover::update_soft_armed() { hal.util->set_soft_armed(arming.is_armed() && hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED); - DataFlash.set_vehicle_armed(hal.util->get_soft_armed()); + logger.set_vehicle_armed(hal.util->get_soft_armed()); } // update AHRS system @@ -177,7 +177,7 @@ void Rover::ahrs_update() } if (should_log(MASK_LOG_IMU)) { - DataFlash.Log_Write_IMU(); + logger.Log_Write_IMU(); } } @@ -204,7 +204,7 @@ void Rover::update_compass(void) ahrs.set_compass(&compass); // update offsets if (should_log(MASK_LOG_COMPASS)) { - DataFlash.Log_Write_Compass(); + logger.Log_Write_Compass(); } } } @@ -221,7 +221,7 @@ void Rover::update_logging1(void) if (should_log(MASK_LOG_THR)) { Log_Write_Throttle(); - DataFlash.Log_Write_Beacon(g2.beacon); + logger.Log_Write_Beacon(g2.beacon); } if (should_log(MASK_LOG_NTUN)) { @@ -229,7 +229,7 @@ void Rover::update_logging1(void) } if (should_log(MASK_LOG_RANGEFINDER)) { - DataFlash.Log_Write_Proximity(g2.proximity); + logger.Log_Write_Proximity(g2.proximity); } } @@ -248,7 +248,7 @@ void Rover::update_logging2(void) } if (should_log(MASK_LOG_IMU)) { - DataFlash.Log_Write_Vibration(); + logger.Log_Write_Vibration(); } } diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index d61615cc3f..6a4edfcc9a 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -180,7 +180,7 @@ void GCS_MAVLINK_Rover::send_rangefinder() const */ void Rover::send_pid_tuning(mavlink_channel_t chan) { - const DataFlash_Class::PID_Info *pid_info; + const AP_Logger::PID_Info *pid_info; // steering PID if (g.gcs_pid_mask & 1) { pid_info = &g2.attitude_control.get_steering_rate_pid().get_pid_info(); @@ -1130,7 +1130,7 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) case MAVLINK_MSG_ID_RADIO: case MAVLINK_MSG_ID_RADIO_STATUS: { - handle_radio_status(msg, rover.DataFlash, rover.should_log(MASK_LOG_PM)); + handle_radio_status(msg, rover.logger, rover.should_log(MASK_LOG_PM)); break; } @@ -1168,7 +1168,7 @@ void Rover::mavlink_delay_cb() } // don't allow potentially expensive logging calls: - DataFlash.EnableWrites(false); + logger.EnableWrites(false); const uint32_t tnow = millis(); if (tnow - last_1hz > 1000) { @@ -1187,7 +1187,7 @@ void Rover::mavlink_delay_cb() gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM"); } - DataFlash.EnableWrites(true); + logger.EnableWrites(true); } AP_AdvancedFailsafe *GCS_MAVLINK_Rover::get_advanced_failsafe() const diff --git a/APMrover2/Log.cpp b/APMrover2/Log.cpp index a44617521c..348926de96 100644 --- a/APMrover2/Log.cpp +++ b/APMrover2/Log.cpp @@ -19,7 +19,7 @@ void Rover::Log_Write_Arm_Disarm() arm_state : arming.is_armed(), arm_checks : arming.get_enabled_checks() }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } // Write an attitude packet @@ -28,26 +28,26 @@ void Rover::Log_Write_Attitude() float desired_pitch_cd = degrees(g2.attitude_control.get_desired_pitch()) * 100.0f; const Vector3f targets(0.0f, desired_pitch_cd, 0.0f); - DataFlash.Log_Write_Attitude(ahrs, targets); + logger.Log_Write_Attitude(ahrs, targets); #if AP_AHRS_NAVEKF_AVAILABLE - DataFlash.Log_Write_EKF(ahrs); - DataFlash.Log_Write_AHRS2(ahrs); + logger.Log_Write_EKF(ahrs); + logger.Log_Write_AHRS2(ahrs); #endif - DataFlash.Log_Write_POS(ahrs); + logger.Log_Write_POS(ahrs); // log steering rate controller - DataFlash.Log_Write_PID(LOG_PIDS_MSG, g2.attitude_control.get_steering_rate_pid().get_pid_info()); - DataFlash.Log_Write_PID(LOG_PIDA_MSG, g2.attitude_control.get_throttle_speed_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIDS_MSG, g2.attitude_control.get_steering_rate_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIDA_MSG, g2.attitude_control.get_throttle_speed_pid().get_pid_info()); // log pitch control for balance bots if (is_balancebot()) { - DataFlash.Log_Write_PID(LOG_PIDP_MSG, g2.attitude_control.get_pitch_to_throttle_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIDP_MSG, g2.attitude_control.get_pitch_to_throttle_pid().get_pid_info()); } // log heel to sail control for sailboats if (g2.motors.has_sail()) { - DataFlash.Log_Write_PID(LOG_PIDR_MSG, g2.attitude_control.get_sailboat_heel_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIDR_MSG, g2.attitude_control.get_sailboat_heel_pid().get_pid_info()); } #if CONFIG_HAL_BOARD == HAL_BOARD_SITL sitl.Log_Write_SIMSTATE(); @@ -75,7 +75,7 @@ void Rover::Log_Write_Depth() } rangefinder_last_reading_ms = reading_ms; - DataFlash.Log_Write("DPTH", "TimeUS,Lat,Lng,Depth", + logger.Log_Write("DPTH", "TimeUS,Lat,Lng,Depth", "sDUm", "FGG0", "QLLf", AP_HAL::micros64(), loc.lat, @@ -99,7 +99,7 @@ void Rover::Log_Write_Error(uint8_t sub_system, uint8_t error_code) sub_system : sub_system, error_code : error_code, }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } // guided mode logging @@ -129,7 +129,7 @@ void Rover::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_targ vel_target_y : vel_target.y, vel_target_z : vel_target.z }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } struct PACKED log_Nav_Tuning { @@ -154,7 +154,7 @@ void Rover::Log_Write_Nav_Tuning() yaw : (uint16_t)ahrs.yaw_sensor, xtrack_error : nav_controller->crosstrack_error() }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } void Rover::Log_Write_Sail() @@ -165,17 +165,17 @@ void Rover::Log_Write_Sail() } // get wind direction - float wind_dir_abs = DataFlash.quiet_nanf(); - float wind_dir_rel = DataFlash.quiet_nanf(); - float wind_speed_true = DataFlash.quiet_nanf(); - float wind_speed_apparent = DataFlash.quiet_nanf(); + float wind_dir_abs = logger.quiet_nanf(); + float wind_dir_rel = logger.quiet_nanf(); + float wind_speed_true = logger.quiet_nanf(); + float wind_speed_apparent = logger.quiet_nanf(); if (rover.g2.windvane.enabled()) { wind_dir_abs = degrees(g2.windvane.get_absolute_wind_direction_rad()); wind_dir_rel = degrees(g2.windvane.get_apparent_wind_direction_rad()); wind_speed_true = g2.windvane.get_true_wind_speed(); wind_speed_apparent = g2.windvane.get_apparent_wind_speed(); } - DataFlash.Log_Write("SAIL", "TimeUS,WindDirAbs,WindDirApp,WindSpdTrue,WindSpdApp,SailOut,VMG", + logger.Log_Write("SAIL", "TimeUS,WindDirAbs,WindDirApp,WindSpdTrue,WindSpdApp,SailOut,VMG", "shhnn%n", "F000000", "Qffffff", AP_HAL::micros64(), (double)wind_dir_abs, @@ -212,13 +212,13 @@ void Rover::Log_Write_Startup(uint8_t type) startup_type : type, command_total : mode_auto.mission.num_commands() }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } // Write a steering packet void Rover::Log_Write_Steering() { - float lat_accel = DataFlash.quiet_nanf(); + float lat_accel = logger.quiet_nanf(); g2.attitude_control.get_lat_accel(lat_accel); struct log_Steering pkt = { LOG_PACKET_HEADER_INIT(LOG_STEERING_MSG), @@ -230,7 +230,7 @@ void Rover::Log_Write_Steering() desired_turn_rate : degrees(g2.attitude_control.get_desired_turn_rate()), turn_rate : degrees(ahrs.get_yaw_rate_earth()) }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } struct PACKED log_Throttle { @@ -247,7 +247,7 @@ struct PACKED log_Throttle { void Rover::Log_Write_Throttle() { const Vector3f accel = ins.get_accel(); - float speed = DataFlash.quiet_nanf(); + float speed = logger.quiet_nanf(); g2.attitude_control.get_forward_speed(speed); struct log_Throttle pkt = { LOG_PACKET_HEADER_INIT(LOG_THR_MSG), @@ -258,7 +258,7 @@ void Rover::Log_Write_Throttle() speed : speed, accel_y : accel.y }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } struct PACKED log_Rangefinder { @@ -295,15 +295,15 @@ void Rover::Log_Write_Rangefinder() ground_speed : static_cast(fabsf(ground_speed * 100.0f)), throttle : int8_t(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)) }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } void Rover::Log_Write_RC(void) { - DataFlash.Log_Write_RCIN(); - DataFlash.Log_Write_RCOUT(); + logger.Log_Write_RCIN(); + logger.Log_Write_RCOUT(); if (rssi.enabled()) { - DataFlash.Log_Write_RSSI(rssi); + logger.Log_Write_RSSI(rssi); } } @@ -336,20 +336,20 @@ void Rover::Log_Write_WheelEncoder() quality_1 : (uint8_t)constrain_float(g2.wheel_encoder.get_signal_quality(1), 0.0f, 100.0f), rpm_1 : wheel_encoder_rpm[1] }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } void Rover::Log_Write_Vehicle_Startup_Messages() { - // only 200(?) bytes are guaranteed by DataFlash + // only 200(?) bytes are guaranteed by AP_Logger Log_Write_Startup(TYPE_GROUNDSTART_MSG); - DataFlash.Log_Write_Mode(control_mode->mode_number(), control_mode_reason); + logger.Log_Write_Mode(control_mode->mode_number(), control_mode_reason); ahrs.Log_Write_Home_And_Origin(); - gps.Write_DataFlash_Log_Startup_messages(); + gps.Write_AP_Logger_Log_Startup_messages(); } // type and unit information can be found in -// libraries/DataFlash/Logstructure.h; search for "log_Units" for +// libraries/AP_Logger/Logstructure.h; search for "log_Units" for // units and "Format characters" for field type information const LogStructure Rover::log_structure[] = { LOG_COMMON_STRUCTURES, @@ -375,7 +375,7 @@ const LogStructure Rover::log_structure[] = { void Rover::log_init(void) { - DataFlash.Init(log_structure, ARRAY_SIZE(log_structure)); + logger.Init(log_structure, ARRAY_SIZE(log_structure)); } #else // LOGGING_ENABLED diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index ed14c5cac5..818370fac4 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -377,8 +377,8 @@ const AP_Param::Info Rover::var_info[] = { GOBJECT(arming, "ARMING_", AP_Arming), // @Group: LOG - // @Path: ../libraries/DataFlash/DataFlash.cpp - GOBJECT(DataFlash, "LOG", DataFlash_Class), + // @Path: ../libraries/AP_Logger/AP_Logger.cpp + GOBJECT(logger, "LOG", AP_Logger), // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp diff --git a/APMrover2/Parameters.h b/APMrover2/Parameters.h index 71a93100b0..f3c8ed5a2b 100644 --- a/APMrover2/Parameters.h +++ b/APMrover2/Parameters.h @@ -207,7 +207,7 @@ public: k_param_button, k_param_osd, - k_param_DataFlash = 253, // Logging Group + k_param_logger = 253, // Logging Group // 254,255: reserved }; diff --git a/APMrover2/Rover.cpp b/APMrover2/Rover.cpp index f501f22b6b..ee3faa4c26 100644 --- a/APMrover2/Rover.cpp +++ b/APMrover2/Rover.cpp @@ -28,7 +28,7 @@ Rover::Rover(void) : channel_throttle(nullptr), channel_aux(nullptr), channel_lateral(nullptr), - DataFlash{g.log_bitmask}, + logger{g.log_bitmask}, modes(&g.mode1), nav_controller(&L1_controller), control_mode(&mode_initializing), diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 508a264620..86b9a43237 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -66,7 +66,7 @@ #include #include #include -#include +#include #include // Mode Filter from Filter library #include // Filter library - butterworth filter #include // Filter library @@ -163,7 +163,7 @@ private: RC_Channel *channel_aux; RC_Channel *channel_lateral; - DataFlash_Class DataFlash; + AP_Logger logger; // sensor drivers AP_GPS gps; diff --git a/APMrover2/commands.cpp b/APMrover2/commands.cpp index 86bc59b4e3..bbfebf0d84 100644 --- a/APMrover2/commands.cpp +++ b/APMrover2/commands.cpp @@ -56,7 +56,7 @@ bool Rover::set_home(const Location& loc, bool lock) if (should_log(MASK_LOG_CMD)) { AP_Mission::Mission_Command temp_cmd; if (mode_auto.mission.read_cmd_from_storage(0, temp_cmd)) { - DataFlash.Log_Write_Mission_Cmd(mode_auto.mission, temp_cmd); + logger.Log_Write_Mission_Cmd(mode_auto.mission, temp_cmd); } } } diff --git a/APMrover2/commands_logic.cpp b/APMrover2/commands_logic.cpp index 7643a40b88..b76aaf6349 100644 --- a/APMrover2/commands_logic.cpp +++ b/APMrover2/commands_logic.cpp @@ -17,7 +17,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) { // log when new commands start if (rover.should_log(MASK_LOG_CMD)) { - rover.DataFlash.Log_Write_Mission_Cmd(mission, cmd); + rover.logger.Log_Write_Mission_Cmd(mission, cmd); } gcs().send_text(MAV_SEVERITY_INFO, "Executing %s(ID=%i)", diff --git a/APMrover2/cruise_learn.cpp b/APMrover2/cruise_learn.cpp index f0a0932b3b..3dcb99d97e 100644 --- a/APMrover2/cruise_learn.cpp +++ b/APMrover2/cruise_learn.cpp @@ -63,7 +63,7 @@ void Rover::cruise_learn_complete() // logging for cruise learn void Rover::log_write_cruise_learn() { - DataFlash_Class::instance()->Log_Write("CRSE", "TimeUS,State,Speed,Throttle", "Qbff", + AP_Logger::instance()->Log_Write("CRSE", "TimeUS,State,Speed,Throttle", "Qbff", AP_HAL::micros64, cruise_learn.learn_start_ms > 0, cruise_learn.speed_filt.get(), diff --git a/APMrover2/sensors.cpp b/APMrover2/sensors.cpp index 783978e64c..c219e5a881 100644 --- a/APMrover2/sensors.cpp +++ b/APMrover2/sensors.cpp @@ -58,7 +58,7 @@ void Rover::update_visual_odom() visual_odom_last_update_ms, g2.visual_odom.get_pos_offset()); // log sensor data - DataFlash.Log_Write_VisualOdom(time_delta_sec, + logger.Log_Write_VisualOdom(time_delta_sec, g2.visual_odom.get_angle_delta(), g2.visual_odom.get_position_delta(), g2.visual_odom.get_confidence()); @@ -268,7 +268,7 @@ void Rover::update_sensor_status_flags(void) if (g2.visual_odom.enabled()) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION; } - if (rover.DataFlash.logging_present()) { // primary logging only (usually File) + if (rover.logger.logging_present()) { // primary logging only (usually File) control_sensors_present |= MAV_SYS_STATUS_LOGGING; } if (rover.g2.proximity.get_status() > AP_Proximity::Proximity_NotConnected) { @@ -292,7 +292,7 @@ void Rover::update_sensor_status_flags(void) control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; // X/Y position control } - if (rover.DataFlash.logging_enabled()) { + if (rover.logger.logging_enabled()) { control_sensors_enabled |= MAV_SYS_STATUS_LOGGING; } @@ -339,7 +339,7 @@ void Rover::update_sensor_status_flags(void) if (rover.g2.proximity.get_status() == AP_Proximity::Proximity_NoData) { control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_LASER_POSITION; } - if (rover.DataFlash.logging_failed()) { + if (rover.logger.logging_failed()) { control_sensors_health &= ~MAV_SYS_STATUS_LOGGING; } diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index 6f96a9b1f0..164a46c17b 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -183,9 +183,9 @@ void Rover::startup_ground(void) // initialise mission library mode_auto.mission.init(); - // initialise DataFlash library + // initialise AP_Logger library #if LOGGING_ENABLED == ENABLED - DataFlash.setVehicle_Startup_Log_Writer( + logger.setVehicle_Startup_Log_Writer( FUNCTOR_BIND(&rover, &Rover::Log_Write_Vehicle_Startup_Messages, void) ); #endif @@ -262,7 +262,7 @@ bool Rover::set_mode(Mode &new_mode, mode_reason_t reason) old_mode.exit(); control_mode_reason = reason; - DataFlash.Log_Write_Mode(control_mode->mode_number(), control_mode_reason); + logger.Log_Write_Mode(control_mode->mode_number(), control_mode_reason); notify_mode(control_mode); return true; @@ -308,7 +308,7 @@ uint8_t Rover::check_digital_pin(uint8_t pin) */ bool Rover::should_log(uint32_t mask) { - return DataFlash.should_log(mask); + return logger.should_log(mask); } /* diff --git a/AntennaTracker/AntennaTracker.cpp b/AntennaTracker/AntennaTracker.cpp index 0864c06e4d..b5cdb4c6ce 100644 --- a/AntennaTracker/AntennaTracker.cpp +++ b/AntennaTracker/AntennaTracker.cpp @@ -44,7 +44,7 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, accumulate, 50, 900), SCHED_TASK(ten_hz_logging_loop, 10, 300), #if LOGGING_ENABLED == ENABLED - SCHED_TASK_CLASS(DataFlash_Class, &tracker.DataFlash, periodic_tasks, 50, 300), + SCHED_TASK_CLASS(AP_Logger, &tracker.logger, periodic_tasks, 50, 300), #endif SCHED_TASK_CLASS(AP_InertialSensor, &tracker.ins, periodic, 50, 50), SCHED_TASK_CLASS(AP_Notify, &tracker.notify, update, 50, 100), @@ -123,23 +123,23 @@ void Tracker::one_second_loop() void Tracker::ten_hz_logging_loop() { if (should_log(MASK_LOG_IMU)) { - DataFlash.Log_Write_IMU(); + logger.Log_Write_IMU(); } if (should_log(MASK_LOG_ATTITUDE)) { Log_Write_Attitude(); } if (should_log(MASK_LOG_RCIN)) { - DataFlash.Log_Write_RCIN(); + logger.Log_Write_RCIN(); } if (should_log(MASK_LOG_RCOUT)) { - DataFlash.Log_Write_RCOUT(); + logger.Log_Write_RCOUT(); } } const AP_HAL::HAL& hal = AP_HAL::get_HAL(); Tracker::Tracker(void) - : DataFlash(g.log_bitmask) + : logger(g.log_bitmask) { memset(&vehicle, 0, sizeof(vehicle)); } diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 8a3d01564c..9b3c7c34e7 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -580,7 +580,7 @@ void Tracker::mavlink_delay_cb() return; } - DataFlash.EnableWrites(false); + logger.EnableWrites(false); uint32_t tnow = AP_HAL::millis(); if (tnow - last_1hz > 1000) { @@ -598,7 +598,7 @@ void Tracker::mavlink_delay_cb() last_5s = tnow; gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM"); } - DataFlash.EnableWrites(true); + logger.EnableWrites(true); } /* diff --git a/AntennaTracker/Log.cpp b/AntennaTracker/Log.cpp index 66453e1876..dac8bf21f5 100644 --- a/AntennaTracker/Log.cpp +++ b/AntennaTracker/Log.cpp @@ -2,7 +2,7 @@ #if LOGGING_ENABLED == ENABLED -// Code to Write and Read packets from DataFlash log memory +// Code to Write and Read packets from AP_Logger log memory // Write an attitude packet void Tracker::Log_Write_Attitude() @@ -10,13 +10,13 @@ void Tracker::Log_Write_Attitude() Vector3f targets; targets.y = nav_status.pitch * 100.0f; targets.z = wrap_360_cd(nav_status.bearing * 100.0f); - DataFlash.Log_Write_Attitude(ahrs, targets); - DataFlash.Log_Write_EKF(ahrs); - DataFlash.Log_Write_AHRS2(ahrs); + logger.Log_Write_Attitude(ahrs, targets); + logger.Log_Write_EKF(ahrs); + logger.Log_Write_AHRS2(ahrs); #if CONFIG_HAL_BOARD == HAL_BOARD_SITL sitl.Log_Write_SIMSTATE(); #endif - DataFlash.Log_Write_POS(ahrs); + logger.Log_Write_POS(ahrs); } struct PACKED log_Vehicle_Baro { @@ -35,7 +35,7 @@ void Tracker::Log_Write_Vehicle_Baro(float pressure, float altitude) press : pressure, alt_diff : altitude }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } struct PACKED log_Vehicle_Pos { @@ -62,11 +62,11 @@ void Tracker::Log_Write_Vehicle_Pos(int32_t lat, int32_t lng, int32_t alt, const vehicle_vel_y : vel.y, vehicle_vel_z : vel.z, }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } // type and unit information can be found in -// libraries/DataFlash/Logstructure.h; search for "log_Units" for +// libraries/AP_Logger/Logstructure.h; search for "log_Units" for // units and "Format characters" for field type information const struct LogStructure Tracker::log_structure[] = { LOG_COMMON_STRUCTURES, @@ -78,13 +78,13 @@ const struct LogStructure Tracker::log_structure[] = { void Tracker::Log_Write_Vehicle_Startup_Messages() { - DataFlash.Log_Write_Mode(control_mode, MODE_REASON_INITIALISED); - gps.Write_DataFlash_Log_Startup_messages(); + logger.Log_Write_Mode(control_mode, MODE_REASON_INITIALISED); + gps.Write_AP_Logger_Log_Startup_messages(); } void Tracker::log_init(void) { - DataFlash.Init(log_structure, ARRAY_SIZE(log_structure)); + logger.Init(log_structure, ARRAY_SIZE(log_structure)); } #else // LOGGING_ENABLED diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 31a638810e..6353ad8904 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -41,7 +41,7 @@ #include // Serial manager library #include // ArduPilot Mega Declination Helper Library -#include +#include #include #include // main loop scheduler #include @@ -98,7 +98,7 @@ private: uint32_t start_time_ms = 0; - DataFlash_Class DataFlash; + AP_Logger logger; AP_GPS gps; diff --git a/AntennaTracker/sensors.cpp b/AntennaTracker/sensors.cpp index 6843d871b6..1258a0b623 100644 --- a/AntennaTracker/sensors.cpp +++ b/AntennaTracker/sensors.cpp @@ -17,7 +17,7 @@ void Tracker::update_compass(void) if (g.compass_enabled && compass.read()) { ahrs.set_compass(&compass); if (should_log(MASK_LOG_COMPASS)) { - DataFlash.Log_Write_Compass(); + logger.Log_Write_Compass(); } } } @@ -103,7 +103,7 @@ void Tracker::update_sensor_status_flags() if (gps.status() > AP_GPS::NO_GPS) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS; } - if (DataFlash.logging_present()) { // primary logging only (usually File) + if (logger.logging_present()) { // primary logging only (usually File) control_sensors_present |= MAV_SYS_STATUS_LOGGING; } @@ -112,7 +112,7 @@ void Tracker::update_sensor_status_flags() ~MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS & ~MAV_SYS_STATUS_SENSOR_BATTERY); - if (DataFlash.logging_enabled()) { + if (logger.logging_enabled()) { control_sensors_enabled |= MAV_SYS_STATUS_LOGGING; } @@ -143,7 +143,7 @@ void Tracker::update_sensor_status_flags() // AHRS subsystem is unhealthy control_sensors_health &= ~MAV_SYS_STATUS_AHRS; } - if (DataFlash.logging_failed()) { + if (logger.logging_failed()) { control_sensors_health &= ~MAV_SYS_STATUS_LOGGING; } if (!battery.healthy() || battery.has_failsafed()) { diff --git a/AntennaTracker/system.cpp b/AntennaTracker/system.cpp index 9a4986256f..4ddb962fa5 100644 --- a/AntennaTracker/system.cpp +++ b/AntennaTracker/system.cpp @@ -76,8 +76,8 @@ void Tracker::init_tracker() barometer.calibrate(); - // initialise DataFlash library - DataFlash.setVehicle_Startup_Log_Writer(FUNCTOR_BIND(&tracker, &Tracker::Log_Write_Vehicle_Startup_Messages, void)); + // initialise AP_Logger library + logger.setVehicle_Startup_Log_Writer(FUNCTOR_BIND(&tracker, &Tracker::Log_Write_Vehicle_Startup_Messages, void)); // set serial ports non-blocking serial_manager.set_blocking_writes_all(false); @@ -163,13 +163,13 @@ void Tracker::set_home(struct Location temp) void Tracker::arm_servos() { hal.util->set_soft_armed(true); - DataFlash.set_vehicle_armed(true); + logger.set_vehicle_armed(true); } void Tracker::disarm_servos() { hal.util->set_soft_armed(false); - DataFlash.set_vehicle_armed(false); + logger.set_vehicle_armed(false); } /* @@ -207,7 +207,7 @@ void Tracker::set_mode(enum ControlMode mode, mode_reason_t reason) } // log mode change - DataFlash.Log_Write_Mode(control_mode, reason); + logger.Log_Write_Mode(control_mode, reason); } /* @@ -215,7 +215,7 @@ void Tracker::set_mode(enum ControlMode mode, mode_reason_t reason) */ bool Tracker::should_log(uint32_t mask) { - if (!DataFlash.should_log(mask)) { + if (!logger.should_log(mask)) { return false; } return true; diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index 1d2eee4c81..deffee9584 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -147,7 +147,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #if LOGGING_ENABLED == ENABLED SCHED_TASK(ten_hz_logging_loop, 10, 350), SCHED_TASK(twentyfive_hz_logging, 25, 110), - SCHED_TASK_CLASS(DataFlash_Class, &copter.DataFlash, periodic_tasks, 400, 300), + SCHED_TASK_CLASS(AP_Logger, &copter.logger, periodic_tasks, 400, 300), #endif SCHED_TASK_CLASS(AP_InertialSensor, &copter.ins, periodic, 400, 50), SCHED_TASK_CLASS(AP_Scheduler, &copter.scheduler, update_logging, 0.1, 75), @@ -312,7 +312,7 @@ void Copter::update_batt_compass(void) compass.read(); // log compass information if (should_log(MASK_LOG_COMPASS) && !ahrs.have_ekf_logging()) { - DataFlash.Log_Write_Compass(); + logger.Log_Write_Compass(); } } } @@ -339,27 +339,27 @@ void Copter::ten_hz_logging_loop() Log_Write_MotBatt(); } if (should_log(MASK_LOG_RCIN)) { - DataFlash.Log_Write_RCIN(); + logger.Log_Write_RCIN(); if (rssi.enabled()) { - DataFlash.Log_Write_RSSI(rssi); + logger.Log_Write_RSSI(rssi); } } if (should_log(MASK_LOG_RCOUT)) { - DataFlash.Log_Write_RCOUT(); + logger.Log_Write_RCOUT(); } if (should_log(MASK_LOG_NTUN) && (flightmode->requires_GPS() || landing_with_GPS())) { pos_control->write_log(); } if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) { - DataFlash.Log_Write_Vibration(); + logger.Log_Write_Vibration(); } if (should_log(MASK_LOG_CTUN)) { attitude_control->control_monitor_log(); #if PROXIMITY_ENABLED == ENABLED - DataFlash.Log_Write_Proximity(g2.proximity); // Write proximity sensor distances + logger.Log_Write_Proximity(g2.proximity); // Write proximity sensor distances #endif #if BEACON_ENABLED == ENABLED - DataFlash.Log_Write_Beacon(g2.beacon); + logger.Log_Write_Beacon(g2.beacon); #endif } #if FRAME_CONFIG == HELI_FRAME @@ -382,7 +382,7 @@ void Copter::twentyfive_hz_logging() // log IMU data if we're not already logging at the higher rate if (should_log(MASK_LOG_IMU) && !should_log(MASK_LOG_IMU_RAW)) { - DataFlash.Log_Write_IMU(); + logger.Log_Write_IMU(); } #endif diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 3dac5ea22f..b792a7386f 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -24,7 +24,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); constructor for main Copter class */ Copter::Copter(void) - : DataFlash(g.log_bitmask), + : logger(g.log_bitmask), flight_modes(&g.flight_mode1), control_mode(STABILIZE), scaleLongDown(1), diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 7f63d1c741..71cf9e9ec5 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -37,7 +37,7 @@ #include #include // Serial manager library #include // ArduPilot GPS library -#include // ArduPilot Mega Flash Memory Library +#include // ArduPilot Mega Flash Memory Library #include #include // ArduPilot Mega Magnetometer Library #include // ArduPilot Mega Vector/Matrix math Library @@ -233,7 +233,7 @@ private: RC_Channel *channel_yaw; // Dataflash - DataFlash_Class DataFlash; + AP_Logger logger; AP_GPS gps; diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index b337d54f19..e3f58d4270 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -228,7 +228,7 @@ void GCS_MAVLINK_Copter::send_pid_tuning() default: continue; } - const DataFlash_Class::PID_Info &pid_info = pid.get_pid_info(); + const AP_Logger::PID_Info &pid_info = pid.get_pid_info(); mavlink_msg_pid_tuning_send(chan, axes[i], pid_info.desired*0.01f, @@ -1360,7 +1360,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) case MAVLINK_MSG_ID_RADIO: case MAVLINK_MSG_ID_RADIO_STATUS: // MAV ID: 109 { - handle_radio_status(msg, copter.DataFlash, copter.should_log(MASK_LOG_PM)); + handle_radio_status(msg, copter.logger, copter.should_log(MASK_LOG_PM)); break; } @@ -1438,7 +1438,7 @@ void Copter::mavlink_delay_cb() static uint32_t last_1hz, last_50hz, last_5s; if (!gcs().chan(0).initialised) return; - DataFlash.EnableWrites(false); + logger.EnableWrites(false); uint32_t tnow = millis(); if (tnow - last_1hz > 1000) { @@ -1457,7 +1457,7 @@ void Copter::mavlink_delay_cb() gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM"); } - DataFlash.EnableWrites(true); + logger.EnableWrites(true); } AP_AdvancedFailsafe *GCS_MAVLINK_Copter::get_advanced_failsafe() const diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index 2eb943e8f4..2a589caeb7 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -2,7 +2,7 @@ #if LOGGING_ENABLED == ENABLED -// Code to Write and Read packets from DataFlash log memory +// Code to Write and Read packets from AP_Logger log memory // Code to interact with the user to dump or erase logs struct PACKED log_Control_Tuning { @@ -29,7 +29,7 @@ void Copter::Log_Write_Control_Tuning() float terr_alt = 0.0f; #if AP_TERRAIN_AVAILABLE && AC_TERRAIN if (!terrain.height_above_terrain(terr_alt, true)) { - terr_alt = DataFlash.quiet_nan(); + terr_alt = logger.quiet_nan(); } #endif float des_alt_m = 0.0f; @@ -43,7 +43,7 @@ void Copter::Log_Write_Control_Tuning() if (target_rangefinder_alt_used) { _target_rangefinder_alt = target_rangefinder_alt * 0.01f; // cm->m } else { - _target_rangefinder_alt = DataFlash.quiet_nan(); + _target_rangefinder_alt = logger.quiet_nan(); } struct log_Control_Tuning pkt = { LOG_PACKET_HEADER_INIT(LOG_CONTROL_TUNING_MSG), @@ -61,7 +61,7 @@ void Copter::Log_Write_Control_Tuning() target_climb_rate : target_climb_rate_cms, climb_rate : climb_rate }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } // Write an attitude packet @@ -69,25 +69,25 @@ void Copter::Log_Write_Attitude() { Vector3f targets = attitude_control->get_att_target_euler_cd(); targets.z = wrap_360_cd(targets.z); - DataFlash.Log_Write_Attitude(ahrs, targets); - DataFlash.Log_Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control); + logger.Log_Write_Attitude(ahrs, targets); + logger.Log_Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control); if (should_log(MASK_LOG_PID)) { - DataFlash.Log_Write_PID(LOG_PIDR_MSG, attitude_control->get_rate_roll_pid().get_pid_info()); - DataFlash.Log_Write_PID(LOG_PIDP_MSG, attitude_control->get_rate_pitch_pid().get_pid_info()); - DataFlash.Log_Write_PID(LOG_PIDY_MSG, attitude_control->get_rate_yaw_pid().get_pid_info()); - DataFlash.Log_Write_PID(LOG_PIDA_MSG, pos_control->get_accel_z_pid().get_pid_info() ); + logger.Log_Write_PID(LOG_PIDR_MSG, attitude_control->get_rate_roll_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIDP_MSG, attitude_control->get_rate_pitch_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIDY_MSG, attitude_control->get_rate_yaw_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIDA_MSG, pos_control->get_accel_z_pid().get_pid_info() ); } } // Write an EKF and POS packet void Copter::Log_Write_EKF_POS() { - DataFlash.Log_Write_EKF(ahrs); - DataFlash.Log_Write_AHRS2(ahrs); + logger.Log_Write_EKF(ahrs); + logger.Log_Write_AHRS2(ahrs); #if CONFIG_HAL_BOARD == HAL_BOARD_SITL sitl.Log_Write_SIMSTATE(); #endif - DataFlash.Log_Write_POS(ahrs); + logger.Log_Write_POS(ahrs); } struct PACKED log_MotBatt { @@ -111,7 +111,7 @@ void Copter::Log_Write_MotBatt() bat_res : (float)(battery.get_resistance()), th_limit : (float)(motors->get_throttle_limit()) }; - DataFlash.WriteBlock(&pkt_mot, sizeof(pkt_mot)); + logger.WriteBlock(&pkt_mot, sizeof(pkt_mot)); #endif } @@ -130,7 +130,7 @@ void Copter::Log_Write_Event(uint8_t id) time_us : AP_HAL::micros64(), id : id }; - DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); + logger.WriteCriticalBlock(&pkt, sizeof(pkt)); } } @@ -152,7 +152,7 @@ void Copter::Log_Write_Data(uint8_t id, int16_t value) id : id, data_value : value }; - DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); + logger.WriteCriticalBlock(&pkt, sizeof(pkt)); } } @@ -174,7 +174,7 @@ void Copter::Log_Write_Data(uint8_t id, uint16_t value) id : id, data_value : value }; - DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); + logger.WriteCriticalBlock(&pkt, sizeof(pkt)); } } @@ -195,7 +195,7 @@ void Copter::Log_Write_Data(uint8_t id, int32_t value) id : id, data_value : value }; - DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); + logger.WriteCriticalBlock(&pkt, sizeof(pkt)); } } @@ -216,7 +216,7 @@ void Copter::Log_Write_Data(uint8_t id, uint32_t value) id : id, data_value : value }; - DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); + logger.WriteCriticalBlock(&pkt, sizeof(pkt)); } } @@ -238,7 +238,7 @@ void Copter::Log_Write_Data(uint8_t id, float value) id : id, data_value : value }; - DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); + logger.WriteCriticalBlock(&pkt, sizeof(pkt)); } } @@ -258,7 +258,7 @@ void Copter::Log_Write_Error(uint8_t sub_system, uint8_t error_code) sub_system : sub_system, error_code : error_code, }; - DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); + logger.WriteCriticalBlock(&pkt, sizeof(pkt)); } struct PACKED log_ParameterTuning { @@ -283,7 +283,7 @@ void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t tuning_high : tune_high }; - DataFlash.WriteBlock(&pkt_tune, sizeof(pkt_tune)); + logger.WriteBlock(&pkt_tune, sizeof(pkt_tune)); } // logs when baro or compass becomes unhealthy @@ -325,7 +325,7 @@ void Copter::Log_Write_Heli() desired_rotor_speed : motors->get_desired_rotor_speed(), main_rotor_speed : motors->get_main_rotor_speed(), }; - DataFlash.WriteBlock(&pkt_heli, sizeof(pkt_heli)); + logger.WriteBlock(&pkt_heli, sizeof(pkt_heli)); } #endif @@ -379,7 +379,7 @@ void Copter::Log_Write_Precland() ekf_outcount : precland.ekf_outlier_count(), estimator : precland.estimator_type() }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); #endif // PRECISION_LANDING == ENABLED } @@ -410,11 +410,11 @@ void Copter::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_tar vel_target_y : vel_target.y, vel_target_z : vel_target.z }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } // type and unit information can be found in -// libraries/DataFlash/Logstructure.h; search for "log_Units" for +// libraries/AP_Logger/Logstructure.h; search for "log_Units" for // units and "Format characters" for field type information const struct LogStructure Copter::log_structure[] = { LOG_COMMON_STRUCTURES, @@ -452,20 +452,20 @@ const struct LogStructure Copter::log_structure[] = { void Copter::Log_Write_Vehicle_Startup_Messages() { - // only 200(?) bytes are guaranteed by DataFlash - DataFlash.Log_Write_MessageF("Frame: %s", get_frame_string()); - DataFlash.Log_Write_Mode(control_mode, control_mode_reason); + // only 200(?) bytes are guaranteed by AP_Logger + logger.Log_Write_MessageF("Frame: %s", get_frame_string()); + logger.Log_Write_Mode(control_mode, control_mode_reason); #if AC_RALLY - DataFlash.Log_Write_Rally(rally); + logger.Log_Write_Rally(rally); #endif ahrs.Log_Write_Home_And_Origin(); - gps.Write_DataFlash_Log_Startup_messages(); + gps.Write_AP_Logger_Log_Startup_messages(); } void Copter::log_init(void) { - DataFlash.Init(log_structure, ARRAY_SIZE(log_structure)); + logger.Init(log_structure, ARRAY_SIZE(log_structure)); } #else // LOGGING_ENABLED diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 4c2742c9bf..75624aa417 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -577,8 +577,8 @@ const AP_Param::Info Copter::var_info[] = { #endif // @Group: LOG - // @Path: ../libraries/DataFlash/DataFlash.cpp - GOBJECT(DataFlash, "LOG", DataFlash_Class), + // @Path: ../libraries/AP_Logger/AP_Logger.cpp + GOBJECT(logger, "LOG", AP_Logger), // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 74ee2e1489..a05df886b0 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -358,7 +358,7 @@ public: k_param_rpm_sensor, k_param_autotune_min_d, // remove k_param_arming, // 252 - AP_Arming - k_param_DataFlash = 253, // 253 - Logging Group + k_param_logger = 253, // 253 - Logging Group // 254,255: reserved diff --git a/ArduCopter/commands.cpp b/ArduCopter/commands.cpp index 8f32b423bb..531adfa2ea 100644 --- a/ArduCopter/commands.cpp +++ b/ArduCopter/commands.cpp @@ -89,7 +89,7 @@ bool Copter::set_home(const Location& loc, bool lock) if (should_log(MASK_LOG_CMD)) { AP_Mission::Mission_Command temp_cmd; if (mode_auto.mission.read_cmd_from_storage(0, temp_cmd)) { - DataFlash.Log_Write_Mission_Cmd(mode_auto.mission, temp_cmd); + logger.Log_Write_Mission_Cmd(mode_auto.mission, temp_cmd); } } #endif diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index 1f498152b0..37b6a49ea1 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -50,7 +50,7 @@ void Copter::crash_check() // log an error in the dataflash Log_Write_Error(ERROR_SUBSYSTEM_CRASH_CHECK, ERROR_CODE_CRASH_CHECK_CRASH); // keep logging even if disarmed: - DataFlash_Class::instance()->set_force_log_disarmed(true); + AP_Logger::instance()->set_force_log_disarmed(true); // send message to gcs gcs().send_text(MAV_SEVERITY_EMERGENCY,"Crash: Disarming"); // disarm motors diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 2213462797..c30f47fffa 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -213,7 +213,7 @@ bool Copter::set_mode(control_mode_t mode, mode_reason_t reason) flightmode = new_flightmode; control_mode = mode; control_mode_reason = reason; - DataFlash.Log_Write_Mode(control_mode, reason); + logger.Log_Write_Mode(control_mode, reason); #if ADSB_ENABLED == ENABLED adsb.set_is_auto_mode((mode == AUTO) || (mode == RTL) || (mode == GUIDED)); diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 4c64ec1ee3..5bc4c6e700 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -379,7 +379,7 @@ bool Copter::ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) { // To-Do: logging when new commands start/end if (copter.should_log(MASK_LOG_CMD)) { - copter.DataFlash.Log_Write_Mission_Cmd(mission, cmd); + copter.logger.Log_Write_Mission_Cmd(mission, cmd); } switch(cmd.id) { diff --git a/ArduCopter/mode_autotune.cpp b/ArduCopter/mode_autotune.cpp index 307d0ddccd..5f208f7f0a 100644 --- a/ArduCopter/mode_autotune.cpp +++ b/ArduCopter/mode_autotune.cpp @@ -114,9 +114,9 @@ void Copter::AutoTune::init_z_limits() void Copter::AutoTune::log_pids() { - copter.DataFlash.Log_Write_PID(LOG_PIDR_MSG, copter.attitude_control->get_rate_roll_pid().get_pid_info()); - copter.DataFlash.Log_Write_PID(LOG_PIDP_MSG, copter.attitude_control->get_rate_pitch_pid().get_pid_info()); - copter.DataFlash.Log_Write_PID(LOG_PIDY_MSG, copter.attitude_control->get_rate_yaw_pid().get_pid_info()); + copter.logger.Log_Write_PID(LOG_PIDR_MSG, copter.attitude_control->get_rate_roll_pid().get_pid_info()); + copter.logger.Log_Write_PID(LOG_PIDP_MSG, copter.attitude_control->get_rate_pitch_pid().get_pid_info()); + copter.logger.Log_Write_PID(LOG_PIDY_MSG, copter.attitude_control->get_rate_yaw_pid().get_pid_info()); } diff --git a/ArduCopter/mode_flowhold.cpp b/ArduCopter/mode_flowhold.cpp index c18687714f..0fce4f8a0f 100644 --- a/ArduCopter/mode_flowhold.cpp +++ b/ArduCopter/mode_flowhold.cpp @@ -211,7 +211,7 @@ void Copter::ModeFlowHold::flowhold_flow_to_angle(Vector2f &bf_angles, bool stic bf_angles.y = constrain_float(bf_angles.y, -copter.aparm.angle_max, copter.aparm.angle_max); if (log_counter++ % 20 == 0) { - DataFlash_Class::instance()->Log_Write("FHLD", "TimeUS,SFx,SFy,Ax,Ay,Qual,Ix,Iy", "Qfffffff", + AP_Logger::instance()->Log_Write("FHLD", "TimeUS,SFx,SFy,Ax,Ay,Qual,Ix,Iy", "Qfffffff", AP_HAL::micros64(), (double)sensor_flow.x, (double)sensor_flow.y, (double)bf_angles.x, (double)bf_angles.y, @@ -511,7 +511,7 @@ void Copter::ModeFlowHold::update_height_estimate(void) // new height estimate for logging height_estimate = ins_height + height_offset; - DataFlash_Class::instance()->Log_Write("FXY", "TimeUS,DFx,DFy,DVx,DVy,Hest,DH,Hofs,InsH,LastInsH,DTms", "QfffffffffI", + AP_Logger::instance()->Log_Write("FXY", "TimeUS,DFx,DFy,DVx,DVy,Hest,DH,Hofs,InsH,LastInsH,DTms", "QfffffffffI", AP_HAL::micros64(), (double)delta_flowrate.x, (double)delta_flowrate.y, diff --git a/ArduCopter/mode_throw.cpp b/ArduCopter/mode_throw.cpp index 66cfa24b07..1fbdf334c3 100644 --- a/ArduCopter/mode_throw.cpp +++ b/ArduCopter/mode_throw.cpp @@ -194,7 +194,7 @@ void Copter::ModeThrow::run() const bool attitude_ok = (stage > Throw_Uprighting) || throw_attitude_good(); const bool height_ok = (stage > Throw_HgtStabilise) || throw_height_good(); const bool pos_ok = (stage > Throw_PosHold) || throw_position_good(); - DataFlash_Class::instance()->Log_Write( + AP_Logger::instance()->Log_Write( "THRO", "TimeUS,Stage,Vel,VelZ,Acc,AccEfZ,Throw,AttOk,HgtOk,PosOk", "s-nnoo----", diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index 305bd5857a..db68f643c8 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -157,7 +157,7 @@ bool Copter::init_arm_motors(const AP_Arming::ArmingMethod method, const bool do } // let dataflash know that we're armed (it may open logs e.g.) - DataFlash_Class::instance()->set_vehicle_armed(true); + AP_Logger::instance()->set_vehicle_armed(true); // disable cpu failsafe because initialising everything takes a while failsafe_disable(); @@ -219,7 +219,7 @@ bool Copter::init_arm_motors(const AP_Arming::ArmingMethod method, const bool do Log_Write_Event(DATA_ARMED); // log flight mode in case it was changed while vehicle was disarmed - DataFlash.Log_Write_Mode(control_mode, control_mode_reason); + logger.Log_Write_Mode(control_mode, control_mode_reason); // reenable failsafe failsafe_enable(); @@ -285,7 +285,7 @@ void Copter::init_disarm_motors() mode_auto.mission.reset(); #endif - DataFlash_Class::instance()->set_vehicle_armed(false); + AP_Logger::instance()->set_vehicle_armed(false); // disable gps velocity based centrefugal force compensation ahrs.set_correct_centrifugal(false); diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index 18bc08ccb4..b02075d16a 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -27,7 +27,7 @@ void Copter::read_rangefinder(void) if (rangefinder.num_sensors() > 0 && should_log(MASK_LOG_CTUN)) { - DataFlash.Log_Write_RFND(rangefinder); + logger.Log_Write_RFND(rangefinder); } rangefinder_state.alt_healthy = ((rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::RangeFinder_Good) && (rangefinder.range_valid_count_orient(ROTATION_PITCH_270) >= RANGEFINDER_HEALTH_MAX)); @@ -79,7 +79,7 @@ void Copter::rpm_update(void) rpm_sensor.update(); if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) { if (should_log(MASK_LOG_RCIN)) { - DataFlash.Log_Write_RPM(rpm_sensor); + logger.Log_Write_RPM(rpm_sensor); } } #endif @@ -216,7 +216,7 @@ void Copter::update_sensor_status_flags(void) if (ap.rc_receiver_present) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER; } - if (copter.DataFlash.logging_present()) { // primary logging only (usually File) + if (copter.logger.logging_present()) { // primary logging only (usually File) control_sensors_present |= MAV_SYS_STATUS_LOGGING; } #if PROXIMITY_ENABLED == ENABLED @@ -277,7 +277,7 @@ void Copter::update_sensor_status_flags(void) control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS; } - if (copter.DataFlash.logging_enabled()) { + if (copter.logger.logging_enabled()) { control_sensors_enabled |= MAV_SYS_STATUS_LOGGING; } @@ -338,7 +338,7 @@ void Copter::update_sensor_status_flags(void) control_sensors_health &= ~MAV_SYS_STATUS_AHRS; } - if (copter.DataFlash.logging_failed()) { + if (copter.logger.logging_failed()) { control_sensors_health &= ~MAV_SYS_STATUS_LOGGING; } @@ -418,7 +418,7 @@ void Copter::update_visual_odom() visual_odom_last_update_ms, g2.visual_odom.get_pos_offset()); // log sensor data - DataFlash.Log_Write_VisualOdom(time_delta_sec, + logger.Log_Write_VisualOdom(time_delta_sec, g2.visual_odom.get_angle_delta(), g2.visual_odom.get_position_delta(), g2.visual_odom.get_confidence()); diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 66b32acdd3..70ba3566d3 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -239,8 +239,8 @@ void Copter::init_ardupilot() g2.smart_rtl.init(); #endif - // initialise DataFlash library - DataFlash.setVehicle_Startup_Log_Writer(FUNCTOR_BIND(&copter, &Copter::Log_Write_Vehicle_Startup_Messages, void)); + // initialise AP_Logger library + logger.setVehicle_Startup_Log_Writer(FUNCTOR_BIND(&copter, &Copter::Log_Write_Vehicle_Startup_Messages, void)); // initialise rc channels including setting mode rc().init(); @@ -408,8 +408,8 @@ void Copter::update_auto_armed() bool Copter::should_log(uint32_t mask) { #if LOGGING_ENABLED == ENABLED - ap.logging_started = DataFlash.logging_started(); - return DataFlash.should_log(mask); + ap.logging_started = logger.logging_started(); + return logger.should_log(mask); #else return false; #endif diff --git a/ArduCopter/toy_mode.cpp b/ArduCopter/toy_mode.cpp index 674a591598..237ab8eb85 100644 --- a/ArduCopter/toy_mode.cpp +++ b/ArduCopter/toy_mode.cpp @@ -991,7 +991,7 @@ void ToyMode::thrust_limiting(float *thrust, uint8_t num_motors) uint16_t pwm[4]; hal.rcout->read(pwm, 4); if (motor_log_counter++ % 10 == 0) { - DataFlash_Class::instance()->Log_Write("THST", "TimeUS,Vol,Mul,M1,M2,M3,M4", "QffHHHH", + AP_Logger::instance()->Log_Write("THST", "TimeUS,Vol,Mul,M1,M2,M3,M4", "QffHHHH", AP_HAL::micros64(), (double)filtered_voltage, (double)thrust_mul, diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 1d0dc13f96..ecf5f381fd 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -85,7 +85,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = { #endif // AP_TERRAIN_AVAILABLE SCHED_TASK(update_is_flying_5Hz, 5, 100), #if LOGGING_ENABLED == ENABLED - SCHED_TASK_CLASS(DataFlash_Class, &plane.DataFlash, periodic_tasks, 50, 400), + SCHED_TASK_CLASS(AP_Logger, &plane.logger, periodic_tasks, 50, 400), #endif SCHED_TASK_CLASS(AP_InertialSensor, &plane.ins, periodic, 50, 50), SCHED_TASK(avoidance_adsb_update, 10, 100), @@ -130,7 +130,7 @@ void Plane::update_soft_armed() { hal.util->set_soft_armed(arming.is_armed() && hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED); - DataFlash.set_vehicle_armed(hal.util->get_soft_armed()); + logger.set_vehicle_armed(hal.util->get_soft_armed()); } // update AHRS system @@ -148,7 +148,7 @@ void Plane::ahrs_update() ahrs.update(); if (should_log(MASK_LOG_IMU)) { - DataFlash.Log_Write_IMU(); + logger.Log_Write_IMU(); } // calculate a scaled roll limit based on current pitch @@ -195,7 +195,7 @@ void Plane::update_compass(void) if (g.compass_enabled && compass.read()) { ahrs.set_compass(&compass); if (should_log(MASK_LOG_COMPASS) && !ahrs.have_ekf_logging()) { - DataFlash.Log_Write_Compass(); + logger.Log_Write_Compass(); } } } @@ -210,10 +210,10 @@ void Plane::update_logging1(void) } if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_IMU)) - DataFlash.Log_Write_IMU(); + logger.Log_Write_IMU(); if (should_log(MASK_LOG_ATTITUDE_MED)) - DataFlash.Log_Write_AOA_SSA(ahrs); + logger.Log_Write_AOA_SSA(ahrs); } /* @@ -231,7 +231,7 @@ void Plane::update_logging2(void) Log_Write_RC(); if (should_log(MASK_LOG_IMU)) - DataFlash.Log_Write_Vibration(); + logger.Log_Write_Vibration(); } diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index dc78fe90d0..f9de2f5cc5 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -344,7 +344,7 @@ void NOINLINE Plane::send_rpm(mavlink_channel_t chan) } // sends a single pid info over the provided channel -void Plane::send_pid_info(const mavlink_channel_t chan, const DataFlash_Class::PID_Info *pid_info, +void Plane::send_pid_info(const mavlink_channel_t chan, const AP_Logger::PID_Info *pid_info, const uint8_t axis, const float achieved) { if (pid_info == nullptr) { @@ -368,7 +368,7 @@ void Plane::send_pid_info(const mavlink_channel_t chan, const DataFlash_Class::P void Plane::send_pid_tuning(mavlink_channel_t chan) { const Vector3f &gyro = ahrs.get_gyro(); - const DataFlash_Class::PID_Info *pid_info; + const AP_Logger::PID_Info *pid_info; if (g.gcs_pid_mask & TUNING_BITS_ROLL) { if (quadplane.in_vtol_mode()) { pid_info = &quadplane.attitude_control->get_rate_roll_pid().get_pid_info(); @@ -1272,7 +1272,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg) case MAVLINK_MSG_ID_RADIO: case MAVLINK_MSG_ID_RADIO_STATUS: { - handle_radio_status(msg, plane.DataFlash, plane.should_log(MASK_LOG_PM)); + handle_radio_status(msg, plane.logger, plane.should_log(MASK_LOG_PM)); break; } @@ -1478,7 +1478,7 @@ void Plane::mavlink_delay_cb() static uint32_t last_1hz, last_50hz, last_5s; if (!gcs().chan(0).initialised) return; - DataFlash.EnableWrites(false); + logger.EnableWrites(false); uint32_t tnow = millis(); if (tnow - last_1hz > 1000) { @@ -1497,7 +1497,7 @@ void Plane::mavlink_delay_cb() gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM"); } - DataFlash.EnableWrites(true); + logger.EnableWrites(true); } /* diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index ef85116b73..d8632c1f47 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -21,31 +21,31 @@ void Plane::Log_Write_Attitude(void) // we need the attitude targets from the AC_AttitudeControl controller, as they // account for the acceleration limits targets = quadplane.attitude_control->get_att_target_euler_cd(); - DataFlash.Log_Write_AttitudeView(*quadplane.ahrs_view, targets); + logger.Log_Write_AttitudeView(*quadplane.ahrs_view, targets); } else { - DataFlash.Log_Write_Attitude(ahrs, targets); + logger.Log_Write_Attitude(ahrs, targets); } if (quadplane.in_vtol_mode() || quadplane.in_assisted_flight()) { // log quadplane PIDs separately from fixed wing PIDs - DataFlash.Log_Write_PID(LOG_PIQR_MSG, quadplane.attitude_control->get_rate_roll_pid().get_pid_info()); - DataFlash.Log_Write_PID(LOG_PIQP_MSG, quadplane.attitude_control->get_rate_pitch_pid().get_pid_info()); - DataFlash.Log_Write_PID(LOG_PIQY_MSG, quadplane.attitude_control->get_rate_yaw_pid().get_pid_info()); - DataFlash.Log_Write_PID(LOG_PIQA_MSG, quadplane.pos_control->get_accel_z_pid().get_pid_info() ); + logger.Log_Write_PID(LOG_PIQR_MSG, quadplane.attitude_control->get_rate_roll_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIQP_MSG, quadplane.attitude_control->get_rate_pitch_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIQY_MSG, quadplane.attitude_control->get_rate_yaw_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIQA_MSG, quadplane.pos_control->get_accel_z_pid().get_pid_info() ); } - DataFlash.Log_Write_PID(LOG_PIDR_MSG, rollController.get_pid_info()); - DataFlash.Log_Write_PID(LOG_PIDP_MSG, pitchController.get_pid_info()); - DataFlash.Log_Write_PID(LOG_PIDY_MSG, yawController.get_pid_info()); - DataFlash.Log_Write_PID(LOG_PIDS_MSG, steerController.get_pid_info()); + logger.Log_Write_PID(LOG_PIDR_MSG, rollController.get_pid_info()); + logger.Log_Write_PID(LOG_PIDP_MSG, pitchController.get_pid_info()); + logger.Log_Write_PID(LOG_PIDY_MSG, yawController.get_pid_info()); + logger.Log_Write_PID(LOG_PIDS_MSG, steerController.get_pid_info()); #if AP_AHRS_NAVEKF_AVAILABLE - DataFlash.Log_Write_EKF(ahrs); - DataFlash.Log_Write_AHRS2(ahrs); + logger.Log_Write_EKF(ahrs); + logger.Log_Write_AHRS2(ahrs); #endif #if CONFIG_HAL_BOARD == HAL_BOARD_SITL sitl.Log_Write_SIMSTATE(); #endif - DataFlash.Log_Write_POS(ahrs); + logger.Log_Write_POS(ahrs); } // do logging at loop rate @@ -72,7 +72,7 @@ void Plane::Log_Write_Startup(uint8_t type) startup_type : type, command_total : mission.num_commands() }; - DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); + logger.WriteCriticalBlock(&pkt, sizeof(pkt)); } struct PACKED log_Control_Tuning { @@ -106,7 +106,7 @@ void Plane::Log_Write_Control_Tuning() throttle_dem : (int16_t)SpdHgt_Controller->get_throttle_demand(), airspeed_estimate : est_airspeed }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } struct PACKED log_Nav_Tuning { @@ -143,7 +143,7 @@ void Plane::Log_Write_Nav_Tuning() target_alt : next_WP_loc.alt, target_airspeed : target_airspeed_cm, }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } struct PACKED log_Status { @@ -174,7 +174,7 @@ void Plane::Log_Write_Status() ,impact : crash_state.impact_detected }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } struct PACKED log_Sonar { @@ -202,9 +202,9 @@ void Plane::Log_Write_Sonar() count : rangefinder_state.in_range_count, correction : rangefinder_state.correction }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); - DataFlash.Log_Write_RFND(rangefinder); + logger.Log_Write_RFND(rangefinder); } struct PACKED log_Arm_Disarm { @@ -221,7 +221,7 @@ void Plane::Log_Arm_Disarm() { arm_state : arming.is_armed(), arm_checks : arming.get_enabled_checks() }; - DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); + logger.WriteCriticalBlock(&pkt, sizeof(pkt)); } @@ -247,21 +247,21 @@ void Plane::Log_Write_AETR() ,flap : SRV_Channels::get_output_scaled(SRV_Channel::k_flap_auto) }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } void Plane::Log_Write_RC(void) { - DataFlash.Log_Write_RCIN(); - DataFlash.Log_Write_RCOUT(); + logger.Log_Write_RCIN(); + logger.Log_Write_RCOUT(); if (rssi.enabled()) { - DataFlash.Log_Write_RSSI(rssi); + logger.Log_Write_RSSI(rssi); } Log_Write_AETR(); } // type and unit information can be found in -// libraries/DataFlash/Logstructure.h; search for "log_Units" for +// libraries/AP_Logger/Logstructure.h; search for "log_Units" for // units and "Format characters" for field type information const struct LogStructure Plane::log_structure[] = { LOG_COMMON_STRUCTURES, @@ -297,12 +297,12 @@ const struct LogStructure Plane::log_structure[] = { void Plane::Log_Write_Vehicle_Startup_Messages() { - // only 200(?) bytes are guaranteed by DataFlash + // only 200(?) bytes are guaranteed by AP_Logger Log_Write_Startup(TYPE_GROUNDSTART_MSG); - DataFlash.Log_Write_Mode(control_mode, control_mode_reason); - DataFlash.Log_Write_Rally(rally); + logger.Log_Write_Mode(control_mode, control_mode_reason); + logger.Log_Write_Rally(rally); ahrs.Log_Write_Home_And_Origin(); - gps.Write_DataFlash_Log_Startup_messages(); + gps.Write_AP_Logger_Log_Startup_messages(); } /* @@ -310,7 +310,7 @@ void Plane::Log_Write_Vehicle_Startup_Messages() */ void Plane::log_init(void) { - DataFlash.Init(log_structure, ARRAY_SIZE(log_structure)); + logger.Init(log_structure, ARRAY_SIZE(log_structure)); } #else // LOGGING_ENABLED diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 7dfde82888..aa94e5c6fb 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1018,8 +1018,8 @@ const AP_Param::Info Plane::var_info[] = { #endif // @Group: LOG - // @Path: ../libraries/DataFlash/DataFlash.cpp - GOBJECT(DataFlash, "LOG", DataFlash_Class), + // @Path: ../libraries/AP_Logger/AP_Logger.cpp + GOBJECT(logger, "LOG", AP_Logger), // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index af5ccd4ac9..4f539f2d87 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -342,7 +342,7 @@ public: k_param_mixing_offset, k_param_dspoiler_rud_rate, - k_param_DataFlash = 253, // Logging Group + k_param_logger = 253, // Logging Group // 254,255: reserved }; diff --git a/ArduPlane/Plane.cpp b/ArduPlane/Plane.cpp index 78e59ee181..3a8200bdcf 100644 --- a/ArduPlane/Plane.cpp +++ b/ArduPlane/Plane.cpp @@ -24,7 +24,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); constructor for main Plane class */ Plane::Plane(void) - : DataFlash(g.log_bitmask) + : logger(g.log_bitmask) { // C++11 doesn't allow in-class initialisation of bitfields auto_state.takeoff_complete = true; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 8cf222be2f..1c5fcc1fe6 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -58,7 +58,7 @@ #include // Serial manager library #include // Camera/Antenna mount #include // ArduPilot Mega Declination Helper Library -#include +#include #include // main loop scheduler #include // loop perf monitoring @@ -196,7 +196,7 @@ private: // notification object for LEDs, buzzers etc (parameter set to false disables external leds) AP_Notify notify; - DataFlash_Class DataFlash; + AP_Logger logger; // scaled roll limit based on pitch int32_t roll_limit_cd; @@ -808,7 +808,7 @@ private: void send_nav_controller_output(mavlink_channel_t chan); void send_servo_out(mavlink_channel_t chan); void send_wind(mavlink_channel_t chan); - void send_pid_info(const mavlink_channel_t chan, const DataFlash_Class::PID_Info *pid_info, const uint8_t axis, const float achieved); + void send_pid_info(const mavlink_channel_t chan, const AP_Logger::PID_Info *pid_info, const uint8_t axis, const float achieved); void send_pid_tuning(mavlink_channel_t chan); void send_rpm(mavlink_channel_t chan); diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index a464b4b9d2..a491833bcf 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -10,7 +10,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) // log when new commands start if (should_log(MASK_LOG_CMD)) { - DataFlash.Log_Write_Mission_Cmd(mission, cmd); + logger.Log_Write_Mission_Cmd(mission, cmd); } // special handling for nav vs non-nav commands @@ -337,7 +337,7 @@ void Plane::do_RTL(int32_t rtl_altitude) setup_glide_slope(); setup_turn_angle(); - DataFlash.Log_Write_Mode(control_mode, control_mode_reason); + logger.Log_Write_Mode(control_mode, control_mode_reason); } /* diff --git a/ArduPlane/qautotune.cpp b/ArduPlane/qautotune.cpp index 5baa800efc..7977ef1450 100644 --- a/ArduPlane/qautotune.cpp +++ b/ArduPlane/qautotune.cpp @@ -51,7 +51,7 @@ void QAutoTune::Log_Write_Event(enum at_event id) { // offset of 30 aligned with ArduCopter autotune events uint8_t ev_id = 30 + (uint8_t)id; - DataFlash_Class::instance()->Log_Write( + AP_Logger::instance()->Log_Write( "EVT", "TimeUS,Id", "s-", @@ -64,9 +64,9 @@ void QAutoTune::Log_Write_Event(enum at_event id) // log VTOL PIDs for during twitch void QAutoTune::log_pids(void) { - DataFlash_Class::instance()->Log_Write_PID(LOG_PIQR_MSG, plane.quadplane.attitude_control->get_rate_roll_pid().get_pid_info()); - DataFlash_Class::instance()->Log_Write_PID(LOG_PIQP_MSG, plane.quadplane.attitude_control->get_rate_pitch_pid().get_pid_info()); - DataFlash_Class::instance()->Log_Write_PID(LOG_PIQY_MSG, plane.quadplane.attitude_control->get_rate_yaw_pid().get_pid_info()); + AP_Logger::instance()->Log_Write_PID(LOG_PIQR_MSG, plane.quadplane.attitude_control->get_rate_roll_pid().get_pid_info()); + AP_Logger::instance()->Log_Write_PID(LOG_PIQP_MSG, plane.quadplane.attitude_control->get_rate_pitch_pid().get_pid_info()); + AP_Logger::instance()->Log_Write_PID(LOG_PIQY_MSG, plane.quadplane.attitude_control->get_rate_yaw_pid().get_pid_info()); } #endif // QAUTOTUNE_ENABLED diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 9e91bce741..4e1ec519ff 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1643,7 +1643,7 @@ void QuadPlane::motors_output(bool run_rate_controller) motors->output(); if (motors->armed() && motors->get_throttle() > 0) { - plane.DataFlash.Log_Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control); + plane.logger.Log_Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control); Log_Write_QControl_Tuning(); const uint32_t now = AP_HAL::millis(); if (now - last_ctrl_log_ms > 100) { @@ -2384,7 +2384,7 @@ void QuadPlane::Log_Write_QControl_Tuning() climb_rate : int16_t(inertial_nav.get_velocity_z()), throttle_mix : attitude_control->get_throttle_mix(), }; - plane.DataFlash.WriteBlock(&pkt, sizeof(pkt)); + plane.logger.WriteBlock(&pkt, sizeof(pkt)); // write multicopter position control message pos_control->write_log(); diff --git a/ArduPlane/sensors.cpp b/ArduPlane/sensors.cpp index 155848241d..5e6b4f583f 100644 --- a/ArduPlane/sensors.cpp +++ b/ArduPlane/sensors.cpp @@ -87,7 +87,7 @@ void Plane::rpm_update(void) rpm_sensor.update(); if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) { if (should_log(MASK_LOG_RC)) { - DataFlash.Log_Write_RPM(rpm_sensor); + logger.Log_Write_RPM(rpm_sensor); } } } @@ -124,7 +124,7 @@ void Plane::update_sensor_status_flags(void) if (have_reverse_thrust()) { control_sensors_present |= MAV_SYS_STATUS_REVERSE_MOTOR; } - if (plane.DataFlash.logging_present()) { // primary logging only (usually File) + if (plane.logger.logging_present()) { // primary logging only (usually File) control_sensors_present |= MAV_SYS_STATUS_LOGGING; } @@ -139,7 +139,7 @@ void Plane::update_sensor_status_flags(void) control_sensors_enabled |= MAV_SYS_STATUS_GEOFENCE; } - if (plane.DataFlash.logging_enabled()) { + if (plane.logger.logging_enabled()) { control_sensors_enabled |= MAV_SYS_STATUS_LOGGING; } @@ -248,7 +248,7 @@ void Plane::update_sensor_status_flags(void) } #endif - if (plane.DataFlash.logging_failed()) { + if (plane.logger.logging_failed()) { control_sensors_health &= ~MAV_SYS_STATUS_LOGGING; } diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 9d417e58e0..2bc6721bd6 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -247,9 +247,9 @@ void Plane::startup_ground(void) // initialise mission library mission.init(); - // initialise DataFlash library + // initialise AP_Logger library #if LOGGING_ENABLED == ENABLED - DataFlash.setVehicle_Startup_Log_Writer( + logger.setVehicle_Startup_Log_Writer( FUNCTOR_BIND(&plane, &Plane::Log_Write_Vehicle_Startup_Messages, void) ); #endif @@ -505,7 +505,7 @@ void Plane::set_mode(enum FlightMode mode, mode_reason_t reason) adsb.set_is_auto_mode(auto_navigation_mode); - DataFlash.Log_Write_Mode(control_mode, control_mode_reason); + logger.Log_Write_Mode(control_mode, control_mode_reason); // update notify with flight mode change notify_flight_mode(control_mode); @@ -735,7 +735,7 @@ void Plane::notify_flight_mode(enum FlightMode mode) bool Plane::should_log(uint32_t mask) { #if LOGGING_ENABLED == ENABLED - return DataFlash.should_log(mask); + return logger.should_log(mask); #else return false; #endif diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 16bb060b96..4ca131c123 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -49,7 +49,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { #endif SCHED_TASK(ten_hz_logging_loop, 10, 350), SCHED_TASK(twentyfive_hz_logging, 25, 110), - SCHED_TASK_CLASS(DataFlash_Class, &sub.DataFlash, periodic_tasks, 400, 300), + SCHED_TASK_CLASS(AP_Logger, &sub.logger, periodic_tasks, 400, 300), SCHED_TASK_CLASS(AP_InertialSensor, &sub.ins, periodic, 400, 50), SCHED_TASK_CLASS(AP_Scheduler, &sub.scheduler, update_logging, 0.1, 75), #if RPM_ENABLED == ENABLED @@ -173,7 +173,7 @@ void Sub::update_batt_compass() compass.read(); // log compass information if (should_log(MASK_LOG_COMPASS) && !ahrs.have_ekf_logging()) { - DataFlash.Log_Write_Compass(); + logger.Log_Write_Compass(); } } } @@ -185,28 +185,28 @@ void Sub::ten_hz_logging_loop() // log attitude data if we're not already logging at the higher rate if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) { Log_Write_Attitude(); - DataFlash.Log_Write_Rate(&ahrs_view, motors, attitude_control, pos_control); + logger.Log_Write_Rate(&ahrs_view, motors, attitude_control, pos_control); if (should_log(MASK_LOG_PID)) { - DataFlash.Log_Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info()); - DataFlash.Log_Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info()); - DataFlash.Log_Write_PID(LOG_PIDY_MSG, attitude_control.get_rate_yaw_pid().get_pid_info()); - DataFlash.Log_Write_PID(LOG_PIDA_MSG, pos_control.get_accel_z_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIDY_MSG, attitude_control.get_rate_yaw_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIDA_MSG, pos_control.get_accel_z_pid().get_pid_info()); } } if (should_log(MASK_LOG_MOTBATT)) { Log_Write_MotBatt(); } if (should_log(MASK_LOG_RCIN)) { - DataFlash.Log_Write_RCIN(); + logger.Log_Write_RCIN(); } if (should_log(MASK_LOG_RCOUT)) { - DataFlash.Log_Write_RCOUT(); + logger.Log_Write_RCOUT(); } if (should_log(MASK_LOG_NTUN) && mode_requires_GPS(control_mode)) { pos_control.write_log(); } if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) { - DataFlash.Log_Write_Vibration(); + logger.Log_Write_Vibration(); } if (should_log(MASK_LOG_CTUN)) { attitude_control.control_monitor_log(); @@ -219,18 +219,18 @@ void Sub::twentyfive_hz_logging() { if (should_log(MASK_LOG_ATTITUDE_FAST)) { Log_Write_Attitude(); - DataFlash.Log_Write_Rate(&ahrs_view, motors, attitude_control, pos_control); + logger.Log_Write_Rate(&ahrs_view, motors, attitude_control, pos_control); if (should_log(MASK_LOG_PID)) { - DataFlash.Log_Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info()); - DataFlash.Log_Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info()); - DataFlash.Log_Write_PID(LOG_PIDY_MSG, attitude_control.get_rate_yaw_pid().get_pid_info()); - DataFlash.Log_Write_PID(LOG_PIDA_MSG, pos_control.get_accel_z_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIDY_MSG, attitude_control.get_rate_yaw_pid().get_pid_info()); + logger.Log_Write_PID(LOG_PIDA_MSG, pos_control.get_accel_z_pid().get_pid_info()); } } // log IMU data if we're not already logging at the higher rate if (should_log(MASK_LOG_IMU) && !should_log(MASK_LOG_IMU_RAW)) { - DataFlash.Log_Write_IMU(); + logger.Log_Write_IMU(); } } diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index c173ea87bc..e40379a48c 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -320,7 +320,7 @@ void Sub::send_pid_tuning(mavlink_channel_t chan) { const Vector3f &gyro = ahrs.get_gyro(); if (g.gcs_pid_mask & 1) { - const DataFlash_Class::PID_Info &pid_info = attitude_control.get_rate_roll_pid().get_pid_info(); + const AP_Logger::PID_Info &pid_info = attitude_control.get_rate_roll_pid().get_pid_info(); mavlink_msg_pid_tuning_send(chan, PID_TUNING_ROLL, pid_info.desired*0.01f, degrees(gyro.x), @@ -333,7 +333,7 @@ void Sub::send_pid_tuning(mavlink_channel_t chan) } } if (g.gcs_pid_mask & 2) { - const DataFlash_Class::PID_Info &pid_info = attitude_control.get_rate_pitch_pid().get_pid_info(); + const AP_Logger::PID_Info &pid_info = attitude_control.get_rate_pitch_pid().get_pid_info(); mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH, pid_info.desired*0.01f, degrees(gyro.y), @@ -346,7 +346,7 @@ void Sub::send_pid_tuning(mavlink_channel_t chan) } } if (g.gcs_pid_mask & 4) { - const DataFlash_Class::PID_Info &pid_info = attitude_control.get_rate_yaw_pid().get_pid_info(); + const AP_Logger::PID_Info &pid_info = attitude_control.get_rate_yaw_pid().get_pid_info(); mavlink_msg_pid_tuning_send(chan, PID_TUNING_YAW, pid_info.desired*0.01f, degrees(gyro.z), @@ -359,7 +359,7 @@ void Sub::send_pid_tuning(mavlink_channel_t chan) } } if (g.gcs_pid_mask & 8) { - const DataFlash_Class::PID_Info &pid_info = pos_control.get_accel_z_pid().get_pid_info(); + const AP_Logger::PID_Info &pid_info = pos_control.get_accel_z_pid().get_pid_info(); mavlink_msg_pid_tuning_send(chan, PID_TUNING_ACCZ, pid_info.desired*0.01f, -(ahrs.get_accel_ef_blended().z + GRAVITY_MSS), @@ -1141,7 +1141,7 @@ void Sub::mavlink_delay_cb() return; } - DataFlash.EnableWrites(false); + logger.EnableWrites(false); uint32_t tnow = AP_HAL::millis(); if (tnow - last_1hz > 1000) { @@ -1160,7 +1160,7 @@ void Sub::mavlink_delay_cb() gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM"); } - DataFlash.EnableWrites(true); + logger.EnableWrites(true); } MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_long_t &packet) { diff --git a/ArduSub/Log.cpp b/ArduSub/Log.cpp index 637f3c3e32..56e3ffbfd2 100644 --- a/ArduSub/Log.cpp +++ b/ArduSub/Log.cpp @@ -2,7 +2,7 @@ #if LOGGING_ENABLED == ENABLED -// Code to Write and Read packets from DataFlash log memory +// Code to Write and Read packets from AP_Logger log memory // Code to interact with the user to dump or erase logs struct PACKED log_Control_Tuning { @@ -47,7 +47,7 @@ void Sub::Log_Write_Control_Tuning() target_climb_rate : (int16_t)pos_control.get_vel_target_z(), climb_rate : climb_rate }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } // Write an attitude packet @@ -55,14 +55,14 @@ void Sub::Log_Write_Attitude() { Vector3f targets = attitude_control.get_att_target_euler_cd(); targets.z = wrap_360_cd(targets.z); - DataFlash.Log_Write_Attitude(ahrs, targets); + logger.Log_Write_Attitude(ahrs, targets); - DataFlash.Log_Write_EKF(ahrs); - DataFlash.Log_Write_AHRS2(ahrs); + logger.Log_Write_EKF(ahrs); + logger.Log_Write_AHRS2(ahrs); #if CONFIG_HAL_BOARD == HAL_BOARD_SITL sitl.Log_Write_SIMSTATE(); #endif - DataFlash.Log_Write_POS(ahrs); + logger.Log_Write_POS(ahrs); } struct PACKED log_MotBatt { @@ -85,7 +85,7 @@ void Sub::Log_Write_MotBatt() bat_res : (float)(battery.get_resistance()), th_limit : (float)(motors.get_throttle_limit()) }; - DataFlash.WriteBlock(&pkt_mot, sizeof(pkt_mot)); + logger.WriteBlock(&pkt_mot, sizeof(pkt_mot)); } struct PACKED log_Event { @@ -103,7 +103,7 @@ void Sub::Log_Write_Event(uint8_t id) time_us : AP_HAL::micros64(), id : id }; - DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); + logger.WriteCriticalBlock(&pkt, sizeof(pkt)); } } @@ -125,7 +125,7 @@ void Sub::Log_Write_Data(uint8_t id, int16_t value) id : id, data_value : value }; - DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); + logger.WriteCriticalBlock(&pkt, sizeof(pkt)); } } @@ -147,7 +147,7 @@ void Sub::Log_Write_Data(uint8_t id, uint16_t value) id : id, data_value : value }; - DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); + logger.WriteCriticalBlock(&pkt, sizeof(pkt)); } } @@ -168,7 +168,7 @@ void Sub::Log_Write_Data(uint8_t id, int32_t value) id : id, data_value : value }; - DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); + logger.WriteCriticalBlock(&pkt, sizeof(pkt)); } } @@ -189,7 +189,7 @@ void Sub::Log_Write_Data(uint8_t id, uint32_t value) id : id, data_value : value }; - DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); + logger.WriteCriticalBlock(&pkt, sizeof(pkt)); } } @@ -211,7 +211,7 @@ void Sub::Log_Write_Data(uint8_t id, float value) id : id, data_value : value }; - DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); + logger.WriteCriticalBlock(&pkt, sizeof(pkt)); } } @@ -231,7 +231,7 @@ void Sub::Log_Write_Error(uint8_t sub_system, uint8_t error_code) sub_system : sub_system, error_code : error_code, }; - DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); + logger.WriteCriticalBlock(&pkt, sizeof(pkt)); } // logs when baro or compass becomes unhealthy @@ -276,11 +276,11 @@ void Sub::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target vel_target_y : vel_target.y, vel_target_z : vel_target.z }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); } // type and unit information can be found in -// libraries/DataFlash/Logstructure.h; search for "log_Units" for +// libraries/AP_Logger/Logstructure.h; search for "log_Units" for // units and "Format characters" for field type information const struct LogStructure Sub::log_structure[] = { LOG_COMMON_STRUCTURES, @@ -308,16 +308,16 @@ const struct LogStructure Sub::log_structure[] = { void Sub::Log_Write_Vehicle_Startup_Messages() { - // only 200(?) bytes are guaranteed by DataFlash - DataFlash.Log_Write_Mode(control_mode, control_mode_reason); + // only 200(?) bytes are guaranteed by AP_Logger + logger.Log_Write_Mode(control_mode, control_mode_reason); ahrs.Log_Write_Home_And_Origin(); - gps.Write_DataFlash_Log_Startup_messages(); + gps.Write_AP_Logger_Log_Startup_messages(); } void Sub::log_init() { - DataFlash.Init(log_structure, ARRAY_SIZE(log_structure)); + logger.Init(log_structure, ARRAY_SIZE(log_structure)); } #else // LOGGING_ENABLED diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 96976e9e42..799d5af6cd 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -482,8 +482,8 @@ const AP_Param::Info Sub::var_info[] = { #endif // @Group: LOG - // @Path: ../libraries/DataFlash/DataFlash.cpp - GOBJECT(DataFlash, "LOG", DataFlash_Class), + // @Path: ../libraries/AP_Logger/AP_Logger.cpp + GOBJECT(logger, "LOG", AP_Logger), // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp diff --git a/ArduSub/Parameters.h b/ArduSub/Parameters.h index a17a302dd7..ac2829d7d1 100644 --- a/ArduSub/Parameters.h +++ b/ArduSub/Parameters.h @@ -58,7 +58,7 @@ public: // Hardware/Software configuration k_param_BoardConfig = 20, // Board configuration (PX4/Linux/etc) k_param_scheduler, // Scheduler (for debugging/perf_info) - k_param_DataFlash, // DataFlash Logging + k_param_logger, // AP_Logger Logging k_param_serial_manager, // Serial ports, AP_SerialManager k_param_notify, // Notify Library, AP_Notify k_param_arming = 26, // Arming checks diff --git a/ArduSub/Sub.cpp b/ArduSub/Sub.cpp index 96b3034542..7b11cdf990 100644 --- a/ArduSub/Sub.cpp +++ b/ArduSub/Sub.cpp @@ -24,7 +24,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); constructor for main Sub class */ Sub::Sub() - : DataFlash(g.log_bitmask), + : logger(g.log_bitmask), control_mode(MANUAL), motors(MAIN_LOOP_RATE), scaleLongDown(1), diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index ac1186ec7f..72461fc57f 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -40,7 +40,7 @@ // Application dependencies #include // Serial manager library #include // ArduPilot GPS library -#include // ArduPilot Mega Flash Memory Library +#include // ArduPilot Mega Flash Memory Library #include #include // ArduPilot Mega Magnetometer Library #include // ArduPilot Mega Inertial Sensor (accel & gyro) Library @@ -163,7 +163,7 @@ private: RC_Channel *channel_lateral; // Dataflash - DataFlash_Class DataFlash; + AP_Logger logger; AP_GPS gps; diff --git a/ArduSub/commands.cpp b/ArduSub/commands.cpp index ed0eb3bb6d..0a84b64708 100644 --- a/ArduSub/commands.cpp +++ b/ArduSub/commands.cpp @@ -78,7 +78,7 @@ bool Sub::set_home(const Location& loc, bool lock) if (should_log(MASK_LOG_CMD)) { AP_Mission::Mission_Command temp_cmd; if (mission.read_cmd_from_storage(0, temp_cmd)) { - DataFlash.Log_Write_Mission_Cmd(mission, temp_cmd); + logger.Log_Write_Mission_Cmd(mission, temp_cmd); } } } diff --git a/ArduSub/commands_logic.cpp b/ArduSub/commands_logic.cpp index ef766ab2b0..f270d52231 100644 --- a/ArduSub/commands_logic.cpp +++ b/ArduSub/commands_logic.cpp @@ -9,7 +9,7 @@ bool Sub::start_command(const AP_Mission::Mission_Command& cmd) { // To-Do: logging when new commands start/end if (should_log(MASK_LOG_CMD)) { - DataFlash.Log_Write_Mission_Cmd(mission, cmd); + logger.Log_Write_Mission_Cmd(mission, cmd); } const Location &target_loc = cmd.content.location; diff --git a/ArduSub/flight_mode.cpp b/ArduSub/flight_mode.cpp index f7e2ef8f62..1929135120 100644 --- a/ArduSub/flight_mode.cpp +++ b/ArduSub/flight_mode.cpp @@ -70,7 +70,7 @@ bool Sub::set_mode(control_mode_t mode, mode_reason_t reason) control_mode = mode; control_mode_reason = reason; - DataFlash.Log_Write_Mode(control_mode, control_mode_reason); + logger.Log_Write_Mode(control_mode, control_mode_reason); // update notify object notify_flight_mode(control_mode); diff --git a/ArduSub/motors.cpp b/ArduSub/motors.cpp index ca32b8c841..dcaa7af635 100644 --- a/ArduSub/motors.cpp +++ b/ArduSub/motors.cpp @@ -26,7 +26,7 @@ bool Sub::init_arm_motors(AP_Arming::ArmingMethod method) } // let dataflash know that we're armed (it may open logs e.g.) - DataFlash_Class::instance()->set_vehicle_armed(true); + AP_Logger::instance()->set_vehicle_armed(true); // disable cpu failsafe because initialising everything takes a while mainloop_failsafe_disable(); @@ -69,7 +69,7 @@ bool Sub::init_arm_motors(AP_Arming::ArmingMethod method) Log_Write_Event(DATA_ARMED); // log flight mode in case it was changed while vehicle was disarmed - DataFlash.Log_Write_Mode(control_mode, control_mode_reason); + logger.Log_Write_Mode(control_mode, control_mode_reason); // reenable failsafe mainloop_failsafe_enable(); @@ -115,7 +115,7 @@ void Sub::init_disarm_motors() // reset the mission mission.reset(); - DataFlash_Class::instance()->set_vehicle_armed(false); + AP_Logger::instance()->set_vehicle_armed(false); // disable gps velocity based centrefugal force compensation ahrs.set_correct_centrifugal(false); diff --git a/ArduSub/sensors.cpp b/ArduSub/sensors.cpp index f6cc83b96b..11a71c5641 100644 --- a/ArduSub/sensors.cpp +++ b/ArduSub/sensors.cpp @@ -74,7 +74,7 @@ void Sub::rpm_update(void) rpm_sensor.update(); if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) { if (should_log(MASK_LOG_RCIN)) { - DataFlash.Log_Write_RPM(rpm_sensor); + logger.Log_Write_RPM(rpm_sensor); } } } diff --git a/ArduSub/system.cpp b/ArduSub/system.cpp index 1c306ee367..edd8aebcf7 100644 --- a/ArduSub/system.cpp +++ b/ArduSub/system.cpp @@ -185,9 +185,9 @@ void Sub::init_ardupilot() // initialise mission library mission.init(); - // initialise DataFlash library + // initialise AP_Logger library #if LOGGING_ENABLED == ENABLED - DataFlash.setVehicle_Startup_Log_Writer(FUNCTOR_BIND(&sub, &Sub::Log_Write_Vehicle_Startup_Messages, void)); + logger.setVehicle_Startup_Log_Writer(FUNCTOR_BIND(&sub, &Sub::Log_Write_Vehicle_Startup_Messages, void)); #endif startup_INS_ground(); @@ -289,8 +289,8 @@ bool Sub::optflow_position_ok() bool Sub::should_log(uint32_t mask) { #if LOGGING_ENABLED == ENABLED - ap.logging_started = DataFlash.logging_started(); - return DataFlash.should_log(mask); + ap.logging_started = logger.logging_started(); + return logger.should_log(mask); #else return false; #endif diff --git a/Tools/Replay/DataFlashFileReader.cpp b/Tools/Replay/DataFlashFileReader.cpp index 3310100af2..b1fd0b067b 100644 --- a/Tools/Replay/DataFlashFileReader.cpp +++ b/Tools/Replay/DataFlashFileReader.cpp @@ -1,4 +1,4 @@ -#include "DataFlashFileReader.h" +#include "AP_LoggerFileReader.h" #include #include @@ -19,11 +19,11 @@ uint64_t now() { return 1.0e6*((ts.tv_sec + (ts.tv_nsec*1.0e-9))); } -DataFlashFileReader::DataFlashFileReader() : +AP_LoggerFileReader::AP_LoggerFileReader() : start_micros(now()) {} -DataFlashFileReader::~DataFlashFileReader() +AP_LoggerFileReader::~AP_LoggerFileReader() { const uint64_t micros = now(); const uint64_t delta = micros - start_micros; @@ -31,7 +31,7 @@ DataFlashFileReader::~DataFlashFileReader() ::printf("Replay rates: %" PRIu64 " bytes/second %" PRIu64 " messages/second\n", bytes_read*1000000/delta, message_count*1000000/delta); } -bool DataFlashFileReader::open_log(const char *logfile) +bool AP_LoggerFileReader::open_log(const char *logfile) { fd = ::open(logfile, O_RDONLY|O_CLOEXEC); if (fd == -1) { @@ -40,14 +40,14 @@ bool DataFlashFileReader::open_log(const char *logfile) return true; } -ssize_t DataFlashFileReader::read_input(void *buffer, const size_t count) +ssize_t AP_LoggerFileReader::read_input(void *buffer, const size_t count) { uint64_t ret = ::read(fd, buffer, count); bytes_read += ret; return ret; } -void DataFlashFileReader::format_type(uint16_t type, char dest[5]) +void AP_LoggerFileReader::format_type(uint16_t type, char dest[5]) { const struct log_Format &f = formats[type]; memset(dest,0,5); @@ -56,12 +56,12 @@ void DataFlashFileReader::format_type(uint16_t type, char dest[5]) } strncpy(dest, f.name, 4); } -void DataFlashFileReader::get_packet_counts(uint64_t dest[]) +void AP_LoggerFileReader::get_packet_counts(uint64_t dest[]) { memcpy(dest, packet_counts, sizeof(packet_counts)); } -bool DataFlashFileReader::update(char type[5]) +bool AP_LoggerFileReader::update(char type[5]) { uint8_t hdr[3]; if (read_input(hdr, 3) != 3) { diff --git a/Tools/Replay/DataFlashFileReader.h b/Tools/Replay/DataFlashFileReader.h index c9f4267cd9..fce4283a2f 100644 --- a/Tools/Replay/DataFlashFileReader.h +++ b/Tools/Replay/DataFlashFileReader.h @@ -1,15 +1,15 @@ #pragma once -#include +#include #define LOGREADER_MAX_FORMATS 255 // must be >= highest MESSAGE -class DataFlashFileReader +class AP_LoggerFileReader { public: - DataFlashFileReader(); - ~DataFlashFileReader(); + AP_LoggerFileReader(); + ~AP_LoggerFileReader(); bool open_log(const char *logfile); bool update(char type[5]); diff --git a/Tools/Replay/LR_MsgHandler.cpp b/Tools/Replay/LR_MsgHandler.cpp index b9bc1650f3..5bbf27d9df 100644 --- a/Tools/Replay/LR_MsgHandler.cpp +++ b/Tools/Replay/LR_MsgHandler.cpp @@ -5,7 +5,7 @@ extern const AP_HAL::HAL& hal; LR_MsgHandler::LR_MsgHandler(struct log_Format &_f, - DataFlash_Class &_dataflash, + AP_Logger &_dataflash, uint64_t &_last_timestamp_usec) : dataflash(_dataflash), last_timestamp_usec(_last_timestamp_usec), MsgHandler(_f) { @@ -406,8 +406,8 @@ void LR_MsgHandler_PARM::process_message(uint8_t *msg) } else { // older logs can have a lot of FMT and PARM messages up the // front which don't have timestamps. Since in Replay we run - // DataFlash's IO only when stop_clock is called, we can - // overflow DataFlash's ringbuffer. This should force us to + // AP_Logger's IO only when stop_clock is called, we can + // overflow AP_Logger's ringbuffer. This should force us to // do IO: hal.scheduler->stop_clock(last_timestamp_usec); } diff --git a/Tools/Replay/LR_MsgHandler.h b/Tools/Replay/LR_MsgHandler.h index 4074f79bef..013f5bd6fc 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, - DataFlash_Class &_dataflash, + AP_Logger &_dataflash, uint64_t &last_timestamp_usec); virtual void process_message(uint8_t *msg) = 0; @@ -20,7 +20,7 @@ public: }; protected: - DataFlash_Class &dataflash; + AP_Logger &dataflash; void wait_timestamp(uint32_t timestamp); void wait_timestamp_usec(uint64_t timestamp); void wait_timestamp_from_msg(uint8_t *msg); @@ -34,7 +34,7 @@ protected: class LR_MsgHandler_AHR2 : public LR_MsgHandler { public: - LR_MsgHandler_AHR2(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_AHR2(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, Vector3f &_ahr2_attitude) : LR_MsgHandler(_f, _dataflash,_last_timestamp_usec), ahr2_attitude(_ahr2_attitude) { }; @@ -49,7 +49,7 @@ private: class LR_MsgHandler_ARM : public LR_MsgHandler { public: - LR_MsgHandler_ARM(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_ARM(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec) : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec) { }; @@ -60,7 +60,7 @@ public: class LR_MsgHandler_ARSP : public LR_MsgHandler { public: - LR_MsgHandler_ARSP(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_ARSP(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, AP_Airspeed &_airspeed) : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), airspeed(_airspeed) { }; @@ -73,7 +73,7 @@ private: class LR_MsgHandler_NKF1 : public LR_MsgHandler { public: - LR_MsgHandler_NKF1(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_NKF1(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec) : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec) { }; @@ -84,7 +84,7 @@ public: class LR_MsgHandler_ATT : public LR_MsgHandler { public: - LR_MsgHandler_ATT(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_ATT(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, Vector3f &_attitude) : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), attitude(_attitude) { }; @@ -98,7 +98,7 @@ private: class LR_MsgHandler_CHEK : public LR_MsgHandler { public: - LR_MsgHandler_CHEK(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_CHEK(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, CheckState &_check_state) : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), check_state(_check_state) @@ -112,7 +112,7 @@ private: class LR_MsgHandler_BARO : public LR_MsgHandler { public: - LR_MsgHandler_BARO(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_BARO(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec) : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec) { }; @@ -125,7 +125,7 @@ public: class LR_MsgHandler_Event : public LR_MsgHandler { public: - LR_MsgHandler_Event(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_Event(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec) : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec) { }; @@ -139,7 +139,7 @@ class LR_MsgHandler_GPS_Base : public LR_MsgHandler { public: - LR_MsgHandler_GPS_Base(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_GPS_Base(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, AP_GPS &_gps, uint32_t &_ground_alt_cm) : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), @@ -156,7 +156,7 @@ private: class LR_MsgHandler_GPS : public LR_MsgHandler_GPS_Base { public: - LR_MsgHandler_GPS(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_GPS(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, AP_GPS &_gps, uint32_t &_ground_alt_cm) : LR_MsgHandler_GPS_Base(_f, _dataflash,_last_timestamp_usec, @@ -177,7 +177,7 @@ private: class LR_MsgHandler_GPS2 : public LR_MsgHandler_GPS_Base { public: - LR_MsgHandler_GPS2(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_GPS2(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, AP_GPS &_gps, uint32_t &_ground_alt_cm) : LR_MsgHandler_GPS_Base(_f, _dataflash, _last_timestamp_usec, @@ -193,7 +193,7 @@ class LR_MsgHandler_GPA_Base : public LR_MsgHandler { public: - LR_MsgHandler_GPA_Base(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_GPA_Base(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, AP_GPS &_gps) : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), gps(_gps) { }; @@ -208,7 +208,7 @@ private: class LR_MsgHandler_GPA : public LR_MsgHandler_GPA_Base { public: - LR_MsgHandler_GPA(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_GPA(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, AP_GPS &_gps) : LR_MsgHandler_GPA_Base(_f, _dataflash,_last_timestamp_usec, _gps), gps(_gps) { }; @@ -222,7 +222,7 @@ private: class LR_MsgHandler_GPA2 : public LR_MsgHandler_GPA_Base { public: - LR_MsgHandler_GPA2(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_GPA2(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, AP_GPS &_gps) : LR_MsgHandler_GPA_Base(_f, _dataflash, _last_timestamp_usec, _gps), gps(_gps) { }; @@ -238,7 +238,7 @@ private: class LR_MsgHandler_IMU_Base : public LR_MsgHandler { public: - LR_MsgHandler_IMU_Base(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_IMU_Base(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, uint8_t &_accel_mask, uint8_t &_gyro_mask, AP_InertialSensor &_ins) : @@ -257,7 +257,7 @@ private: class LR_MsgHandler_IMU : public LR_MsgHandler_IMU_Base { public: - LR_MsgHandler_IMU(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_IMU(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, uint8_t &_accel_mask, uint8_t &_gyro_mask, AP_InertialSensor &_ins) @@ -270,7 +270,7 @@ public: class LR_MsgHandler_IMU2 : public LR_MsgHandler_IMU_Base { public: - LR_MsgHandler_IMU2(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_IMU2(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, uint8_t &_accel_mask, uint8_t &_gyro_mask, AP_InertialSensor &_ins) @@ -283,7 +283,7 @@ public: class LR_MsgHandler_IMU3 : public LR_MsgHandler_IMU_Base { public: - LR_MsgHandler_IMU3(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_IMU3(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, uint8_t &_accel_mask, uint8_t &_gyro_mask, AP_InertialSensor &_ins) @@ -297,7 +297,7 @@ public: class LR_MsgHandler_IMT_Base : public LR_MsgHandler { public: - LR_MsgHandler_IMT_Base(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_IMT_Base(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, uint8_t &_accel_mask, uint8_t &_gyro_mask, bool &_use_imt, @@ -319,7 +319,7 @@ private: class LR_MsgHandler_IMT : public LR_MsgHandler_IMT_Base { public: - LR_MsgHandler_IMT(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_IMT(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, uint8_t &_accel_mask, uint8_t &_gyro_mask, bool &_use_imt, @@ -333,7 +333,7 @@ public: class LR_MsgHandler_IMT2 : public LR_MsgHandler_IMT_Base { public: - LR_MsgHandler_IMT2(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_IMT2(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, uint8_t &_accel_mask, uint8_t &_gyro_mask, bool &_use_imt, @@ -347,7 +347,7 @@ public: class LR_MsgHandler_IMT3 : public LR_MsgHandler_IMT_Base { public: - LR_MsgHandler_IMT3(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_IMT3(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, uint8_t &_accel_mask, uint8_t &_gyro_mask, bool &_use_imt, @@ -362,7 +362,7 @@ public: class LR_MsgHandler_MAG_Base : public LR_MsgHandler { public: - LR_MsgHandler_MAG_Base(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_MAG_Base(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, Compass &_compass) : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), compass(_compass) { }; @@ -376,7 +376,7 @@ private: class LR_MsgHandler_MAG : public LR_MsgHandler_MAG_Base { public: - LR_MsgHandler_MAG(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_MAG(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, Compass &_compass) : LR_MsgHandler_MAG_Base(_f, _dataflash, _last_timestamp_usec,_compass) {}; @@ -386,7 +386,7 @@ public: class LR_MsgHandler_MAG2 : public LR_MsgHandler_MAG_Base { public: - LR_MsgHandler_MAG2(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_MAG2(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, Compass &_compass) : LR_MsgHandler_MAG_Base(_f, _dataflash, _last_timestamp_usec,_compass) {}; @@ -398,7 +398,7 @@ public: class LR_MsgHandler_MSG : public LR_MsgHandler { public: - LR_MsgHandler_MSG(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_MSG(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, VehicleType::vehicle_type &_vehicle, AP_AHRS &_ahrs) : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), @@ -416,7 +416,7 @@ private: class LR_MsgHandler_NTUN_Copter : public LR_MsgHandler { public: - LR_MsgHandler_NTUN_Copter(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_NTUN_Copter(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, Vector3f &_inavpos) : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), inavpos(_inavpos) {}; @@ -430,7 +430,7 @@ private: class LR_MsgHandler_PARM : public LR_MsgHandler { public: - LR_MsgHandler_PARM(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_PARM(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, const std::function&set_parameter_callback) : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), @@ -447,7 +447,7 @@ private: class LR_MsgHandler_PM : public LR_MsgHandler { public: - LR_MsgHandler_PM(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_PM(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec) : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec) { }; @@ -460,7 +460,7 @@ private: class LR_MsgHandler_SIM : public LR_MsgHandler { public: - LR_MsgHandler_SIM(log_Format &_f, DataFlash_Class &_dataflash, + LR_MsgHandler_SIM(log_Format &_f, AP_Logger &_dataflash, uint64_t &_last_timestamp_usec, Vector3f &_sim_attitude) : LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), diff --git a/Tools/Replay/LogReader.cpp b/Tools/Replay/LogReader.cpp index 7bd829ce80..09d808952d 100644 --- a/Tools/Replay/LogReader.cpp +++ b/Tools/Replay/LogReader.cpp @@ -7,7 +7,7 @@ #include #include #include -#include +#include #include "LogReader.h" #include @@ -38,11 +38,11 @@ LogReader::LogReader(AP_AHRS &_ahrs, Compass &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed, - DataFlash_Class &_dataflash, + AP_Logger &_dataflash, struct LogStructure *log_structure, uint8_t log_structure_count, const char **&_nottypes): - DataFlashFileReader(), + AP_LoggerFileReader(), vehicle(VehicleType::VEHICLE_UNKNOWN), ahrs(_ahrs), ins(_ins), @@ -214,7 +214,7 @@ uint8_t LogReader::map_fmt_type(const char *name, uint8_t intype) if (already_mapped) { continue; } - if (DataFlash_Class::instance()->msg_type_in_use(n)) { + if (AP_Logger::instance()->msg_type_in_use(n)) { continue; } mapped_msgid[intype] = n; @@ -277,7 +277,7 @@ bool LogReader::handle_log_format_msg(const struct log_Format &f) s.labels = f.labels; } - // emit the FMT to DataFlash: + // emit the FMT to AP_Logger: struct log_Format pkt {}; pkt.head1 = HEAD_BYTE1; pkt.head2 = HEAD_BYTE2; diff --git a/Tools/Replay/LogReader.h b/Tools/Replay/LogReader.h index f0a33e34dc..cae4a486a6 100644 --- a/Tools/Replay/LogReader.h +++ b/Tools/Replay/LogReader.h @@ -1,9 +1,9 @@ #include "VehicleType.h" -#include "DataFlashFileReader.h" +#include "AP_LoggerFileReader.h" #include "LR_MsgHandler.h" #include "Parameters.h" -class LogReader : public DataFlashFileReader +class LogReader : public AP_LoggerFileReader { public: LogReader(AP_AHRS &_ahrs, @@ -11,7 +11,7 @@ public: Compass &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed, - DataFlash_Class &_dataflash, + AP_Logger &_dataflash, 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; - DataFlash_Class &dataflash; + AP_Logger &dataflash; struct LogStructure *_log_structure; uint8_t _log_structure_count; diff --git a/Tools/Replay/MsgHandler.h b/Tools/Replay/MsgHandler.h index f0f149b90b..035f4cbf13 100644 --- a/Tools/Replay/MsgHandler.h +++ b/Tools/Replay/MsgHandler.h @@ -1,6 +1,6 @@ #pragma once -#include +#include #include "VehicleType.h" #include diff --git a/Tools/Replay/Replay.cpp b/Tools/Replay/Replay.cpp index 69d2fb90a5..91096b16a5 100644 --- a/Tools/Replay/Replay.cpp +++ b/Tools/Replay/Replay.cpp @@ -25,7 +25,7 @@ #endif #include "LogReader.h" -#include "DataFlashFileReader.h" +#include "AP_LoggerFileReader.h" #include "Replay.h" #if CONFIG_HAL_BOARD == HAL_BOARD_SITL @@ -74,8 +74,8 @@ const AP_Param::Info ReplayVehicle::var_info[] = { GOBJECT(compass, "COMPASS_", Compass), // @Group: LOG - // @Path: ../libraries/DataFlash/DataFlash.cpp - GOBJECT(dataflash, "LOG", DataFlash_Class), + // @Path: ../libraries/AP_Logger/AP_Logger.cpp + GOBJECT(dataflash, "LOG", AP_Logger), // @Group: EK3_ // @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -326,7 +326,7 @@ void Replay::_parse_command_line(uint8_t argc, char * const argv[]) } } -class IMUCounter : public DataFlashFileReader { +class IMUCounter : public AP_LoggerFileReader { public: IMUCounter() {} bool handle_log_format_msg(const struct log_Format &f); diff --git a/Tools/Replay/Replay.h b/Tools/Replay/Replay.h index 7456116562..2a201c64c3 100644 --- a/Tools/Replay/Replay.h +++ b/Tools/Replay/Replay.h @@ -26,7 +26,7 @@ #include #include #include -#include +#include #include #include #include @@ -69,7 +69,7 @@ public: AP_Int32 unused; // logging is magic for Replay; this is unused struct LogStructure log_structure[256] = { }; - DataFlash_Class dataflash{unused}; + AP_Logger dataflash{unused}; private: Parameters g; diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index c7a9aba426..0181275b8d 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -1,7 +1,7 @@ #include #include "AC_PosControl.h" #include -#include +#include extern const AP_HAL::HAL& hal; @@ -838,7 +838,7 @@ void AC_PosControl::write_log() float accel_x, accel_y; lean_angles_to_accel(accel_x, accel_y); - DataFlash_Class::instance()->Log_Write("PSC", "TimeUS,TPX,TPY,PX,PY,TVX,TVY,VX,VY,TAX,TAY,AX,AY", + AP_Logger::instance()->Log_Write("PSC", "TimeUS,TPX,TPY,PX,PY,TVX,TVY,VX,VY,TAX,TAY,AX,AY", "smmmmnnnnoooo", "FBBBBBBBBBBBB", "Qffffffffffff", AP_HAL::micros64(), (double)pos_target.x, diff --git a/libraries/AC_AttitudeControl/ControlMonitor.cpp b/libraries/AC_AttitudeControl/ControlMonitor.cpp index 1da4ce43e0..2f191ff549 100644 --- a/libraries/AC_AttitudeControl/ControlMonitor.cpp +++ b/libraries/AC_AttitudeControl/ControlMonitor.cpp @@ -24,15 +24,15 @@ void AC_AttitudeControl::control_monitor_filter_pid(float value, float &rms) */ void AC_AttitudeControl::control_monitor_update(void) { - const DataFlash_Class::PID_Info &iroll = get_rate_roll_pid().get_pid_info(); + const AP_Logger::PID_Info &iroll = get_rate_roll_pid().get_pid_info(); control_monitor_filter_pid(iroll.P + iroll.FF, _control_monitor.rms_roll_P); control_monitor_filter_pid(iroll.D, _control_monitor.rms_roll_D); - const DataFlash_Class::PID_Info &ipitch = get_rate_pitch_pid().get_pid_info(); + const AP_Logger::PID_Info &ipitch = get_rate_pitch_pid().get_pid_info(); control_monitor_filter_pid(ipitch.P + iroll.FF, _control_monitor.rms_pitch_P); control_monitor_filter_pid(ipitch.D, _control_monitor.rms_pitch_D); - const DataFlash_Class::PID_Info &iyaw = get_rate_yaw_pid().get_pid_info(); + const AP_Logger::PID_Info &iyaw = get_rate_yaw_pid().get_pid_info(); control_monitor_filter_pid(iyaw.P + iyaw.D + iyaw.FF, _control_monitor.rms_yaw); } @@ -41,7 +41,7 @@ void AC_AttitudeControl::control_monitor_update(void) */ void AC_AttitudeControl::control_monitor_log(void) { - DataFlash_Class::instance()->Log_Write("CTRL", "TimeUS,RMSRollP,RMSRollD,RMSPitchP,RMSPitchD,RMSYaw", "Qfffff", + AP_Logger::instance()->Log_Write("CTRL", "TimeUS,RMSRollP,RMSRollD,RMSPitchP,RMSPitchD,RMSYaw", "Qfffff", AP_HAL::micros64(), (double)safe_sqrt(_control_monitor.rms_roll_P), (double)safe_sqrt(_control_monitor.rms_roll_D), diff --git a/libraries/AC_AutoTune/AC_AutoTune.cpp b/libraries/AC_AutoTune/AC_AutoTune.cpp index ac3cbc7026..ac4952bb3b 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune.cpp @@ -661,7 +661,7 @@ void AC_AutoTune::control_attitude() // log this iterations lean angle and rotation rate Log_Write_AutoTuneDetails(lean_angle, rotation_rate); - DataFlash_Class::instance()->Log_Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control); + AP_Logger::instance()->Log_Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control); log_pids(); break; } @@ -1696,7 +1696,7 @@ void AC_AutoTune::get_poshold_attitude(int32_t &roll_cd_out, int32_t &pitch_cd_o // Write an Autotune data packet void AC_AutoTune::Log_Write_AutoTune(uint8_t _axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt) { - DataFlash_Class::instance()->Log_Write( + AP_Logger::instance()->Log_Write( "ATUN", "TimeUS,Axis,TuneStep,Targ,Min,Max,RP,RD,SP,ddt", "s--ddd---o", @@ -1717,7 +1717,7 @@ void AC_AutoTune::Log_Write_AutoTune(uint8_t _axis, uint8_t tune_step, float mea // Write an Autotune data packet void AC_AutoTune::Log_Write_AutoTuneDetails(float angle_cd, float rate_cds) { - DataFlash_Class::instance()->Log_Write( + AP_Logger::instance()->Log_Write( "ATDE", "TimeUS,Angle,Rate", "sdk", diff --git a/libraries/AC_PID/AC_PID.h b/libraries/AC_PID/AC_PID.h index 521a0ca0cf..150f0cc4c2 100644 --- a/libraries/AC_PID/AC_PID.h +++ b/libraries/AC_PID/AC_PID.h @@ -7,7 +7,7 @@ #include #include #include -#include +#include #define AC_PID_FILT_HZ_DEFAULT 20.0f // default input filter frequency #define AC_PID_FILT_HZ_MIN 0.01f // minimum input filter frequency @@ -80,7 +80,7 @@ public: void set_desired_rate(float desired) { _pid_info.desired = desired; } void set_actual_rate(float actual) { _pid_info.actual = actual; } - const DataFlash_Class::PID_Info& get_pid_info(void) const { return _pid_info; } + const AP_Logger::PID_Info& get_pid_info(void) const { return _pid_info; } // parameter var table static const struct AP_Param::GroupInfo var_info[]; @@ -106,5 +106,5 @@ protected: float _input; // last input for derivative float _derivative; // last derivative for low-pass filter - DataFlash_Class::PID_Info _pid_info; + AP_Logger::PID_Info _pid_info; }; diff --git a/libraries/APM_Control/AP_AutoTune.cpp b/libraries/APM_Control/AP_AutoTune.cpp index 35efa3b3a5..44ccb7ef62 100644 --- a/libraries/APM_Control/AP_AutoTune.cpp +++ b/libraries/APM_Control/AP_AutoTune.cpp @@ -266,7 +266,7 @@ void AP_AutoTune::check_save(void) */ void AP_AutoTune::log_param_change(float v, const char *suffix) { - DataFlash_Class *dataflash = DataFlash_Class::instance(); + AP_Logger *dataflash = AP_Logger::instance(); if (!dataflash->logging_started()) { return; } @@ -327,7 +327,7 @@ void AP_AutoTune::save_gains(const ATGains &v) void AP_AutoTune::write_log(float servo, float demanded, float achieved) { - DataFlash_Class *dataflash = DataFlash_Class::instance(); + AP_Logger *dataflash = AP_Logger::instance(); if (!dataflash->logging_started()) { return; } diff --git a/libraries/APM_Control/AP_AutoTune.h b/libraries/APM_Control/AP_AutoTune.h index 65e03f9f43..1ca71d8128 100644 --- a/libraries/APM_Control/AP_AutoTune.h +++ b/libraries/APM_Control/AP_AutoTune.h @@ -2,7 +2,7 @@ #include #include -#include +#include class AP_AutoTune { public: diff --git a/libraries/APM_Control/AP_PitchController.h b/libraries/APM_Control/AP_PitchController.h index d2da91c2c4..525b7b29c4 100644 --- a/libraries/APM_Control/AP_PitchController.h +++ b/libraries/APM_Control/AP_PitchController.h @@ -4,7 +4,7 @@ #include #include #include "AP_AutoTune.h" -#include +#include #include class AP_PitchController { @@ -29,7 +29,7 @@ public: void autotune_start(void) { autotune.start(); } void autotune_restore(void) { autotune.stop(); } - const DataFlash_Class::PID_Info& get_pid_info(void) const { return _pid_info; } + const AP_Logger::PID_Info& get_pid_info(void) const { return _pid_info; } static const struct AP_Param::GroupInfo var_info[]; @@ -47,7 +47,7 @@ private: uint32_t _last_t; float _last_out; - DataFlash_Class::PID_Info _pid_info; + AP_Logger::PID_Info _pid_info; int32_t _get_rate_out(float desired_rate, float scaler, bool disable_integrator, float aspeed); float _get_coordination_rate_offset(float &aspeed, bool &inverted) const; diff --git a/libraries/APM_Control/AP_RollController.h b/libraries/APM_Control/AP_RollController.h index 74a9c2ecf4..c0878f9d86 100644 --- a/libraries/APM_Control/AP_RollController.h +++ b/libraries/APM_Control/AP_RollController.h @@ -4,7 +4,7 @@ #include #include #include "AP_AutoTune.h" -#include +#include #include class AP_RollController { @@ -29,7 +29,7 @@ public: void autotune_start(void) { autotune.start(); } void autotune_restore(void) { autotune.stop(); } - const DataFlash_Class::PID_Info& get_pid_info(void) const { return _pid_info; } + const AP_Logger::PID_Info& get_pid_info(void) const { return _pid_info; } static const struct AP_Param::GroupInfo var_info[]; @@ -52,7 +52,7 @@ private: uint32_t _last_t; float _last_out; - DataFlash_Class::PID_Info _pid_info; + AP_Logger::PID_Info _pid_info; int32_t _get_rate_out(float desired_rate, float scaler, bool disable_integrator); diff --git a/libraries/APM_Control/AP_SteerController.h b/libraries/APM_Control/AP_SteerController.h index c3dd206d56..5cad3afe45 100644 --- a/libraries/APM_Control/AP_SteerController.h +++ b/libraries/APM_Control/AP_SteerController.h @@ -3,7 +3,7 @@ #include #include #include -#include +#include class AP_SteerController { public: @@ -46,7 +46,7 @@ public: static const struct AP_Param::GroupInfo var_info[]; - const DataFlash_Class::PID_Info& get_pid_info(void) const { return _pid_info; } + const AP_Logger::PID_Info& get_pid_info(void) const { return _pid_info; } void set_reverse(bool reverse) { _reverse = reverse; @@ -67,7 +67,7 @@ private: AP_Float _deratefactor; AP_Float _mindegree; - DataFlash_Class::PID_Info _pid_info {}; + AP_Logger::PID_Info _pid_info {}; AP_AHRS &_ahrs; diff --git a/libraries/APM_Control/AP_YawController.h b/libraries/APM_Control/AP_YawController.h index 09edd6daf7..8748dae5a3 100644 --- a/libraries/APM_Control/AP_YawController.h +++ b/libraries/APM_Control/AP_YawController.h @@ -3,7 +3,7 @@ #include #include #include -#include +#include #include class AP_YawController { @@ -26,7 +26,7 @@ public: void reset_I(); - const DataFlash_Class::PID_Info& get_pid_info(void) const {return _pid_info; } + const AP_Logger::PID_Info& get_pid_info(void) const {return _pid_info; } static const struct AP_Param::GroupInfo var_info[]; @@ -45,7 +45,7 @@ private: float _integrator; - DataFlash_Class::PID_Info _pid_info; + AP_Logger::PID_Info _pid_info; AP_AHRS &_ahrs; }; diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index a335c1ca67..690287299e 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -17,7 +17,7 @@ #include "AP_AHRS.h" #include "AP_AHRS_View.h" #include -#include +#include extern const AP_HAL::HAL& hal; @@ -475,7 +475,7 @@ Vector2f AP_AHRS::rotate_body_to_earth2D(const Vector2f &bf) const // log ahrs home and EKF origin to dataflash void AP_AHRS::Log_Write_Home_And_Origin() { - DataFlash_Class *df = DataFlash_Class::instance(); + AP_Logger *df = AP_Logger::instance(); if (df == nullptr) { return; } diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 25471a88c5..357adda59e 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -22,7 +22,7 @@ #include #include #include -#include +#include #include #include "AP_Airspeed.h" #include "AP_Airspeed_MS4525.h" @@ -428,7 +428,7 @@ void AP_Airspeed::update(bool log) #endif if (log) { - DataFlash_Class *_dataflash = DataFlash_Class::instance(); + AP_Logger *_dataflash = AP_Logger::instance(); if (_dataflash != nullptr) { _dataflash->Log_Write_Airspeed(*this); } diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 6b881c4b6a..4f4259ac4e 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -200,11 +200,11 @@ bool AP_Arming::logging_checks(bool report) { if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_LOGGING)) { - if (DataFlash_Class::instance()->logging_failed()) { + if (AP_Logger::instance()->logging_failed()) { check_failed(ARMING_CHECK_LOGGING, report, "Logging failed"); return false; } - if (!DataFlash_Class::instance()->CardInserted()) { + if (!AP_Logger::instance()->CardInserted()) { check_failed(ARMING_CHECK_LOGGING, report, "No SD card"); return false; } @@ -720,11 +720,11 @@ bool AP_Arming::arm_checks(ArmingMethod method) } } - // note that this will prepare DataFlash to start logging + // note that this will prepare AP_Logger to start logging // so should be the last check to be done before arming if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_LOGGING)) { - DataFlash_Class *df = DataFlash_Class::instance(); + AP_Logger *df = AP_Logger::instance(); df->PrepForArming(); if (!df->logging_started()) { check_failed(ARMING_CHECK_LOGGING, true, "Logging not started"); diff --git a/libraries/AP_BLHeli/AP_BLHeli.cpp b/libraries/AP_BLHeli/AP_BLHeli.cpp index cd901e1421..6caa37d4f6 100644 --- a/libraries/AP_BLHeli/AP_BLHeli.cpp +++ b/libraries/AP_BLHeli/AP_BLHeli.cpp @@ -30,7 +30,7 @@ #include #include #include -#include +#include extern const AP_HAL::HAL& hal; @@ -1346,7 +1346,7 @@ void AP_BLHeli::read_telemetry_packet(void) last_telem[last_telem_esc] = td; last_telem[last_telem_esc].count++; - DataFlash_Class *df = DataFlash_Class::instance(); + AP_Logger *df = AP_Logger::instance(); if (df && df->logging_enabled()) { struct log_Esc pkt = { LOG_PACKET_HEADER_INIT(uint8_t(LOG_ESC1_MSG+last_telem_esc)), diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index 81904618f4..b835843e68 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -734,7 +734,7 @@ void AP_Baro::_probe_i2c_barometers(void) bool AP_Baro::should_df_log() const { - DataFlash_Class *instance = DataFlash_Class::instance(); + AP_Logger *instance = AP_Logger::instance(); if (instance == nullptr) { return false; } @@ -816,7 +816,7 @@ void AP_Baro::update(void) // logging if (should_df_log() && !AP::ahrs().have_ekf_logging()) { - DataFlash_Class::instance()->Log_Write_Baro(); + AP_Logger::instance()->Log_Write_Baro(); } } diff --git a/libraries/AP_Baro/AP_Baro_ICM20789.cpp b/libraries/AP_Baro/AP_Baro_ICM20789.cpp index bf3ec4c4da..41802fd26e 100644 --- a/libraries/AP_Baro/AP_Baro_ICM20789.cpp +++ b/libraries/AP_Baro/AP_Baro_ICM20789.cpp @@ -27,7 +27,7 @@ #include #include -#include +#include #include @@ -343,7 +343,7 @@ void AP_Baro_ICM20789::update() { #if BARO_ICM20789_DEBUG // useful for debugging - DataFlash_Class::instance()->Log_Write("ICMB", "TimeUS,Traw,Praw,P,T", "QIIff", + AP_Logger::instance()->Log_Write("ICMB", "TimeUS,Traw,Praw,P,T", "QIIff", AP_HAL::micros64(), dd.Traw, dd.Praw, dd.P, dd.T); #endif diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index 6a5f93193a..3a5ee5cf66 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -12,7 +12,7 @@ #endif #include -#include +#include #include extern const AP_HAL::HAL& hal; @@ -237,7 +237,7 @@ AP_BattMonitor::read() } } - DataFlash_Class *df = DataFlash_Class::instance(); + AP_Logger *df = AP_Logger::instance(); if (df->should_log(_log_battery_bit)) { df->Log_Write_Current(); df->Log_Write_Power(); diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index 40769d4834..2868ceb6a9 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -390,7 +390,7 @@ void AP_Camera::setup_feedback_callback(void) // log_picture - log picture taken and send feedback to GCS void AP_Camera::log_picture() { - DataFlash_Class *df = DataFlash_Class::instance(); + AP_Logger *df = AP_Logger::instance(); if (df == nullptr) { return; } @@ -437,7 +437,7 @@ void AP_Camera::update_trigger() _camera_trigger_logged = _camera_trigger_count; gcs().send_message(MSG_CAMERA_FEEDBACK); - DataFlash_Class *df = DataFlash_Class::instance(); + AP_Logger *df = AP_Logger::instance(); if (df != nullptr) { if (df->should_log(log_camera_bit)) { uint32_t tdiff = AP_HAL::micros() - timestamp32; diff --git a/libraries/AP_Compass/AP_Compass_MMC3416.cpp b/libraries/AP_Compass/AP_Compass_MMC3416.cpp index e1e13f3cad..1902bc14f1 100644 --- a/libraries/AP_Compass/AP_Compass_MMC3416.cpp +++ b/libraries/AP_Compass/AP_Compass_MMC3416.cpp @@ -21,7 +21,7 @@ #include #include #include -#include +#include extern const AP_HAL::HAL &hal; @@ -224,7 +224,7 @@ void AP_Compass_MMC3416::timer() } #if 0 - DataFlash_Class::instance()->Log_Write("MMO", "TimeUS,Nx,Ny,Nz,Ox,Oy,Oz", "Qffffff", + AP_Logger::instance()->Log_Write("MMO", "TimeUS,Nx,Ny,Nz,Ox,Oy,Oz", "Qffffff", AP_HAL::micros64(), (double)new_offset.x, (double)new_offset.y, diff --git a/libraries/AP_Compass/Compass_learn.cpp b/libraries/AP_Compass/Compass_learn.cpp index 4404b5167d..307997c7d0 100644 --- a/libraries/AP_Compass/Compass_learn.cpp +++ b/libraries/AP_Compass/Compass_learn.cpp @@ -3,7 +3,7 @@ #include #include -#include +#include #include "Compass_learn.h" #include @@ -104,7 +104,7 @@ void CompassLearn::update(void) } if (sample_available) { - DataFlash_Class::instance()->Log_Write("COFS", "TimeUS,OfsX,OfsY,OfsZ,Var,Yaw,WVar,N", "QffffffI", + AP_Logger::instance()->Log_Write("COFS", "TimeUS,OfsX,OfsY,OfsZ,Var,Yaw,WVar,N", "QffffffI", AP_HAL::micros64(), (double)best_offsets.x, (double)best_offsets.y, diff --git a/libraries/AP_Follow/AP_Follow.cpp b/libraries/AP_Follow/AP_Follow.cpp index 145328e6ee..8ce59147ab 100644 --- a/libraries/AP_Follow/AP_Follow.cpp +++ b/libraries/AP_Follow/AP_Follow.cpp @@ -307,7 +307,7 @@ void AP_Follow::handle_msg(const mavlink_message_t &msg) } // log lead's estimated vs reported position - DataFlash_Class::instance()->Log_Write("FOLL", + AP_Logger::instance()->Log_Write("FOLL", "TimeUS,Lat,Lon,Alt,VelN,VelE,VelD,LatE,LonE,AltE", // labels "sDUmnnnDUm", // units "F--B000--B", // mults diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 02d7fac99a..f9e3032cfc 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -561,7 +561,7 @@ AP_GPS::GPS_Status AP_GPS::highest_supported_status(uint8_t instance) const bool AP_GPS::should_df_log() const { - DataFlash_Class *instance = DataFlash_Class::instance(); + AP_Logger *instance = AP_Logger::instance(); if (instance == nullptr) { return false; } @@ -657,7 +657,7 @@ void AP_GPS::update_instance(uint8_t instance) if (data_should_be_logged && should_df_log() && !AP::ahrs().have_ekf_logging()) { - DataFlash_Class::instance()->Log_Write_GPS(instance); + AP_Logger::instance()->Log_Write_GPS(instance); } if (state[instance].status >= GPS_OK_FIX_3D) { @@ -1086,13 +1086,13 @@ void AP_GPS::handle_gps_rtcm_data(const mavlink_message_t *msg) } } -void AP_GPS::Write_DataFlash_Log_Startup_messages() +void AP_GPS::Write_AP_Logger_Log_Startup_messages() { for (uint8_t instance=0; instanceWrite_DataFlash_Log_Startup_messages(); + drivers[instance]->Write_AP_Logger_Log_Startup_messages(); } } diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index 69b3d3ecc2..2d0ff96786 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -409,7 +409,7 @@ public: static const struct AP_Param::GroupInfo var_info[]; - void Write_DataFlash_Log_Startup_messages(); + void Write_AP_Logger_Log_Startup_messages(); // indicate which bit in LOG_BITMASK indicates gps logging enabled void set_log_gps_bit(uint32_t bit) { _log_gps_bit = bit; } diff --git a/libraries/AP_GPS/AP_GPS_GSOF.cpp b/libraries/AP_GPS/AP_GPS_GSOF.cpp index 3026e5791f..89476a1a4f 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.cpp +++ b/libraries/AP_GPS/AP_GPS_GSOF.cpp @@ -22,7 +22,7 @@ #include "AP_GPS.h" #include "AP_GPS_GSOF.h" -#include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_GPS/AP_GPS_NOVA.cpp b/libraries/AP_GPS/AP_GPS_NOVA.cpp index af6bae57d4..c2e9b249c2 100644 --- a/libraries/AP_GPS/AP_GPS_NOVA.cpp +++ b/libraries/AP_GPS/AP_GPS_NOVA.cpp @@ -19,7 +19,7 @@ #include "AP_GPS.h" #include "AP_GPS_NOVA.h" -#include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_GPS/AP_GPS_SBF.cpp b/libraries/AP_GPS/AP_GPS_SBF.cpp index b56b7cc4fa..b643482fe4 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.cpp +++ b/libraries/AP_GPS/AP_GPS_SBF.cpp @@ -22,7 +22,7 @@ #include "AP_GPS.h" #include "AP_GPS_SBF.h" -#include +#include #include extern const AP_HAL::HAL& hal; @@ -260,7 +260,7 @@ AP_GPS_SBF::log_ExtEventPVTGeodetic(const msg4007 &temp) COG:temp.COG }; - DataFlash_Class::instance()->WriteBlock(&header, sizeof(header)); + AP_Logger::instance()->WriteBlock(&header, sizeof(header)); } bool diff --git a/libraries/AP_GPS/AP_GPS_SBP.cpp b/libraries/AP_GPS/AP_GPS_SBP.cpp index ab884a9568..8132304318 100644 --- a/libraries/AP_GPS/AP_GPS_SBP.cpp +++ b/libraries/AP_GPS/AP_GPS_SBP.cpp @@ -22,7 +22,7 @@ #include "AP_GPS.h" #include "AP_GPS_SBP.h" -#include +#include extern const AP_HAL::HAL& hal; @@ -404,7 +404,7 @@ AP_GPS_SBP::logging_log_full_update() last_iar_num_hypotheses : last_iar_num_hypotheses, }; - DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt)); + AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt)); }; void @@ -438,7 +438,7 @@ AP_GPS_SBP::logging_log_raw_sbp(uint16_t msg_type, msg_len : msg_len, }; memcpy(pkt.data, msg_buff, MIN(msg_len, 48)); - DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt)); + AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt)); for (uint8_t i = 0; i < pages - 1; i++) { struct log_SbpRAWM pkt2 = { @@ -451,7 +451,7 @@ AP_GPS_SBP::logging_log_raw_sbp(uint16_t msg_type, msg_len : msg_len, }; memcpy(pkt2.data, &msg_buff[48 + i * 104], MIN(msg_len - (48 + i * 104), 104)); - DataFlash_Class::instance()->WriteBlock(&pkt2, sizeof(pkt2)); + AP_Logger::instance()->WriteBlock(&pkt2, sizeof(pkt2)); } }; diff --git a/libraries/AP_GPS/AP_GPS_SBP.h b/libraries/AP_GPS/AP_GPS_SBP.h index 1de5c9f9e5..6384c92cd8 100644 --- a/libraries/AP_GPS/AP_GPS_SBP.h +++ b/libraries/AP_GPS/AP_GPS_SBP.h @@ -177,7 +177,7 @@ private: uint32_t crc_error_counter; // ************************************************************************ - // Logging to DataFlash + // Logging to AP_Logger // ************************************************************************ void logging_log_full_update(); diff --git a/libraries/AP_GPS/AP_GPS_SBP2.cpp b/libraries/AP_GPS/AP_GPS_SBP2.cpp index f5ac59e122..9894fded26 100644 --- a/libraries/AP_GPS/AP_GPS_SBP2.cpp +++ b/libraries/AP_GPS/AP_GPS_SBP2.cpp @@ -22,7 +22,7 @@ #include "AP_GPS.h" #include "AP_GPS_SBP2.h" -#include +#include #include #include @@ -454,7 +454,7 @@ AP_GPS_SBP2::logging_log_full_update() last_injected_data_ms : last_injected_data_ms, last_iar_num_hypotheses : 0, }; - DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt)); + AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt)); }; void @@ -488,7 +488,7 @@ AP_GPS_SBP2::logging_log_raw_sbp(uint16_t msg_type, msg_len : msg_len, }; memcpy(pkt.data, msg_buff, MIN(msg_len, 48)); - DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt)); + AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt)); for (uint8_t i = 0; i < pages - 1; i++) { struct log_SbpRAWM pkt2 = { @@ -501,7 +501,7 @@ AP_GPS_SBP2::logging_log_raw_sbp(uint16_t msg_type, msg_len : msg_len, }; memcpy(pkt2.data, &msg_buff[48 + i * 104], MIN(msg_len - (48 + i * 104), 104)); - DataFlash_Class::instance()->WriteBlock(&pkt2, sizeof(pkt2)); + AP_Logger::instance()->WriteBlock(&pkt2, sizeof(pkt2)); } }; @@ -520,5 +520,5 @@ AP_GPS_SBP2::logging_ext_event() { level : last_event.flags.level, quality : last_event.flags.quality, }; - DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt)); + AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt)); }; diff --git a/libraries/AP_GPS/AP_GPS_SBP2.h b/libraries/AP_GPS/AP_GPS_SBP2.h index 3a4ad4a62a..ef174066c9 100644 --- a/libraries/AP_GPS/AP_GPS_SBP2.h +++ b/libraries/AP_GPS/AP_GPS_SBP2.h @@ -188,7 +188,7 @@ private: uint32_t crc_error_counter; // ************************************************************************ - // Logging to DataFlash + // Logging to AP_Logger // ************************************************************************ void logging_log_full_update(); diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index 0a78d22bbc..428544e64b 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -21,7 +21,7 @@ #include "AP_GPS.h" #include "AP_GPS_UBLOX.h" #include -#include +#include #include #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \ @@ -499,7 +499,7 @@ void AP_GPS_UBLOX::log_mon_hw(void) pkt.aPower = _buffer.mon_hw_68.aPower; pkt.agcCnt = _buffer.mon_hw_68.agcCnt; } - DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt)); + AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt)); } void AP_GPS_UBLOX::log_mon_hw2(void) @@ -517,7 +517,7 @@ void AP_GPS_UBLOX::log_mon_hw2(void) ofsQ : _buffer.mon_hw2.ofsQ, magQ : _buffer.mon_hw2.magQ, }; - DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt)); + AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt)); } #if UBLOX_RXM_RAW_LOGGING @@ -543,7 +543,7 @@ void AP_GPS_UBLOX::log_rxm_raw(const struct ubx_rxm_raw &raw) cno : raw.svinfo[i].cno, lli : raw.svinfo[i].lli }; - DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt)); + AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt)); } } @@ -564,7 +564,7 @@ void AP_GPS_UBLOX::log_rxm_rawx(const struct ubx_rxm_rawx &raw) numMeas : raw.numMeas, recStat : raw.recStat }; - DataFlash_Class::instance()->WriteBlock(&header, sizeof(header)); + AP_Logger::instance()->WriteBlock(&header, sizeof(header)); for (uint8_t i=0; iWriteBlock(&pkt, sizeof(pkt)); + AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt)); } } #endif // UBLOX_RXM_RAW_LOGGING @@ -1375,12 +1375,12 @@ bool AP_GPS_UBLOX::get_lag(float &lag_sec) const return true; } -void AP_GPS_UBLOX::Write_DataFlash_Log_Startup_messages() const +void AP_GPS_UBLOX::Write_AP_Logger_Log_Startup_messages() const { - AP_GPS_Backend::Write_DataFlash_Log_Startup_messages(); + AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages(); if (_have_version) { - DataFlash_Class::instance()->Log_Write_MessageF("u-blox %d HW: %s SW: %s", + AP_Logger::instance()->Log_Write_MessageF("u-blox %d HW: %s SW: %s", state.instance+1, _version.hwVersion, _version.swVersion); diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.h b/libraries/AP_GPS/AP_GPS_UBLOX.h index 0e35990806..5d8fbce19e 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.h +++ b/libraries/AP_GPS/AP_GPS_UBLOX.h @@ -115,7 +115,7 @@ public: } void broadcast_configuration_failure_reason(void) const override; - void Write_DataFlash_Log_Startup_messages() const override; + void Write_AP_Logger_Log_Startup_messages() const override; // get the velocity lag, returns true if the driver is confident in the returned value bool get_lag(float &lag_sec) const override; diff --git a/libraries/AP_GPS/GPS_Backend.cpp b/libraries/AP_GPS/GPS_Backend.cpp index 7e31b7dbbd..0e73a52f2e 100644 --- a/libraries/AP_GPS/GPS_Backend.cpp +++ b/libraries/AP_GPS/GPS_Backend.cpp @@ -163,11 +163,11 @@ void AP_GPS_Backend::broadcast_gps_type() const gcs().send_text(MAV_SEVERITY_INFO, buffer); } -void AP_GPS_Backend::Write_DataFlash_Log_Startup_messages() const +void AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages() const { char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1]; _detection_message(buffer, sizeof(buffer)); - DataFlash_Class::instance()->Log_Write_Message(buffer); + AP_Logger::instance()->Log_Write_Message(buffer); } bool AP_GPS_Backend::should_df_log() const diff --git a/libraries/AP_GPS/GPS_Backend.h b/libraries/AP_GPS/GPS_Backend.h index 768092cba4..a2ed0def20 100644 --- a/libraries/AP_GPS/GPS_Backend.h +++ b/libraries/AP_GPS/GPS_Backend.h @@ -61,7 +61,7 @@ public: virtual const char *name() const = 0; void broadcast_gps_type() const; - virtual void Write_DataFlash_Log_Startup_messages() const; + virtual void Write_AP_Logger_Log_Startup_messages() const; virtual bool prepare_for_arming(void) { return true; } diff --git a/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp b/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp index 947e2a50ee..7d037a28ea 100644 --- a/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp +++ b/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp @@ -8,7 +8,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/GPS_UBLOX_passthrough.cpp b/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/GPS_UBLOX_passthrough.cpp index 09ca30e341..0a47947364 100644 --- a/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/GPS_UBLOX_passthrough.cpp +++ b/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/GPS_UBLOX_passthrough.cpp @@ -8,7 +8,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index 691a437f61..50602644b0 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -29,7 +29,7 @@ #if CH_CFG_USE_DYNAMIC == TRUE -#include +#include #include #include #include "hwdef/common/stm32_util.h" @@ -238,7 +238,7 @@ void Scheduler::reboot(bool hold_in_bootloader) #ifndef NO_DATAFLASH //stop logging - DataFlash_Class::instance()->StopLogging(); + AP_Logger::instance()->StopLogging(); // stop sdcard driver, if active sdcard_stop(); diff --git a/libraries/AP_HAL_F4Light/HAL_F4Light_Class.cpp b/libraries/AP_HAL_F4Light/HAL_F4Light_Class.cpp index 7709445725..07fc15bdbe 100644 --- a/libraries/AP_HAL_F4Light/HAL_F4Light_Class.cpp +++ b/libraries/AP_HAL_F4Light/HAL_F4Light_Class.cpp @@ -294,7 +294,7 @@ void HAL_F4Light::run(int argc,char* const argv[], Callbacks* callbacks) const printf("\nEnabling SD at %ldms\n", AP_HAL::millis()); SD.begin(F4Light::SPIDeviceManager::_get_device(BOARD_SDCARD_NAME)); #elif defined(BOARD_DATAFLASH_FATFS) - printf("\nEnabling DataFlash as SD at %ldms\n", AP_HAL::millis()); + printf("\nEnabling AP_Logger as SD at %ldms\n", AP_HAL::millis()); SD.begin(F4Light::SPIDeviceManager::_get_device(HAL_DATAFLASH_NAME)); #endif diff --git a/libraries/AP_HAL_F4Light/SPIDevice.cpp b/libraries/AP_HAL_F4Light/SPIDevice.cpp index 9758e8bcaa..91747b8b20 100644 --- a/libraries/AP_HAL_F4Light/SPIDevice.cpp +++ b/libraries/AP_HAL_F4Light/SPIDevice.cpp @@ -254,7 +254,7 @@ bool SPIDevice::transfer(const uint8_t *out, uint32_t send_len, uint8_t *recv, u _recv_len = recv_len; -#define MIN_DMA_BYTES 1 // 4 // write to 2-byte register not uses DMA, 4-byte command to DataFlash will +#define MIN_DMA_BYTES 1 // 4 // write to 2-byte register not uses DMA, 4-byte command to AP_Logger will //#define MIN_DMA_BYTES 32 // for debug switch(_desc.mode){ diff --git a/libraries/AP_HAL_F4Light/hardware/sd/FatFs/drivers/sd.h b/libraries/AP_HAL_F4Light/hardware/sd/FatFs/drivers/sd.h index c7e41f1652..0558d2e6d9 100644 --- a/libraries/AP_HAL_F4Light/hardware/sd/FatFs/drivers/sd.h +++ b/libraries/AP_HAL_F4Light/hardware/sd/FatFs/drivers/sd.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------- - Low level SD card and DataFlash include file + Low level SD card and AP_Logger include file /-----------------------------------------------------------------------*/ #ifndef _SD_DEFINED diff --git a/libraries/AP_HAL_F4Light/hardware/sd/Sd2Card.cpp b/libraries/AP_HAL_F4Light/hardware/sd/Sd2Card.cpp index edc73c34bb..48e4d1edff 100644 --- a/libraries/AP_HAL_F4Light/hardware/sd/Sd2Card.cpp +++ b/libraries/AP_HAL_F4Light/hardware/sd/Sd2Card.cpp @@ -247,13 +247,13 @@ uint8_t Sd2Card::init(AP_HAL::OwnPtr spi) { GPIO::_write(DF_RESET,1); if (!_spi) { - printf("DataFlash SPIDeviceDriver not found\n"); + printf("AP_Logger SPIDeviceDriver not found\n"); return false; } _spi_sem = _spi->get_semaphore(); if (!_spi_sem) { - printf("DataFlash SPIDeviceDriver semaphore is null\n"); + printf("AP_Logger SPIDeviceDriver semaphore is null\n"); return false; } @@ -270,8 +270,8 @@ uint8_t Sd2Card::init(AP_HAL::OwnPtr spi) { DSTATUS ret; ret = disk_initialize(0); - printf("\nDataFlash initialize: status %d size %ldMb\n", ret, sectorCount()/2048UL); - gcs().send_text(MAV_SEVERITY_INFO, "\nDataFlash initialize: status %d size %ldMb\n", ret, sectorCount()/2048UL); + printf("\nAP_Logger initialize: status %d size %ldMb\n", ret, sectorCount()/2048UL); + gcs().send_text(MAV_SEVERITY_INFO, "\nAP_Logger initialize: status %d size %ldMb\n", ret, sectorCount()/2048UL); return ret == RES_OK; } diff --git a/libraries/AP_HAL_F4Light/hardware/sd/SdFatFs.cpp b/libraries/AP_HAL_F4Light/hardware/sd/SdFatFs.cpp index 098ab765f6..33764397ca 100644 --- a/libraries/AP_HAL_F4Light/hardware/sd/SdFatFs.cpp +++ b/libraries/AP_HAL_F4Light/hardware/sd/SdFatFs.cpp @@ -29,10 +29,10 @@ FRESULT SdFatFs::init(Sd2Card *card) { return res; } -#if defined(BOARD_DATAFLASH_FATFS) // in DataFlash +#if defined(BOARD_DATAFLASH_FATFS) // in AP_Logger // always reformat internal flash - printf("Formatting DataFlash to FAT..."); + printf("Formatting AP_Logger to FAT..."); #else // reformat SD card in case of filesystem error @@ -56,7 +56,7 @@ FRESULT SdFatFs::init(Sd2Card *card) { FRESULT SdFatFs::format(const char *filepath, Sd2Card *card){ -#if defined(BOARD_DATAFLASH_FATFS) // in DataFlash +#if defined(BOARD_DATAFLASH_FATFS) // in AP_Logger _card->ioctl(CTRL_FORMAT,0); // clear chip diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.h b/libraries/AP_InertialSensor/AP_InertialSensor.h index 970f034250..ee4e82f459 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor.h @@ -32,10 +32,10 @@ class AuxiliaryBus; class AP_AHRS; /* - forward declare DataFlash class. We can't include DataFlash.h + forward declare AP_Logger class. We can't include logger.h because of mutual dependencies */ -class DataFlash_Class; +class AP_Logger; /* AP_InertialSensor is an abstraction for gyro and accel measurements * which are correctly aligned to the body axes and scaled to SI units. @@ -304,7 +304,7 @@ public: AP_Int8 _sensor_mask; AP_Int8 _batch_options_mask; - // Parameters controlling pushing data to DataFlash: + // Parameters controlling pushing data to AP_Logger: // Each DF message is ~ 108 bytes in size, so we use about 1kB/s of // logging bandwidth with a 100ms interval. If we are taking // 1024 samples then we need to send 32 packets, so it will diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp index 9d624bac26..d9691403ca 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp @@ -1,7 +1,7 @@ #include #include "AP_InertialSensor.h" #include "AP_InertialSensor_Backend.h" -#include +#include #if AP_MODULE_SUPPORTED #include #include @@ -216,7 +216,7 @@ void AP_InertialSensor_Backend::_notify_new_gyro_raw_sample(uint8_t instance, void AP_InertialSensor_Backend::log_gyro_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &gyro) { - DataFlash_Class *dataflash = DataFlash_Class::instance(); + AP_Logger *dataflash = AP_Logger::instance(); if (dataflash == nullptr) { // should not have been called return; @@ -348,7 +348,7 @@ void AP_InertialSensor_Backend::_notify_new_gyro_sensor_rate_sample(uint8_t inst void AP_InertialSensor_Backend::log_accel_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &accel) { - DataFlash_Class *dataflash = DataFlash_Class::instance(); + AP_Logger *dataflash = AP_Logger::instance(); if (dataflash == nullptr) { // should not have been called return; @@ -465,7 +465,7 @@ bool AP_InertialSensor_Backend::should_log_imu_raw() const // tracker does not set a bit return false; } - const DataFlash_Class *instance = DataFlash_Class::instance(); + const AP_Logger *instance = AP_Logger::instance(); if (instance == nullptr) { return false; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h index 447bf5958c..ba5d920bc6 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h @@ -36,7 +36,7 @@ using namespace F4Light; #endif class AuxiliaryBus; -class DataFlash_Class; +class AP_Logger; class AP_InertialSensor_Backend { diff --git a/libraries/AP_InertialSensor/BatchSampler.cpp b/libraries/AP_InertialSensor/BatchSampler.cpp index 1eae46cb9a..46e9d0c3e5 100644 --- a/libraries/AP_InertialSensor/BatchSampler.cpp +++ b/libraries/AP_InertialSensor/BatchSampler.cpp @@ -27,7 +27,7 @@ const AP_Param::GroupInfo AP_InertialSensor::BatchSampler::var_info[] = { // @Param: BAT_LGIN // @DisplayName: logging interval - // @Description: Interval between pushing samples to the DataFlash log + // @Description: Interval between pushing samples to the AP_Logger log // @Units: ms // @Increment: 10 AP_GROUPINFO("BAT_LGIN", 4, AP_InertialSensor::BatchSampler, push_interval_ms, 20), @@ -173,10 +173,10 @@ void AP_InertialSensor::BatchSampler::push_data_to_log() return; } if (AP_HAL::millis() - last_sent_ms < (uint16_t)push_interval_ms) { - // avoid flooding DataFlash's buffer + // avoid flooding AP_Logger's buffer return; } - DataFlash_Class *dataflash = DataFlash_Class::instance(); + AP_Logger *dataflash = AP_Logger::instance(); if (dataflash == nullptr) { // should not have been called return; @@ -250,7 +250,7 @@ bool AP_InertialSensor::BatchSampler::should_log(uint8_t _instance, IMU_SENSOR_T if (data_write_offset >= _required_count) { return false; } - DataFlash_Class *dataflash = DataFlash_Class::instance(); + AP_Logger *dataflash = AP_Logger::instance(); if (dataflash == nullptr) { return false; } diff --git a/libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp b/libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp index 3262546e89..5ca43c534a 100644 --- a/libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp +++ b/libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp @@ -12,7 +12,7 @@ #include #include #include -#include +#include #include #include #include @@ -49,7 +49,7 @@ static uint32_t accel_deltat_min[INS_MAX_INSTANCES]; static uint32_t accel_deltat_max[INS_MAX_INSTANCES]; static uint32_t gyro_deltat_min[INS_MAX_INSTANCES]; static uint32_t gyro_deltat_max[INS_MAX_INSTANCES]; -static DataFlash_File DataFlash("/fs/microsd/VIBTEST"); +static AP_Logger_File AP_Logger("/fs/microsd/VIBTEST"); static const struct LogStructure log_structure[] = { LOG_COMMON_STRUCTURES, @@ -96,8 +96,8 @@ void setup(void) ioctl(accel_fd[1], ACCELIOCSSAMPLERATE, 1600); ioctl(accel_fd[1], SENSORIOCSQUEUEDEPTH, 100); - DataFlash.Init(log_structure, ARRAY_SIZE(log_structure)); - DataFlash.StartNewLog(); + logger.Init(log_structure, ARRAY_SIZE(log_structure)); + logger.StartNewLog(); } void loop(void) @@ -130,7 +130,7 @@ void loop(void) AccY : accel_report.y, AccZ : accel_report.z }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); got_sample = true; total_samples[i]++; } @@ -154,7 +154,7 @@ void loop(void) GyrY : gyro_report.y, GyrZ : gyro_report.z }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + logger.WriteBlock(&pkt, sizeof(pkt)); got_sample = true; total_samples[i]++; } diff --git a/libraries/AP_KDECAN/AP_KDECAN.cpp b/libraries/AP_KDECAN/AP_KDECAN.cpp index 0f538af0c1..ef18f2d85b 100644 --- a/libraries/AP_KDECAN/AP_KDECAN.cpp +++ b/libraries/AP_KDECAN/AP_KDECAN.cpp @@ -600,7 +600,7 @@ void AP_KDECAN::update() debug_can(2, "KDECAN: failed to get PWM semaphore on write\n\r"); } - DataFlash_Class *df = DataFlash_Class::instance(); + AP_Logger *df = AP_Logger::instance(); if (df == nullptr || !df->should_log(0xFFFFFFFF)) { return; diff --git a/libraries/AP_Landing/AP_Landing.cpp b/libraries/AP_Landing/AP_Landing.cpp index 80d7f9f968..1c2592b1de 100644 --- a/libraries/AP_Landing/AP_Landing.cpp +++ b/libraries/AP_Landing/AP_Landing.cpp @@ -363,7 +363,7 @@ bool AP_Landing::override_servos(void) { // returns a PID_Info object if there is one available for the selected landing // type, otherwise returns a nullptr, indicating no data to be logged/sent -const DataFlash_Class::PID_Info* AP_Landing::get_pid_info(void) const +const AP_Logger::PID_Info* AP_Landing::get_pid_info(void) const { switch (type) { case TYPE_DEEPSTALL: diff --git a/libraries/AP_Landing/AP_Landing.h b/libraries/AP_Landing/AP_Landing.h index 6b655f8763..4fe5065723 100644 --- a/libraries/AP_Landing/AP_Landing.h +++ b/libraries/AP_Landing/AP_Landing.h @@ -101,7 +101,7 @@ public: void set_initial_slope(void) { initial_slope = slope; } bool is_expecting_impact(void) const; void Log(void) const; - const DataFlash_Class::PID_Info * get_pid_info(void) const; + const AP_Logger::PID_Info * get_pid_info(void) const; // landing altitude offset (meters) float alt_offset; diff --git a/libraries/AP_Landing/AP_Landing_Deepstall.cpp b/libraries/AP_Landing/AP_Landing_Deepstall.cpp index ca5ce48ffa..933064f161 100644 --- a/libraries/AP_Landing/AP_Landing_Deepstall.cpp +++ b/libraries/AP_Landing/AP_Landing_Deepstall.cpp @@ -423,13 +423,13 @@ bool AP_Landing_Deepstall::send_deepstall_message(mavlink_channel_t chan) const return true; } -const DataFlash_Class::PID_Info& AP_Landing_Deepstall::get_pid_info(void) const +const AP_Logger::PID_Info& AP_Landing_Deepstall::get_pid_info(void) const { return ds_PID.get_pid_info(); } void AP_Landing_Deepstall::Log(void) const { - const DataFlash_Class::PID_Info& pid_info = ds_PID.get_pid_info(); + const AP_Logger::PID_Info& pid_info = ds_PID.get_pid_info(); struct log_DSTL pkt = { LOG_PACKET_HEADER_INIT(LOG_DSTL_MSG), time_us : AP_HAL::micros64(), @@ -449,7 +449,7 @@ void AP_Landing_Deepstall::Log(void) const { I : pid_info.I, D : pid_info.D, }; - DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt)); + AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt)); } // termination handling, expected to set the servo outputs diff --git a/libraries/AP_Landing/AP_Landing_Deepstall.h b/libraries/AP_Landing/AP_Landing_Deepstall.h index 8468d2042d..95820a0714 100644 --- a/libraries/AP_Landing/AP_Landing_Deepstall.h +++ b/libraries/AP_Landing/AP_Landing_Deepstall.h @@ -109,7 +109,7 @@ private: bool send_deepstall_message(mavlink_channel_t chan) const; - const DataFlash_Class::PID_Info& get_pid_info(void) const; + const AP_Logger::PID_Info& get_pid_info(void) const; //private helpers void build_approach_path(bool use_current_heading); diff --git a/libraries/AP_Landing/AP_Landing_Slope.cpp b/libraries/AP_Landing/AP_Landing_Slope.cpp index e9260d7ab8..b351fc77b8 100644 --- a/libraries/AP_Landing/AP_Landing_Slope.cpp +++ b/libraries/AP_Landing/AP_Landing_Slope.cpp @@ -382,8 +382,8 @@ bool AP_Landing::type_slope_is_complete(void) const void AP_Landing::type_slope_log(void) const { - // log to DataFlash - DataFlash_Class::instance()->Log_Write("LAND", "TimeUS,stage,f1,f2,slope,slopeInit,altO", "QBBBfff", + // log to AP_Logger + AP_Logger::instance()->Log_Write("LAND", "TimeUS,stage,f1,f2,slope,slopeInit,altO", "QBBBfff", AP_HAL::micros64(), type_slope_stage, flags, diff --git a/libraries/AP_LandingGear/AP_LandingGear.cpp b/libraries/AP_LandingGear/AP_LandingGear.cpp index a455b7a654..42659127ab 100644 --- a/libraries/AP_LandingGear/AP_LandingGear.cpp +++ b/libraries/AP_LandingGear/AP_LandingGear.cpp @@ -3,7 +3,7 @@ #include #include #include -#include +#include #include extern const AP_HAL::HAL& hal; @@ -250,7 +250,7 @@ void AP_LandingGear::update(float height_above_ground_m) // log weight on wheels state void AP_LandingGear::log_wow_state(LG_WOW_State state) { - DataFlash_Class::instance()->Log_Write("LGR", "TimeUS,LandingGear,WeightOnWheels", "Qbb", + AP_Logger::instance()->Log_Write("LGR", "TimeUS,LandingGear,WeightOnWheels", "Qbb", AP_HAL::micros64(), (int8_t)gear_state_current, (int8_t)state); } diff --git a/libraries/AP_Logger/AP_Logger.cpp b/libraries/AP_Logger/AP_Logger.cpp index ab3420af68..62864f29c8 100644 --- a/libraries/AP_Logger/AP_Logger.cpp +++ b/libraries/AP_Logger/AP_Logger.cpp @@ -1,17 +1,17 @@ -#include "DataFlash.h" +#include "AP_Logger.h" -#include "DataFlash_Backend.h" +#include "AP_Logger_Backend.h" -#include "DataFlash_File.h" -#include "DataFlash_File_sd.h" -#include "DataFlash_MAVLink.h" +#include "AP_Logger_File.h" +#include "AP_Logger_File_sd.h" +#include "AP_Logger_MAVLink.h" #include #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT -#include "DataFlash_Revo.h" +#include "AP_Logger_Revo.h" #endif -DataFlash_Class *DataFlash_Class::_instance; +AP_Logger *AP_Logger::_instance; extern const AP_HAL::HAL& hal; @@ -23,65 +23,65 @@ extern const AP_HAL::HAL& hal; #define HAL_DATAFLASH_MAV_BUFSIZE 8 #endif -const AP_Param::GroupInfo DataFlash_Class::var_info[] = { +const AP_Param::GroupInfo AP_Logger::var_info[] = { // @Param: _BACKEND_TYPE - // @DisplayName: DataFlash Backend Storage type + // @DisplayName: AP_Logger Backend Storage type // @Description: 0 for None, 1 for File, 2 for dataflash mavlink, 3 for both file and dataflash // @Values: 0:None,1:File,2:MAVLink,3:BothFileAndMAVLink // @User: Standard - AP_GROUPINFO("_BACKEND_TYPE", 0, DataFlash_Class, _params.backend_types, DATAFLASH_BACKEND_FILE), + AP_GROUPINFO("_BACKEND_TYPE", 0, AP_Logger, _params.backend_types, DATAFLASH_BACKEND_FILE), // @Param: _FILE_BUFSIZE - // @DisplayName: Maximum DataFlash File Backend buffer size (in kilobytes) - // @Description: The DataFlash_File backend uses a buffer to store data before writing to the block device. Raising this value may reduce "gaps" in your SD card logging. This buffer size may be reduced depending on available memory. PixHawk requires at least 4 kilobytes. Maximum value available here is 64 kilobytes. + // @DisplayName: Maximum AP_Logger File Backend buffer size (in kilobytes) + // @Description: The AP_Logger_File backend uses a buffer to store data before writing to the block device. Raising this value may reduce "gaps" in your SD card logging. This buffer size may be reduced depending on available memory. PixHawk requires at least 4 kilobytes. Maximum value available here is 64 kilobytes. // @User: Standard - AP_GROUPINFO("_FILE_BUFSIZE", 1, DataFlash_Class, _params.file_bufsize, HAL_DATAFLASH_FILE_BUFSIZE), + AP_GROUPINFO("_FILE_BUFSIZE", 1, AP_Logger, _params.file_bufsize, HAL_DATAFLASH_FILE_BUFSIZE), // @Param: _DISARMED // @DisplayName: Enable logging while disarmed // @Description: If LOG_DISARMED is set to 1 then logging will be enabled while disarmed. This can make for very large logfiles but can help a lot when tracking down startup issues // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("_DISARMED", 2, DataFlash_Class, _params.log_disarmed, 0), + AP_GROUPINFO("_DISARMED", 2, AP_Logger, _params.log_disarmed, 0), // @Param: _REPLAY // @DisplayName: Enable logging of information needed for Replay // @Description: If LOG_REPLAY is set to 1 then the EKF2 state estimator will log detailed information needed for diagnosing problems with the Kalman filter. It is suggested that you also raise LOG_FILE_BUFSIZE to give more buffer space for logging and use a high quality microSD card to ensure no sensor data is lost // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("_REPLAY", 3, DataFlash_Class, _params.log_replay, 0), + AP_GROUPINFO("_REPLAY", 3, AP_Logger, _params.log_replay, 0), // @Param: _FILE_DSRMROT // @DisplayName: Stop logging to current file on disarm // @Description: When set, the current log file is closed when the vehicle is disarmed. If LOG_DISARMED is set then a fresh log will be opened. // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("_FILE_DSRMROT", 4, DataFlash_Class, _params.file_disarm_rot, 0), + AP_GROUPINFO("_FILE_DSRMROT", 4, AP_Logger, _params.file_disarm_rot, 0), // @Param: _MAV_BUFSIZE - // @DisplayName: Maximum DataFlash MAVLink Backend buffer size - // @Description: Maximum amount of memory to allocate to DataFlash-over-mavlink + // @DisplayName: Maximum AP_Logger MAVLink Backend buffer size + // @Description: Maximum amount of memory to allocate to AP_Logger-over-mavlink // @User: Advanced // @Units: kB - AP_GROUPINFO("_MAV_BUFSIZE", 5, DataFlash_Class, _params.mav_bufsize, HAL_DATAFLASH_MAV_BUFSIZE), + AP_GROUPINFO("_MAV_BUFSIZE", 5, AP_Logger, _params.mav_bufsize, HAL_DATAFLASH_MAV_BUFSIZE), AP_GROUPEND }; #define streq(x, y) (!strcmp(x, y)) -DataFlash_Class::DataFlash_Class(const AP_Int32 &log_bitmask) +AP_Logger::AP_Logger(const AP_Int32 &log_bitmask) : _log_bitmask(log_bitmask) { AP_Param::setup_object_defaults(this, var_info); if (_instance != nullptr) { - AP_HAL::panic("DataFlash must be singleton"); + AP_HAL::panic("AP_Logger must be singleton"); } _instance = this; } -void DataFlash_Class::Init(const struct LogStructure *structures, uint8_t num_types) +void AP_Logger::Init(const struct LogStructure *structures, uint8_t num_types) { gcs().send_text(MAV_SEVERITY_INFO, "Preparing log system"); #if CONFIG_HAL_BOARD == HAL_BOARD_SITL @@ -99,15 +99,15 @@ void DataFlash_Class::Init(const struct LogStructure *structures, uint8_t num_ty #if HAL_OS_POSIX_IO || HAL_OS_FATFS_IO if (_params.backend_types == DATAFLASH_BACKEND_FILE || _params.backend_types == DATAFLASH_BACKEND_BOTH) { - DFMessageWriter_DFLogStart *message_writer = - new DFMessageWriter_DFLogStart(); + LoggerMessageWriter_DFLogStart *message_writer = + new LoggerMessageWriter_DFLogStart(); if (message_writer != nullptr) { - backends[_next_backend] = new DataFlash_File(*this, + 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 DataFlash_File"); + hal.console->printf("Unable to open AP_Logger_File"); } else { _next_backend++; } @@ -117,19 +117,19 @@ void DataFlash_Class::Init(const struct LogStructure *structures, uint8_t num_ty if (_params.backend_types == DATAFLASH_BACKEND_FILE || _params.backend_types == DATAFLASH_BACKEND_BOTH) { - DFMessageWriter_DFLogStart *message_writer = - new DFMessageWriter_DFLogStart(); + LoggerMessageWriter_DFLogStart *message_writer = + new LoggerMessageWriter_DFLogStart(); if (message_writer != nullptr) { #if defined(BOARD_SDCARD_NAME) || defined(BOARD_DATAFLASH_FATFS) - backends[_next_backend] = new DataFlash_File(*this, message_writer, HAL_BOARD_LOG_DIRECTORY); + backends[_next_backend] = new AP_Logger_File(*this, message_writer, HAL_BOARD_LOG_DIRECTORY); #else - backends[_next_backend] = new DataFlash_Revo(*this, message_writer); // restore dataflash logs + backends[_next_backend] = new AP_Logger_Revo(*this, message_writer); // restore dataflash logs #endif } if (backends[_next_backend] == nullptr) { - printf("Unable to open DataFlash_Revo"); + printf("Unable to open AP_Logger_Revo"); } else { _next_backend++; } @@ -144,14 +144,14 @@ void DataFlash_Class::Init(const struct LogStructure *structures, uint8_t num_ty AP_HAL::panic("Too many backends"); return; } - DFMessageWriter_DFLogStart *message_writer = - new DFMessageWriter_DFLogStart(); + LoggerMessageWriter_DFLogStart *message_writer = + new LoggerMessageWriter_DFLogStart(); if (message_writer != nullptr) { - backends[_next_backend] = new DataFlash_MAVLink(*this, + backends[_next_backend] = new AP_Logger_MAVLink(*this, message_writer); } if (backends[_next_backend] == nullptr) { - hal.console->printf("Unable to open DataFlash_MAVLink"); + hal.console->printf("Unable to open AP_Logger_MAVLink"); } else { _next_backend++; } @@ -190,7 +190,7 @@ static uint8_t count_commas(const char *string) } /// return a unit name given its ID -const char* DataFlash_Class::unit_name(const uint8_t unit_id) +const char* AP_Logger::unit_name(const uint8_t unit_id) { for(uint8_t i=0; iunits[fieldnum]), multiplier_name(logstructure->multipliers[fieldnum])); } /// pretty-print log structures /// @note structures MUST be well-formed -void DataFlash_Class::dump_structures(const struct LogStructure *logstructures, const uint8_t num_types) +void AP_Logger::dump_structures(const struct LogStructure *logstructures, const uint8_t num_types) { #if DEBUG_LOG_STRUCTURES for (uint16_t i=0; iCardInserted()) { return true; @@ -541,40 +541,40 @@ bool DataFlash_Class::CardInserted(void) { return false; } -void DataFlash_Class::Prep() { +void AP_Logger::Prep() { FOR_EACH_BACKEND(Prep()); } -void DataFlash_Class::StopLogging() +void AP_Logger::StopLogging() { FOR_EACH_BACKEND(stop_logging()); } -uint16_t DataFlash_Class::find_last_log() const { +uint16_t AP_Logger::find_last_log() const { if (_next_backend == 0) { return 0; } return backends[0]->find_last_log(); } -void DataFlash_Class::get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page) { +void AP_Logger::get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page) { if (_next_backend == 0) { return; } backends[0]->get_log_boundaries(log_num, start_page, end_page); } -void DataFlash_Class::get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) { +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 DataFlash_Class::get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) { +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 DataFlash_Class::get_num_logs(void) { +uint16_t AP_Logger::get_num_logs(void) { if (_next_backend == 0) { return 0; } @@ -582,7 +582,7 @@ uint16_t DataFlash_Class::get_num_logs(void) { } /* we're started if any of the backends are started */ -bool DataFlash_Class::logging_started(void) { +bool AP_Logger::logging_started(void) { for (uint8_t i=0; i< _next_backend; i++) { if (backends[i]->logging_started()) { return true; @@ -591,7 +591,7 @@ bool DataFlash_Class::logging_started(void) { return false; } -void DataFlash_Class::handle_mavlink_msg(GCS_MAVLINK &link, mavlink_message_t* msg) +void AP_Logger::handle_mavlink_msg(GCS_MAVLINK &link, mavlink_message_t* msg) { switch (msg->msgid) { case MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS: @@ -609,46 +609,46 @@ void DataFlash_Class::handle_mavlink_msg(GCS_MAVLINK &link, mavlink_message_t* m } } -void DataFlash_Class::periodic_tasks() { +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 - // currently only DataFlash_File support this: -void DataFlash_Class::flush(void) { + // currently only AP_Logger_File support this: +void AP_Logger::flush(void) { FOR_EACH_BACKEND(flush()); } #endif -void DataFlash_Class::Log_Write_EntireMission(const AP_Mission &mission) +void AP_Logger::Log_Write_EntireMission(const AP_Mission &mission) { FOR_EACH_BACKEND(Log_Write_EntireMission(mission)); } -void DataFlash_Class::Log_Write_Message(const char *message) +void AP_Logger::Log_Write_Message(const char *message) { FOR_EACH_BACKEND(Log_Write_Message(message)); } -void DataFlash_Class::Log_Write_Mode(uint8_t mode, uint8_t reason) +void AP_Logger::Log_Write_Mode(uint8_t mode, uint8_t reason) { FOR_EACH_BACKEND(Log_Write_Mode(mode, reason)); } -void DataFlash_Class::Log_Write_Parameter(const char *name, float value) +void AP_Logger::Log_Write_Parameter(const char *name, float value) { FOR_EACH_BACKEND(Log_Write_Parameter(name, value)); } -void DataFlash_Class::Log_Write_Mission_Cmd(const AP_Mission &mission, +void AP_Logger::Log_Write_Mission_Cmd(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd) { FOR_EACH_BACKEND(Log_Write_Mission_Cmd(mission, cmd)); } -uint32_t DataFlash_Class::num_dropped() const +uint32_t AP_Logger::num_dropped() const { if (_next_backend == 0) { return 0; @@ -659,14 +659,14 @@ uint32_t DataFlash_Class::num_dropped() const // end functions pass straight through to backend -void DataFlash_Class::internal_error() const { +void AP_Logger::internal_error() const { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL - AP_HAL::panic("Internal DataFlash error"); + AP_HAL::panic("Internal AP_Logger error"); #endif } /* Log_Write support */ -void DataFlash_Class::Log_Write(const char *name, const char *labels, const char *fmt, ...) +void AP_Logger::Log_Write(const char *name, const char *labels, const char *fmt, ...) { va_list arg_list; @@ -675,7 +675,7 @@ void DataFlash_Class::Log_Write(const char *name, const char *labels, const char va_end(arg_list); } -void DataFlash_Class::Log_Write(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...) +void AP_Logger::Log_Write(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...) { va_list arg_list; @@ -684,7 +684,7 @@ void DataFlash_Class::Log_Write(const char *name, const char *labels, const char va_end(arg_list); } -void DataFlash_Class::Log_WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list) +void AP_Logger::Log_WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list) { struct log_write_fmt *f = msg_fmt_for_name(name, labels, units, mults, fmt); if (f == nullptr) { @@ -710,7 +710,7 @@ void DataFlash_Class::Log_WriteV(const char *name, const char *labels, const cha #if CONFIG_HAL_BOARD == HAL_BOARD_SITL -void DataFlash_Class::assert_same_fmt_for_name(const DataFlash_Class::log_write_fmt *f, +void AP_Logger::assert_same_fmt_for_name(const AP_Logger::log_write_fmt *f, const char *name, const char *labels, const char *units, @@ -756,7 +756,7 @@ void DataFlash_Class::assert_same_fmt_for_name(const DataFlash_Class::log_write_ } #endif -DataFlash_Class::log_write_fmt *DataFlash_Class::msg_fmt_for_name(const char *name, const char *labels, const char *units, const char *mults, const char *fmt) +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) { @@ -832,7 +832,7 @@ DataFlash_Class::log_write_fmt *DataFlash_Class::msg_fmt_for_name(const char *na return f; } -const struct LogStructure *DataFlash_Class::structure_for_msg_type(const uint8_t msg_type) +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); @@ -844,7 +844,7 @@ const struct LogStructure *DataFlash_Class::structure_for_msg_type(const uint8_t return nullptr; } -const struct DataFlash_Class::log_write_fmt *DataFlash_Class::log_write_fmt_for_msg_type(const uint8_t msg_type) const +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) { @@ -857,7 +857,7 @@ const struct DataFlash_Class::log_write_fmt *DataFlash_Class::log_write_fmt_for_ // returns true if the msg_type is already taken -bool DataFlash_Class::msg_type_in_use(const uint8_t msg_type) const +bool AP_Logger::msg_type_in_use(const uint8_t msg_type) const { // check static list of messages (e.g. from LOG_BASE_STRUCTURES) // check the write format types to see if we've used this one @@ -878,7 +878,7 @@ bool DataFlash_Class::msg_type_in_use(const uint8_t msg_type) const } // find a free message type -int16_t DataFlash_Class::find_free_msg_type() const +int16_t AP_Logger::find_free_msg_type() const { // avoid using 255 here; perhaps we want to use it to extend things later for (uint16_t msg_type=254; msg_type>0; msg_type--) { // more likely to be free at end @@ -893,7 +893,7 @@ int16_t DataFlash_Class::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 DataFlash_Class::fill_log_write_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const +bool AP_Logger::fill_log_write_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const { // find log structure information corresponding to msg_type: struct log_write_fmt *f; @@ -937,7 +937,7 @@ bool DataFlash_Class::fill_log_write_logstructure(struct LogStructure &logstruct * returns an int16_t; if it returns -1 then an error has occurred. * This was mechanically converted from init_field_types in * Tools/Replay/MsgHandler.cpp */ -int16_t DataFlash_Class::Log_Write_calc_msg_len(const char *fmt) const +int16_t AP_Logger::Log_Write_calc_msg_len(const char *fmt) const { uint8_t len = LOG_PACKET_HEADER_LEN; for (uint8_t i=0; i #include #include -#include +#include #include #include #include @@ -26,11 +26,11 @@ #include -#include "DFMessageWriter.h" +#include "LoggerMessageWriter.h" -class DataFlash_Backend; +class AP_Logger_Backend; -enum DataFlash_Backend_Type { +enum AP_Logger_Backend_Type { DATAFLASH_BACKEND_NONE = 0, DATAFLASH_BACKEND_FILE = 1, DATAFLASH_BACKEND_MAVLINK = 2, @@ -41,21 +41,21 @@ enum DataFlash_Backend_Type { class AC_AttitudeControl; class AC_PosControl; -class DataFlash_Class +class AP_Logger { - friend class DataFlash_Backend; // for _num_types + friend class AP_Logger_Backend; // for _num_types public: FUNCTOR_TYPEDEF(vehicle_startup_message_Log_Writer, void); - DataFlash_Class(const AP_Int32 &log_bitmask); + AP_Logger(const AP_Int32 &log_bitmask); /* Do not allow copies */ - DataFlash_Class(const DataFlash_Class &other) = delete; - DataFlash_Class &operator=(const DataFlash_Class&) = delete; + AP_Logger(const AP_Logger &other) = delete; + AP_Logger &operator=(const AP_Logger&) = delete; // get singleton instance - static DataFlash_Class *instance(void) { + static AP_Logger *instance(void) { return _instance; } @@ -167,7 +167,7 @@ public: bool logging_started(void); #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX - // currently only DataFlash_File support this: + // currently only AP_Logger_File support this: void flush(void); #endif @@ -207,7 +207,7 @@ public: // methods for mavlink SYS_STATUS message (send_sys_status) // these methods cover only the first logging backend used - - // typically DataFlash_File. + // typically AP_Logger_File. bool logging_present() const; bool logging_enabled() const; bool logging_failed() const; @@ -242,7 +242,7 @@ protected: private: #define DATAFLASH_MAX_BACKENDS 2 uint8_t _next_backend; - DataFlash_Backend *backends[DATAFLASH_MAX_BACKENDS]; + AP_Logger_Backend *backends[DATAFLASH_MAX_BACKENDS]; const AP_Int32 &_log_bitmask; void internal_error() const; @@ -305,9 +305,9 @@ private: uint8_t imu_instance, enum LogMessages type); - void backend_starting_new_log(const DataFlash_Backend *backend); + void backend_starting_new_log(const AP_Logger_Backend *backend); - static DataFlash_Class *_instance; + static AP_Logger *_instance; #if CONFIG_HAL_BOARD == HAL_BOARD_SITL bool validate_structure(const struct LogStructure *logstructure, int16_t offset); diff --git a/libraries/AP_Logger/AP_Logger_Backend.cpp b/libraries/AP_Logger/AP_Logger_Backend.cpp index 790e0acdde..c56a85eb02 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.cpp +++ b/libraries/AP_Logger/AP_Logger_Backend.cpp @@ -1,62 +1,62 @@ -#include "DataFlash_Backend.h" +#include "AP_Logger_Backend.h" -#include "DFMessageWriter.h" +#include "LoggerMessageWriter.h" extern const AP_HAL::HAL& hal; -DataFlash_Backend::DataFlash_Backend(DataFlash_Class &front, - class DFMessageWriter_DFLogStart *writer) : +AP_Logger_Backend::AP_Logger_Backend(AP_Logger &front, + class LoggerMessageWriter_DFLogStart *writer) : _front(front), _startup_messagewriter(writer) { writer->set_dataflash_backend(this); } -uint8_t DataFlash_Backend::num_types() const +uint8_t AP_Logger_Backend::num_types() const { return _front._num_types; } -const struct LogStructure *DataFlash_Backend::structure(uint8_t num) const +const struct LogStructure *AP_Logger_Backend::structure(uint8_t num) const { return _front.structure(num); } -uint8_t DataFlash_Backend::num_units() const +uint8_t AP_Logger_Backend::num_units() const { return _front._num_units; } -const struct UnitStructure *DataFlash_Backend::unit(uint8_t num) const +const struct UnitStructure *AP_Logger_Backend::unit(uint8_t num) const { return _front.unit(num); } -uint8_t DataFlash_Backend::num_multipliers() const +uint8_t AP_Logger_Backend::num_multipliers() const { return _front._num_multipliers; } -const struct MultiplierStructure *DataFlash_Backend::multiplier(uint8_t num) const +const struct MultiplierStructure *AP_Logger_Backend::multiplier(uint8_t num) const { return _front.multiplier(num); } -DataFlash_Backend::vehicle_startup_message_Log_Writer DataFlash_Backend::vehicle_message_writer() { +AP_Logger_Backend::vehicle_startup_message_Log_Writer AP_Logger_Backend::vehicle_message_writer() { return _front._vehicle_messages; } -void DataFlash_Backend::periodic_10Hz(const uint32_t now) +void AP_Logger_Backend::periodic_10Hz(const uint32_t now) { } -void DataFlash_Backend::periodic_1Hz() +void AP_Logger_Backend::periodic_1Hz() { } -void DataFlash_Backend::periodic_fullrate() +void AP_Logger_Backend::periodic_fullrate() { } -void DataFlash_Backend::periodic_tasks() +void AP_Logger_Backend::periodic_tasks() { uint32_t now = AP_HAL::millis(); if (now - _last_periodic_1Hz > 1000) { @@ -70,13 +70,13 @@ void DataFlash_Backend::periodic_tasks() periodic_fullrate(); } -void DataFlash_Backend::start_new_log_reset_variables() +void AP_Logger_Backend::start_new_log_reset_variables() { _startup_messagewriter->reset(); _front.backend_starting_new_log(this); } -void DataFlash_Backend::internal_error() { +void AP_Logger_Backend::internal_error() { _internal_errors++; #if CONFIG_HAL_BOARD == HAL_BOARD_SITL abort(); @@ -84,14 +84,14 @@ void DataFlash_Backend::internal_error() { } // this method can be overridden to do extra things with your buffer. -// for example, in DataFlash_MAVLink we may push messages into the UART. -void DataFlash_Backend::push_log_blocks() { +// for example, in AP_Logger_MAVLink we may push messages into the UART. +void AP_Logger_Backend::push_log_blocks() { WriteMoreStartupMessages(); } // returns true if all format messages have been written, and thus it is OK // for other messages to go out to the log -bool DataFlash_Backend::WriteBlockCheckStartupMessages() +bool AP_Logger_Backend::WriteBlockCheckStartupMessages() { #if APM_BUILD_TYPE(APM_BUILD_Replay) return true; @@ -125,7 +125,7 @@ bool DataFlash_Backend::WriteBlockCheckStartupMessages() } // source more messages from the startup message writer: -void DataFlash_Backend::WriteMoreStartupMessages() +void AP_Logger_Backend::WriteMoreStartupMessages() { if (_startup_messagewriter->finished()) { @@ -142,7 +142,7 @@ void DataFlash_Backend::WriteMoreStartupMessages() */ -bool DataFlash_Backend::Log_Write_Emit_FMT(uint8_t msg_type) +bool AP_Logger_Backend::Log_Write_Emit_FMT(uint8_t msg_type) { // get log structure from front end: char ls_name[LS_NAME_SIZE] = {}; @@ -178,14 +178,14 @@ bool DataFlash_Backend::Log_Write_Emit_FMT(uint8_t msg_type) return true; } -bool DataFlash_Backend::Log_Write(const uint8_t msg_type, va_list arg_list, bool is_critical) +bool AP_Logger_Backend::Log_Write(const uint8_t msg_type, va_list arg_list, bool is_critical) { // stack-allocate a buffer so we can WriteBlock(); this could be // 255 bytes! If we were willing to lose the WriteBlock // abstraction we could do WriteBytes() here instead? const char *fmt = nullptr; uint8_t msg_len; - DataFlash_Class::log_write_fmt *f; + AP_Logger::log_write_fmt *f; for (f = _front.log_write_fmts; f; f=f->next) { if (f->msg_type == msg_type) { fmt = f->fmt; @@ -295,7 +295,7 @@ bool DataFlash_Backend::Log_Write(const uint8_t msg_type, va_list arg_list, bool return WritePrioritisedBlock(buffer, msg_len, is_critical); } -bool DataFlash_Backend::StartNewLogOK() const +bool AP_Logger_Backend::StartNewLogOK() const { if (logging_started()) { return false; @@ -313,7 +313,7 @@ bool DataFlash_Backend::StartNewLogOK() const } #if CONFIG_HAL_BOARD == HAL_BOARD_SITL -void DataFlash_Backend::validate_WritePrioritisedBlock(const void *pBuffer, +void AP_Logger_Backend::validate_WritePrioritisedBlock(const void *pBuffer, uint16_t size) { // just check the first few packets to avoid too much overhead @@ -338,7 +338,7 @@ void DataFlash_Backend::validate_WritePrioritisedBlock(const void *pBuffer, uint8_t type_len; const struct LogStructure *s = _front.structure_for_msg_type(type); if (s == nullptr) { - const struct DataFlash_Class::log_write_fmt *t = _front.log_write_fmt_for_msg_type(type); + const struct AP_Logger::log_write_fmt *t = _front.log_write_fmt_for_msg_type(type); if (t == nullptr) { AP_HAL::panic("No structure for msg_type=%u", type); } @@ -355,7 +355,7 @@ void DataFlash_Backend::validate_WritePrioritisedBlock(const void *pBuffer, } #endif -bool DataFlash_Backend::WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) +bool AP_Logger_Backend::WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL validate_WritePrioritisedBlock(pBuffer, size); @@ -372,7 +372,7 @@ bool DataFlash_Backend::WritePrioritisedBlock(const void *pBuffer, uint16_t size return _WritePrioritisedBlock(pBuffer, size, is_critical); } -bool DataFlash_Backend::ShouldLog(bool is_critical) +bool AP_Logger_Backend::ShouldLog(bool is_critical) { if (!_front.WritesEnabled()) { return false; @@ -405,7 +405,7 @@ bool DataFlash_Backend::ShouldLog(bool is_critical) return true; } -bool DataFlash_Backend::Log_Write_MessageF(const char *fmt, ...) +bool AP_Logger_Backend::Log_Write_MessageF(const char *fmt, ...) { char msg[65] {}; // sizeof(log_Message.msg) + null-termination diff --git a/libraries/AP_Logger/AP_Logger_Backend.h b/libraries/AP_Logger/AP_Logger_Backend.h index fd30816e86..8b0dfc4fa0 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.h +++ b/libraries/AP_Logger/AP_Logger_Backend.h @@ -1,17 +1,17 @@ #pragma once -#include "DataFlash.h" +#include "AP_Logger.h" -class DFMessageWriter_DFLogStart; +class LoggerMessageWriter_DFLogStart; -class DataFlash_Backend +class AP_Logger_Backend { public: FUNCTOR_TYPEDEF(vehicle_startup_message_Log_Writer, void); - DataFlash_Backend(DataFlash_Class &front, - class DFMessageWriter_DFLogStart *writer); + AP_Logger_Backend(AP_Logger &front, + class LoggerMessageWriter_DFLogStart *writer); vehicle_startup_message_Log_Writer vehicle_message_writer(); @@ -56,7 +56,7 @@ public: /* stop logging - close output files etc etc. * * note that this doesn't stop logging from starting up again - * immediately - e.g. DataFlash_MAVLink might get another start + * immediately - e.g. AP_Logger_MAVLink might get another start * packet from a client. */ virtual void stop_logging(void) = 0; @@ -65,7 +65,7 @@ public: void Log_Fill_Format_Units(const struct LogStructure *s, struct log_Format_Units &pkt); #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX - // currently only DataFlash_File support this: + // currently only AP_Logger_File support this: virtual void flush(void) { } #endif @@ -125,7 +125,7 @@ public: protected: - DataFlash_Class &_front; + AP_Logger &_front; virtual void periodic_10Hz(const uint32_t now); virtual void periodic_1Hz(); @@ -142,7 +142,7 @@ protected: virtual void WriteMoreStartupMessages(); virtual void push_log_blocks(); - DFMessageWriter_DFLogStart *_startup_messagewriter; + LoggerMessageWriter_DFLogStart *_startup_messagewriter; bool _writing_startup_messages; uint8_t _internal_errors; diff --git a/libraries/AP_Logger/AP_Logger_File.cpp b/libraries/AP_Logger/AP_Logger_File.cpp index 60f6e0c27d..6304368d11 100644 --- a/libraries/AP_Logger/AP_Logger_File.cpp +++ b/libraries/AP_Logger/AP_Logger_File.cpp @@ -1,5 +1,5 @@ /* - DataFlash logging - file oriented variant + AP_Logger logging - file oriented variant This uses posix file IO to create log files called logs/NN.bin in the given directory @@ -13,7 +13,7 @@ #include #if HAL_OS_POSIX_IO || HAL_OS_FATFS_IO -#include "DataFlash_File.h" +#include "AP_Logger_File.h" #include @@ -52,10 +52,10 @@ extern const AP_HAL::HAL& hal; /* constructor */ -DataFlash_File::DataFlash_File(DataFlash_Class &front, - DFMessageWriter_DFLogStart *writer, +AP_Logger_File::AP_Logger_File(AP_Logger &front, + LoggerMessageWriter_DFLogStart *writer, const char *log_directory) : - DataFlash_Backend(front, writer), + AP_Logger_Backend(front, writer), _write_fd(-1), _read_fd(-1), _log_directory(log_directory), @@ -91,9 +91,9 @@ DataFlash_File::DataFlash_File(DataFlash_Class &front, } -void DataFlash_File::Init() +void AP_Logger_File::Init() { - DataFlash_Backend::Init(); + AP_Logger_Backend::Init(); // create the log directory if need be int ret; struct stat st; @@ -120,7 +120,7 @@ void DataFlash_File::Init() // If we can't allocate the full size, try to reduce it until we can allocate it while (!_writebuf.set_size(bufsize) && bufsize >= _writebuf_chunk) { - hal.console->printf("DataFlash_File: Couldn't set buffer size to=%u\n", (unsigned)bufsize); + hal.console->printf("AP_Logger_File: Couldn't set buffer size to=%u\n", (unsigned)bufsize); bufsize >>= 1; } @@ -129,13 +129,13 @@ void DataFlash_File::Init() return; } - hal.console->printf("DataFlash_File: buffer size=%u\n", (unsigned)bufsize); + hal.console->printf("AP_Logger_File: buffer size=%u\n", (unsigned)bufsize); _initialised = true; - hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&DataFlash_File::_io_timer, void)); + hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Logger_File::_io_timer, void)); } -bool DataFlash_File::file_exists(const char *filename) const +bool AP_Logger_File::file_exists(const char *filename) const { struct stat st; if (stat(filename, &st) == -1) { @@ -146,7 +146,7 @@ bool DataFlash_File::file_exists(const char *filename) const return true; } -bool DataFlash_File::log_exists(const uint16_t lognum) const +bool AP_Logger_File::log_exists(const uint16_t lognum) const { char *filename = _log_file_name(lognum); if (filename == nullptr) { @@ -157,13 +157,13 @@ bool DataFlash_File::log_exists(const uint16_t lognum) const return ret; } -void DataFlash_File::periodic_1Hz() +void AP_Logger_File::periodic_1Hz() { if (!io_thread_alive()) { if (io_thread_warning_decimation_counter == 0 && _initialised) { // we don't print this error unless we did initialise. When _initialised is set to true // we register the IO timer callback - gcs().send_text(MAV_SEVERITY_CRITICAL, "DataFlash: stuck thread (%s)", last_io_operation); + gcs().send_text(MAV_SEVERITY_CRITICAL, "AP_Logger: stuck thread (%s)", last_io_operation); } if (io_thread_warning_decimation_counter++ > 57) { io_thread_warning_decimation_counter = 0; @@ -180,12 +180,12 @@ void DataFlash_File::periodic_1Hz() df_stats_log(); } -void DataFlash_File::periodic_fullrate() +void AP_Logger_File::periodic_fullrate() { - DataFlash_Backend::push_log_blocks(); + AP_Logger_Backend::push_log_blocks(); } -uint32_t DataFlash_File::bufferspace_available() +uint32_t AP_Logger_File::bufferspace_available() { const uint32_t space = _writebuf.space(); const uint32_t crit = critical_message_reserved_space(); @@ -194,14 +194,14 @@ uint32_t DataFlash_File::bufferspace_available() } // return true for CardInserted() if we successfully initialized -bool DataFlash_File::CardInserted(void) const +bool AP_Logger_File::CardInserted(void) const { return _initialised && !_open_error; } // returns the amount of disk space available in _log_directory (in bytes) // returns -1 on error -int64_t DataFlash_File::disk_space_avail() +int64_t AP_Logger_File::disk_space_avail() { #if HAL_OS_POSIX_IO struct statfs _stats; @@ -220,7 +220,7 @@ int64_t DataFlash_File::disk_space_avail() // returns the total amount of disk space (in use + available) in // _log_directory (in bytes). // returns -1 on error -int64_t DataFlash_File::disk_space() +int64_t AP_Logger_File::disk_space() { #if HAL_OS_POSIX_IO struct statfs _stats; @@ -238,7 +238,7 @@ int64_t DataFlash_File::disk_space() // returns the available space in _log_directory as a percentage // returns -1.0f on error -float DataFlash_File::avail_space_percent() +float AP_Logger_File::avail_space_percent() { int64_t avail = disk_space_avail(); if (avail == -1) { @@ -254,7 +254,7 @@ float DataFlash_File::avail_space_percent() // find_oldest_log - find oldest log in _log_directory // returns 0 if no log was found -uint16_t DataFlash_File::find_oldest_log() +uint16_t AP_Logger_File::find_oldest_log() { if (_cached_oldest_log != 0) { return _cached_oldest_log; @@ -317,7 +317,7 @@ uint16_t DataFlash_File::find_oldest_log() return current_oldest_log; } -void DataFlash_File::Prep_MinSpace() +void AP_Logger_File::Prep_MinSpace() { const uint16_t first_log_to_remove = find_oldest_log(); if (first_log_to_remove == 0) { @@ -374,7 +374,7 @@ void DataFlash_File::Prep_MinSpace() } while (log_to_remove != first_log_to_remove); } -void DataFlash_File::Prep() { +void AP_Logger_File::Prep() { if (!NeedPrep()) { return; } @@ -385,7 +385,7 @@ void DataFlash_File::Prep() { Prep_MinSpace(); } -bool DataFlash_File::NeedPrep() +bool AP_Logger_File::NeedPrep() { if (!CardInserted()) { // should not have been called?! @@ -404,7 +404,7 @@ bool DataFlash_File::NeedPrep() The number in the log filename will *not* be zero-padded. Note: Caller must free. */ -char *DataFlash_File::_log_file_name_short(const uint16_t log_num) const +char *AP_Logger_File::_log_file_name_short(const uint16_t log_num) const { char *buf = nullptr; if (asprintf(&buf, "%s/%u.BIN", _log_directory, (unsigned)log_num) == -1) { @@ -418,7 +418,7 @@ char *DataFlash_File::_log_file_name_short(const uint16_t log_num) const The number in the log filename will be zero-padded. Note: Caller must free. */ -char *DataFlash_File::_log_file_name_long(const uint16_t log_num) const +char *AP_Logger_File::_log_file_name_long(const uint16_t log_num) const { char *buf = nullptr; if (asprintf(&buf, "%s/%08u.BIN", _log_directory, (unsigned)log_num) == -1) { @@ -433,7 +433,7 @@ char *DataFlash_File::_log_file_name_long(const uint16_t log_num) const appropirate name, otherwise the long (zero-padded) version is. Note: Caller must free. */ -char *DataFlash_File::_log_file_name(const uint16_t log_num) const +char *AP_Logger_File::_log_file_name(const uint16_t log_num) const { char *filename = _log_file_name_short(log_num); if (filename == nullptr) { @@ -450,7 +450,7 @@ char *DataFlash_File::_log_file_name(const uint16_t log_num) const return path name of the lastlog.txt marker file Note: Caller must free. */ -char *DataFlash_File::_lastlog_file_name(void) const +char *AP_Logger_File::_lastlog_file_name(void) const { char *buf = nullptr; if (asprintf(&buf, "%s/LASTLOG.TXT", _log_directory) == -1) { @@ -461,7 +461,7 @@ char *DataFlash_File::_lastlog_file_name(void) const // remove all log files -void DataFlash_File::EraseAll() +void AP_Logger_File::EraseAll() { if (hal.util->get_soft_armed()) { // do not want to do any filesystem operations while we are e.g. flying @@ -495,7 +495,7 @@ void DataFlash_File::EraseAll() } } -bool DataFlash_File::WritesOK() const +bool AP_Logger_File::WritesOK() const { if (_write_fd == -1) { return false; @@ -507,16 +507,16 @@ bool DataFlash_File::WritesOK() const } -bool DataFlash_File::StartNewLogOK() const +bool AP_Logger_File::StartNewLogOK() const { if (_open_error) { return false; } - return DataFlash_Backend::StartNewLogOK(); + return AP_Logger_Backend::StartNewLogOK(); } /* Write a block of data at current offset */ -bool DataFlash_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) +bool AP_Logger_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) { if (! WriteBlockCheckStartupMessages()) { _dropped++; @@ -570,7 +570,7 @@ bool DataFlash_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, /* find the highest log number */ -uint16_t DataFlash_File::find_last_log() +uint16_t AP_Logger_File::find_last_log() { unsigned ret = 0; char *fname = _lastlog_file_name(); @@ -594,7 +594,7 @@ uint16_t DataFlash_File::find_last_log() return ret; } -uint32_t DataFlash_File::_get_log_size(const uint16_t log_num) +uint32_t AP_Logger_File::_get_log_size(const uint16_t log_num) { char *fname = _log_file_name(log_num); if (fname == nullptr) { @@ -619,7 +619,7 @@ uint32_t DataFlash_File::_get_log_size(const uint16_t log_num) return st.st_size; } -uint32_t DataFlash_File::_get_log_time(const uint16_t log_num) +uint32_t AP_Logger_File::_get_log_time(const uint16_t log_num) { char *fname = _log_file_name(log_num); if (fname == nullptr) { @@ -654,7 +654,7 @@ uint32_t DataFlash_File::_get_log_time(const uint16_t log_num) and so on. Thus the highest list entry number is equal to the number of logs. */ -uint16_t DataFlash_File::_log_num_from_list_entry(const uint16_t list_entry) +uint16_t AP_Logger_File::_log_num_from_list_entry(const uint16_t list_entry) { uint16_t oldest_log = find_oldest_log(); if (oldest_log == 0) { @@ -672,7 +672,7 @@ uint16_t DataFlash_File::_log_num_from_list_entry(const uint16_t list_entry) /* find the number of pages in a log */ -void DataFlash_File::get_log_boundaries(const uint16_t list_entry, uint16_t & start_page, uint16_t & end_page) +void AP_Logger_File::get_log_boundaries(const uint16_t list_entry, uint16_t & start_page, uint16_t & end_page) { const uint16_t log_num = _log_num_from_list_entry(list_entry); if (log_num == 0) { @@ -689,7 +689,7 @@ void DataFlash_File::get_log_boundaries(const uint16_t list_entry, uint16_t & st /* retrieve data from a log file */ -int16_t DataFlash_File::get_log_data(const uint16_t list_entry, const uint16_t page, const uint32_t offset, const uint16_t len, uint8_t *data) +int16_t AP_Logger_File::get_log_data(const uint16_t list_entry, const uint16_t page, const uint32_t offset, const uint16_t len, uint8_t *data) { if (!_initialised || _open_error) { return -1; @@ -771,7 +771,7 @@ int16_t DataFlash_File::get_log_data(const uint16_t list_entry, const uint16_t p /* find size and date of a log */ -void DataFlash_File::get_log_info(const uint16_t list_entry, uint32_t &size, uint32_t &time_utc) +void AP_Logger_File::get_log_info(const uint16_t list_entry, uint32_t &size, uint32_t &time_utc) { uint16_t log_num = _log_num_from_list_entry(list_entry); if (log_num == 0) { @@ -790,7 +790,7 @@ void DataFlash_File::get_log_info(const uint16_t list_entry, uint32_t &size, uin /* get the number of logs - note that the log numbers must be consecutive */ -uint16_t DataFlash_File::get_num_logs() +uint16_t AP_Logger_File::get_num_logs() { uint16_t ret = 0; uint16_t high = find_last_log(); @@ -815,7 +815,7 @@ uint16_t DataFlash_File::get_num_logs() /* stop logging */ -void DataFlash_File::stop_logging(void) +void AP_Logger_File::stop_logging(void) { // best-case effort to avoid annoying the IO thread const bool have_sem = write_fd_semaphore.take(1); @@ -831,7 +831,7 @@ void DataFlash_File::stop_logging(void) } } -void DataFlash_File::PrepForArming() +void AP_Logger_File::PrepForArming() { if (logging_started()) { return; @@ -842,7 +842,7 @@ void DataFlash_File::PrepForArming() /* start writing to a new log file */ -uint16_t DataFlash_File::start_new_log(void) +uint16_t AP_Logger_File::start_new_log(void) { stop_logging(); @@ -943,7 +943,7 @@ uint16_t DataFlash_File::start_new_log(void) #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX -void DataFlash_File::flush(void) +void AP_Logger_File::flush(void) #if APM_BUILD_TYPE(APM_BUILD_Replay) || APM_BUILD_TYPE(APM_BUILD_UNKNOWN) { uint32_t tnow = AP_HAL::millis(); @@ -971,7 +971,7 @@ void DataFlash_File::flush(void) #endif // APM_BUILD_TYPE(APM_BUILD_Replay) || APM_BUILD_TYPE(APM_BUILD_UNKNOWN) #endif -void DataFlash_File::_io_timer(void) +void AP_Logger_File::_io_timer(void) { uint32_t tnow = AP_HAL::millis(); _io_timer_heartbeat = tnow; @@ -1066,7 +1066,7 @@ void DataFlash_File::_io_timer(void) } // this sensor is enabled if we should be logging at the moment -bool DataFlash_File::logging_enabled() const +bool AP_Logger_File::logging_enabled() const { if (hal.util->get_soft_armed() || _front.log_while_disarmed()) { @@ -1075,13 +1075,13 @@ bool DataFlash_File::logging_enabled() const return false; } -bool DataFlash_File::io_thread_alive() const +bool AP_Logger_File::io_thread_alive() const { // if the io thread hasn't had a heartbeat in a full second then it is dead return (AP_HAL::millis() - _io_timer_heartbeat) < 1000; } -bool DataFlash_File::logging_failed() const +bool AP_Logger_File::logging_failed() const { if (!_initialised) { return true; @@ -1099,7 +1099,7 @@ bool DataFlash_File::logging_failed() const } -void DataFlash_File::vehicle_was_disarmed() +void AP_Logger_File::vehicle_was_disarmed() { if (_front._params.file_disarm_rot) { // rotate our log. Closing the current one and letting the @@ -1109,7 +1109,7 @@ void DataFlash_File::vehicle_was_disarmed() } } -void DataFlash_File::Log_Write_DataFlash_Stats_File(const struct df_stats &_stats) +void AP_Logger_File::Log_Write_AP_Logger_Stats_File(const struct df_stats &_stats) { struct log_DSF pkt = { LOG_PACKET_HEADER_INIT(LOG_DF_FILE_STATS), @@ -1126,7 +1126,7 @@ void DataFlash_File::Log_Write_DataFlash_Stats_File(const struct df_stats &_stat WriteBlock(&pkt, sizeof(pkt)); } -void DataFlash_File::df_stats_gather(const uint16_t bytes_written) { +void AP_Logger_File::df_stats_gather(const uint16_t bytes_written) { const uint32_t space_remaining = _writebuf.space(); if (space_remaining < stats.buf_space_min) { stats.buf_space_min = space_remaining; @@ -1139,13 +1139,13 @@ void DataFlash_File::df_stats_gather(const uint16_t bytes_written) { stats.blocks++; } -void DataFlash_File::df_stats_clear() { +void AP_Logger_File::df_stats_clear() { memset(&stats, '\0', sizeof(stats)); stats.buf_space_min = -1; } -void DataFlash_File::df_stats_log() { - Log_Write_DataFlash_Stats_File(stats); +void AP_Logger_File::df_stats_log() { + Log_Write_AP_Logger_Stats_File(stats); df_stats_clear(); } diff --git a/libraries/AP_Logger/AP_Logger_File.h b/libraries/AP_Logger/AP_Logger_File.h index 87d1fe3309..9a3ec0f112 100644 --- a/libraries/AP_Logger/AP_Logger_File.h +++ b/libraries/AP_Logger/AP_Logger_File.h @@ -1,5 +1,5 @@ /* - DataFlash logging - file oriented variant + AP_Logger logging - file oriented variant This uses posix file IO to create log files called logNN.dat in the given directory @@ -9,14 +9,14 @@ #if HAL_OS_POSIX_IO || HAL_OS_FATFS_IO #include -#include "DataFlash_Backend.h" +#include "AP_Logger_Backend.h" -class DataFlash_File : public DataFlash_Backend +class AP_Logger_File : public AP_Logger_Backend { public: // constructor - DataFlash_File(DataFlash_Class &front, - DFMessageWriter_DFLogStart *, + AP_Logger_File(AP_Logger &front, + LoggerMessageWriter_DFLogStart *, const char *log_directory); // initialisation @@ -169,7 +169,7 @@ private: }; struct df_stats stats; - void Log_Write_DataFlash_Stats_File(const struct df_stats &_stats); + void Log_Write_AP_Logger_Stats_File(const struct df_stats &_stats); void df_stats_gather(uint16_t bytes_written); void df_stats_log(); void df_stats_clear(); diff --git a/libraries/AP_Logger/AP_Logger_File_sd.cpp b/libraries/AP_Logger/AP_Logger_File_sd.cpp index b11af43e45..37fec81bce 100644 --- a/libraries/AP_Logger/AP_Logger_File_sd.cpp +++ b/libraries/AP_Logger/AP_Logger_File_sd.cpp @@ -1,5 +1,5 @@ /* - DataFlash logging - file oriented variant + AP_Logger logging - file oriented variant This uses SD library to create log files called logs/NN.bin in the given directory @@ -15,7 +15,7 @@ #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT && (defined(BOARD_SDCARD_NAME) || defined(BOARD_DATAFLASH_FATFS)) -#include "DataFlash_File_sd.h" +#include "AP_Logger_File_sd.h" #include #include @@ -40,10 +40,10 @@ extern const AP_HAL::HAL& hal; /* constructor */ -DataFlash_File::DataFlash_File(DataFlash_Class &front, - DFMessageWriter_DFLogStart *writer, +AP_Logger_File::AP_Logger_File(AP_Logger &front, + LoggerMessageWriter_DFLogStart *writer, const char *log_directory) : - DataFlash_Backend(front, writer), + AP_Logger_Backend(front, writer), _write_fd(File()), _read_fd(File()), _log_directory(log_directory), @@ -52,9 +52,9 @@ DataFlash_File::DataFlash_File(DataFlash_Class &front, {} -void DataFlash_File::Init() +void AP_Logger_File::Init() { - DataFlash_Backend::Init(); + AP_Logger_Backend::Init(); if(HAL_F4Light::state.sd_busy) return; // SD mounted via USB @@ -92,7 +92,7 @@ void DataFlash_File::Init() // If we can't allocate the full size, try to reduce it until we can allocate it while (!_writebuf.set_size(bufsize) && bufsize >= _writebuf_chunk) { - printf("DataFlash_File: Couldn't set buffer size to=%u\n", (unsigned)bufsize); + printf("AP_Logger_File: Couldn't set buffer size to=%u\n", (unsigned)bufsize); bufsize /= 2; } @@ -101,18 +101,18 @@ void DataFlash_File::Init() return; } - printf("DataFlash_File: buffer size=%u\n", (unsigned)bufsize); + printf("AP_Logger_File: buffer size=%u\n", (unsigned)bufsize); _initialised = true; - hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&DataFlash_File::_io_timer, void)); + hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Logger_File::_io_timer, void)); } -bool DataFlash_File::file_exists(const char *filename) const +bool AP_Logger_File::file_exists(const char *filename) const { return SD.exists(filename); } -bool DataFlash_File::log_exists(const uint16_t lognum) const +bool AP_Logger_File::log_exists(const uint16_t lognum) const { char *filename = _log_file_name(lognum); if (filename == nullptr) { @@ -124,7 +124,7 @@ bool DataFlash_File::log_exists(const uint16_t lognum) const return ret; } -void DataFlash_File::periodic_1Hz() +void AP_Logger_File::periodic_1Hz() { if (!(_write_fd) || !_initialised || _open_error || _busy) return; // too early @@ -141,12 +141,12 @@ void DataFlash_File::periodic_1Hz() } } -void DataFlash_File::periodic_fullrate() +void AP_Logger_File::periodic_fullrate() { - DataFlash_Backend::push_log_blocks(); + AP_Logger_Backend::push_log_blocks(); } -uint32_t DataFlash_File::bufferspace_available() +uint32_t AP_Logger_File::bufferspace_available() { const uint32_t space = _writebuf.space(); const uint32_t crit = critical_message_reserved_space(); @@ -155,14 +155,14 @@ uint32_t DataFlash_File::bufferspace_available() } // return true for CardInserted() if we successfully initialized -bool DataFlash_File::CardInserted(void) const +bool AP_Logger_File::CardInserted(void) const { return _initialised && !_open_error && !HAL_F4Light::state.sd_busy; } // returns the available space in _log_directory as a percentage // returns -1.0f on error -float DataFlash_File::avail_space_percent(uint32_t *free) +float AP_Logger_File::avail_space_percent(uint32_t *free) { uint32_t space; @@ -179,7 +179,7 @@ float DataFlash_File::avail_space_percent(uint32_t *free) // find_oldest_log - find oldest log in _log_directory // returns 0 if no log was found -uint16_t DataFlash_File::find_oldest_log() +uint16_t AP_Logger_File::find_oldest_log() { if (_cached_oldest_log != 0) { return _cached_oldest_log; @@ -253,7 +253,7 @@ uint16_t DataFlash_File::find_oldest_log() #else // result cached later -uint16_t DataFlash_File::find_oldest_log() +uint16_t AP_Logger_File::find_oldest_log() { if (_cached_oldest_log != 0) { @@ -274,7 +274,7 @@ uint16_t DataFlash_File::find_oldest_log() #endif -void DataFlash_File::Prep_MinSpace() +void AP_Logger_File::Prep_MinSpace() { const uint16_t first_log_to_remove = find_oldest_log(); if (first_log_to_remove != 0) { @@ -342,7 +342,7 @@ void DataFlash_File::Prep_MinSpace() } -void DataFlash_File::Prep() { +void AP_Logger_File::Prep() { if (hal.util->get_soft_armed()) { // do not want to do any filesystem operations while we are e.g. flying return; @@ -350,7 +350,7 @@ void DataFlash_File::Prep() { Prep_MinSpace(); } -bool DataFlash_File::NeedPrep() +bool AP_Logger_File::NeedPrep() { if (!CardInserted()) { // should not have been called?! @@ -368,7 +368,7 @@ bool DataFlash_File::NeedPrep() construct a log file name given a log number. Note: Caller must free. */ -char *DataFlash_File::_log_file_name(const uint16_t log_num) const +char *AP_Logger_File::_log_file_name(const uint16_t log_num) const { char *buf = (char *)malloc(256); if(!buf) return nullptr; @@ -382,7 +382,7 @@ char *DataFlash_File::_log_file_name(const uint16_t log_num) const return path name of the lastlog.txt marker file Note: Caller must free. */ -char *DataFlash_File::_lastlog_file_name(void) const +char *AP_Logger_File::_lastlog_file_name(void) const { char *buf = (char *)malloc(256); if(!buf) return nullptr; @@ -393,7 +393,7 @@ char *DataFlash_File::_lastlog_file_name(void) const // remove all log files -void DataFlash_File::EraseAll() +void AP_Logger_File::EraseAll() { uint16_t log_num; const bool was_logging = (_write_fd != -1); @@ -421,7 +421,7 @@ void DataFlash_File::EraseAll() } -bool DataFlash_File::WritesOK() const +bool AP_Logger_File::WritesOK() const { if (!_write_fd) { return false; @@ -433,17 +433,17 @@ bool DataFlash_File::WritesOK() const } -bool DataFlash_File::StartNewLogOK() const +bool AP_Logger_File::StartNewLogOK() const { if (_open_error) { return false; } - return DataFlash_Backend::StartNewLogOK(); + return AP_Logger_Backend::StartNewLogOK(); } /* Write a block of data at current offset */ -bool DataFlash_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) +bool AP_Logger_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) { if (! WriteBlockCheckStartupMessages()) { _dropped++; @@ -497,7 +497,7 @@ bool DataFlash_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, /* find the highest log number */ -uint16_t DataFlash_File::find_last_log() +uint16_t AP_Logger_File::find_last_log() { unsigned ret = 0; char *fname = _lastlog_file_name(); @@ -518,7 +518,7 @@ uint16_t DataFlash_File::find_last_log() return ret; } -uint32_t DataFlash_File::_get_log_size(const uint16_t log_num) const +uint32_t AP_Logger_File::_get_log_size(const uint16_t log_num) const { char *fname = _log_file_name(log_num); if (fname == nullptr) { @@ -536,7 +536,7 @@ uint32_t DataFlash_File::_get_log_size(const uint16_t log_num) const return sz; } -uint32_t DataFlash_File::_get_log_time(const uint16_t log_num) const +uint32_t AP_Logger_File::_get_log_time(const uint16_t log_num) const { char *fname = _log_file_name(log_num); if (fname == nullptr) { @@ -576,7 +576,7 @@ uint32_t DataFlash_File::_get_log_time(const uint16_t log_num) const and so on. Thus the highest list entry number is equal to the number of logs. */ -uint16_t DataFlash_File::_log_num_from_list_entry(const uint16_t list_entry) +uint16_t AP_Logger_File::_log_num_from_list_entry(const uint16_t list_entry) { uint16_t oldest_log = find_oldest_log(); if (oldest_log == 0) { @@ -603,7 +603,7 @@ uint16_t DataFlash_File::_log_num_from_list_entry(const uint16_t list_entry) /* find the number of pages in a log */ -void DataFlash_File::get_log_boundaries(const uint16_t list_entry, uint16_t & start_page, uint16_t & end_page) +void AP_Logger_File::get_log_boundaries(const uint16_t list_entry, uint16_t & start_page, uint16_t & end_page) { const uint16_t log_num = _log_num_from_list_entry(list_entry); //if (log_num == 0) { @@ -621,7 +621,7 @@ void DataFlash_File::get_log_boundaries(const uint16_t list_entry, uint16_t & st /* retrieve data from a log file */ -int16_t DataFlash_File::get_log_data(const uint16_t list_entry, const uint16_t page, const uint32_t offset, const uint16_t len, uint8_t *data) +int16_t AP_Logger_File::get_log_data(const uint16_t list_entry, const uint16_t page, const uint32_t offset, const uint16_t len, uint8_t *data) { if (!_initialised || _open_error) { return -1; @@ -665,7 +665,7 @@ int16_t DataFlash_File::get_log_data(const uint16_t list_entry, const uint16_t p /* find size and date of a log */ -void DataFlash_File::get_log_info(const uint16_t list_entry, uint32_t &size, uint32_t &time_utc) +void AP_Logger_File::get_log_info(const uint16_t list_entry, uint32_t &size, uint32_t &time_utc) { uint16_t log_num = _log_num_from_list_entry(list_entry); // if (log_num == 0) { @@ -686,7 +686,7 @@ void DataFlash_File::get_log_info(const uint16_t list_entry, uint32_t &size, uin /* get the number of logs [no more - note that the log numbers must be consecutive ] */ -uint16_t DataFlash_File::get_num_logs() +uint16_t AP_Logger_File::get_num_logs() { uint16_t ret = 0; uint16_t high = find_last_log(); @@ -714,7 +714,7 @@ uint16_t DataFlash_File::get_num_logs() /* stop logging */ -void DataFlash_File::stop_logging(void) +void AP_Logger_File::stop_logging(void) { if (_write_fd) { _write_fd.close(); @@ -722,7 +722,7 @@ void DataFlash_File::stop_logging(void) } -void DataFlash_File::PrepForArming() +void AP_Logger_File::PrepForArming() { if (logging_started()) { return; @@ -733,7 +733,7 @@ void DataFlash_File::PrepForArming() /* start writing to a new log file */ -uint16_t DataFlash_File::start_new_log(void) +uint16_t AP_Logger_File::start_new_log(void) { stop_logging(); @@ -826,7 +826,7 @@ uint16_t DataFlash_File::start_new_log(void) return log_num; } -void DataFlash_File::_io_timer(void) +void AP_Logger_File::_io_timer(void) { uint32_t tnow = AP_HAL::millis(); _io_timer_heartbeat = tnow; @@ -876,7 +876,7 @@ void DataFlash_File::_io_timer(void) _write_fd.close(); #if defined(BOARD_DATAFLASH_FATFS) if(FR_INT_ERR == err || FR_NO_FILESYSTEM == err) { // internal error - bad filesystem - gcs().send_text(MAV_SEVERITY_INFO, "Formatting DataFlash, please wait"); + gcs().send_text(MAV_SEVERITY_INFO, "Formatting AP_Logger, please wait"); uint32_t t=AP_HAL::millis(); _busy = true; // format requires a long time and 1s task will kill process SD.format(_log_directory); @@ -945,7 +945,7 @@ void DataFlash_File::_io_timer(void) } // this sensor is enabled if we should be logging at the moment -bool DataFlash_File::logging_enabled() const +bool AP_Logger_File::logging_enabled() const { if (hal.util->get_soft_armed() || _front.log_while_disarmed()) { @@ -954,7 +954,7 @@ bool DataFlash_File::logging_enabled() const return false; } -bool DataFlash_File::io_thread_alive() const +bool AP_Logger_File::io_thread_alive() const { uint32_t tnow = AP_HAL::millis(); // if the io thread hasn't had a heartbeat in a 5 second then it is dead @@ -963,7 +963,7 @@ bool DataFlash_File::io_thread_alive() const return false; } -bool DataFlash_File::logging_failed() const +bool AP_Logger_File::logging_failed() const { bool op=false; @@ -986,7 +986,7 @@ bool DataFlash_File::logging_failed() const } -void DataFlash_File::vehicle_was_disarmed() +void AP_Logger_File::vehicle_was_disarmed() { if (_front._params.file_disarm_rot) { // rotate our log. Closing the current one and letting the @@ -1010,7 +1010,7 @@ const uint16_t mos[] = {0, 31, 59, 90, 120, 151, 181, 212, 243, 273, 304, 33 #define Daysto32(year, mon) (((year - 1) / 4) + MONTAB(year)[mon]) -uint32_t DataFlash_File::to_timestamp(const struct tm *t) +uint32_t AP_Logger_File::to_timestamp(const struct tm *t) { /* convert time structure to scalar time */ int32_t days; uint32_t secs; diff --git a/libraries/AP_Logger/AP_Logger_File_sd.h b/libraries/AP_Logger/AP_Logger_File_sd.h index b020f70a93..08bf234e43 100644 --- a/libraries/AP_Logger/AP_Logger_File_sd.h +++ b/libraries/AP_Logger/AP_Logger_File_sd.h @@ -1,5 +1,5 @@ /* - DataFlash logging - file oriented variant + AP_Logger logging - file oriented variant This uses posix file IO to create log files called logNN.dat in the given directory @@ -11,16 +11,16 @@ #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT && (defined(BOARD_SDCARD_NAME) || defined(BOARD_DATAFLASH_FATFS)) #include -#include "DataFlash_Backend.h" +#include "AP_Logger_Backend.h" #include -class DataFlash_File : public DataFlash_Backend +class AP_Logger_File : public AP_Logger_Backend { public: // constructor - DataFlash_File(DataFlash_Class &front, - DFMessageWriter_DFLogStart *, + AP_Logger_File(AP_Logger &front, + LoggerMessageWriter_DFLogStart *, const char *log_directory); // initialisation diff --git a/libraries/AP_Logger/AP_Logger_MAVLink.cpp b/libraries/AP_Logger/AP_Logger_MAVLink.cpp index 810b793f2e..6913580d57 100644 --- a/libraries/AP_Logger/AP_Logger_MAVLink.cpp +++ b/libraries/AP_Logger/AP_Logger_MAVLink.cpp @@ -1,8 +1,8 @@ /* - DataFlash Remote(via MAVLink) logging + AP_Logger Remote(via MAVLink) logging */ -#include "DataFlash_MAVLink.h" +#include "AP_Logger_MAVLink.h" #if DATAFLASH_MAVLINK_SUPPORT @@ -23,9 +23,9 @@ extern const AP_HAL::HAL& hal; // initialisation -void DataFlash_MAVLink::Init() +void AP_Logger_MAVLink::Init() { - DataFlash_Backend::Init(); + AP_Logger_Backend::Init(); _blocks = nullptr; while (_blockcount >= 8) { // 8 is a *magic* number @@ -46,21 +46,21 @@ void DataFlash_MAVLink::Init() _initialised = true; } -bool DataFlash_MAVLink::logging_failed() const +bool AP_Logger_MAVLink::logging_failed() const { return !_sending_to_client; } -uint32_t DataFlash_MAVLink::bufferspace_available() { +uint32_t AP_Logger_MAVLink::bufferspace_available() { return (_blockcount_free * 200 + remaining_space_in_current_block()); } -uint8_t DataFlash_MAVLink::remaining_space_in_current_block() { +uint8_t AP_Logger_MAVLink::remaining_space_in_current_block() { // note that _current_block *could* be NULL ATM. return (MAVLINK_MSG_REMOTE_LOG_DATA_BLOCK_FIELD_DATA_LEN - _latest_block_len); } -void DataFlash_MAVLink::enqueue_block(dm_block_queue_t &queue, struct dm_block *block) +void AP_Logger_MAVLink::enqueue_block(dm_block_queue_t &queue, struct dm_block *block) { if (queue.youngest != nullptr) { queue.youngest->next = block; @@ -70,7 +70,7 @@ void DataFlash_MAVLink::enqueue_block(dm_block_queue_t &queue, struct dm_block * queue.youngest = block; } -struct DataFlash_MAVLink::dm_block *DataFlash_MAVLink::dequeue_seqno(DataFlash_MAVLink::dm_block_queue_t &queue, uint32_t seqno) +struct AP_Logger_MAVLink::dm_block *AP_Logger_MAVLink::dequeue_seqno(AP_Logger_MAVLink::dm_block_queue_t &queue, uint32_t seqno) { struct dm_block *prev = nullptr; for (struct dm_block *block=queue.oldest; block != nullptr; block=block->next) { @@ -96,7 +96,7 @@ struct DataFlash_MAVLink::dm_block *DataFlash_MAVLink::dequeue_seqno(DataFlash_M return nullptr; } -bool DataFlash_MAVLink::free_seqno_from_queue(uint32_t seqno, dm_block_queue_t &queue) +bool AP_Logger_MAVLink::free_seqno_from_queue(uint32_t seqno, dm_block_queue_t &queue) { struct dm_block *block = dequeue_seqno(queue, seqno); if (block != nullptr) { @@ -109,7 +109,7 @@ bool DataFlash_MAVLink::free_seqno_from_queue(uint32_t seqno, dm_block_queue_t & } -bool DataFlash_MAVLink::WritesOK() const +bool AP_Logger_MAVLink::WritesOK() const { if (!_sending_to_client) { return false; @@ -120,7 +120,7 @@ bool DataFlash_MAVLink::WritesOK() const /* Write a block of data at current offset */ // DM_write: 70734 events, 0 overruns, 167806us elapsed, 2us avg, min 1us max 34us 0.620us rms -bool DataFlash_MAVLink::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) +bool AP_Logger_MAVLink::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) { if (!semaphore.take_nonblocking()) { _dropped++; @@ -172,9 +172,9 @@ bool DataFlash_MAVLink::_WritePrioritisedBlock(const void *pBuffer, uint16_t siz } //Get a free block -struct DataFlash_MAVLink::dm_block *DataFlash_MAVLink::next_block() +struct AP_Logger_MAVLink::dm_block *AP_Logger_MAVLink::next_block() { - DataFlash_MAVLink::dm_block *ret = _blocks_free; + AP_Logger_MAVLink::dm_block *ret = _blocks_free; if (ret != nullptr) { _blocks_free = ret->next; _blockcount_free--; @@ -186,7 +186,7 @@ struct DataFlash_MAVLink::dm_block *DataFlash_MAVLink::next_block() return ret; } -void DataFlash_MAVLink::free_all_blocks() +void AP_Logger_MAVLink::free_all_blocks() { _blocks_free = nullptr; _current_block = nullptr; @@ -213,7 +213,7 @@ void DataFlash_MAVLink::free_all_blocks() _latest_block_len = 0; } -void DataFlash_MAVLink::stop_logging() +void AP_Logger_MAVLink::stop_logging() { if (_sending_to_client) { _sending_to_client = false; @@ -221,7 +221,7 @@ void DataFlash_MAVLink::stop_logging() } } -void DataFlash_MAVLink::handle_ack(mavlink_channel_t chan, +void AP_Logger_MAVLink::handle_ack(mavlink_channel_t chan, mavlink_message_t* msg, uint32_t seqno) { @@ -267,7 +267,7 @@ void DataFlash_MAVLink::handle_ack(mavlink_channel_t chan, } } -void DataFlash_MAVLink::remote_log_block_status_msg(mavlink_channel_t chan, +void AP_Logger_MAVLink::remote_log_block_status_msg(mavlink_channel_t chan, mavlink_message_t* msg) { mavlink_remote_log_block_status_t packet; @@ -283,7 +283,7 @@ void DataFlash_MAVLink::remote_log_block_status_msg(mavlink_channel_t chan, semaphore.give(); } -void DataFlash_MAVLink::handle_retry(uint32_t seqno) +void AP_Logger_MAVLink::handle_retry(uint32_t seqno) { if (!_initialised || !_sending_to_client) { return; @@ -296,13 +296,13 @@ void DataFlash_MAVLink::handle_retry(uint32_t seqno) } } -void DataFlash_MAVLink::stats_init() { +void AP_Logger_MAVLink::stats_init() { _dropped = 0; _internal_errors = 0; stats.resends = 0; stats_reset(); } -void DataFlash_MAVLink::stats_reset() { +void AP_Logger_MAVLink::stats_reset() { stats.state_free = 0; stats.state_free_min = -1; // unsigned wrap stats.state_free_max = 0; @@ -318,7 +318,7 @@ void DataFlash_MAVLink::stats_reset() { stats.collection_count = 0; } -void DataFlash_MAVLink::Log_Write_DF_MAV(DataFlash_MAVLink &df) +void AP_Logger_MAVLink::Log_Write_DF_MAV(AP_Logger_MAVLink &df) { if (df.stats.collection_count == 0) { return; @@ -344,7 +344,7 @@ void DataFlash_MAVLink::Log_Write_DF_MAV(DataFlash_MAVLink &df) WriteBlock(&pkt,sizeof(pkt)); } -void DataFlash_MAVLink::stats_log() +void AP_Logger_MAVLink::stats_log() { if (!_initialised) { return; @@ -376,7 +376,7 @@ void DataFlash_MAVLink::stats_log() stats_reset(); } -uint8_t DataFlash_MAVLink::stack_size(struct dm_block *stack) +uint8_t AP_Logger_MAVLink::stack_size(struct dm_block *stack) { uint8_t ret = 0; for (struct dm_block *block=stack; block != nullptr; block=block->next) { @@ -384,12 +384,12 @@ uint8_t DataFlash_MAVLink::stack_size(struct dm_block *stack) } return ret; } -uint8_t DataFlash_MAVLink::queue_size(dm_block_queue_t queue) +uint8_t AP_Logger_MAVLink::queue_size(dm_block_queue_t queue) { return stack_size(queue.oldest); } -void DataFlash_MAVLink::stats_collect() +void AP_Logger_MAVLink::stats_collect() { if (!_initialised) { return; @@ -443,7 +443,7 @@ void DataFlash_MAVLink::stats_collect() /* while we "successfully" send log blocks from a queue, move them to * the sent list. DO NOT call this for blocks already sent! */ -bool DataFlash_MAVLink::send_log_blocks_from_queue(dm_block_queue_t &queue) +bool AP_Logger_MAVLink::send_log_blocks_from_queue(dm_block_queue_t &queue) { uint8_t sent_count = 0; while (queue.oldest != nullptr) { @@ -454,7 +454,7 @@ bool DataFlash_MAVLink::send_log_blocks_from_queue(dm_block_queue_t &queue) return false; } queue.sent_count++; - struct DataFlash_MAVLink::dm_block *tmp = dequeue_seqno(queue,queue.oldest->seqno); + struct AP_Logger_MAVLink::dm_block *tmp = dequeue_seqno(queue,queue.oldest->seqno); if (tmp != nullptr) { // should never be nullptr enqueue_block(_blocks_sent, tmp); } else { @@ -464,13 +464,13 @@ bool DataFlash_MAVLink::send_log_blocks_from_queue(dm_block_queue_t &queue) return true; } -void DataFlash_MAVLink::push_log_blocks() +void AP_Logger_MAVLink::push_log_blocks() { if (!_initialised || !_sending_to_client) { return; } - DataFlash_Backend::WriteMoreStartupMessages(); + AP_Logger_Backend::WriteMoreStartupMessages(); if (!semaphore.take_nonblocking()) { return; @@ -488,7 +488,7 @@ void DataFlash_MAVLink::push_log_blocks() semaphore.give(); } -void DataFlash_MAVLink::do_resends(uint32_t now) +void AP_Logger_MAVLink::do_resends(uint32_t now) { if (!_initialised || !_sending_to_client) { return; @@ -521,12 +521,12 @@ void DataFlash_MAVLink::do_resends(uint32_t now) // NOTE: any functions called from these periodic functions MUST // handle locking of the blocks structures by taking the semaphore // appropriately! -void DataFlash_MAVLink::periodic_10Hz(const uint32_t now) +void AP_Logger_MAVLink::periodic_10Hz(const uint32_t now) { do_resends(now); stats_collect(); } -void DataFlash_MAVLink::periodic_1Hz() +void AP_Logger_MAVLink::periodic_1Hz() { if (_sending_to_client && _last_response_time + 10000 < _last_send_time) { @@ -538,13 +538,13 @@ void DataFlash_MAVLink::periodic_1Hz() stats_log(); } -void DataFlash_MAVLink::periodic_fullrate() +void AP_Logger_MAVLink::periodic_fullrate() { push_log_blocks(); } //TODO: handle full txspace properly -bool DataFlash_MAVLink::send_log_block(struct dm_block &block) +bool AP_Logger_MAVLink::send_log_block(struct dm_block &block) { mavlink_channel_t chan = mavlink_channel_t(_chan - MAVLINK_COMM_0); if (!_initialised) { diff --git a/libraries/AP_Logger/AP_Logger_MAVLink.h b/libraries/AP_Logger/AP_Logger_MAVLink.h index 829729cdb2..95502466ed 100644 --- a/libraries/AP_Logger/AP_Logger_MAVLink.h +++ b/libraries/AP_Logger/AP_Logger_MAVLink.h @@ -1,5 +1,5 @@ /* - DataFlash logging - MAVLink variant + AP_Logger logging - MAVLink variant - transfers blocks of the open log file to a client using MAVLink */ @@ -11,18 +11,18 @@ #include -#include "DataFlash_Backend.h" +#include "AP_Logger_Backend.h" extern const AP_HAL::HAL& hal; #define DF_MAVLINK_DISABLE_INTERRUPTS 0 -class DataFlash_MAVLink : public DataFlash_Backend +class AP_Logger_MAVLink : public AP_Logger_Backend { public: // constructor - DataFlash_MAVLink(DataFlash_Class &front, DFMessageWriter_DFLogStart *writer) : - DataFlash_Backend(front, writer), + AP_Logger_MAVLink(AP_Logger &front, LoggerMessageWriter_DFLogStart *writer) : + AP_Logger_Backend(front, writer), _max_blocks_per_send_blocks(8) ,_perf_packing(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "DM_packing")) { @@ -144,7 +144,7 @@ private: uint8_t _next_block_number_to_resend; bool _sending_to_client; - void Log_Write_DF_MAV(DataFlash_MAVLink &df); + void Log_Write_DF_MAV(AP_Logger_MAVLink &df); uint32_t bufferspace_available() override; // in bytes uint8_t remaining_space_in_current_block(); diff --git a/libraries/AP_Logger/AP_Logger_MAVLinkLogTransfer.cpp b/libraries/AP_Logger/AP_Logger_MAVLinkLogTransfer.cpp index 0f186c3cf8..ff132111a5 100644 --- a/libraries/AP_Logger/AP_Logger_MAVLinkLogTransfer.cpp +++ b/libraries/AP_Logger/AP_Logger_MAVLinkLogTransfer.cpp @@ -19,13 +19,13 @@ #include -#include +#include #include // for LOG_ENTRY extern const AP_HAL::HAL& hal; // We avoid doing log messages when timing is critical: -bool DataFlash_Class::should_handle_log_message() +bool AP_Logger::should_handle_log_message() { if (!WritesEnabled()) { // this is currently used as a proxy for "in_mavlink_delay" @@ -40,7 +40,7 @@ bool DataFlash_Class::should_handle_log_message() /** handle all types of log download requests from the GCS */ -void DataFlash_Class::handle_log_message(GCS_MAVLINK &link, mavlink_message_t *msg) +void AP_Logger::handle_log_message(GCS_MAVLINK &link, mavlink_message_t *msg) { if (!should_handle_log_message()) { return; @@ -64,7 +64,7 @@ void DataFlash_Class::handle_log_message(GCS_MAVLINK &link, mavlink_message_t *m /** handle all types of log download requests from the GCS */ -void DataFlash_Class::handle_log_request_list(GCS_MAVLINK &link, mavlink_message_t *msg) +void AP_Logger::handle_log_request_list(GCS_MAVLINK &link, mavlink_message_t *msg) { if (_log_sending_link != nullptr) { link.send_text(MAV_SEVERITY_INFO, "Log download in progress"); @@ -100,7 +100,7 @@ void DataFlash_Class::handle_log_request_list(GCS_MAVLINK &link, mavlink_message /** handle request for log data */ -void DataFlash_Class::handle_log_request_data(GCS_MAVLINK &link, mavlink_message_t *msg) +void AP_Logger::handle_log_request_data(GCS_MAVLINK &link, mavlink_message_t *msg) { if (_log_sending_link != nullptr) { // some GCS (e.g. MAVProxy) attempt to stream request_data @@ -154,7 +154,7 @@ void DataFlash_Class::handle_log_request_data(GCS_MAVLINK &link, mavlink_message /** handle request to erase log data */ -void DataFlash_Class::handle_log_request_erase(GCS_MAVLINK &link, mavlink_message_t *msg) +void AP_Logger::handle_log_request_erase(GCS_MAVLINK &link, mavlink_message_t *msg) { // mavlink_log_erase_t packet; // mavlink_msg_log_erase_decode(msg, &packet); @@ -165,7 +165,7 @@ void DataFlash_Class::handle_log_request_erase(GCS_MAVLINK &link, mavlink_messag /** handle request to stop transfer and resume normal logging */ -void DataFlash_Class::handle_log_request_end(GCS_MAVLINK &link, mavlink_message_t *msg) +void AP_Logger::handle_log_request_end(GCS_MAVLINK &link, mavlink_message_t *msg) { mavlink_log_request_end_t packet; mavlink_msg_log_request_end_decode(msg, &packet); @@ -177,7 +177,7 @@ void DataFlash_Class::handle_log_request_end(GCS_MAVLINK &link, mavlink_message_ /** trigger sending of log messages if there are some pending */ -void DataFlash_Class::handle_log_send() +void AP_Logger::handle_log_send() { if (_log_sending_link == nullptr) { return; @@ -198,7 +198,7 @@ void DataFlash_Class::handle_log_send() } } -void DataFlash_Class::handle_log_sending() +void AP_Logger::handle_log_sending() { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL // assume USB speeds in SITL for the purposes of log download @@ -231,7 +231,7 @@ void DataFlash_Class::handle_log_sending() /** trigger sending of log messages if there are some pending */ -void DataFlash_Class::handle_log_send_listing() +void AP_Logger::handle_log_send_listing() { if (!HAVE_PAYLOAD_SPACE(_log_sending_link->get_chan(), LOG_ENTRY)) { // no space @@ -266,7 +266,7 @@ void DataFlash_Class::handle_log_send_listing() /** trigger sending of log data if there are some pending */ -bool DataFlash_Class::handle_log_send_data() +bool AP_Logger::handle_log_send_data() { if (!HAVE_PAYLOAD_SPACE(_log_sending_link->get_chan(), LOG_DATA)) { // no space diff --git a/libraries/AP_Logger/AP_Logger_Revo.cpp b/libraries/AP_Logger/AP_Logger_Revo.cpp index e080c1ad25..d2217b2443 100644 --- a/libraries/AP_Logger/AP_Logger_Revo.cpp +++ b/libraries/AP_Logger/AP_Logger_Revo.cpp @@ -1,5 +1,5 @@ /* - hacked up DataFlash library for Desktop support + hacked up AP_Logger library for Desktop support */ @@ -8,7 +8,7 @@ #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT && defined(BOARD_DATAFLASH_CS_PIN) && !defined(BOARD_DATAFLASH_FATFS) -#include "DataFlash_Revo.h" +#include "AP_Logger_Revo.h" #include @@ -30,25 +30,25 @@ extern const AP_HAL::HAL& hal; static uint8_t buffer[2][DF_PAGE_SIZE]; static uint8_t cmd[4]; -AP_HAL::OwnPtr DataFlash_Revo::_spi = nullptr; -AP_HAL::Semaphore *DataFlash_Revo::_spi_sem = nullptr; -bool DataFlash_Revo::log_write_started=false; -bool DataFlash_Revo::flash_died=false; +AP_HAL::OwnPtr AP_Logger_Revo::_spi = nullptr; +AP_HAL::Semaphore *AP_Logger_Revo::_spi_sem = nullptr; +bool AP_Logger_Revo::log_write_started=false; +bool AP_Logger_Revo::flash_died=false; // the last page holds the log format in first 4 bytes. Please change // this if (and only if!) the low level format changes #define DF_LOGGING_FORMAT 0x28122013L -uint32_t DataFlash_Revo::bufferspace_available() +uint32_t AP_Logger_Revo::bufferspace_available() { - // because DataFlash_Block devices are ring buffers, we *always* + // because AP_Logger_Block devices are ring buffers, we *always* // have room... return df_NumPages * df_PageSize; } // *** DATAFLASH PUBLIC FUNCTIONS *** -void DataFlash_Revo::StartWrite(uint16_t PageAdr) +void AP_Logger_Revo::StartWrite(uint16_t PageAdr) { df_BufferIdx = 0; df_BufferNum = 0; @@ -56,7 +56,7 @@ void DataFlash_Revo::StartWrite(uint16_t PageAdr) WaitReady(); } -void DataFlash_Revo::FinishWrite(void) +void AP_Logger_Revo::FinishWrite(void) { // Write Buffer to flash, NO WAIT BufferToPage(df_BufferNum, df_PageAdr, 0); @@ -81,7 +81,7 @@ void DataFlash_Revo::FinishWrite(void) df_BufferIdx = 0; } -bool DataFlash_Revo::WritesOK() const +bool AP_Logger_Revo::WritesOK() const { if (!CardInserted()) { return false; @@ -92,7 +92,7 @@ bool DataFlash_Revo::WritesOK() const return true; } -bool DataFlash_Revo::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, +bool AP_Logger_Revo::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) { // is_critical is ignored - we're a ring buffer and never run out @@ -140,18 +140,18 @@ bool DataFlash_Revo::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, // Get the last page written to -uint16_t DataFlash_Revo::GetWritePage() +uint16_t AP_Logger_Revo::GetWritePage() { return df_PageAdr; } // Get the last page read -uint16_t DataFlash_Revo::GetPage() +uint16_t AP_Logger_Revo::GetPage() { return df_Read_PageAdr; } -void DataFlash_Revo::StartRead(uint16_t PageAdr) +void AP_Logger_Revo::StartRead(uint16_t PageAdr) { df_Read_BufferNum = 0; df_Read_PageAdr = PageAdr; @@ -172,7 +172,7 @@ void DataFlash_Revo::StartRead(uint16_t PageAdr) df_Read_BufferIdx = sizeof(ph); } -bool DataFlash_Revo::ReadBlock(void *pBuffer, uint16_t size) +bool AP_Logger_Revo::ReadBlock(void *pBuffer, uint16_t size) { while (size > 0) { uint16_t n = df_PageSize - df_Read_BufferIdx; @@ -211,23 +211,23 @@ bool DataFlash_Revo::ReadBlock(void *pBuffer, uint16_t size) return true; } -void DataFlash_Revo::SetFileNumber(uint16_t FileNumber) +void AP_Logger_Revo::SetFileNumber(uint16_t FileNumber) { df_FileNumber = FileNumber; df_FilePage = 1; } -uint16_t DataFlash_Revo::GetFileNumber() +uint16_t AP_Logger_Revo::GetFileNumber() { return df_FileNumber; } -uint16_t DataFlash_Revo::GetFilePage() +uint16_t AP_Logger_Revo::GetFilePage() { return df_FilePage; } -void DataFlash_Revo::EraseAll() +void AP_Logger_Revo::EraseAll() { log_write_started = false; @@ -251,12 +251,12 @@ void DataFlash_Revo::EraseAll() //] } -bool DataFlash_Revo::NeedPrep(void) +bool AP_Logger_Revo::NeedPrep(void) { return NeedErase(); } -void DataFlash_Revo::Prep() +void AP_Logger_Revo::Prep() { if (hal.util->get_soft_armed()) { // do not want to do any filesystem operations while we are e.g. flying @@ -270,7 +270,7 @@ void DataFlash_Revo::Prep() /* * we need to erase if the logging format has changed */ -bool DataFlash_Revo::NeedErase(void) +bool AP_Logger_Revo::NeedErase(void) { uint32_t version = 0; StartRead(df_NumPages+1); // last page @@ -287,7 +287,7 @@ bool DataFlash_Revo::NeedErase(void) /** get raw data from a log */ -int16_t DataFlash_Revo::get_log_data_raw(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) +int16_t AP_Logger_Revo::get_log_data_raw(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) { uint16_t data_page_size = df_PageSize - sizeof(struct PageHeader); @@ -314,7 +314,7 @@ int16_t DataFlash_Revo::get_log_data_raw(uint16_t log_num, uint16_t page, uint32 /** get data from a log, accounting for adding FMT headers */ -int16_t DataFlash_Revo::get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) +int16_t AP_Logger_Revo::get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) { if (offset == 0) { uint8_t header[3]; @@ -354,7 +354,7 @@ int16_t DataFlash_Revo::get_log_data(uint16_t log_num, uint16_t page, uint32_t o // Public Methods ////////////////////////////////////////////////////////////// -void DataFlash_Revo::Init() +void AP_Logger_Revo::Init() { df_NumPages=0; @@ -376,13 +376,13 @@ void DataFlash_Revo::Init() _spi = hal.spi->get_device(HAL_DATAFLASH_NAME); if (!_spi) { - AP_HAL::panic("PANIC: DataFlash SPIDeviceDriver not found"); + AP_HAL::panic("PANIC: AP_Logger SPIDeviceDriver not found"); return; /* never reached */ } _spi_sem = _spi->get_semaphore(); if (!_spi_sem) { - AP_HAL::panic("PANIC: DataFlash SPIDeviceDriver semaphore is null"); + AP_HAL::panic("PANIC: AP_Logger SPIDeviceDriver semaphore is null"); return; /* never reached */ } @@ -391,7 +391,7 @@ void DataFlash_Revo::Init() WITH_SEMAPHORE(_spi_sem); _spi->set_speed(AP_HAL::Device::SPEED_LOW); - DataFlash_Backend::Init(); + AP_Logger_Backend::Init(); } df_NumPages = BOARD_DATAFLASH_PAGES - 1; // reserve last page for config information @@ -410,7 +410,7 @@ void DataFlash_Revo::Init() } -void DataFlash_Revo::WaitReady() { +void AP_Logger_Revo::WaitReady() { if(flash_died) return; uint32_t t = AP_HAL::millis(); @@ -426,7 +426,7 @@ void DataFlash_Revo::WaitReady() { } // try to take a semaphore safely from both in a timer and outside -bool DataFlash_Revo::_sem_take(uint8_t timeout) +bool AP_Logger_Revo::_sem_take(uint8_t timeout) { if(!_spi_sem || flash_died) return false; @@ -434,7 +434,7 @@ bool DataFlash_Revo::_sem_take(uint8_t timeout) return _spi_sem->take(timeout); } -bool DataFlash_Revo::cs_assert(){ +bool AP_Logger_Revo::cs_assert(){ if (!_sem_take(HAL_SEMAPHORE_BLOCK_FOREVER)) return false; @@ -444,7 +444,7 @@ bool DataFlash_Revo::cs_assert(){ return true; } -void DataFlash_Revo::cs_release(){ +void AP_Logger_Revo::cs_release(){ GPIO::_write(DF_RESET,1); _spi_sem->give(); @@ -452,7 +452,7 @@ void DataFlash_Revo::cs_release(){ // This function is mainly to test the device -void DataFlash_Revo::ReadManufacturerID() +void AP_Logger_Revo::ReadManufacturerID() { if (!cs_assert()) return; @@ -467,7 +467,7 @@ void DataFlash_Revo::ReadManufacturerID() cs_release(); } -bool DataFlash_Revo::getSectorCount(uint32_t *ptr){ +bool AP_Logger_Revo::getSectorCount(uint32_t *ptr){ uint8_t capacity = df_device & 0xFF; uint8_t memtype = (df_device>>8) & 0xFF; uint32_t size=0; @@ -546,7 +546,7 @@ bool DataFlash_Revo::getSectorCount(uint32_t *ptr){ } // Read the status register -uint8_t DataFlash_Revo::ReadStatusReg() +uint8_t AP_Logger_Revo::ReadStatusReg() { uint8_t tmp; @@ -569,7 +569,7 @@ uint8_t DataFlash_Revo::ReadStatusReg() return tmp; } -uint8_t DataFlash_Revo::ReadStatus() +uint8_t AP_Logger_Revo::ReadStatus() { // We only want to extract the READY/BUSY bit int32_t status = ReadStatusReg(); @@ -579,7 +579,7 @@ uint8_t DataFlash_Revo::ReadStatus() } -void DataFlash_Revo::PageToBuffer(unsigned char BufferNum, uint16_t pageNum) +void AP_Logger_Revo::PageToBuffer(unsigned char BufferNum, uint16_t pageNum) { uint32_t PageAdr = pageNum * DF_PAGE_SIZE; @@ -596,7 +596,7 @@ void DataFlash_Revo::PageToBuffer(unsigned char BufferNum, uint16_t pageNum) cs_release(); } -void DataFlash_Revo::BufferToPage (unsigned char BufferNum, uint16_t pageNum, unsigned char wait) +void AP_Logger_Revo::BufferToPage (unsigned char BufferNum, uint16_t pageNum, unsigned char wait) { uint32_t PageAdr = pageNum * DF_PAGE_SIZE; @@ -619,12 +619,12 @@ void DataFlash_Revo::BufferToPage (unsigned char BufferNum, uint16_t pageNum, un } -void DataFlash_Revo::BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data) +void AP_Logger_Revo::BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data) { buffer[BufferNum][IntPageAdr] = (uint8_t)Data; } -void DataFlash_Revo::BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr, +void AP_Logger_Revo::BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr, const void *pHeader, uint8_t hdr_size, const void *pBuffer, uint16_t size) { @@ -641,7 +641,7 @@ void DataFlash_Revo::BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr, // read size bytes of data to a page. The caller must ensure that // the data fits within the page, otherwise it will wrap to the // start of the page -bool DataFlash_Revo::BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size) +bool AP_Logger_Revo::BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size) { memcpy(pBuffer, &buffer[BufferNum][IntPageAdr], size); return true; @@ -655,7 +655,7 @@ bool DataFlash_Revo::BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBu */ -void DataFlash_Revo::PageErase (uint16_t pageNum) +void AP_Logger_Revo::PageErase (uint16_t pageNum) { uint32_t PageAdr = pageNum * DF_PAGE_SIZE; @@ -675,7 +675,7 @@ void DataFlash_Revo::PageErase (uint16_t pageNum) } -void DataFlash_Revo::ChipErase() +void AP_Logger_Revo::ChipErase() { cmd[0] = JEDEC_BULK_ERASE; @@ -690,7 +690,7 @@ void DataFlash_Revo::ChipErase() } -void DataFlash_Revo::Flash_Jedec_WriteEnable(void) +void AP_Logger_Revo::Flash_Jedec_WriteEnable(void) { // activate dataflash command decoder if (!cs_assert()) return; @@ -702,9 +702,9 @@ void DataFlash_Revo::Flash_Jedec_WriteEnable(void) ////////////////////////////////////////// -// This function determines the number of whole or partial log files in the DataFlash +// This function determines the number of whole or partial log files in the AP_Logger // Wholly overwritten files are (of course) lost. -uint16_t DataFlash_Revo::get_num_logs(void) +uint16_t AP_Logger_Revo::get_num_logs(void) { uint16_t lastpage; uint16_t last; @@ -740,8 +740,8 @@ uint16_t DataFlash_Revo::get_num_logs(void) } -// This function starts a new log file in the DataFlash -uint16_t DataFlash_Revo::start_new_log(void) +// This function starts a new log file in the AP_Logger +uint16_t AP_Logger_Revo::start_new_log(void) { uint16_t last_page = find_last_page(); @@ -780,8 +780,8 @@ uint16_t DataFlash_Revo::start_new_log(void) } // This function finds the first and last pages of a log file -// The first page may be greater than the last page if the DataFlash has been filled and partially overwritten. -void DataFlash_Revo::get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page) +// The first page may be greater than the last page if the AP_Logger has been filled and partially overwritten. +void AP_Logger_Revo::get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page) { uint16_t num = get_num_logs(); uint16_t look; @@ -834,7 +834,7 @@ void DataFlash_Revo::get_log_boundaries(uint16_t log_num, uint16_t & start_page, } -bool DataFlash_Revo::check_wrapped(void) +bool AP_Logger_Revo::check_wrapped(void) { StartRead(df_NumPages); if(GetFileNumber() == 0xFFFF) @@ -845,7 +845,7 @@ bool DataFlash_Revo::check_wrapped(void) // This funciton finds the last log number -uint16_t DataFlash_Revo::find_last_log(void) +uint16_t AP_Logger_Revo::find_last_log(void) { uint16_t last_page = find_last_page(); StartRead(last_page); @@ -853,7 +853,7 @@ uint16_t DataFlash_Revo::find_last_log(void) } // This function finds the last page of the last file -uint16_t DataFlash_Revo::find_last_page(void) +uint16_t AP_Logger_Revo::find_last_page(void) { uint16_t look; uint16_t bottom = 1; @@ -894,7 +894,7 @@ uint16_t DataFlash_Revo::find_last_page(void) } // This function finds the last page of a particular log file -uint16_t DataFlash_Revo::find_last_page_of_log(uint16_t log_number) +uint16_t AP_Logger_Revo::find_last_page_of_log(uint16_t log_number) { uint16_t look; uint16_t bottom; @@ -946,7 +946,7 @@ uint16_t DataFlash_Revo::find_last_page_of_log(uint16_t log_number) } -void DataFlash_Revo::get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) +void AP_Logger_Revo::get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) { uint16_t start, end; get_log_boundaries(log_num, start, end); diff --git a/libraries/AP_Logger/AP_Logger_Revo.h b/libraries/AP_Logger/AP_Logger_Revo.h index b5c84f70d3..05e9ab4843 100644 --- a/libraries/AP_Logger/AP_Logger_Revo.h +++ b/libraries/AP_Logger/AP_Logger_Revo.h @@ -1,12 +1,12 @@ /* ************************************************************ */ -/* DataFlash_Revo Log library */ +/* AP_Logger_Revo Log library */ /* ************************************************************ */ #pragma once #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT #include -#include "DataFlash_Backend.h" +#include "AP_Logger_Backend.h" #include #include @@ -43,7 +43,7 @@ using namespace F4Light; -class DataFlash_Revo : public DataFlash_Backend +class AP_Logger_Revo : public AP_Logger_Backend { private: //Methods @@ -97,7 +97,7 @@ private: uint16_t FilePage; }; - // DataFlash Log variables... + // AP_Logger Log variables... uint8_t df_BufferNum; uint8_t df_Read_BufferNum; uint16_t df_BufferIdx; @@ -150,8 +150,8 @@ protected: public: - DataFlash_Revo(DataFlash_Class &front, DFMessageWriter_DFLogStart *writer) : - DataFlash_Backend(front, writer) { } + AP_Logger_Revo(AP_Logger &front, LoggerMessageWriter_DFLogStart *writer) : + AP_Logger_Backend(front, writer) { } void Init() override; void ReadManufacturerID(); diff --git a/libraries/AP_Logger/LogFile.cpp b/libraries/AP_Logger/LogFile.cpp index b8a2e9cde6..6c50cfb9c5 100644 --- a/libraries/AP_Logger/LogFile.cpp +++ b/libraries/AP_Logger/LogFile.cpp @@ -12,13 +12,13 @@ #include #include -#include "DataFlash.h" -#include "DataFlash_File.h" -#include "DataFlash_File_sd.h" -#include "DataFlash_MAVLink.h" -#include "DataFlash_Revo.h" -#include "DataFlash_File_sd.h" -#include "DFMessageWriter.h" +#include "AP_Logger.h" +#include "AP_Logger_File.h" +#include "AP_Logger_File_sd.h" +#include "AP_Logger_MAVLink.h" +#include "AP_Logger_Revo.h" +#include "AP_Logger_File_sd.h" +#include "LoggerMessageWriter.h" extern const AP_HAL::HAL& hal; @@ -26,7 +26,7 @@ extern const AP_HAL::HAL& hal; /* write a structure format to the log - should be in frontend */ -void DataFlash_Backend::Log_Fill_Format(const struct LogStructure *s, struct log_Format &pkt) +void AP_Logger_Backend::Log_Fill_Format(const struct LogStructure *s, struct log_Format &pkt) { memset(&pkt, 0, sizeof(pkt)); pkt.head1 = HEAD_BYTE1; @@ -42,7 +42,7 @@ void DataFlash_Backend::Log_Fill_Format(const struct LogStructure *s, struct log /* Pack a LogStructure packet into a structure suitable to go to the logfile: */ -void DataFlash_Backend::Log_Fill_Format_Units(const struct LogStructure *s, struct log_Format_Units &pkt) +void AP_Logger_Backend::Log_Fill_Format_Units(const struct LogStructure *s, struct log_Format_Units &pkt) { memset(&pkt, 0, sizeof(pkt)); pkt.head1 = HEAD_BYTE1; @@ -57,7 +57,7 @@ void DataFlash_Backend::Log_Fill_Format_Units(const struct LogStructure *s, stru /* write a structure format to the log */ -bool DataFlash_Backend::Log_Write_Format(const struct LogStructure *s) +bool AP_Logger_Backend::Log_Write_Format(const struct LogStructure *s) { struct log_Format pkt; Log_Fill_Format(s, pkt); @@ -67,7 +67,7 @@ bool DataFlash_Backend::Log_Write_Format(const struct LogStructure *s) /* write a unit definition */ -bool DataFlash_Backend::Log_Write_Unit(const struct UnitStructure *s) +bool AP_Logger_Backend::Log_Write_Unit(const struct UnitStructure *s) { struct log_Unit pkt = { LOG_PACKET_HEADER_INIT(LOG_UNIT_MSG), @@ -83,7 +83,7 @@ bool DataFlash_Backend::Log_Write_Unit(const struct UnitStructure *s) /* write a unit-multiplier definition */ -bool DataFlash_Backend::Log_Write_Multiplier(const struct MultiplierStructure *s) +bool AP_Logger_Backend::Log_Write_Multiplier(const struct MultiplierStructure *s) { struct log_Format_Multiplier pkt = { LOG_PACKET_HEADER_INIT(LOG_MULT_MSG), @@ -98,7 +98,7 @@ bool DataFlash_Backend::Log_Write_Multiplier(const struct MultiplierStructure *s /* write the units for a format to the log */ -bool DataFlash_Backend::Log_Write_Format_Units(const struct LogStructure *s) +bool AP_Logger_Backend::Log_Write_Format_Units(const struct LogStructure *s) { struct log_Format_Units pkt; Log_Fill_Format_Units(s, pkt); @@ -108,7 +108,7 @@ bool DataFlash_Backend::Log_Write_Format_Units(const struct LogStructure *s) /* write a parameter to the log */ -bool DataFlash_Backend::Log_Write_Parameter(const char *name, float value) +bool AP_Logger_Backend::Log_Write_Parameter(const char *name, float value) { struct log_Parameter pkt = { LOG_PACKET_HEADER_INIT(LOG_PARAMETER_MSG), @@ -123,7 +123,7 @@ bool DataFlash_Backend::Log_Write_Parameter(const char *name, float value) /* write a parameter to the log */ -bool DataFlash_Backend::Log_Write_Parameter(const AP_Param *ap, +bool AP_Logger_Backend::Log_Write_Parameter(const AP_Param *ap, const AP_Param::ParamToken &token, enum ap_var_type type) { @@ -133,7 +133,7 @@ bool DataFlash_Backend::Log_Write_Parameter(const AP_Param *ap, } // Write an GPS packet -void DataFlash_Class::Log_Write_GPS(uint8_t i, uint64_t time_us) +void AP_Logger::Log_Write_GPS(uint8_t i, uint64_t time_us) { const AP_GPS &gps = AP::gps(); if (time_us == 0) { @@ -179,7 +179,7 @@ void DataFlash_Class::Log_Write_GPS(uint8_t i, uint64_t time_us) // Write an RFND (rangefinder) packet -void DataFlash_Class::Log_Write_RFND(const RangeFinder &rangefinder) +void AP_Logger::Log_Write_RFND(const RangeFinder &rangefinder) { AP_RangeFinder_Backend *s0 = rangefinder.get_backend(0); AP_RangeFinder_Backend *s1 = rangefinder.get_backend(1); @@ -198,7 +198,7 @@ void DataFlash_Class::Log_Write_RFND(const RangeFinder &rangefinder) } // Write an RCIN packet -void DataFlash_Class::Log_Write_RCIN(void) +void AP_Logger::Log_Write_RCIN(void) { uint16_t values[14] = {}; rc().get_radio_in(values, ARRAY_SIZE(values)); @@ -224,7 +224,7 @@ void DataFlash_Class::Log_Write_RCIN(void) } // Write an SERVO packet -void DataFlash_Class::Log_Write_RCOUT(void) +void AP_Logger::Log_Write_RCOUT(void) { struct log_RCOUT pkt = { LOG_PACKET_HEADER_INIT(LOG_RCOUT_MSG), @@ -249,7 +249,7 @@ void DataFlash_Class::Log_Write_RCOUT(void) } // Write an RSSI packet -void DataFlash_Class::Log_Write_RSSI(AP_RSSI &rssi) +void AP_Logger::Log_Write_RSSI(AP_RSSI &rssi) { struct log_RSSI pkt = { LOG_PACKET_HEADER_INIT(LOG_RSSI_MSG), @@ -259,7 +259,7 @@ void DataFlash_Class::Log_Write_RSSI(AP_RSSI &rssi) WriteBlock(&pkt, sizeof(pkt)); } -void DataFlash_Class::Log_Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type) +void AP_Logger::Log_Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type) { AP_Baro &baro = AP::baro(); float climbrate = baro.get_climb_rate(); @@ -280,7 +280,7 @@ void DataFlash_Class::Log_Write_Baro_instance(uint64_t time_us, uint8_t baro_ins } // Write a BARO packet -void DataFlash_Class::Log_Write_Baro(uint64_t time_us) +void AP_Logger::Log_Write_Baro(uint64_t time_us) { if (time_us == 0) { time_us = AP_HAL::micros64(); @@ -295,7 +295,7 @@ void DataFlash_Class::Log_Write_Baro(uint64_t time_us) } } -void DataFlash_Class::Log_Write_IMU_instance(const uint64_t time_us, const uint8_t imu_instance, const enum LogMessages type) +void AP_Logger::Log_Write_IMU_instance(const uint64_t time_us, const uint8_t imu_instance, const enum LogMessages type) { const AP_InertialSensor &ins = AP::ins(); const Vector3f &gyro = ins.get_gyro(imu_instance); @@ -321,7 +321,7 @@ void DataFlash_Class::Log_Write_IMU_instance(const uint64_t time_us, const uint8 } // Write an raw accel/gyro data packet -void DataFlash_Class::Log_Write_IMU() +void AP_Logger::Log_Write_IMU() { uint64_t time_us = AP_HAL::micros64(); @@ -342,7 +342,7 @@ void DataFlash_Class::Log_Write_IMU() } // Write an accel/gyro delta time data packet -void DataFlash_Class::Log_Write_IMUDT_instance(const uint64_t time_us, const uint8_t imu_instance, const enum LogMessages type) +void AP_Logger::Log_Write_IMUDT_instance(const uint64_t time_us, const uint8_t imu_instance, const enum LogMessages type) { const AP_InertialSensor &ins = AP::ins(); float delta_t = ins.get_delta_time(); @@ -368,7 +368,7 @@ void DataFlash_Class::Log_Write_IMUDT_instance(const uint64_t time_us, const uin WriteBlock(&pkt, sizeof(pkt)); } -void DataFlash_Class::Log_Write_IMUDT(uint64_t time_us, uint8_t imu_mask) +void AP_Logger::Log_Write_IMUDT(uint64_t time_us, uint8_t imu_mask) { const AP_InertialSensor &ins = AP::ins(); if (imu_mask & 1) { @@ -391,7 +391,7 @@ void DataFlash_Class::Log_Write_IMUDT(uint64_t time_us, uint8_t imu_mask) } } -void DataFlash_Class::Log_Write_Vibration() +void AP_Logger::Log_Write_Vibration() { uint64_t time_us = AP_HAL::micros64(); const AP_InertialSensor &ins = AP::ins(); @@ -409,7 +409,7 @@ void DataFlash_Class::Log_Write_Vibration() WriteBlock(&pkt, sizeof(pkt)); } -bool DataFlash_Backend::Log_Write_Mission_Cmd(const AP_Mission &mission, +bool AP_Logger_Backend::Log_Write_Mission_Cmd(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd) { mavlink_mission_item_int_t mav_cmd = {}; @@ -432,15 +432,15 @@ bool DataFlash_Backend::Log_Write_Mission_Cmd(const AP_Mission &mission, return WriteBlock(&pkt, sizeof(pkt)); } -void DataFlash_Backend::Log_Write_EntireMission(const AP_Mission &mission) +void AP_Logger_Backend::Log_Write_EntireMission(const AP_Mission &mission) { - DFMessageWriter_WriteEntireMission writer; + LoggerMessageWriter_WriteEntireMission writer; writer.set_dataflash_backend(this); writer.process(); } // Write a text message to the log -bool DataFlash_Backend::Log_Write_Message(const char *message) +bool AP_Logger_Backend::Log_Write_Message(const char *message) { struct log_Message pkt = { LOG_PACKET_HEADER_INIT(LOG_MESSAGE_MSG), @@ -451,7 +451,7 @@ bool DataFlash_Backend::Log_Write_Message(const char *message) return WriteCriticalBlock(&pkt, sizeof(pkt)); } -void DataFlash_Class::Log_Write_Power(void) +void AP_Logger::Log_Write_Power(void) { #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS uint8_t safety_and_armed = uint8_t(hal.util->safety_switch_state()); @@ -472,7 +472,7 @@ void DataFlash_Class::Log_Write_Power(void) } // Write an AHRS2 packet -void DataFlash_Class::Log_Write_AHRS2(AP_AHRS &ahrs) +void AP_Logger::Log_Write_AHRS2(AP_AHRS &ahrs) { Vector3f euler; struct Location loc; @@ -499,7 +499,7 @@ void DataFlash_Class::Log_Write_AHRS2(AP_AHRS &ahrs) } // Write a POS packet -void DataFlash_Class::Log_Write_POS(AP_AHRS &ahrs) +void AP_Logger::Log_Write_POS(AP_AHRS &ahrs) { Location loc; if (!ahrs.get_position(loc)) { @@ -520,7 +520,7 @@ void DataFlash_Class::Log_Write_POS(AP_AHRS &ahrs) } #if AP_AHRS_NAVEKF_AVAILABLE -void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs) +void AP_Logger::Log_Write_EKF(AP_AHRS_NavEKF &ahrs) { // only log EKF2 if enabled if (ahrs.get_NavEKF2().activeCores() > 0) { @@ -536,7 +536,7 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs) /* write an EKF timing message */ -void DataFlash_Class::Log_Write_EKF_Timing(const char *name, uint64_t time_us, const struct ekf_timing &timing) +void AP_Logger::Log_Write_EKF_Timing(const char *name, uint64_t time_us, const struct ekf_timing &timing) { Log_Write(name, "TimeUS,Cnt,IMUMin,IMUMax,EKFMin,EKFMax,AngMin,AngMax,VMin,VMax", @@ -553,7 +553,7 @@ void DataFlash_Class::Log_Write_EKF_Timing(const char *name, uint64_t time_us, c (double)timing.delVelDT_max); } -void DataFlash_Class::Log_Write_EKF2(AP_AHRS_NavEKF &ahrs) +void AP_Logger::Log_Write_EKF2(AP_AHRS_NavEKF &ahrs) { uint64_t time_us = AP_HAL::micros64(); // Write first EKF packet @@ -893,7 +893,7 @@ void DataFlash_Class::Log_Write_EKF2(AP_AHRS_NavEKF &ahrs) } -void DataFlash_Class::Log_Write_EKF3(AP_AHRS_NavEKF &ahrs) +void AP_Logger::Log_Write_EKF3(AP_AHRS_NavEKF &ahrs) { uint64_t time_us = AP_HAL::micros64(); // Write first EKF packet @@ -1289,7 +1289,7 @@ void DataFlash_Class::Log_Write_EKF3(AP_AHRS_NavEKF &ahrs) } #endif -void DataFlash_Class::Log_Write_Radio(const mavlink_radio_t &packet) +void AP_Logger::Log_Write_Radio(const mavlink_radio_t &packet) { struct log_Radio pkt = { LOG_PACKET_HEADER_INIT(LOG_RADIO_MSG), @@ -1306,7 +1306,7 @@ void DataFlash_Class::Log_Write_Radio(const mavlink_radio_t &packet) } // Write a Camera packet -void DataFlash_Class::Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const Location ¤t_loc, uint64_t timestamp_us) +void AP_Logger::Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const Location ¤t_loc, uint64_t timestamp_us) { int32_t altitude, altitude_rel, altitude_gps; if (current_loc.relative_alt) { @@ -1341,19 +1341,19 @@ void DataFlash_Class::Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS & } // Write a Camera packet -void DataFlash_Class::Log_Write_Camera(const AP_AHRS &ahrs, const Location ¤t_loc, uint64_t timestamp_us) +void AP_Logger::Log_Write_Camera(const AP_AHRS &ahrs, const Location ¤t_loc, uint64_t timestamp_us) { Log_Write_CameraInfo(LOG_CAMERA_MSG, ahrs, current_loc, timestamp_us); } // Write a Trigger packet -void DataFlash_Class::Log_Write_Trigger(const AP_AHRS &ahrs, const Location ¤t_loc) +void AP_Logger::Log_Write_Trigger(const AP_AHRS &ahrs, const Location ¤t_loc) { Log_Write_CameraInfo(LOG_TRIGGER_MSG, ahrs, current_loc, 0); } // Write an attitude packet -void DataFlash_Class::Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets) +void AP_Logger::Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets) { struct log_Attitude pkt = { LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG), @@ -1371,7 +1371,7 @@ void DataFlash_Class::Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets) } // Write an attitude packet -void DataFlash_Class::Log_Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets) +void AP_Logger::Log_Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets) { struct log_Attitude pkt = { LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG), @@ -1388,7 +1388,7 @@ void DataFlash_Class::Log_Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f WriteBlock(&pkt, sizeof(pkt)); } -void DataFlash_Class::Log_Write_Current_instance(const uint64_t time_us, +void AP_Logger::Log_Write_Current_instance(const uint64_t time_us, const uint8_t battery_instance, const enum LogMessages type, const enum LogMessages celltype) @@ -1429,7 +1429,7 @@ void DataFlash_Class::Log_Write_Current_instance(const uint64_t time_us, } // Write an Current data packet -void DataFlash_Class::Log_Write_Current() +void AP_Logger::Log_Write_Current() { // Big painful assert to ensure that logging won't produce suprising results when the // number of battery monitors changes, does have the built in expectation that @@ -1451,7 +1451,7 @@ void DataFlash_Class::Log_Write_Current() } } -void DataFlash_Class::Log_Write_Compass_instance(const uint64_t time_us, const uint8_t mag_instance, const enum LogMessages type) +void AP_Logger::Log_Write_Compass_instance(const uint64_t time_us, const uint8_t mag_instance, const enum LogMessages type) { const Compass &compass = AP::compass(); @@ -1477,7 +1477,7 @@ void DataFlash_Class::Log_Write_Compass_instance(const uint64_t time_us, const u } // Write a Compass packet -void DataFlash_Class::Log_Write_Compass(uint64_t time_us) +void AP_Logger::Log_Write_Compass(uint64_t time_us) { if (time_us == 0) { time_us = AP_HAL::micros64(); @@ -1497,7 +1497,7 @@ void DataFlash_Class::Log_Write_Compass(uint64_t time_us) } // Write a mode packet. -bool DataFlash_Backend::Log_Write_Mode(uint8_t mode, uint8_t reason) +bool AP_Logger_Backend::Log_Write_Mode(uint8_t mode, uint8_t reason) { struct log_Mode pkt = { LOG_PACKET_HEADER_INIT(LOG_MODE_MSG), @@ -1510,12 +1510,12 @@ bool DataFlash_Backend::Log_Write_Mode(uint8_t mode, uint8_t reason) } // Write ESC status messages -void DataFlash_Class::Log_Write_ESC(void) +void AP_Logger::Log_Write_ESC(void) { } // Write a AIRSPEED packet -void DataFlash_Class::Log_Write_Airspeed(AP_Airspeed &airspeed) +void AP_Logger::Log_Write_Airspeed(AP_Airspeed &airspeed) { uint64_t now = AP_HAL::micros64(); for (uint8_t i=0; ivehicle_message_writer()) { if (_dataflash_backend->bufferspace_available() < 200) { return; @@ -128,13 +128,13 @@ void DFMessageWriter_DFLogStart::process() _finished = true; } -void DFMessageWriter_WriteSysInfo::reset() +void LoggerMessageWriter_WriteSysInfo::reset() { - DFMessageWriter::reset(); + LoggerMessageWriter::reset(); stage = ws_blockwriter_stage_init; } -void DFMessageWriter_WriteSysInfo::process() { +void LoggerMessageWriter_WriteSysInfo::process() { const AP_FWVersion &fwver = AP::fwversion(); switch(stage) { @@ -181,7 +181,7 @@ void DFMessageWriter_WriteSysInfo::process() { _finished = true; // all done! } -void DFMessageWriter_WriteEntireMission::process() { +void LoggerMessageWriter_WriteEntireMission::process() { const AP_Mission *_mission = AP::mission(); if (_mission == nullptr) { _finished = true; @@ -229,9 +229,9 @@ void DFMessageWriter_WriteEntireMission::process() { _finished = true; } -void DFMessageWriter_WriteEntireMission::reset() +void LoggerMessageWriter_WriteEntireMission::reset() { - DFMessageWriter::reset(); + LoggerMessageWriter::reset(); stage = em_blockwriter_stage_init; _mission_number_to_send = 0; } diff --git a/libraries/AP_Logger/LoggerMessageWriter.h b/libraries/AP_Logger/LoggerMessageWriter.h index 490a5508e7..b03e7fb711 100644 --- a/libraries/AP_Logger/LoggerMessageWriter.h +++ b/libraries/AP_Logger/LoggerMessageWriter.h @@ -1,27 +1,27 @@ #pragma once -#include "DataFlash_Backend.h" +#include "AP_Logger_Backend.h" #include -class DFMessageWriter { +class LoggerMessageWriter { public: virtual void reset() = 0; virtual void process() = 0; virtual bool finished() { return _finished; } - virtual void set_dataflash_backend(class DataFlash_Backend *backend) { + virtual void set_dataflash_backend(class AP_Logger_Backend *backend) { _dataflash_backend = backend; } protected: bool _finished = false; - DataFlash_Backend *_dataflash_backend = nullptr; + AP_Logger_Backend *_dataflash_backend = nullptr; }; -class DFMessageWriter_WriteSysInfo : public DFMessageWriter { +class LoggerMessageWriter_WriteSysInfo : public LoggerMessageWriter { public: void reset() override; @@ -37,7 +37,7 @@ private: write_sysinfo_blockwriter_stage stage = ws_blockwriter_stage_init; }; -class DFMessageWriter_WriteEntireMission : public DFMessageWriter { +class LoggerMessageWriter_WriteEntireMission : public LoggerMessageWriter { public: void reset() override; @@ -55,16 +55,16 @@ private: entire_mission_blockwriter_stage stage = em_blockwriter_stage_init; }; -class DFMessageWriter_DFLogStart : public DFMessageWriter { +class LoggerMessageWriter_DFLogStart : public LoggerMessageWriter { public: - DFMessageWriter_DFLogStart() : + LoggerMessageWriter_DFLogStart() : _writesysinfo(), _writeentiremission() { } - virtual void set_dataflash_backend(class DataFlash_Backend *backend) override { - DFMessageWriter::set_dataflash_backend(backend); + virtual void set_dataflash_backend(class AP_Logger_Backend *backend) override { + LoggerMessageWriter::set_dataflash_backend(backend); _writesysinfo.set_dataflash_backend(backend); _writeentiremission.set_dataflash_backend(backend); } @@ -103,6 +103,6 @@ private: enum ap_var_type type; - DFMessageWriter_WriteSysInfo _writesysinfo; - DFMessageWriter_WriteEntireMission _writeentiremission; + LoggerMessageWriter_WriteSysInfo _writesysinfo; + LoggerMessageWriter_WriteEntireMission _writeentiremission; }; diff --git a/libraries/AP_Logger/examples/AP_Logger_AllTypes/AP_Logger_AllTypes.cpp b/libraries/AP_Logger/examples/AP_Logger_AllTypes/AP_Logger_AllTypes.cpp index 7ebee15787..f040b34515 100644 --- a/libraries/AP_Logger/examples/AP_Logger_AllTypes/AP_Logger_AllTypes.cpp +++ b/libraries/AP_Logger/examples/AP_Logger_AllTypes/AP_Logger_AllTypes.cpp @@ -3,7 +3,7 @@ */ #include -#include +#include #include #include @@ -83,7 +83,7 @@ static const struct LogStructure log_structure[] = { static uint16_t log_num; -class DataFlashTest_AllTypes : public AP_HAL::HAL::Callbacks { +class AP_LoggerTest_AllTypes : public AP_HAL::HAL::Callbacks { public: void setup(); void loop(); @@ -91,30 +91,30 @@ public: private: AP_Int32 log_bitmask; - DataFlash_Class dataflash{log_bitmask}; + AP_Logger dataflash{log_bitmask}; void print_mode(AP_HAL::BetterStream *port, uint8_t mode); void Log_Write_TypeMessages(); void Log_Write_TypeMessages_Log_Write(); - void flush_dataflash(DataFlash_Class &dataflash); + void flush_dataflash(AP_Logger &dataflash); }; -void DataFlashTest_AllTypes::flush_dataflash(DataFlash_Class &_dataflash) +void AP_LoggerTest_AllTypes::flush_dataflash(AP_Logger &_dataflash) { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX _dataflash.flush(); #else // flush is not available on e.g. px4 as it would be a somewhat // dangerous operation, but if we wait long enough (at time of - // writing, 2 seconds, see DataFlash_File::_io_timer) the data + // writing, 2 seconds, see AP_Logger_File::_io_timer) the data // will go out. hal.scheduler->delay(3000); #endif } -void DataFlashTest_AllTypes::Log_Write_TypeMessages() +void AP_LoggerTest_AllTypes::Log_Write_TypeMessages() { log_num = dataflash.find_last_log(); hal.console->printf("Using log number %u\n", log_num); @@ -161,7 +161,7 @@ void DataFlashTest_AllTypes::Log_Write_TypeMessages() dataflash.StopLogging(); } -void DataFlashTest_AllTypes::Log_Write_TypeMessages_Log_Write() +void AP_LoggerTest_AllTypes::Log_Write_TypeMessages_Log_Write() { log_num = dataflash.find_last_log(); hal.console->printf("Using log number for Log_Write %u\n", log_num); @@ -203,14 +203,14 @@ void DataFlashTest_AllTypes::Log_Write_TypeMessages_Log_Write() dataflash.StopLogging(); } -void DataFlashTest_AllTypes::setup(void) +void AP_LoggerTest_AllTypes::setup(void) { hal.console->printf("Dataflash All Types 1.0\n"); log_bitmask = (uint32_t)-1; dataflash.Init(log_structure, ARRAY_SIZE(log_structure)); dataflash.set_vehicle_armed(true); - dataflash.Log_Write_Message("DataFlash Test"); + dataflash.Log_Write_Message("AP_Logger Test"); // Test hal.scheduler->delay(20); @@ -221,7 +221,7 @@ void DataFlashTest_AllTypes::setup(void) hal.console->printf("tests done\n"); } -void DataFlashTest_AllTypes::loop(void) +void AP_LoggerTest_AllTypes::loop(void) { hal.console->printf("all done\n"); hal.scheduler->delay(1000); @@ -233,6 +233,6 @@ const struct AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { GCS_Dummy _gcs; -static DataFlashTest_AllTypes dataflashtest; +static AP_LoggerTest_AllTypes dataflashtest; AP_HAL_MAIN_CALLBACKS(&dataflashtest); diff --git a/libraries/AP_Logger/examples/AP_Logger_test/AP_Logger_test.cpp b/libraries/AP_Logger/examples/AP_Logger_test/AP_Logger_test.cpp index 35f8fa6683..720cef9d0e 100644 --- a/libraries/AP_Logger/examples/AP_Logger_test/AP_Logger_test.cpp +++ b/libraries/AP_Logger/examples/AP_Logger_test/AP_Logger_test.cpp @@ -1,10 +1,10 @@ /* - * Example of DataFlash library. + * Example of AP_Logger library. * originally based on code by Jordi MuĂ’oz and Jose Julio */ #include -#include +#include #include #include @@ -32,7 +32,7 @@ static const struct LogStructure log_structure[] = { static uint16_t log_num; -class DataFlashTest { +class AP_LoggerTest { public: void setup(); void loop(); @@ -40,20 +40,20 @@ public: private: AP_Int32 log_bitmask; - DataFlash_Class dataflash{log_bitmask}; + AP_Logger dataflash{log_bitmask}; }; -static DataFlashTest dataflashtest; +static AP_LoggerTest dataflashtest; -void DataFlashTest::setup(void) +void AP_LoggerTest::setup(void) { hal.console->printf("Dataflash Log Test 1.0\n"); log_bitmask = (uint32_t)-1; dataflash.Init(log_structure, ARRAY_SIZE(log_structure)); dataflash.set_vehicle_armed(true); - dataflash.Log_Write_Message("DataFlash Test"); + dataflash.Log_Write_Message("AP_Logger Test"); // Test hal.scheduler->delay(20); @@ -95,7 +95,7 @@ void DataFlashTest::setup(void) hal.scheduler->delay(100); } -void DataFlashTest::loop(void) +void AP_LoggerTest::loop(void) { hal.console->printf("\nTest complete.\n"); hal.scheduler->delay(20000); diff --git a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp index 2c77c1c7db..5dd9e2ca45 100644 --- a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp +++ b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp @@ -12,7 +12,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index 2f36218cb4..46ac4cc559 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -26,7 +26,7 @@ #include #include #include -#include +#include // maximum number of mounts #define AP_MOUNT_MAX_INSTANCES 1 diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp index a9646928ce..35f65c4e30 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp @@ -4,7 +4,7 @@ #include "AP_Mount_SoloGimbal.h" #include "SoloGimbal.h" -#include +#include #include #include @@ -118,7 +118,7 @@ void AP_Mount_SoloGimbal::handle_gimbal_report(mavlink_channel_t chan, const mav _gimbal.update_target(_angle_ef_target_rad); _gimbal.receive_feedback(chan,msg); - DataFlash_Class *df = DataFlash_Class::instance(); + AP_Logger *df = AP_Logger::instance(); if (df == nullptr) { return; } diff --git a/libraries/AP_Mount/SoloGimbal.cpp b/libraries/AP_Mount/SoloGimbal.cpp index 651dea37fc..af228aada2 100644 --- a/libraries/AP_Mount/SoloGimbal.cpp +++ b/libraries/AP_Mount/SoloGimbal.cpp @@ -383,7 +383,7 @@ void SoloGimbal::update_target(const Vector3f &newTarget) void SoloGimbal::write_logs() { - DataFlash_Class *dataflash = DataFlash_Class::instance(); + AP_Logger *dataflash = AP_Logger::instance(); if (dataflash == nullptr) { return; } diff --git a/libraries/AP_Mount/SoloGimbal_Parameters.cpp b/libraries/AP_Mount/SoloGimbal_Parameters.cpp index f1e672c97f..88b5926940 100644 --- a/libraries/AP_Mount/SoloGimbal_Parameters.cpp +++ b/libraries/AP_Mount/SoloGimbal_Parameters.cpp @@ -177,7 +177,7 @@ void SoloGimbal_Parameters::handle_param_value(const mavlink_message_t *msg) mavlink_param_value_t packet; mavlink_msg_param_value_decode(msg, &packet); - DataFlash_Class *dataflash = DataFlash_Class::instance(); + AP_Logger *dataflash = AP_Logger::instance(); if (dataflash != nullptr) { dataflash->Log_Write_Parameter(packet.param_id, packet.param_value); } diff --git a/libraries/AP_Mount/SoloGimbal_Parameters.h b/libraries/AP_Mount/SoloGimbal_Parameters.h index 04f8bb6fa4..35a76609db 100644 --- a/libraries/AP_Mount/SoloGimbal_Parameters.h +++ b/libraries/AP_Mount/SoloGimbal_Parameters.h @@ -2,7 +2,7 @@ #include #include #include -#include +#include enum gmb_param_state_t { GMB_PARAMSTATE_NOT_YET_READ=0, // parameter has yet to be initialized diff --git a/libraries/AP_Mount/examples/trivial_AP_Mount/trivial_AP_Mount.cpp b/libraries/AP_Mount/examples/trivial_AP_Mount/trivial_AP_Mount.cpp index 24c62ba54f..a051b195e0 100644 --- a/libraries/AP_Mount/examples/trivial_AP_Mount/trivial_AP_Mount.cpp +++ b/libraries/AP_Mount/examples/trivial_AP_Mount/trivial_AP_Mount.cpp @@ -19,7 +19,7 @@ #include #include #include -#include +#include #include #include diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index 2219d6a911..2cc07d4a38 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -4,7 +4,7 @@ #include "AP_NavEKF2_core.h" #include #include -#include +#include #include /* @@ -563,24 +563,24 @@ void NavEKF2::check_log_write(void) return; } if (logging.log_compass) { - DataFlash_Class::instance()->Log_Write_Compass(imuSampleTime_us); + AP_Logger::instance()->Log_Write_Compass(imuSampleTime_us); logging.log_compass = false; } if (logging.log_gps) { - DataFlash_Class::instance()->Log_Write_GPS(AP::gps().primary_sensor(), imuSampleTime_us); + AP_Logger::instance()->Log_Write_GPS(AP::gps().primary_sensor(), imuSampleTime_us); logging.log_gps = false; } if (logging.log_baro) { - DataFlash_Class::instance()->Log_Write_Baro(imuSampleTime_us); + AP_Logger::instance()->Log_Write_Baro(imuSampleTime_us); logging.log_baro = false; } if (logging.log_imu) { - DataFlash_Class::instance()->Log_Write_IMUDT(imuSampleTime_us, _logging_mask.get()); + AP_Logger::instance()->Log_Write_IMUDT(imuSampleTime_us, _logging_mask.get()); logging.log_imu = false; } // this is an example of an ad-hoc log in EKF - // DataFlash_Class::instance()->Log_Write("NKA", "TimeUS,X", "Qf", AP_HAL::micros64(), (double)2.4f); + // AP_Logger::instance()->Log_Write("NKA", "TimeUS,X", "Qf", AP_HAL::micros64(), (double)2.4f); } @@ -601,7 +601,7 @@ bool NavEKF2::InitialiseFilter(void) _framesPerPrediction = uint8_t((EKF_TARGET_DT / (_frameTimeUsec * 1.0e-6) + 0.5)); // see if we will be doing logging - DataFlash_Class *dataflash = DataFlash_Class::instance(); + AP_Logger *dataflash = AP_Logger::instance(); if (dataflash != nullptr) { logging.enabled = dataflash->log_replay(); } diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index 24b356cfa9..7f06a2e00e 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -4,7 +4,7 @@ #include "AP_NavEKF3_core.h" #include #include -#include +#include #include /* @@ -595,24 +595,24 @@ void NavEKF3::check_log_write(void) return; } if (logging.log_compass) { - DataFlash_Class::instance()->Log_Write_Compass(imuSampleTime_us); + AP_Logger::instance()->Log_Write_Compass(imuSampleTime_us); logging.log_compass = false; } if (logging.log_gps) { - DataFlash_Class::instance()->Log_Write_GPS(AP::gps().primary_sensor(), imuSampleTime_us); + AP_Logger::instance()->Log_Write_GPS(AP::gps().primary_sensor(), imuSampleTime_us); logging.log_gps = false; } if (logging.log_baro) { - DataFlash_Class::instance()->Log_Write_Baro(imuSampleTime_us); + AP_Logger::instance()->Log_Write_Baro(imuSampleTime_us); logging.log_baro = false; } if (logging.log_imu) { - DataFlash_Class::instance()->Log_Write_IMUDT(imuSampleTime_us, _logging_mask.get()); + AP_Logger::instance()->Log_Write_IMUDT(imuSampleTime_us, _logging_mask.get()); logging.log_imu = false; } // this is an example of an ad-hoc log in EKF - // DataFlash_Class::instance()->Log_Write("NKA", "TimeUS,X", "Qf", AP_HAL::micros64(), (double)2.4f); + // AP_Logger::instance()->Log_Write("NKA", "TimeUS,X", "Qf", AP_HAL::micros64(), (double)2.4f); } @@ -635,7 +635,7 @@ bool NavEKF3::InitialiseFilter(void) if (core == nullptr) { // see if we will be doing logging - DataFlash_Class *dataflash = DataFlash_Class::instance(); + AP_Logger *dataflash = AP_Logger::instance(); if (dataflash != nullptr) { logging.enabled = dataflash->log_replay(); } diff --git a/libraries/AP_OpticalFlow/OpticalFlow.cpp b/libraries/AP_OpticalFlow/OpticalFlow.cpp index 75c421e69b..90ae25cc1c 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/OpticalFlow.cpp @@ -5,7 +5,7 @@ #include "AP_OpticalFlow_Pixart.h" #include "AP_OpticalFlow_PX4Flow.h" #include "AP_OpticalFlow_CXOF.h" -#include +#include extern const AP_HAL::HAL& hal; @@ -156,7 +156,7 @@ void OpticalFlow::update_state(const OpticalFlow_state &state) void OpticalFlow::Log_Write_Optflow() { - DataFlash_Class *instance = DataFlash_Class::instance(); + AP_Logger *instance = AP_Logger::instance(); if (instance == nullptr) { return; } diff --git a/libraries/AP_Scheduler/AP_Scheduler.cpp b/libraries/AP_Scheduler/AP_Scheduler.cpp index fb1d675551..51ec4c7d74 100644 --- a/libraries/AP_Scheduler/AP_Scheduler.cpp +++ b/libraries/AP_Scheduler/AP_Scheduler.cpp @@ -23,7 +23,7 @@ #include #include #include -#include +#include #include #include @@ -279,7 +279,7 @@ void AP_Scheduler::update_logging() perf_info.update_logging(); } if (_log_performance_bit != (uint32_t)-1 && - DataFlash_Class::instance()->should_log(_log_performance_bit)) { + AP_Logger::instance()->should_log(_log_performance_bit)) { Log_Write_Performance(); } perf_info.set_loop_rate(get_loop_rate_hz()); @@ -298,7 +298,7 @@ void AP_Scheduler::Log_Write_Performance() mem_avail : hal.util->available_memory(), load : (uint16_t)(load_average() * 1000) }; - DataFlash_Class::instance()->WriteCriticalBlock(&pkt, sizeof(pkt)); + AP_Logger::instance()->WriteCriticalBlock(&pkt, sizeof(pkt)); } namespace AP { diff --git a/libraries/AP_Scheduler/PerfInfo.cpp b/libraries/AP_Scheduler/PerfInfo.cpp index 780c7b5e90..83cb916b04 100644 --- a/libraries/AP_Scheduler/PerfInfo.cpp +++ b/libraries/AP_Scheduler/PerfInfo.cpp @@ -1,6 +1,6 @@ #include "PerfInfo.h" -#include +#include #include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp b/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp index fe28961843..2dee9aba98 100644 --- a/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp +++ b/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp @@ -6,12 +6,12 @@ #include #include #include -#include +#include const AP_HAL::HAL& hal = AP_HAL::get_HAL(); AP_Int32 log_bitmask; -DataFlash_Class DataFlash{log_bitmask}; +AP_Logger AP_Logger{log_bitmask}; class SchedTest { public: diff --git a/libraries/AP_SmartRTL/AP_SmartRTL.cpp b/libraries/AP_SmartRTL/AP_SmartRTL.cpp index fda1957969..ee18483603 100644 --- a/libraries/AP_SmartRTL/AP_SmartRTL.cpp +++ b/libraries/AP_SmartRTL/AP_SmartRTL.cpp @@ -825,7 +825,7 @@ void AP_SmartRTL::deactivate(SRTL_Actions action, const char *reason) void AP_SmartRTL::log_action(SRTL_Actions action, const Vector3f &point) { if (!_example_mode) { - DataFlash_Class::instance()->Log_Write_SRTL(_active, _path_points_count, _path_points_max, action, point); + AP_Logger::instance()->Log_Write_SRTL(_active, _path_points_count, _path_points_max, action, point); } } diff --git a/libraries/AP_SmartRTL/AP_SmartRTL.h b/libraries/AP_SmartRTL/AP_SmartRTL.h index 685e9a84b8..4ba64dc439 100644 --- a/libraries/AP_SmartRTL/AP_SmartRTL.h +++ b/libraries/AP_SmartRTL/AP_SmartRTL.h @@ -4,7 +4,7 @@ #include #include #include -#include +#include #include // definitions and macros diff --git a/libraries/AP_Soaring/AP_Soaring.cpp b/libraries/AP_Soaring/AP_Soaring.cpp index aa79eb6196..25e4b9c9f4 100644 --- a/libraries/AP_Soaring/AP_Soaring.cpp +++ b/libraries/AP_Soaring/AP_Soaring.cpp @@ -279,7 +279,7 @@ void SoaringController::update_thermalling() #endif // write log - save the data. - DataFlash_Class::instance()->Log_Write("SOAR", "TimeUS,nettorate,dx,dy,x0,x1,x2,x3,lat,lng,alt,dx_w,dy_w", "QfffffffLLfff", + AP_Logger::instance()->Log_Write("SOAR", "TimeUS,nettorate,dx,dy,x0,x1,x2,x3,lat,lng,alt,dx_w,dy_w", "QfffffffLLfff", AP_HAL::micros64(), (double)_vario.reading, (double)dx, diff --git a/libraries/AP_Soaring/AP_Soaring.h b/libraries/AP_Soaring/AP_Soaring.h index 63ad1b7788..57c6de0ad1 100644 --- a/libraries/AP_Soaring/AP_Soaring.h +++ b/libraries/AP_Soaring/AP_Soaring.h @@ -11,7 +11,7 @@ #include #include -#include +#include #include #include "ExtendedKalmanFilter.h" #include "Variometer.h" diff --git a/libraries/AP_Soaring/Variometer.cpp b/libraries/AP_Soaring/Variometer.cpp index fe7c9c48b1..f2cf697480 100644 --- a/libraries/AP_Soaring/Variometer.cpp +++ b/libraries/AP_Soaring/Variometer.cpp @@ -38,7 +38,7 @@ void Variometer::update(const float polar_K, const float polar_B, const float po _prev_update_time = AP_HAL::micros64(); new_data = true; - DataFlash_Class::instance()->Log_Write("VAR", "TimeUS,aspd_raw,aspd_filt,alt,roll,raw,filt", "Qffffff", + AP_Logger::instance()->Log_Write("VAR", "TimeUS,aspd_raw,aspd_filt,alt,roll,raw,filt", "Qffffff", AP_HAL::micros64(), (double)aspd, (double)_aspd_filt, diff --git a/libraries/AP_Soaring/Variometer.h b/libraries/AP_Soaring/Variometer.h index fea389a484..2d17f9b8ea 100644 --- a/libraries/AP_Soaring/Variometer.h +++ b/libraries/AP_Soaring/Variometer.h @@ -7,7 +7,7 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity. #include #include -#include +#include #include #define ASPD_FILT 0.05 diff --git a/libraries/AP_SpdHgtControl/AP_SpdHgtControl.h b/libraries/AP_SpdHgtControl/AP_SpdHgtControl.h index 71e9c06545..10827292af 100644 --- a/libraries/AP_SpdHgtControl/AP_SpdHgtControl.h +++ b/libraries/AP_SpdHgtControl/AP_SpdHgtControl.h @@ -12,7 +12,7 @@ #include #include -#include +#include #include class AP_SpdHgtControl { diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index f7f74d9728..be2d49bbc8 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -1076,8 +1076,8 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm, // Calculate pitch demand _update_pitch(); - // log to DataFlash - DataFlash_Class::instance()->Log_Write( + // log to AP_Logger + AP_Logger::instance()->Log_Write( "TECS", "TimeUS,h,dh,hdem,dhdem,spdem,sp,dsp,ith,iph,th,ph,dspdem,w,f", "smnmnnnn----o--", @@ -1098,7 +1098,7 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm, (double)_TAS_rate_dem, (double)logging.SKE_weighting, _flags_byte); - DataFlash_Class::instance()->Log_Write("TEC2", "TimeUS,KErr,PErr,EDelta,LF", "Qffff", + AP_Logger::instance()->Log_Write("TEC2", "TimeUS,KErr,PErr,EDelta,LF", "Qffff", now, (double)logging.SKE_error, (double)logging.SPE_error, diff --git a/libraries/AP_TECS/AP_TECS.h b/libraries/AP_TECS/AP_TECS.h index ec3b67ded1..9e1d678d70 100644 --- a/libraries/AP_TECS/AP_TECS.h +++ b/libraries/AP_TECS/AP_TECS.h @@ -23,7 +23,7 @@ #include #include #include -#include +#include #include class AP_TECS : public AP_SpdHgtControl { diff --git a/libraries/AP_Terrain/AP_Terrain.cpp b/libraries/AP_Terrain/AP_Terrain.cpp index 1b706eaf5d..512c9ef098 100644 --- a/libraries/AP_Terrain/AP_Terrain.cpp +++ b/libraries/AP_Terrain/AP_Terrain.cpp @@ -18,7 +18,7 @@ #include #include #include -#include +#include #include "AP_Terrain.h" #if AP_TERRAIN_AVAILABLE @@ -370,7 +370,7 @@ void AP_Terrain::log_terrain_data() pending : pending, loaded : loaded }; - DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt)); + AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt)); } /* diff --git a/libraries/AP_Terrain/AP_Terrain.h b/libraries/AP_Terrain/AP_Terrain.h index 673bb441e4..656f0ec61e 100644 --- a/libraries/AP_Terrain/AP_Terrain.h +++ b/libraries/AP_Terrain/AP_Terrain.h @@ -16,7 +16,7 @@ #include #include -#include +#include #if (HAL_OS_POSIX_IO || HAL_OS_FATFS_IO) && defined(HAL_BOARD_TERRAIN_DIRECTORY) #define AP_TERRAIN_AVAILABLE 1 @@ -167,7 +167,7 @@ public: float lookahead(float bearing, float distance, float climb_ratio); /* - log terrain status to DataFlash + log terrain status to AP_Logger */ void log_terrain_data(); diff --git a/libraries/AP_Tuning/AP_Tuning.cpp b/libraries/AP_Tuning/AP_Tuning.cpp index 4d06113950..7715d293ac 100644 --- a/libraries/AP_Tuning/AP_Tuning.cpp +++ b/libraries/AP_Tuning/AP_Tuning.cpp @@ -226,7 +226,7 @@ void AP_Tuning::check_input(uint8_t flightmode) */ void AP_Tuning::Log_Write_Parameter_Tuning(float value) { - DataFlash_Class::instance()->Log_Write("PTUN", "TimeUS,Set,Parm,Value,CenterValue", "QBBff", + AP_Logger::instance()->Log_Write("PTUN", "TimeUS,Set,Parm,Value,CenterValue", "QBBff", AP_HAL::micros64(), parmset, current_parm, diff --git a/libraries/AP_Tuning/AP_Tuning.h b/libraries/AP_Tuning/AP_Tuning.h index 2c171c4e94..61616e40fa 100644 --- a/libraries/AP_Tuning/AP_Tuning.h +++ b/libraries/AP_Tuning/AP_Tuning.h @@ -2,7 +2,7 @@ #include #include -#include +#include /* transmitter tuning library. Meant to be subclassed per vehicle type diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_Servers.cpp b/libraries/AP_UAVCAN/AP_UAVCAN_Servers.cpp index bdfb65efde..9b05381cb1 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN_Servers.cpp +++ b/libraries/AP_UAVCAN/AP_UAVCAN_Servers.cpp @@ -32,7 +32,7 @@ #include #include -#include +#include #if HAL_OS_POSIX_IO #include @@ -79,7 +79,7 @@ class AP_UAVCAN_FileEventTracer : public uavcan::dynamic_node_id_server::IEventT protected: virtual void onEvent(uavcan::dynamic_node_id_server::TraceCode code, uavcan::int64_t argument) { - DataFlash_Class::instance()->Log_Write("UCEV", "TimeUS,code,arg", "s--", "F--", "Qhq", AP_HAL::micros64(), code, argument); + AP_Logger::instance()->Log_Write("UCEV", "TimeUS,code,arg", "s--", "F--", "Qhq", AP_HAL::micros64(), code, argument); } }; diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 81e84aeb63..37ff969c79 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -6,7 +6,7 @@ #include #include #include "GCS_MAVLink.h" -#include +#include #include #include #include @@ -334,7 +334,7 @@ protected: void handle_rally_point(mavlink_message_t *msg); virtual void handle_mount_message(const mavlink_message_t *msg); void handle_param_value(mavlink_message_t *msg); - void handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio); + void handle_radio_status(mavlink_message_t *msg, AP_Logger &dataflash, bool log_radio); void handle_serial_control(const mavlink_message_t *msg); void handle_vision_position_delta(mavlink_message_t *msg); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 78e47e7547..135e349e32 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -690,7 +690,7 @@ void GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *fmt, ...) va_end(arg_list); } -void GCS_MAVLINK::handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio) +void GCS_MAVLINK::handle_radio_status(mavlink_message_t *msg, AP_Logger &dataflash, bool log_radio) { mavlink_radio_t packet; mavlink_msg_radio_decode(msg, &packet); @@ -1172,8 +1172,8 @@ int8_t GCS_MAVLINK::deferred_message_to_send_index() void GCS_MAVLINK::update_send() { if (!hal.scheduler->in_delay_callback()) { - // DataFlash_Class will not send log data if we are armed. - DataFlash_Class::instance()->handle_log_send(); + // AP_Logger will not send log data if we are armed. + AP_Logger::instance()->handle_log_send(); } if (!deferred_messages_initialised) { @@ -1841,7 +1841,7 @@ void GCS_MAVLINK::send_ahrs() */ void GCS::send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text) { - DataFlash_Class *dataflash = DataFlash_Class::instance(); + AP_Logger *dataflash = AP_Logger::instance(); if (dataflash != nullptr) { dataflash->Log_Write_Message(text); } @@ -2516,9 +2516,9 @@ void GCS_MAVLINK::handle_timesync(mavlink_message_t *msg) msg->sysid, round_trip_time_us*0.001f); #endif - DataFlash_Class *df = DataFlash_Class::instance(); + AP_Logger *df = AP_Logger::instance(); if (df != nullptr) { - DataFlash_Class::instance()->Log_Write( + AP_Logger::instance()->Log_Write( "TSYN", "TimeUS,SysID,RTT", "s-s", @@ -2567,7 +2567,7 @@ void GCS_MAVLINK::send_timesync() void GCS_MAVLINK::handle_statustext(mavlink_message_t *msg) { - DataFlash_Class *df = DataFlash_Class::instance(); + AP_Logger *df = AP_Logger::instance(); if (df == nullptr) { return; } @@ -2796,7 +2796,7 @@ void GCS_MAVLINK::log_vision_position_estimate_data(const uint64_t usec, const float pitch, const float yaw) { - DataFlash_Class::instance()->Log_Write("VISP", "TimeUS,RemTimeUS,PX,PY,PZ,Roll,Pitch,Yaw", + AP_Logger::instance()->Log_Write("VISP", "TimeUS,RemTimeUS,PX,PY,PZ,Roll,Pitch,Yaw", "ssmmmddh", "FF000000", "QQffffff", (uint64_t)AP_HAL::micros64(), (uint64_t)usec, @@ -2891,7 +2891,7 @@ void GCS_MAVLINK::handle_common_message(mavlink_message_t *msg) case MAVLINK_MSG_ID_LOG_ERASE: case MAVLINK_MSG_ID_LOG_REQUEST_END: case MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS: - DataFlash_Class::instance()->handle_mavlink_msg(*this, msg); + AP_Logger::instance()->handle_mavlink_msg(*this, msg); break; @@ -3030,7 +3030,7 @@ void GCS_MAVLINK::handle_common_mission_message(mavlink_message_t *msg) case MAVLINK_MSG_ID_MISSION_ITEM_INT: { if (handle_mission_item(msg, *_mission)) { - DataFlash_Class::instance()->Log_Write_EntireMission(*_mission); + AP_Logger::instance()->Log_Write_EntireMission(*_mission); } break; } diff --git a/libraries/GCS_MAVLink/GCS_Param.cpp b/libraries/GCS_MAVLink/GCS_Param.cpp index 96aa9dc74d..7ca3daaa40 100644 --- a/libraries/GCS_MAVLink/GCS_Param.cpp +++ b/libraries/GCS_MAVLink/GCS_Param.cpp @@ -292,9 +292,9 @@ void GCS_MAVLINK::handle_param_set(mavlink_message_t *msg) // save the change vp->save(force_save); - DataFlash_Class *DataFlash = DataFlash_Class::instance(); - if (DataFlash != nullptr) { - DataFlash->Log_Write_Parameter(key, vp->cast_to_float(var_type)); + AP_Logger *AP_Logger = AP_Logger::instance(); + if (AP_Logger != nullptr) { + AP_Logger->Log_Write_Parameter(key, vp->cast_to_float(var_type)); } } @@ -318,8 +318,8 @@ void GCS::send_parameter_value(const char *param_name, ap_var_type param_type, f } } } - // also log to DataFlash - DataFlash_Class *dataflash = DataFlash_Class::instance(); + // also log to AP_Logger + AP_Logger *dataflash = AP_Logger::instance(); if (dataflash != nullptr) { dataflash->Log_Write_Parameter(param_name, param_value); } diff --git a/libraries/GCS_MAVLink/GCS_serial_control.cpp b/libraries/GCS_MAVLink/GCS_serial_control.cpp index 117641c690..0791905684 100644 --- a/libraries/GCS_MAVLink/GCS_serial_control.cpp +++ b/libraries/GCS_MAVLink/GCS_serial_control.cpp @@ -20,7 +20,7 @@ #include #include "GCS.h" -#include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/PID/PID.h b/libraries/PID/PID.h index 3d1c72d057..38b6f40445 100644 --- a/libraries/PID/PID.h +++ b/libraries/PID/PID.h @@ -4,7 +4,7 @@ #include #include -#include +#include #include #include @@ -98,7 +98,7 @@ public: static const struct AP_Param::GroupInfo var_info[]; - const DataFlash_Class::PID_Info& get_pid_info(void) const { return _pid_info; } + const AP_Logger::PID_Info& get_pid_info(void) const { return _pid_info; } private: AP_Float _kp; @@ -113,7 +113,7 @@ private: float _get_pid(float error, uint16_t dt, float scaler); - DataFlash_Class::PID_Info _pid_info {}; + AP_Logger::PID_Info _pid_info {}; /// Low pass filter cut frequency for derivative calculation. /// diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp index 69c49454a0..50099779ed 100644 --- a/libraries/SITL/SIM_Aircraft.cpp +++ b/libraries/SITL/SIM_Aircraft.cpp @@ -29,7 +29,7 @@ #include #endif -#include +#include #include using namespace SITL; @@ -187,7 +187,7 @@ void Aircraft::update_position(void) #if 0 // logging of raw sitl data Vector3f accel_ef = dcm * accel_body; - DataFlash_Class::instance()->Log_Write("SITL", "TimeUS,VN,VE,VD,AN,AE,AD,PN,PE,PD", "Qfffffffff", + AP_Logger::instance()->Log_Write("SITL", "TimeUS,VN,VE,VD,AN,AE,AD,PN,PE,PD", "Qfffffffff", AP_HAL::micros64(), velocity_ef.x, velocity_ef.y, velocity_ef.z, accel_ef.x, accel_ef.y, accel_ef.z, @@ -662,7 +662,7 @@ void Aircraft::smooth_sensors(void) dcm.to_euler(&R2, &P2, &Y2); #if 0 - DataFlash_Class::instance()->Log_Write("SMOO", "TimeUS,AEx,AEy,AEz,DPx,DPy,DPz,R,P,Y,R2,P2,Y2", + AP_Logger::instance()->Log_Write("SMOO", "TimeUS,AEx,AEy,AEz,DPx,DPy,DPz,R,P,Y,R2,P2,Y2", "Qffffffffffff", AP_HAL::micros64(), degrees(angle_differential.x), diff --git a/libraries/SITL/SIM_FlightAxis.cpp b/libraries/SITL/SIM_FlightAxis.cpp index e6ef0d467c..759fe782ad 100644 --- a/libraries/SITL/SIM_FlightAxis.cpp +++ b/libraries/SITL/SIM_FlightAxis.cpp @@ -27,7 +27,7 @@ #include #include -#include +#include #include "pthread.h" extern const AP_HAL::HAL& hal; diff --git a/libraries/SITL/SIM_Morse.cpp b/libraries/SITL/SIM_Morse.cpp index b9bb5d4ab8..cfaa54b56d 100644 --- a/libraries/SITL/SIM_Morse.cpp +++ b/libraries/SITL/SIM_Morse.cpp @@ -27,7 +27,7 @@ #include #include -#include +#include #include "pthread.h" #include diff --git a/libraries/SITL/SIM_XPlane.cpp b/libraries/SITL/SIM_XPlane.cpp index 5dd90798bb..3f8bee80c0 100644 --- a/libraries/SITL/SIM_XPlane.cpp +++ b/libraries/SITL/SIM_XPlane.cpp @@ -26,7 +26,7 @@ #include #include -#include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index cef73e8edb..26e4b42288 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -22,7 +22,7 @@ #include #include #include -#include +#include extern const AP_HAL::HAL& hal; @@ -170,7 +170,7 @@ void SITL::simstate_send(mavlink_channel_t chan) state.longitude*1.0e7); } -/* report SITL state to DataFlash */ +/* report SITL state to AP_Logger */ void SITL::Log_Write_SIMSTATE() { float yaw; @@ -195,7 +195,7 @@ void SITL::Log_Write_SIMSTATE() q3 : state.quaternion.q3, q4 : state.quaternion.q4, }; - DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt)); + AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt)); } /* diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index d2b892ba23..73707135c0 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -9,7 +9,7 @@ #include "SIM_Gripper_EPM.h" #include "SIM_Parachute.h" -class DataFlash_Class; +class AP_Logger; namespace SITL {