Skip to content

Commit

Permalink
GLOBAL: use AP::logger() and strip redundant Log_ from methods
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker authored and tridge committed Jan 18, 2019
1 parent 8e2a229 commit 6fc76a3
Show file tree
Hide file tree
Showing 95 changed files with 432 additions and 432 deletions.
10 changes: 5 additions & 5 deletions APMrover2/APMrover2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,7 @@ void Rover::ahrs_update()
}

if (should_log(MASK_LOG_IMU)) {
logger.Log_Write_IMU();
logger.Write_IMU();
}
}

Expand All @@ -204,7 +204,7 @@ void Rover::update_compass(void)
ahrs.set_compass(&compass);
// update offsets
if (should_log(MASK_LOG_COMPASS)) {
logger.Log_Write_Compass();
logger.Write_Compass();
}
}
}
Expand All @@ -221,15 +221,15 @@ void Rover::update_logging1(void)

if (should_log(MASK_LOG_THR)) {
Log_Write_Throttle();
logger.Log_Write_Beacon(g2.beacon);
logger.Write_Beacon(g2.beacon);
}

if (should_log(MASK_LOG_NTUN)) {
Log_Write_Nav_Tuning();
}

if (should_log(MASK_LOG_RANGEFINDER)) {
logger.Log_Write_Proximity(g2.proximity);
logger.Write_Proximity(g2.proximity);
}
}

Expand All @@ -248,7 +248,7 @@ void Rover::update_logging2(void)
}

if (should_log(MASK_LOG_IMU)) {
logger.Log_Write_Vibration();
logger.Write_Vibration();
}
}

Expand Down
28 changes: 14 additions & 14 deletions APMrover2/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);

logger.Log_Write_Attitude(ahrs, targets);
logger.Write_Attitude(ahrs, targets);

#if AP_AHRS_NAVEKF_AVAILABLE
logger.Log_Write_EKF(ahrs);
logger.Log_Write_AHRS2(ahrs);
logger.Write_EKF(ahrs);
logger.Write_AHRS2(ahrs);
#endif
logger.Log_Write_POS(ahrs);
logger.Write_POS(ahrs);

// log steering rate controller
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());
logger.Write_PID(LOG_PIDS_MSG, g2.attitude_control.get_steering_rate_pid().get_pid_info());
logger.Write_PID(LOG_PIDA_MSG, g2.attitude_control.get_throttle_speed_pid().get_pid_info());

// log pitch control for balance bots
if (is_balancebot()) {
logger.Log_Write_PID(LOG_PIDP_MSG, g2.attitude_control.get_pitch_to_throttle_pid().get_pid_info());
logger.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()) {
logger.Log_Write_PID(LOG_PIDR_MSG, g2.attitude_control.get_sailboat_heel_pid().get_pid_info());
logger.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();
Expand Down Expand Up @@ -75,7 +75,7 @@ void Rover::Log_Write_Depth()
}
rangefinder_last_reading_ms = reading_ms;

logger.Log_Write("DPTH", "TimeUS,Lat,Lng,Depth",
logger.Write("DPTH", "TimeUS,Lat,Lng,Depth",
"sDUm", "FGG0", "QLLf",
AP_HAL::micros64(),
loc.lat,
Expand Down Expand Up @@ -175,7 +175,7 @@ void Rover::Log_Write_Sail()
wind_speed_true = g2.windvane.get_true_wind_speed();
wind_speed_apparent = g2.windvane.get_apparent_wind_speed();
}
logger.Log_Write("SAIL", "TimeUS,WindDirAbs,WindDirApp,WindSpdTrue,WindSpdApp,SailOut,VMG",
logger.Write("SAIL", "TimeUS,WindDirAbs,WindDirApp,WindSpdTrue,WindSpdApp,SailOut,VMG",
"shhnn%n", "F000000", "Qffffff",
AP_HAL::micros64(),
(double)wind_dir_abs,
Expand Down Expand Up @@ -300,10 +300,10 @@ void Rover::Log_Write_Rangefinder()

void Rover::Log_Write_RC(void)
{
logger.Log_Write_RCIN();
logger.Log_Write_RCOUT();
logger.Write_RCIN();
logger.Write_RCOUT();
if (rssi.enabled()) {
logger.Log_Write_RSSI(rssi);
logger.Write_RSSI(rssi);
}
}

Expand Down Expand Up @@ -343,7 +343,7 @@ void Rover::Log_Write_Vehicle_Startup_Messages()
{
// only 200(?) bytes are guaranteed by AP_Logger
Log_Write_Startup(TYPE_GROUNDSTART_MSG);
logger.Log_Write_Mode(control_mode->mode_number(), control_mode_reason);
logger.Write_Mode(control_mode->mode_number(), control_mode_reason);
ahrs.Log_Write_Home_And_Origin();
gps.Write_AP_Logger_Log_Startup_messages();
}
Expand Down
2 changes: 1 addition & 1 deletion APMrover2/commands.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)) {
logger.Log_Write_Mission_Cmd(mode_auto.mission, temp_cmd);
logger.Write_Mission_Cmd(mode_auto.mission, temp_cmd);
}
}
}
Expand Down
2 changes: 1 addition & 1 deletion APMrover2/commands_logic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.logger.Log_Write_Mission_Cmd(mission, cmd);
rover.logger.Write_Mission_Cmd(mission, cmd);
}

gcs().send_text(MAV_SEVERITY_INFO, "Executing %s(ID=%i)",
Expand Down
2 changes: 1 addition & 1 deletion APMrover2/cruise_learn.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ void Rover::cruise_learn_complete()
// logging for cruise learn
void Rover::log_write_cruise_learn()
{
AP_Logger::instance()->Log_Write("CRSE", "TimeUS,State,Speed,Throttle", "Qbff",
AP::logger().Write("CRSE", "TimeUS,State,Speed,Throttle", "Qbff",
AP_HAL::micros64,
cruise_learn.learn_start_ms > 0,
cruise_learn.speed_filt.get(),
Expand Down
2 changes: 1 addition & 1 deletion APMrover2/sensors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ void Rover::update_visual_odom()
visual_odom_last_update_ms,
g2.visual_odom.get_pos_offset());
// log sensor data
logger.Log_Write_VisualOdom(time_delta_sec,
logger.Write_VisualOdom(time_delta_sec,
g2.visual_odom.get_angle_delta(),
g2.visual_odom.get_position_delta(),
g2.visual_odom.get_confidence());
Expand Down
4 changes: 2 additions & 2 deletions APMrover2/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -185,7 +185,7 @@ void Rover::startup_ground(void)

// initialise AP_Logger library
#if LOGGING_ENABLED == ENABLED
logger.setVehicle_Startup_Log_Writer(
logger.setVehicle_Startup_Writer(
FUNCTOR_BIND(&rover, &Rover::Log_Write_Vehicle_Startup_Messages, void)
);
#endif
Expand Down Expand Up @@ -262,7 +262,7 @@ bool Rover::set_mode(Mode &new_mode, mode_reason_t reason)
old_mode.exit();

control_mode_reason = reason;
logger.Log_Write_Mode(control_mode->mode_number(), control_mode_reason);
logger.Write_Mode(control_mode->mode_number(), control_mode_reason);

notify_mode(control_mode);
return true;
Expand Down
6 changes: 3 additions & 3 deletions AntennaTracker/AntennaTracker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,16 +123,16 @@ void Tracker::one_second_loop()
void Tracker::ten_hz_logging_loop()
{
if (should_log(MASK_LOG_IMU)) {
logger.Log_Write_IMU();
logger.Write_IMU();
}
if (should_log(MASK_LOG_ATTITUDE)) {
Log_Write_Attitude();
}
if (should_log(MASK_LOG_RCIN)) {
logger.Log_Write_RCIN();
logger.Write_RCIN();
}
if (should_log(MASK_LOG_RCOUT)) {
logger.Log_Write_RCOUT();
logger.Write_RCOUT();
}
}

Expand Down
10 changes: 5 additions & 5 deletions AntennaTracker/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
logger.Log_Write_Attitude(ahrs, targets);
logger.Log_Write_EKF(ahrs);
logger.Log_Write_AHRS2(ahrs);
logger.Write_Attitude(ahrs, targets);
logger.Write_EKF(ahrs);
logger.Write_AHRS2(ahrs);
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
sitl.Log_Write_SIMSTATE();
#endif
logger.Log_Write_POS(ahrs);
logger.Write_POS(ahrs);
}

struct PACKED log_Vehicle_Baro {
Expand Down Expand Up @@ -78,7 +78,7 @@ const struct LogStructure Tracker::log_structure[] = {

void Tracker::Log_Write_Vehicle_Startup_Messages()
{
logger.Log_Write_Mode(control_mode, MODE_REASON_INITIALISED);
logger.Write_Mode(control_mode, MODE_REASON_INITIALISED);
gps.Write_AP_Logger_Log_Startup_messages();
}

Expand Down
2 changes: 1 addition & 1 deletion AntennaTracker/sensors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)) {
logger.Log_Write_Compass();
logger.Write_Compass();
}
}
}
Expand Down
4 changes: 2 additions & 2 deletions AntennaTracker/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ void Tracker::init_tracker()
barometer.calibrate();

// initialise AP_Logger library
logger.setVehicle_Startup_Log_Writer(FUNCTOR_BIND(&tracker, &Tracker::Log_Write_Vehicle_Startup_Messages, void));
logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&tracker, &Tracker::Log_Write_Vehicle_Startup_Messages, void));

// set serial ports non-blocking
serial_manager.set_blocking_writes_all(false);
Expand Down Expand Up @@ -207,7 +207,7 @@ void Tracker::set_mode(enum ControlMode mode, mode_reason_t reason)
}

// log mode change
logger.Log_Write_Mode(control_mode, reason);
logger.Write_Mode(control_mode, reason);
}

/*
Expand Down
16 changes: 8 additions & 8 deletions ArduCopter/ArduCopter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()) {
logger.Log_Write_Compass();
logger.Write_Compass();
}
}
}
Expand All @@ -339,27 +339,27 @@ void Copter::ten_hz_logging_loop()
Log_Write_MotBatt();
}
if (should_log(MASK_LOG_RCIN)) {
logger.Log_Write_RCIN();
logger.Write_RCIN();
if (rssi.enabled()) {
logger.Log_Write_RSSI(rssi);
logger.Write_RSSI(rssi);
}
}
if (should_log(MASK_LOG_RCOUT)) {
logger.Log_Write_RCOUT();
logger.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)) {
logger.Log_Write_Vibration();
logger.Write_Vibration();
}
if (should_log(MASK_LOG_CTUN)) {
attitude_control->control_monitor_log();
#if PROXIMITY_ENABLED == ENABLED
logger.Log_Write_Proximity(g2.proximity); // Write proximity sensor distances
logger.Write_Proximity(g2.proximity); // Write proximity sensor distances
#endif
#if BEACON_ENABLED == ENABLED
logger.Log_Write_Beacon(g2.beacon);
logger.Write_Beacon(g2.beacon);
#endif
}
#if FRAME_CONFIG == HELI_FRAME
Expand All @@ -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)) {
logger.Log_Write_IMU();
logger.Write_IMU();
}
#endif

Expand Down
24 changes: 12 additions & 12 deletions ArduCopter/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
logger.Log_Write_Attitude(ahrs, targets);
logger.Log_Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control);
logger.Write_Attitude(ahrs, targets);
logger.Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control);
if (should_log(MASK_LOG_PID)) {
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() );
logger.Write_PID(LOG_PIDR_MSG, attitude_control->get_rate_roll_pid().get_pid_info());
logger.Write_PID(LOG_PIDP_MSG, attitude_control->get_rate_pitch_pid().get_pid_info());
logger.Write_PID(LOG_PIDY_MSG, attitude_control->get_rate_yaw_pid().get_pid_info());
logger.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()
{
logger.Log_Write_EKF(ahrs);
logger.Log_Write_AHRS2(ahrs);
logger.Write_EKF(ahrs);
logger.Write_AHRS2(ahrs);
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
sitl.Log_Write_SIMSTATE();
#endif
logger.Log_Write_POS(ahrs);
logger.Write_POS(ahrs);
}

struct PACKED log_MotBatt {
Expand Down Expand Up @@ -453,10 +453,10 @@ const struct LogStructure Copter::log_structure[] = {
void Copter::Log_Write_Vehicle_Startup_Messages()
{
// 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);
logger.Write_MessageF("Frame: %s", get_frame_string());
logger.Write_Mode(control_mode, control_mode_reason);
#if AC_RALLY
logger.Log_Write_Rally(rally);
logger.Write_Rally(rally);
#endif
ahrs.Log_Write_Home_And_Origin();
gps.Write_AP_Logger_Log_Startup_messages();
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/commands.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)) {
logger.Log_Write_Mission_Cmd(mode_auto.mission, temp_cmd);
logger.Write_Mission_Cmd(mode_auto.mission, temp_cmd);
}
}
#endif
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/crash_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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:
AP_Logger::instance()->set_force_log_disarmed(true);
AP::logger().set_force_log_disarmed(true);
// send message to gcs
gcs().send_text(MAV_SEVERITY_EMERGENCY,"Crash: Disarming");
// disarm motors
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
logger.Log_Write_Mode(control_mode, reason);
logger.Write_Mode(control_mode, reason);

#if ADSB_ENABLED == ENABLED
adsb.set_is_auto_mode((mode == AUTO) || (mode == RTL) || (mode == GUIDED));
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.logger.Log_Write_Mission_Cmd(mission, cmd);
copter.logger.Write_Mission_Cmd(mission, cmd);
}

switch(cmd.id) {
Expand Down
6 changes: 3 additions & 3 deletions ArduCopter/mode_autotune.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,9 +114,9 @@ void Copter::AutoTune::init_z_limits()

void Copter::AutoTune::log_pids()
{
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());
copter.logger.Write_PID(LOG_PIDR_MSG, copter.attitude_control->get_rate_roll_pid().get_pid_info());
copter.logger.Write_PID(LOG_PIDP_MSG, copter.attitude_control->get_rate_pitch_pid().get_pid_info());
copter.logger.Write_PID(LOG_PIDY_MSG, copter.attitude_control->get_rate_yaw_pid().get_pid_info());
}


Expand Down
Loading

0 comments on commit 6fc76a3

Please sign in to comment.