mirror of https://github.com/ArduPilot/ardupilot
GLOBAL: use AP::logger() and strip redundant Log_ from methods
This commit is contained in:
parent
8e2a229e5d
commit
6fc76a32af
|
@ -177,7 +177,7 @@ void Rover::ahrs_update()
|
|||
}
|
||||
|
||||
if (should_log(MASK_LOG_IMU)) {
|
||||
logger.Log_Write_IMU();
|
||||
logger.Write_IMU();
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -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();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -221,7 +221,7 @@ 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)) {
|
||||
|
@ -229,7 +229,7 @@ void Rover::update_logging1(void)
|
|||
}
|
||||
|
||||
if (should_log(MASK_LOG_RANGEFINDER)) {
|
||||
logger.Log_Write_Proximity(g2.proximity);
|
||||
logger.Write_Proximity(g2.proximity);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -248,7 +248,7 @@ void Rover::update_logging2(void)
|
|||
}
|
||||
|
||||
if (should_log(MASK_LOG_IMU)) {
|
||||
logger.Log_Write_Vibration();
|
||||
logger.Write_Vibration();
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -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();
|
||||
|
@ -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,
|
||||
|
@ -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,
|
||||
|
@ -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);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -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();
|
||||
}
|
||||
|
|
|
@ -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);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -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)",
|
||||
|
|
|
@ -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(),
|
||||
|
|
|
@ -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());
|
||||
|
|
|
@ -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
|
||||
|
@ -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;
|
||||
|
|
|
@ -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();
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -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 {
|
||||
|
@ -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();
|
||||
}
|
||||
|
||||
|
|
|
@ -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();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -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);
|
||||
|
@ -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);
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -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();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -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
|
||||
|
@ -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
|
||||
|
||||
|
|
|
@ -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 {
|
||||
|
@ -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();
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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));
|
||||
|
|
|
@ -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) {
|
||||
|
|
|
@ -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());
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -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) {
|
||||
AP_Logger::instance()->Log_Write("FHLD", "TimeUS,SFx,SFy,Ax,Ay,Qual,Ix,Iy", "Qfffffff",
|
||||
AP::logger().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;
|
||||
|
||||
AP_Logger::instance()->Log_Write("FXY", "TimeUS,DFx,DFy,DVx,DVy,Hest,DH,Hofs,InsH,LastInsH,DTms", "QfffffffffI",
|
||||
AP::logger().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,
|
||||
|
|
|
@ -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();
|
||||
AP_Logger::instance()->Log_Write(
|
||||
AP::logger().Write(
|
||||
"THRO",
|
||||
"TimeUS,Stage,Vel,VelZ,Acc,AccEfZ,Throw,AttOk,HgtOk,PosOk",
|
||||
"s-nnoo----",
|
||||
|
|
|
@ -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.)
|
||||
AP_Logger::instance()->set_vehicle_armed(true);
|
||||
AP::logger().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
|
||||
logger.Log_Write_Mode(control_mode, control_mode_reason);
|
||||
logger.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
|
||||
|
||||
AP_Logger::instance()->set_vehicle_armed(false);
|
||||
AP::logger().set_vehicle_armed(false);
|
||||
|
||||
// disable gps velocity based centrefugal force compensation
|
||||
ahrs.set_correct_centrifugal(false);
|
||||
|
|
|
@ -27,7 +27,7 @@ void Copter::read_rangefinder(void)
|
|||
|
||||
if (rangefinder.num_sensors() > 0 &&
|
||||
should_log(MASK_LOG_CTUN)) {
|
||||
logger.Log_Write_RFND(rangefinder);
|
||||
logger.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)) {
|
||||
logger.Log_Write_RPM(rpm_sensor);
|
||||
logger.Write_RPM(rpm_sensor);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
@ -418,7 +418,7 @@ void Copter::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());
|
||||
|
|
|
@ -240,7 +240,7 @@ void Copter::init_ardupilot()
|
|||
#endif
|
||||
|
||||
// initialise AP_Logger library
|
||||
logger.setVehicle_Startup_Log_Writer(FUNCTOR_BIND(&copter, &Copter::Log_Write_Vehicle_Startup_Messages, void));
|
||||
logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&copter, &Copter::Log_Write_Vehicle_Startup_Messages, void));
|
||||
|
||||
// initialise rc channels including setting mode
|
||||
rc().init();
|
||||
|
|
|
@ -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) {
|
||||
AP_Logger::instance()->Log_Write("THST", "TimeUS,Vol,Mul,M1,M2,M3,M4", "QffHHHH",
|
||||
AP::logger().Write("THST", "TimeUS,Vol,Mul,M1,M2,M3,M4", "QffHHHH",
|
||||
AP_HAL::micros64(),
|
||||
(double)filtered_voltage,
|
||||
(double)thrust_mul,
|
||||
|
|
|
@ -148,7 +148,7 @@ void Plane::ahrs_update()
|
|||
ahrs.update();
|
||||
|
||||
if (should_log(MASK_LOG_IMU)) {
|
||||
logger.Log_Write_IMU();
|
||||
logger.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()) {
|
||||
logger.Log_Write_Compass();
|
||||
logger.Write_Compass();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -210,10 +210,10 @@ void Plane::update_logging1(void)
|
|||
}
|
||||
|
||||
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_IMU))
|
||||
logger.Log_Write_IMU();
|
||||
logger.Write_IMU();
|
||||
|
||||
if (should_log(MASK_LOG_ATTITUDE_MED))
|
||||
logger.Log_Write_AOA_SSA(ahrs);
|
||||
logger.Write_AOA_SSA(ahrs);
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -231,7 +231,7 @@ void Plane::update_logging2(void)
|
|||
Log_Write_RC();
|
||||
|
||||
if (should_log(MASK_LOG_IMU))
|
||||
logger.Log_Write_Vibration();
|
||||
logger.Write_Vibration();
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -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();
|
||||
logger.Log_Write_AttitudeView(*quadplane.ahrs_view, targets);
|
||||
logger.Write_AttitudeView(*quadplane.ahrs_view, targets);
|
||||
} else {
|
||||
logger.Log_Write_Attitude(ahrs, targets);
|
||||
logger.Write_Attitude(ahrs, targets);
|
||||
}
|
||||
if (quadplane.in_vtol_mode() || quadplane.in_assisted_flight()) {
|
||||
// log quadplane PIDs separately from fixed wing PIDs
|
||||
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() );
|
||||
logger.Write_PID(LOG_PIQR_MSG, quadplane.attitude_control->get_rate_roll_pid().get_pid_info());
|
||||
logger.Write_PID(LOG_PIQP_MSG, quadplane.attitude_control->get_rate_pitch_pid().get_pid_info());
|
||||
logger.Write_PID(LOG_PIQY_MSG, quadplane.attitude_control->get_rate_yaw_pid().get_pid_info());
|
||||
logger.Write_PID(LOG_PIQA_MSG, quadplane.pos_control->get_accel_z_pid().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());
|
||||
logger.Write_PID(LOG_PIDR_MSG, rollController.get_pid_info());
|
||||
logger.Write_PID(LOG_PIDP_MSG, pitchController.get_pid_info());
|
||||
logger.Write_PID(LOG_PIDY_MSG, yawController.get_pid_info());
|
||||
logger.Write_PID(LOG_PIDS_MSG, steerController.get_pid_info());
|
||||
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
logger.Log_Write_EKF(ahrs);
|
||||
logger.Log_Write_AHRS2(ahrs);
|
||||
logger.Write_EKF(ahrs);
|
||||
logger.Write_AHRS2(ahrs);
|
||||
#endif
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
sitl.Log_Write_SIMSTATE();
|
||||
#endif
|
||||
logger.Log_Write_POS(ahrs);
|
||||
logger.Write_POS(ahrs);
|
||||
}
|
||||
|
||||
// do logging at loop rate
|
||||
|
@ -204,7 +204,7 @@ void Plane::Log_Write_Sonar()
|
|||
};
|
||||
logger.WriteBlock(&pkt, sizeof(pkt));
|
||||
|
||||
logger.Log_Write_RFND(rangefinder);
|
||||
logger.Write_RFND(rangefinder);
|
||||
}
|
||||
|
||||
struct PACKED log_Arm_Disarm {
|
||||
|
@ -252,10 +252,10 @@ void Plane::Log_Write_AETR()
|
|||
|
||||
void Plane::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);
|
||||
}
|
||||
Log_Write_AETR();
|
||||
}
|
||||
|
@ -299,8 +299,8 @@ void Plane::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, control_mode_reason);
|
||||
logger.Log_Write_Rally(rally);
|
||||
logger.Write_Mode(control_mode, control_mode_reason);
|
||||
logger.Write_Rally(rally);
|
||||
ahrs.Log_Write_Home_And_Origin();
|
||||
gps.Write_AP_Logger_Log_Startup_messages();
|
||||
}
|
||||
|
|
|
@ -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)) {
|
||||
logger.Log_Write_Mission_Cmd(mission, cmd);
|
||||
logger.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();
|
||||
|
||||
logger.Log_Write_Mode(control_mode, control_mode_reason);
|
||||
logger.Write_Mode(control_mode, control_mode_reason);
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -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;
|
||||
AP_Logger::instance()->Log_Write(
|
||||
AP::logger().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)
|
||||
{
|
||||
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());
|
||||
AP::logger().Write_PID(LOG_PIQR_MSG, plane.quadplane.attitude_control->get_rate_roll_pid().get_pid_info());
|
||||
AP::logger().Write_PID(LOG_PIQP_MSG, plane.quadplane.attitude_control->get_rate_pitch_pid().get_pid_info());
|
||||
AP::logger().Write_PID(LOG_PIQY_MSG, plane.quadplane.attitude_control->get_rate_yaw_pid().get_pid_info());
|
||||
}
|
||||
|
||||
#endif // QAUTOTUNE_ENABLED
|
||||
|
|
|
@ -1643,7 +1643,7 @@ void QuadPlane::motors_output(bool run_rate_controller)
|
|||
|
||||
motors->output();
|
||||
if (motors->armed() && motors->get_throttle() > 0) {
|
||||
plane.logger.Log_Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control);
|
||||
plane.logger.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) {
|
||||
|
|
|
@ -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)) {
|
||||
logger.Log_Write_RPM(rpm_sensor);
|
||||
logger.Write_RPM(rpm_sensor);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -249,7 +249,7 @@ void Plane::startup_ground(void)
|
|||
|
||||
// initialise AP_Logger library
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
logger.setVehicle_Startup_Log_Writer(
|
||||
logger.setVehicle_Startup_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);
|
||||
|
||||
logger.Log_Write_Mode(control_mode, control_mode_reason);
|
||||
logger.Write_Mode(control_mode, control_mode_reason);
|
||||
|
||||
// update notify with flight mode change
|
||||
notify_flight_mode(control_mode);
|
||||
|
|
|
@ -173,7 +173,7 @@ void Sub::update_batt_compass()
|
|||
compass.read();
|
||||
// log compass information
|
||||
if (should_log(MASK_LOG_COMPASS) && !ahrs.have_ekf_logging()) {
|
||||
logger.Log_Write_Compass();
|
||||
logger.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();
|
||||
logger.Log_Write_Rate(&ahrs_view, motors, attitude_control, pos_control);
|
||||
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());
|
||||
}
|
||||
}
|
||||
if (should_log(MASK_LOG_MOTBATT)) {
|
||||
Log_Write_MotBatt();
|
||||
}
|
||||
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();
|
||||
}
|
||||
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)) {
|
||||
logger.Log_Write_Vibration();
|
||||
logger.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();
|
||||
logger.Log_Write_Rate(&ahrs_view, motors, attitude_control, pos_control);
|
||||
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());
|
||||
}
|
||||
}
|
||||
|
||||
// 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();
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -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);
|
||||
logger.Log_Write_Attitude(ahrs, targets);
|
||||
logger.Write_Attitude(ahrs, targets);
|
||||
|
||||
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 {
|
||||
|
@ -309,7 +309,7 @@ const struct LogStructure Sub::log_structure[] = {
|
|||
void Sub::Log_Write_Vehicle_Startup_Messages()
|
||||
{
|
||||
// only 200(?) bytes are guaranteed by AP_Logger
|
||||
logger.Log_Write_Mode(control_mode, control_mode_reason);
|
||||
logger.Write_Mode(control_mode, control_mode_reason);
|
||||
ahrs.Log_Write_Home_And_Origin();
|
||||
gps.Write_AP_Logger_Log_Startup_messages();
|
||||
}
|
||||
|
|
|
@ -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)) {
|
||||
logger.Log_Write_Mission_Cmd(mission, temp_cmd);
|
||||
logger.Write_Mission_Cmd(mission, temp_cmd);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -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)) {
|
||||
logger.Log_Write_Mission_Cmd(mission, cmd);
|
||||
logger.Write_Mission_Cmd(mission, cmd);
|
||||
}
|
||||
|
||||
const Location &target_loc = cmd.content.location;
|
||||
|
|
|
@ -70,7 +70,7 @@ bool Sub::set_mode(control_mode_t mode, mode_reason_t reason)
|
|||
|
||||
control_mode = mode;
|
||||
control_mode_reason = reason;
|
||||
logger.Log_Write_Mode(control_mode, control_mode_reason);
|
||||
logger.Write_Mode(control_mode, control_mode_reason);
|
||||
|
||||
// update notify object
|
||||
notify_flight_mode(control_mode);
|
||||
|
|
|
@ -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.)
|
||||
AP_Logger::instance()->set_vehicle_armed(true);
|
||||
AP::logger().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
|
||||
logger.Log_Write_Mode(control_mode, control_mode_reason);
|
||||
logger.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();
|
||||
|
||||
AP_Logger::instance()->set_vehicle_armed(false);
|
||||
AP::logger().set_vehicle_armed(false);
|
||||
|
||||
// disable gps velocity based centrefugal force compensation
|
||||
ahrs.set_correct_centrifugal(false);
|
||||
|
|
|
@ -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)) {
|
||||
logger.Log_Write_RPM(rpm_sensor);
|
||||
logger.Write_RPM(rpm_sensor);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -187,7 +187,7 @@ void Sub::init_ardupilot()
|
|||
|
||||
// initialise AP_Logger library
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
logger.setVehicle_Startup_Log_Writer(FUNCTOR_BIND(&sub, &Sub::Log_Write_Vehicle_Startup_Messages, void));
|
||||
logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&sub, &Sub::Log_Write_Vehicle_Startup_Messages, void));
|
||||
#endif
|
||||
|
||||
startup_INS_ground();
|
||||
|
|
|
@ -214,7 +214,7 @@ uint8_t LogReader::map_fmt_type(const char *name, uint8_t intype)
|
|||
if (already_mapped) {
|
||||
continue;
|
||||
}
|
||||
if (AP_Logger::instance()->msg_type_in_use(n)) {
|
||||
if (AP::logger().msg_type_in_use(n)) {
|
||||
continue;
|
||||
}
|
||||
mapped_msgid[intype] = n;
|
||||
|
|
|
@ -614,13 +614,13 @@ void Replay::set_signal_handlers(void)
|
|||
void Replay::write_ekf_logs(void)
|
||||
{
|
||||
if (!LogReader::in_list("EKF", nottypes)) {
|
||||
_vehicle.dataflash.Log_Write_EKF(_vehicle.ahrs);
|
||||
_vehicle.dataflash.Write_EKF(_vehicle.ahrs);
|
||||
}
|
||||
if (!LogReader::in_list("AHRS2", nottypes)) {
|
||||
_vehicle.dataflash.Log_Write_AHRS2(_vehicle.ahrs);
|
||||
_vehicle.dataflash.Write_AHRS2(_vehicle.ahrs);
|
||||
}
|
||||
if (!LogReader::in_list("POS", nottypes)) {
|
||||
_vehicle.dataflash.Log_Write_POS(_vehicle.ahrs);
|
||||
_vehicle.dataflash.Write_POS(_vehicle.ahrs);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -728,7 +728,7 @@ void Replay::log_check_generate(void)
|
|||
_vehicle.EKF2.getVelNED(-1,velocity);
|
||||
_vehicle.EKF2.getLLH(loc);
|
||||
|
||||
_vehicle.dataflash.Log_Write(
|
||||
_vehicle.dataflash.Write(
|
||||
"CHEK",
|
||||
"TimeUS,Roll,Pitch,Yaw,Lat,Lng,Alt,VN,VE,VD",
|
||||
"sdddDUmnnn",
|
||||
|
|
|
@ -838,7 +838,7 @@ void AC_PosControl::write_log()
|
|||
float accel_x, accel_y;
|
||||
lean_angles_to_accel(accel_x, accel_y);
|
||||
|
||||
AP_Logger::instance()->Log_Write("PSC", "TimeUS,TPX,TPY,PX,PY,TVX,TVY,VX,VY,TAX,TAY,AX,AY",
|
||||
AP::logger().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,
|
||||
|
|
|
@ -41,7 +41,7 @@ void AC_AttitudeControl::control_monitor_update(void)
|
|||
*/
|
||||
void AC_AttitudeControl::control_monitor_log(void)
|
||||
{
|
||||
AP_Logger::instance()->Log_Write("CTRL", "TimeUS,RMSRollP,RMSRollD,RMSPitchP,RMSPitchD,RMSYaw", "Qfffff",
|
||||
AP::logger().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),
|
||||
|
|
|
@ -661,7 +661,7 @@ void AC_AutoTune::control_attitude()
|
|||
|
||||
// log this iterations lean angle and rotation rate
|
||||
Log_Write_AutoTuneDetails(lean_angle, rotation_rate);
|
||||
AP_Logger::instance()->Log_Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control);
|
||||
AP::logger().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)
|
||||
{
|
||||
AP_Logger::instance()->Log_Write(
|
||||
AP::logger().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)
|
||||
{
|
||||
AP_Logger::instance()->Log_Write(
|
||||
AP::logger().Write(
|
||||
"ATDE",
|
||||
"TimeUS,Angle,Rate",
|
||||
"sdk",
|
||||
|
|
|
@ -279,7 +279,7 @@ void AP_AutoTune::log_param_change(float v, const char *suffix)
|
|||
strncpy(&key[9], suffix, AP_MAX_NAME_SIZE-9);
|
||||
}
|
||||
key[AP_MAX_NAME_SIZE] = 0;
|
||||
dataflash->Log_Write_Parameter(key, v);
|
||||
dataflash->Write_Parameter(key, v);
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -483,13 +483,13 @@ void AP_AHRS::Log_Write_Home_And_Origin()
|
|||
// log ekf origin if set
|
||||
Location ekf_orig;
|
||||
if (get_origin(ekf_orig)) {
|
||||
df->Log_Write_Origin(LogOriginType::ekf_origin, ekf_orig);
|
||||
df->Write_Origin(LogOriginType::ekf_origin, ekf_orig);
|
||||
}
|
||||
#endif
|
||||
|
||||
// log ahrs home if set
|
||||
if (home_is_set()) {
|
||||
df->Log_Write_Origin(LogOriginType::ahrs_home, _home);
|
||||
df->Write_Origin(LogOriginType::ahrs_home, _home);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -430,7 +430,7 @@ void AP_Airspeed::update(bool log)
|
|||
if (log) {
|
||||
AP_Logger *_dataflash = AP_Logger::instance();
|
||||
if (_dataflash != nullptr) {
|
||||
_dataflash->Log_Write_Airspeed(*this);
|
||||
_dataflash->Write_Airspeed(*this);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -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 (AP_Logger::instance()->logging_failed()) {
|
||||
if (AP::logger().logging_failed()) {
|
||||
check_failed(ARMING_CHECK_LOGGING, report, "Logging failed");
|
||||
return false;
|
||||
}
|
||||
if (!AP_Logger::instance()->CardInserted()) {
|
||||
if (!AP::logger().CardInserted()) {
|
||||
check_failed(ARMING_CHECK_LOGGING, report, "No SD card");
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -816,7 +816,7 @@ void AP_Baro::update(void)
|
|||
|
||||
// logging
|
||||
if (should_df_log() && !AP::ahrs().have_ekf_logging()) {
|
||||
AP_Logger::instance()->Log_Write_Baro();
|
||||
AP::logger().Write_Baro();
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -343,7 +343,7 @@ void AP_Baro_ICM20789::update()
|
|||
{
|
||||
#if BARO_ICM20789_DEBUG
|
||||
// useful for debugging
|
||||
AP_Logger::instance()->Log_Write("ICMB", "TimeUS,Traw,Praw,P,T", "QIIff",
|
||||
AP::logger().Write("ICMB", "TimeUS,Traw,Praw,P,T", "QIIff",
|
||||
AP_HAL::micros64(),
|
||||
dd.Traw, dd.Praw, dd.P, dd.T);
|
||||
#endif
|
||||
|
|
|
@ -239,8 +239,8 @@ AP_BattMonitor::read()
|
|||
|
||||
AP_Logger *df = AP_Logger::instance();
|
||||
if (df->should_log(_log_battery_bit)) {
|
||||
df->Log_Write_Current();
|
||||
df->Log_Write_Power();
|
||||
df->Write_Current();
|
||||
df->Write_Power();
|
||||
}
|
||||
|
||||
check_failsafes();
|
||||
|
|
|
@ -397,11 +397,11 @@ void AP_Camera::log_picture()
|
|||
if (!using_feedback_pin()) {
|
||||
gcs().send_message(MSG_CAMERA_FEEDBACK);
|
||||
if (df->should_log(log_camera_bit)) {
|
||||
df->Log_Write_Camera(ahrs, current_loc);
|
||||
df->Write_Camera(ahrs, current_loc);
|
||||
}
|
||||
} else {
|
||||
if (df->should_log(log_camera_bit)) {
|
||||
df->Log_Write_Trigger(ahrs, current_loc);
|
||||
df->Write_Trigger(ahrs, current_loc);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -442,7 +442,7 @@ void AP_Camera::update_trigger()
|
|||
if (df->should_log(log_camera_bit)) {
|
||||
uint32_t tdiff = AP_HAL::micros() - timestamp32;
|
||||
uint64_t timestamp = AP_HAL::micros64();
|
||||
df->Log_Write_Camera(ahrs, current_loc, timestamp - tdiff);
|
||||
df->Write_Camera(ahrs, current_loc, timestamp - tdiff);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -224,7 +224,7 @@ void AP_Compass_MMC3416::timer()
|
|||
}
|
||||
|
||||
#if 0
|
||||
AP_Logger::instance()->Log_Write("MMO", "TimeUS,Nx,Ny,Nz,Ox,Oy,Oz", "Qffffff",
|
||||
AP::logger().Write("MMO", "TimeUS,Nx,Ny,Nz,Ox,Oy,Oz", "Qffffff",
|
||||
AP_HAL::micros64(),
|
||||
(double)new_offset.x,
|
||||
(double)new_offset.y,
|
||||
|
|
|
@ -104,7 +104,7 @@ void CompassLearn::update(void)
|
|||
}
|
||||
|
||||
if (sample_available) {
|
||||
AP_Logger::instance()->Log_Write("COFS", "TimeUS,OfsX,OfsY,OfsZ,Var,Yaw,WVar,N", "QffffffI",
|
||||
AP::logger().Write("COFS", "TimeUS,OfsX,OfsY,OfsZ,Var,Yaw,WVar,N", "QffffffI",
|
||||
AP_HAL::micros64(),
|
||||
(double)best_offsets.x,
|
||||
(double)best_offsets.y,
|
||||
|
|
|
@ -307,7 +307,7 @@ void AP_Follow::handle_msg(const mavlink_message_t &msg)
|
|||
}
|
||||
|
||||
// log lead's estimated vs reported position
|
||||
AP_Logger::instance()->Log_Write("FOLL",
|
||||
AP::logger().Write("FOLL",
|
||||
"TimeUS,Lat,Lon,Alt,VelN,VelE,VelD,LatE,LonE,AltE", // labels
|
||||
"sDUmnnnDUm", // units
|
||||
"F--B000--B", // mults
|
||||
|
|
|
@ -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()) {
|
||||
AP_Logger::instance()->Log_Write_GPS(instance);
|
||||
AP::logger().Write_GPS(instance);
|
||||
}
|
||||
|
||||
if (state[instance].status >= GPS_OK_FIX_3D) {
|
||||
|
|
|
@ -260,7 +260,7 @@ AP_GPS_SBF::log_ExtEventPVTGeodetic(const msg4007 &temp)
|
|||
COG:temp.COG
|
||||
};
|
||||
|
||||
AP_Logger::instance()->WriteBlock(&header, sizeof(header));
|
||||
AP::logger().WriteBlock(&header, sizeof(header));
|
||||
}
|
||||
|
||||
bool
|
||||
|
|
|
@ -404,7 +404,7 @@ AP_GPS_SBP::logging_log_full_update()
|
|||
last_iar_num_hypotheses : last_iar_num_hypotheses,
|
||||
};
|
||||
|
||||
AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt));
|
||||
AP::logger().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));
|
||||
AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt));
|
||||
AP::logger().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));
|
||||
AP_Logger::instance()->WriteBlock(&pkt2, sizeof(pkt2));
|
||||
AP::logger().WriteBlock(&pkt2, sizeof(pkt2));
|
||||
}
|
||||
};
|
||||
|
||||
|
|
|
@ -454,7 +454,7 @@ AP_GPS_SBP2::logging_log_full_update()
|
|||
last_injected_data_ms : last_injected_data_ms,
|
||||
last_iar_num_hypotheses : 0,
|
||||
};
|
||||
AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt));
|
||||
AP::logger().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));
|
||||
AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt));
|
||||
AP::logger().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));
|
||||
AP_Logger::instance()->WriteBlock(&pkt2, sizeof(pkt2));
|
||||
AP::logger().WriteBlock(&pkt2, sizeof(pkt2));
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -520,5 +520,5 @@ AP_GPS_SBP2::logging_ext_event() {
|
|||
level : last_event.flags.level,
|
||||
quality : last_event.flags.quality,
|
||||
};
|
||||
AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt));
|
||||
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
||||
};
|
||||
|
|
|
@ -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;
|
||||
}
|
||||
AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt));
|
||||
AP::logger().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,
|
||||
};
|
||||
AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt));
|
||||
AP::logger().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
|
||||
};
|
||||
AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt));
|
||||
AP::logger().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
|
||||
};
|
||||
AP_Logger::instance()->WriteBlock(&header, sizeof(header));
|
||||
AP::logger().WriteBlock(&header, sizeof(header));
|
||||
|
||||
for (uint8_t i=0; i<raw.numMeas; i++) {
|
||||
struct log_GPS_RAWS pkt = {
|
||||
|
@ -583,7 +583,7 @@ void AP_GPS_UBLOX::log_rxm_rawx(const struct ubx_rxm_rawx &raw)
|
|||
doStdev : raw.svinfo[i].doStdev,
|
||||
trkStat : raw.svinfo[i].trkStat
|
||||
};
|
||||
AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt));
|
||||
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
}
|
||||
#endif // UBLOX_RXM_RAW_LOGGING
|
||||
|
@ -1380,7 +1380,7 @@ void AP_GPS_UBLOX::Write_AP_Logger_Log_Startup_messages() const
|
|||
AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages();
|
||||
|
||||
if (_have_version) {
|
||||
AP_Logger::instance()->Log_Write_MessageF("u-blox %d HW: %s SW: %s",
|
||||
AP::logger().Write_MessageF("u-blox %d HW: %s SW: %s",
|
||||
state.instance+1,
|
||||
_version.hwVersion,
|
||||
_version.swVersion);
|
||||
|
|
|
@ -167,7 +167,7 @@ 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));
|
||||
AP_Logger::instance()->Log_Write_Message(buffer);
|
||||
AP::logger().Write_Message(buffer);
|
||||
}
|
||||
|
||||
bool AP_GPS_Backend::should_df_log() const
|
||||
|
|
|
@ -238,7 +238,7 @@ void Scheduler::reboot(bool hold_in_bootloader)
|
|||
|
||||
#ifndef NO_DATAFLASH
|
||||
//stop logging
|
||||
AP_Logger::instance()->StopLogging();
|
||||
AP::logger().StopLogging();
|
||||
|
||||
// stop sdcard driver, if active
|
||||
sdcard_stop();
|
||||
|
|
|
@ -199,7 +199,7 @@ void AP_InertialSensor::BatchSampler::push_data_to_log()
|
|||
}
|
||||
break;
|
||||
}
|
||||
if (!dataflash->Log_Write_ISBH(isb_seqnum,
|
||||
if (!dataflash->Write_ISBH(isb_seqnum,
|
||||
type,
|
||||
instance,
|
||||
multiplier,
|
||||
|
@ -212,7 +212,7 @@ void AP_InertialSensor::BatchSampler::push_data_to_log()
|
|||
isbh_sent = true;
|
||||
}
|
||||
// pack and send a data packet:
|
||||
if (!dataflash->Log_Write_ISBD(isb_seqnum,
|
||||
if (!dataflash->Write_ISBD(isb_seqnum,
|
||||
data_read_offset/samples_per_msg,
|
||||
&data_x[data_read_offset],
|
||||
&data_y[data_read_offset],
|
||||
|
|
|
@ -449,7 +449,7 @@ void AP_Landing_Deepstall::Log(void) const {
|
|||
I : pid_info.I,
|
||||
D : pid_info.D,
|
||||
};
|
||||
AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt));
|
||||
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
// termination handling, expected to set the servo outputs
|
||||
|
|
|
@ -383,7 +383,7 @@ bool AP_Landing::type_slope_is_complete(void) const
|
|||
void AP_Landing::type_slope_log(void) const
|
||||
{
|
||||
// log to AP_Logger
|
||||
AP_Logger::instance()->Log_Write("LAND", "TimeUS,stage,f1,f2,slope,slopeInit,altO", "QBBBfff",
|
||||
AP::logger().Write("LAND", "TimeUS,stage,f1,f2,slope,slopeInit,altO", "QBBBfff",
|
||||
AP_HAL::micros64(),
|
||||
type_slope_stage,
|
||||
flags,
|
||||
|
|
|
@ -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)
|
||||
{
|
||||
AP_Logger::instance()->Log_Write("LGR", "TimeUS,LandingGear,WeightOnWheels", "Qbb",
|
||||
AP::logger().Write("LGR", "TimeUS,LandingGear,WeightOnWheels", "Qbb",
|
||||
AP_HAL::micros64(),
|
||||
(int8_t)gear_state_current, (int8_t)state);
|
||||
}
|
||||
|
|
|
@ -289,7 +289,7 @@ bool AP_Logger::validate_structure(const struct LogStructure *logstructure, cons
|
|||
}
|
||||
|
||||
// check that the structure is of an appropriate length to take fields
|
||||
const int16_t msg_len = Log_Write_calc_msg_len(logstructure->format);
|
||||
const int16_t msg_len = Write_calc_msg_len(logstructure->format);
|
||||
if (msg_len != logstructure->msg_len) {
|
||||
Debug("Calculated message length for (%s) based on format field (%s) does not match structure size (%d != %u)", logstructure->name, logstructure->format, msg_len, logstructure->msg_len);
|
||||
passed = false;
|
||||
|
@ -429,7 +429,7 @@ bool AP_Logger::logging_failed() const
|
|||
return false;
|
||||
}
|
||||
|
||||
void AP_Logger::Log_Write_MessageF(const char *fmt, ...)
|
||||
void AP_Logger::Write_MessageF(const char *fmt, ...)
|
||||
{
|
||||
char msg[65] {}; // sizeof(log_Message.msg) + null-termination
|
||||
|
||||
|
@ -438,7 +438,7 @@ void AP_Logger::Log_Write_MessageF(const char *fmt, ...)
|
|||
hal.util->vsnprintf(msg, sizeof(msg), fmt, ap);
|
||||
va_end(ap);
|
||||
|
||||
Log_Write_Message(msg);
|
||||
Write_Message(msg);
|
||||
}
|
||||
|
||||
void AP_Logger::backend_starting_new_log(const AP_Logger_Backend *backend)
|
||||
|
@ -493,7 +493,7 @@ void AP_Logger::PrepForArming()
|
|||
FOR_EACH_BACKEND(PrepForArming());
|
||||
}
|
||||
|
||||
void AP_Logger::setVehicle_Startup_Log_Writer(vehicle_startup_message_Log_Writer writer)
|
||||
void AP_Logger::setVehicle_Startup_Writer(vehicle_startup_message_Writer writer)
|
||||
{
|
||||
_vehicle_messages = writer;
|
||||
}
|
||||
|
@ -622,30 +622,30 @@ void AP_Logger::flush(void) {
|
|||
#endif
|
||||
|
||||
|
||||
void AP_Logger::Log_Write_EntireMission(const AP_Mission &mission)
|
||||
void AP_Logger::Write_EntireMission(const AP_Mission &mission)
|
||||
{
|
||||
FOR_EACH_BACKEND(Log_Write_EntireMission(mission));
|
||||
FOR_EACH_BACKEND(Write_EntireMission(mission));
|
||||
}
|
||||
|
||||
void AP_Logger::Log_Write_Message(const char *message)
|
||||
void AP_Logger::Write_Message(const char *message)
|
||||
{
|
||||
FOR_EACH_BACKEND(Log_Write_Message(message));
|
||||
FOR_EACH_BACKEND(Write_Message(message));
|
||||
}
|
||||
|
||||
void AP_Logger::Log_Write_Mode(uint8_t mode, uint8_t reason)
|
||||
void AP_Logger::Write_Mode(uint8_t mode, uint8_t reason)
|
||||
{
|
||||
FOR_EACH_BACKEND(Log_Write_Mode(mode, reason));
|
||||
FOR_EACH_BACKEND(Write_Mode(mode, reason));
|
||||
}
|
||||
|
||||
void AP_Logger::Log_Write_Parameter(const char *name, float value)
|
||||
void AP_Logger::Write_Parameter(const char *name, float value)
|
||||
{
|
||||
FOR_EACH_BACKEND(Log_Write_Parameter(name, value));
|
||||
FOR_EACH_BACKEND(Write_Parameter(name, value));
|
||||
}
|
||||
|
||||
void AP_Logger::Log_Write_Mission_Cmd(const AP_Mission &mission,
|
||||
void AP_Logger::Write_Mission_Cmd(const AP_Mission &mission,
|
||||
const AP_Mission::Mission_Command &cmd)
|
||||
{
|
||||
FOR_EACH_BACKEND(Log_Write_Mission_Cmd(mission, cmd));
|
||||
FOR_EACH_BACKEND(Write_Mission_Cmd(mission, cmd));
|
||||
}
|
||||
|
||||
uint32_t AP_Logger::num_dropped() const
|
||||
|
@ -665,26 +665,26 @@ void AP_Logger::internal_error() const {
|
|||
#endif
|
||||
}
|
||||
|
||||
/* Log_Write support */
|
||||
void AP_Logger::Log_Write(const char *name, const char *labels, const char *fmt, ...)
|
||||
/* Write support */
|
||||
void AP_Logger::Write(const char *name, const char *labels, const char *fmt, ...)
|
||||
{
|
||||
va_list arg_list;
|
||||
|
||||
va_start(arg_list, fmt);
|
||||
Log_WriteV(name, labels, nullptr, nullptr, fmt, arg_list);
|
||||
WriteV(name, labels, nullptr, nullptr, fmt, arg_list);
|
||||
va_end(arg_list);
|
||||
}
|
||||
|
||||
void AP_Logger::Log_Write(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...)
|
||||
void AP_Logger::Write(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...)
|
||||
{
|
||||
va_list arg_list;
|
||||
|
||||
va_start(arg_list, fmt);
|
||||
Log_WriteV(name, labels, units, mults, fmt, arg_list);
|
||||
WriteV(name, labels, units, mults, fmt, arg_list);
|
||||
va_end(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)
|
||||
void AP_Logger::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) {
|
||||
|
@ -696,14 +696,14 @@ void AP_Logger::Log_WriteV(const char *name, const char *labels, const char *uni
|
|||
|
||||
for (uint8_t i=0; i<_next_backend; i++) {
|
||||
if (!(f->sent_mask & (1U<<i))) {
|
||||
if (!backends[i]->Log_Write_Emit_FMT(f->msg_type)) {
|
||||
if (!backends[i]->Write_Emit_FMT(f->msg_type)) {
|
||||
continue;
|
||||
}
|
||||
f->sent_mask |= (1U<<i);
|
||||
}
|
||||
va_list arg_copy;
|
||||
va_copy(arg_copy, arg_list);
|
||||
backends[i]->Log_Write(f->msg_type, arg_copy);
|
||||
backends[i]->Write(f->msg_type, arg_copy);
|
||||
va_end(arg_copy);
|
||||
}
|
||||
}
|
||||
|
@ -750,7 +750,7 @@ void AP_Logger::assert_same_fmt_for_name(const AP_Logger::log_write_fmt *f,
|
|||
passed = false;
|
||||
}
|
||||
if (!passed) {
|
||||
Debug("Format definition must be consistent for every call of Log_Write");
|
||||
Debug("Format definition must be consistent for every call of Write");
|
||||
abort();
|
||||
}
|
||||
}
|
||||
|
@ -786,7 +786,7 @@ AP_Logger::log_write_fmt *AP_Logger::msg_fmt_for_name(const char *name, const ch
|
|||
f->units = units;
|
||||
f->mults = mults;
|
||||
|
||||
int16_t tmp = Log_Write_calc_msg_len(fmt);
|
||||
int16_t tmp = Write_calc_msg_len(fmt);
|
||||
if (tmp == -1) {
|
||||
free(f);
|
||||
return nullptr;
|
||||
|
@ -937,7 +937,7 @@ bool AP_Logger::fill_log_write_logstructure(struct LogStructure &logstruct, cons
|
|||
* 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 AP_Logger::Log_Write_calc_msg_len(const char *fmt) const
|
||||
int16_t AP_Logger::Write_calc_msg_len(const char *fmt) const
|
||||
{
|
||||
uint8_t len = LOG_PACKET_HEADER_LEN;
|
||||
for (uint8_t i=0; i<strlen(fmt); i++) {
|
||||
|
@ -972,12 +972,12 @@ int16_t AP_Logger::Log_Write_calc_msg_len(const char *fmt) const
|
|||
return len;
|
||||
}
|
||||
|
||||
/* End of Log_Write support */
|
||||
/* End of Write support */
|
||||
|
||||
#undef FOR_EACH_BACKEND
|
||||
|
||||
// Write information about a series of IMU readings to log:
|
||||
bool AP_Logger::Log_Write_ISBH(const uint16_t seqno,
|
||||
bool AP_Logger::Write_ISBH(const uint16_t seqno,
|
||||
const AP_InertialSensor::IMU_SENSOR_TYPE sensor_type,
|
||||
const uint8_t sensor_instance,
|
||||
const uint16_t mult,
|
||||
|
@ -1010,7 +1010,7 @@ bool AP_Logger::Log_Write_ISBH(const uint16_t seqno,
|
|||
|
||||
|
||||
// Write a series of IMU readings to log:
|
||||
bool AP_Logger::Log_Write_ISBD(const uint16_t isb_seqno,
|
||||
bool AP_Logger::Write_ISBD(const uint16_t isb_seqno,
|
||||
const uint16_t seqno,
|
||||
const int16_t x[32],
|
||||
const int16_t y[32],
|
||||
|
|
|
@ -46,7 +46,7 @@ class AP_Logger
|
|||
friend class AP_Logger_Backend; // for _num_types
|
||||
|
||||
public:
|
||||
FUNCTOR_TYPEDEF(vehicle_startup_message_Log_Writer, void);
|
||||
FUNCTOR_TYPEDEF(vehicle_startup_message_Writer, void);
|
||||
|
||||
AP_Logger(const AP_Int32 &log_bitmask);
|
||||
|
||||
|
@ -78,7 +78,7 @@ public:
|
|||
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
|
||||
uint16_t get_num_logs(void);
|
||||
|
||||
void setVehicle_Startup_Log_Writer(vehicle_startup_message_Log_Writer writer);
|
||||
void setVehicle_Startup_Writer(vehicle_startup_message_Writer writer);
|
||||
|
||||
void PrepForArming();
|
||||
|
||||
|
@ -87,67 +87,67 @@ public:
|
|||
|
||||
void StopLogging();
|
||||
|
||||
void Log_Write_Parameter(const char *name, float value);
|
||||
void Log_Write_GPS(uint8_t instance, uint64_t time_us=0);
|
||||
void Log_Write_RFND(const RangeFinder &rangefinder);
|
||||
void Log_Write_IMU();
|
||||
void Log_Write_IMUDT(uint64_t time_us, uint8_t imu_mask);
|
||||
bool Log_Write_ISBH(uint16_t seqno,
|
||||
void Write_Parameter(const char *name, float value);
|
||||
void Write_GPS(uint8_t instance, uint64_t time_us=0);
|
||||
void Write_RFND(const RangeFinder &rangefinder);
|
||||
void Write_IMU();
|
||||
void Write_IMUDT(uint64_t time_us, uint8_t imu_mask);
|
||||
bool Write_ISBH(uint16_t seqno,
|
||||
AP_InertialSensor::IMU_SENSOR_TYPE sensor_type,
|
||||
uint8_t instance,
|
||||
uint16_t multiplier,
|
||||
uint16_t sample_count,
|
||||
uint64_t sample_us,
|
||||
float sample_rate_hz);
|
||||
bool Log_Write_ISBD(uint16_t isb_seqno,
|
||||
bool Write_ISBD(uint16_t isb_seqno,
|
||||
uint16_t seqno,
|
||||
const int16_t x[32],
|
||||
const int16_t y[32],
|
||||
const int16_t z[32]);
|
||||
void Log_Write_Vibration();
|
||||
void Log_Write_RCIN(void);
|
||||
void Log_Write_RCOUT(void);
|
||||
void Log_Write_RSSI(AP_RSSI &rssi);
|
||||
void Log_Write_Baro(uint64_t time_us=0);
|
||||
void Log_Write_Power(void);
|
||||
void Log_Write_AHRS2(AP_AHRS &ahrs);
|
||||
void Log_Write_POS(AP_AHRS &ahrs);
|
||||
void Write_Vibration();
|
||||
void Write_RCIN(void);
|
||||
void Write_RCOUT(void);
|
||||
void Write_RSSI(AP_RSSI &rssi);
|
||||
void Write_Baro(uint64_t time_us=0);
|
||||
void Write_Power(void);
|
||||
void Write_AHRS2(AP_AHRS &ahrs);
|
||||
void Write_POS(AP_AHRS &ahrs);
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
void Log_Write_EKF(AP_AHRS_NavEKF &ahrs);
|
||||
void Write_EKF(AP_AHRS_NavEKF &ahrs);
|
||||
#endif
|
||||
void Log_Write_Radio(const mavlink_radio_t &packet);
|
||||
void Log_Write_Message(const char *message);
|
||||
void Log_Write_MessageF(const char *fmt, ...);
|
||||
void Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const Location ¤t_loc, uint64_t timestamp_us=0);
|
||||
void Log_Write_Camera(const AP_AHRS &ahrs, const Location ¤t_loc, uint64_t timestamp_us=0);
|
||||
void Log_Write_Trigger(const AP_AHRS &ahrs, const Location ¤t_loc);
|
||||
void Log_Write_ESC(void);
|
||||
void Log_Write_Airspeed(AP_Airspeed &airspeed);
|
||||
void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets);
|
||||
void Log_Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets);
|
||||
void Log_Write_Current();
|
||||
void Log_Write_Compass(uint64_t time_us=0);
|
||||
void Log_Write_Mode(uint8_t mode, uint8_t reason);
|
||||
void Write_Radio(const mavlink_radio_t &packet);
|
||||
void Write_Message(const char *message);
|
||||
void Write_MessageF(const char *fmt, ...);
|
||||
void Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const Location ¤t_loc, uint64_t timestamp_us=0);
|
||||
void Write_Camera(const AP_AHRS &ahrs, const Location ¤t_loc, uint64_t timestamp_us=0);
|
||||
void Write_Trigger(const AP_AHRS &ahrs, const Location ¤t_loc);
|
||||
void Write_ESC(void);
|
||||
void Write_Airspeed(AP_Airspeed &airspeed);
|
||||
void Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets);
|
||||
void Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets);
|
||||
void Write_Current();
|
||||
void Write_Compass(uint64_t time_us=0);
|
||||
void Write_Mode(uint8_t mode, uint8_t reason);
|
||||
|
||||
void Log_Write_EntireMission(const AP_Mission &mission);
|
||||
void Log_Write_Mission_Cmd(const AP_Mission &mission,
|
||||
void Write_EntireMission(const AP_Mission &mission);
|
||||
void Write_Mission_Cmd(const AP_Mission &mission,
|
||||
const AP_Mission::Mission_Command &cmd);
|
||||
void Log_Write_Origin(uint8_t origin_type, const Location &loc);
|
||||
void Log_Write_RPM(const AP_RPM &rpm_sensor);
|
||||
void Log_Write_Rate(const AP_AHRS_View *ahrs,
|
||||
void Write_Origin(uint8_t origin_type, const Location &loc);
|
||||
void Write_RPM(const AP_RPM &rpm_sensor);
|
||||
void Write_Rate(const AP_AHRS_View *ahrs,
|
||||
const AP_Motors &motors,
|
||||
const AC_AttitudeControl &attitude_control,
|
||||
const AC_PosControl &pos_control);
|
||||
void Log_Write_Rally(const AP_Rally &rally);
|
||||
void Log_Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence);
|
||||
void Log_Write_AOA_SSA(AP_AHRS &ahrs);
|
||||
void Log_Write_Beacon(AP_Beacon &beacon);
|
||||
void Log_Write_Proximity(AP_Proximity &proximity);
|
||||
void Log_Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& point);
|
||||
void Write_Rally(const AP_Rally &rally);
|
||||
void Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence);
|
||||
void Write_AOA_SSA(AP_AHRS &ahrs);
|
||||
void Write_Beacon(AP_Beacon &beacon);
|
||||
void Write_Proximity(AP_Proximity &proximity);
|
||||
void Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& point);
|
||||
|
||||
void Log_Write(const char *name, const char *labels, const char *fmt, ...);
|
||||
void Log_Write(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...);
|
||||
void Log_WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list);
|
||||
void Write(const char *name, const char *labels, const char *fmt, ...);
|
||||
void Write(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...);
|
||||
void WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list);
|
||||
|
||||
// This structure provides information on the internal member data of a PID for logging purposes
|
||||
struct PID_Info {
|
||||
|
@ -159,7 +159,7 @@ public:
|
|||
float FF;
|
||||
};
|
||||
|
||||
void Log_Write_PID(uint8_t msg_type, const PID_Info &info);
|
||||
void Write_PID(uint8_t msg_type, const PID_Info &info);
|
||||
|
||||
// returns true if logging of a message should be attempted
|
||||
bool should_log(uint32_t mask) const;
|
||||
|
@ -188,7 +188,7 @@ public:
|
|||
}
|
||||
uint8_t log_replay(void) const { return _params.log_replay; }
|
||||
|
||||
vehicle_startup_message_Log_Writer _vehicle_messages;
|
||||
vehicle_startup_message_Writer _vehicle_messages;
|
||||
|
||||
// parameter support
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
@ -248,7 +248,7 @@ private:
|
|||
void internal_error() const;
|
||||
|
||||
/*
|
||||
* support for dynamic Log_Write; user-supplies name, format,
|
||||
* support for dynamic Write; user-supplies name, format,
|
||||
* labels and values in a single function call.
|
||||
*/
|
||||
|
||||
|
@ -281,27 +281,27 @@ private:
|
|||
|
||||
// calculate the length of a message using fields specified in
|
||||
// fmt; includes the message header
|
||||
int16_t Log_Write_calc_msg_len(const char *fmt) const;
|
||||
int16_t Write_calc_msg_len(const char *fmt) const;
|
||||
|
||||
bool _armed;
|
||||
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
void Log_Write_EKF2(AP_AHRS_NavEKF &ahrs);
|
||||
void Log_Write_EKF3(AP_AHRS_NavEKF &ahrs);
|
||||
void Write_EKF2(AP_AHRS_NavEKF &ahrs);
|
||||
void Write_EKF3(AP_AHRS_NavEKF &ahrs);
|
||||
#endif
|
||||
|
||||
void Log_Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type);
|
||||
void Log_Write_IMU_instance(uint64_t time_us,
|
||||
void Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type);
|
||||
void Write_IMU_instance(uint64_t time_us,
|
||||
uint8_t imu_instance,
|
||||
enum LogMessages type);
|
||||
void Log_Write_Compass_instance(uint64_t time_us,
|
||||
void Write_Compass_instance(uint64_t time_us,
|
||||
uint8_t mag_instance,
|
||||
enum LogMessages type);
|
||||
void Log_Write_Current_instance(uint64_t time_us,
|
||||
void Write_Current_instance(uint64_t time_us,
|
||||
uint8_t battery_instance,
|
||||
enum LogMessages type,
|
||||
enum LogMessages celltype);
|
||||
void Log_Write_IMUDT_instance(uint64_t time_us,
|
||||
void Write_IMUDT_instance(uint64_t time_us,
|
||||
uint8_t imu_instance,
|
||||
enum LogMessages type);
|
||||
|
||||
|
@ -325,7 +325,7 @@ private:
|
|||
bool seen_ids[256] = { };
|
||||
#endif
|
||||
|
||||
void Log_Write_EKF_Timing(const char *name, uint64_t time_us, const struct ekf_timing &timing);
|
||||
void Write_EKF_Timing(const char *name, uint64_t time_us, const struct ekf_timing &timing);
|
||||
|
||||
// possibly expensive calls to start log system:
|
||||
void Prep();
|
||||
|
|
|
@ -42,7 +42,7 @@ const struct MultiplierStructure *AP_Logger_Backend::multiplier(uint8_t num) con
|
|||
return _front.multiplier(num);
|
||||
}
|
||||
|
||||
AP_Logger_Backend::vehicle_startup_message_Log_Writer AP_Logger_Backend::vehicle_message_writer() {
|
||||
AP_Logger_Backend::vehicle_startup_message_Writer AP_Logger_Backend::vehicle_message_writer() {
|
||||
return _front._vehicle_messages;
|
||||
}
|
||||
|
||||
|
@ -138,11 +138,11 @@ void AP_Logger_Backend::WriteMoreStartupMessages()
|
|||
}
|
||||
|
||||
/*
|
||||
* support for Log_Write():
|
||||
* support for Write():
|
||||
*/
|
||||
|
||||
|
||||
bool AP_Logger_Backend::Log_Write_Emit_FMT(uint8_t msg_type)
|
||||
bool AP_Logger_Backend::Write_Emit_FMT(uint8_t msg_type)
|
||||
{
|
||||
// get log structure from front end:
|
||||
char ls_name[LS_NAME_SIZE] = {};
|
||||
|
@ -168,17 +168,17 @@ bool AP_Logger_Backend::Log_Write_Emit_FMT(uint8_t msg_type)
|
|||
return false;
|
||||
}
|
||||
|
||||
if (!Log_Write_Format(&logstruct)) {
|
||||
if (!Write_Format(&logstruct)) {
|
||||
return false;
|
||||
}
|
||||
if (!Log_Write_Format_Units(&logstruct)) {
|
||||
if (!Write_Format_Units(&logstruct)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool AP_Logger_Backend::Log_Write(const uint8_t msg_type, va_list arg_list, bool is_critical)
|
||||
bool AP_Logger_Backend::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
|
||||
|
@ -405,7 +405,7 @@ bool AP_Logger_Backend::ShouldLog(bool is_critical)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool AP_Logger_Backend::Log_Write_MessageF(const char *fmt, ...)
|
||||
bool AP_Logger_Backend::Write_MessageF(const char *fmt, ...)
|
||||
{
|
||||
char msg[65] {}; // sizeof(log_Message.msg) + null-termination
|
||||
|
||||
|
@ -414,5 +414,5 @@ bool AP_Logger_Backend::Log_Write_MessageF(const char *fmt, ...)
|
|||
hal.util->vsnprintf(msg, sizeof(msg), fmt, ap);
|
||||
va_end(ap);
|
||||
|
||||
return Log_Write_Message(msg);
|
||||
return Write_Message(msg);
|
||||
}
|
||||
|
|
|
@ -8,12 +8,12 @@ class AP_Logger_Backend
|
|||
{
|
||||
|
||||
public:
|
||||
FUNCTOR_TYPEDEF(vehicle_startup_message_Log_Writer, void);
|
||||
FUNCTOR_TYPEDEF(vehicle_startup_message_Writer, void);
|
||||
|
||||
AP_Logger_Backend(AP_Logger &front,
|
||||
class LoggerMessageWriter_DFLogStart *writer);
|
||||
|
||||
vehicle_startup_message_Log_Writer vehicle_message_writer();
|
||||
vehicle_startup_message_Writer vehicle_message_writer();
|
||||
|
||||
void internal_error();
|
||||
|
||||
|
@ -61,8 +61,8 @@ public:
|
|||
*/
|
||||
virtual void stop_logging(void) = 0;
|
||||
|
||||
void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt);
|
||||
void Log_Fill_Format_Units(const struct LogStructure *s, struct log_Format_Units &pkt);
|
||||
void Fill_Format(const struct LogStructure *structure, struct log_Format &pkt);
|
||||
void 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 AP_Logger_File support this:
|
||||
|
@ -85,15 +85,15 @@ public:
|
|||
uint8_t num_multipliers() const;
|
||||
const struct MultiplierStructure *multiplier(uint8_t multiplier) const;
|
||||
|
||||
void Log_Write_EntireMission(const AP_Mission &mission);
|
||||
bool Log_Write_Format(const struct LogStructure *structure);
|
||||
bool Log_Write_Message(const char *message);
|
||||
bool Log_Write_MessageF(const char *fmt, ...);
|
||||
bool Log_Write_Mission_Cmd(const AP_Mission &mission,
|
||||
void Write_EntireMission(const AP_Mission &mission);
|
||||
bool Write_Format(const struct LogStructure *structure);
|
||||
bool Write_Message(const char *message);
|
||||
bool Write_MessageF(const char *fmt, ...);
|
||||
bool Write_Mission_Cmd(const AP_Mission &mission,
|
||||
const AP_Mission::Mission_Command &cmd);
|
||||
bool Log_Write_Mode(uint8_t mode, uint8_t reason = 0);
|
||||
bool Log_Write_Parameter(const char *name, float value);
|
||||
bool Log_Write_Parameter(const AP_Param *ap,
|
||||
bool Write_Mode(uint8_t mode, uint8_t reason = 0);
|
||||
bool Write_Parameter(const char *name, float value);
|
||||
bool Write_Parameter(const AP_Param *ap,
|
||||
const AP_Param::ParamToken &token,
|
||||
enum ap_var_type type);
|
||||
|
||||
|
@ -102,15 +102,15 @@ public:
|
|||
}
|
||||
|
||||
/*
|
||||
* Log_Write support
|
||||
* Write support
|
||||
*/
|
||||
// write a FMT message out (if it hasn't been done already).
|
||||
// Returns true if the FMT message has ever been written.
|
||||
bool Log_Write_Emit_FMT(uint8_t msg_type);
|
||||
bool Write_Emit_FMT(uint8_t msg_type);
|
||||
|
||||
// write a log message out to the log of msg_type type, with
|
||||
// values contained in arg_list:
|
||||
bool Log_Write(uint8_t msg_type, va_list arg_list, bool is_critical=false);
|
||||
bool Write(uint8_t msg_type, va_list arg_list, bool is_critical=false);
|
||||
|
||||
// these methods are used when reporting system status over mavlink
|
||||
virtual bool logging_enabled() const = 0;
|
||||
|
@ -118,9 +118,9 @@ public:
|
|||
|
||||
virtual void vehicle_was_disarmed() { };
|
||||
|
||||
bool Log_Write_Unit(const struct UnitStructure *s);
|
||||
bool Log_Write_Multiplier(const struct MultiplierStructure *s);
|
||||
bool Log_Write_Format_Units(const struct LogStructure *structure);
|
||||
bool Write_Unit(const struct UnitStructure *s);
|
||||
bool Write_Multiplier(const struct MultiplierStructure *s);
|
||||
bool Write_Format_Units(const struct LogStructure *structure);
|
||||
|
||||
|
||||
protected:
|
||||
|
|
|
@ -1109,7 +1109,7 @@ void AP_Logger_File::vehicle_was_disarmed()
|
|||
}
|
||||
}
|
||||
|
||||
void AP_Logger_File::Log_Write_AP_Logger_Stats_File(const struct df_stats &_stats)
|
||||
void AP_Logger_File::Write_AP_Logger_Stats_File(const struct df_stats &_stats)
|
||||
{
|
||||
struct log_DSF pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_DF_FILE_STATS),
|
||||
|
@ -1145,7 +1145,7 @@ void AP_Logger_File::df_stats_clear() {
|
|||
}
|
||||
|
||||
void AP_Logger_File::df_stats_log() {
|
||||
Log_Write_AP_Logger_Stats_File(stats);
|
||||
Write_AP_Logger_Stats_File(stats);
|
||||
df_stats_clear();
|
||||
}
|
||||
|
||||
|
|
|
@ -169,7 +169,7 @@ private:
|
|||
};
|
||||
struct df_stats stats;
|
||||
|
||||
void Log_Write_AP_Logger_Stats_File(const struct df_stats &_stats);
|
||||
void 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();
|
||||
|
|
|
@ -318,7 +318,7 @@ void AP_Logger_MAVLink::stats_reset() {
|
|||
stats.collection_count = 0;
|
||||
}
|
||||
|
||||
void AP_Logger_MAVLink::Log_Write_DF_MAV(AP_Logger_MAVLink &df)
|
||||
void AP_Logger_MAVLink::Write_DF_MAV(AP_Logger_MAVLink &df)
|
||||
{
|
||||
if (df.stats.collection_count == 0) {
|
||||
return;
|
||||
|
@ -352,7 +352,7 @@ void AP_Logger_MAVLink::stats_log()
|
|||
if (stats.collection_count == 0) {
|
||||
return;
|
||||
}
|
||||
Log_Write_DF_MAV(*this);
|
||||
Write_DF_MAV(*this);
|
||||
#if REMOTE_LOG_DEBUGGING
|
||||
printf("D:%d Retry:%d Resent:%d E:%d SF:%d/%d/%d SP:%d/%d/%d SS:%d/%d/%d SR:%d/%d/%d\n",
|
||||
dropped,
|
||||
|
|
|
@ -144,7 +144,7 @@ private:
|
|||
uint8_t _next_block_number_to_resend;
|
||||
bool _sending_to_client;
|
||||
|
||||
void Log_Write_DF_MAV(AP_Logger_MAVLink &df);
|
||||
void Write_DF_MAV(AP_Logger_MAVLink &df);
|
||||
|
||||
uint32_t bufferspace_available() override; // in bytes
|
||||
uint8_t remaining_space_in_current_block();
|
||||
|
|
|
@ -331,7 +331,7 @@ int16_t AP_Logger_Revo::get_log_data(uint16_t log_num, uint16_t page, uint32_t o
|
|||
struct log_Format pkt;
|
||||
uint8_t t = offset / sizeof(pkt);
|
||||
uint8_t ofs = offset % sizeof(pkt);
|
||||
Log_Fill_Format(structure(t), pkt);
|
||||
Fill_Format(structure(t), pkt);
|
||||
uint8_t n = sizeof(pkt) - ofs;
|
||||
if (n > len) {
|
||||
n = len;
|
||||
|
|
|
@ -26,7 +26,7 @@ extern const AP_HAL::HAL& hal;
|
|||
/*
|
||||
write a structure format to the log - should be in frontend
|
||||
*/
|
||||
void AP_Logger_Backend::Log_Fill_Format(const struct LogStructure *s, struct log_Format &pkt)
|
||||
void AP_Logger_Backend::Fill_Format(const struct LogStructure *s, struct log_Format &pkt)
|
||||
{
|
||||
memset(&pkt, 0, sizeof(pkt));
|
||||
pkt.head1 = HEAD_BYTE1;
|
||||
|
@ -42,7 +42,7 @@ void AP_Logger_Backend::Log_Fill_Format(const struct LogStructure *s, struct log
|
|||
/*
|
||||
Pack a LogStructure packet into a structure suitable to go to the logfile:
|
||||
*/
|
||||
void AP_Logger_Backend::Log_Fill_Format_Units(const struct LogStructure *s, struct log_Format_Units &pkt)
|
||||
void AP_Logger_Backend::Fill_Format_Units(const struct LogStructure *s, struct log_Format_Units &pkt)
|
||||
{
|
||||
memset(&pkt, 0, sizeof(pkt));
|
||||
pkt.head1 = HEAD_BYTE1;
|
||||
|
@ -57,17 +57,17 @@ void AP_Logger_Backend::Log_Fill_Format_Units(const struct LogStructure *s, stru
|
|||
/*
|
||||
write a structure format to the log
|
||||
*/
|
||||
bool AP_Logger_Backend::Log_Write_Format(const struct LogStructure *s)
|
||||
bool AP_Logger_Backend::Write_Format(const struct LogStructure *s)
|
||||
{
|
||||
struct log_Format pkt;
|
||||
Log_Fill_Format(s, pkt);
|
||||
Fill_Format(s, pkt);
|
||||
return WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
/*
|
||||
write a unit definition
|
||||
*/
|
||||
bool AP_Logger_Backend::Log_Write_Unit(const struct UnitStructure *s)
|
||||
bool AP_Logger_Backend::Write_Unit(const struct UnitStructure *s)
|
||||
{
|
||||
struct log_Unit pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_UNIT_MSG),
|
||||
|
@ -83,7 +83,7 @@ bool AP_Logger_Backend::Log_Write_Unit(const struct UnitStructure *s)
|
|||
/*
|
||||
write a unit-multiplier definition
|
||||
*/
|
||||
bool AP_Logger_Backend::Log_Write_Multiplier(const struct MultiplierStructure *s)
|
||||
bool AP_Logger_Backend::Write_Multiplier(const struct MultiplierStructure *s)
|
||||
{
|
||||
struct log_Format_Multiplier pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_MULT_MSG),
|
||||
|
@ -98,17 +98,17 @@ bool AP_Logger_Backend::Log_Write_Multiplier(const struct MultiplierStructure *s
|
|||
/*
|
||||
write the units for a format to the log
|
||||
*/
|
||||
bool AP_Logger_Backend::Log_Write_Format_Units(const struct LogStructure *s)
|
||||
bool AP_Logger_Backend::Write_Format_Units(const struct LogStructure *s)
|
||||
{
|
||||
struct log_Format_Units pkt;
|
||||
Log_Fill_Format_Units(s, pkt);
|
||||
Fill_Format_Units(s, pkt);
|
||||
return WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
/*
|
||||
write a parameter to the log
|
||||
*/
|
||||
bool AP_Logger_Backend::Log_Write_Parameter(const char *name, float value)
|
||||
bool AP_Logger_Backend::Write_Parameter(const char *name, float value)
|
||||
{
|
||||
struct log_Parameter pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_PARAMETER_MSG),
|
||||
|
@ -123,17 +123,17 @@ bool AP_Logger_Backend::Log_Write_Parameter(const char *name, float value)
|
|||
/*
|
||||
write a parameter to the log
|
||||
*/
|
||||
bool AP_Logger_Backend::Log_Write_Parameter(const AP_Param *ap,
|
||||
bool AP_Logger_Backend::Write_Parameter(const AP_Param *ap,
|
||||
const AP_Param::ParamToken &token,
|
||||
enum ap_var_type type)
|
||||
{
|
||||
char name[16];
|
||||
ap->copy_name_token(token, &name[0], sizeof(name), true);
|
||||
return Log_Write_Parameter(name, ap->cast_to_float(type));
|
||||
return Write_Parameter(name, ap->cast_to_float(type));
|
||||
}
|
||||
|
||||
// Write an GPS packet
|
||||
void AP_Logger::Log_Write_GPS(uint8_t i, uint64_t time_us)
|
||||
void AP_Logger::Write_GPS(uint8_t i, uint64_t time_us)
|
||||
{
|
||||
const AP_GPS &gps = AP::gps();
|
||||
if (time_us == 0) {
|
||||
|
@ -179,7 +179,7 @@ void AP_Logger::Log_Write_GPS(uint8_t i, uint64_t time_us)
|
|||
|
||||
|
||||
// Write an RFND (rangefinder) packet
|
||||
void AP_Logger::Log_Write_RFND(const RangeFinder &rangefinder)
|
||||
void AP_Logger::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 AP_Logger::Log_Write_RFND(const RangeFinder &rangefinder)
|
|||
}
|
||||
|
||||
// Write an RCIN packet
|
||||
void AP_Logger::Log_Write_RCIN(void)
|
||||
void AP_Logger::Write_RCIN(void)
|
||||
{
|
||||
uint16_t values[14] = {};
|
||||
rc().get_radio_in(values, ARRAY_SIZE(values));
|
||||
|
@ -224,7 +224,7 @@ void AP_Logger::Log_Write_RCIN(void)
|
|||
}
|
||||
|
||||
// Write an SERVO packet
|
||||
void AP_Logger::Log_Write_RCOUT(void)
|
||||
void AP_Logger::Write_RCOUT(void)
|
||||
{
|
||||
struct log_RCOUT pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_RCOUT_MSG),
|
||||
|
@ -245,11 +245,11 @@ void AP_Logger::Log_Write_RCOUT(void)
|
|||
chan14 : hal.rcout->read(13)
|
||||
};
|
||||
WriteBlock(&pkt, sizeof(pkt));
|
||||
Log_Write_ESC();
|
||||
Write_ESC();
|
||||
}
|
||||
|
||||
// Write an RSSI packet
|
||||
void AP_Logger::Log_Write_RSSI(AP_RSSI &rssi)
|
||||
void AP_Logger::Write_RSSI(AP_RSSI &rssi)
|
||||
{
|
||||
struct log_RSSI pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_RSSI_MSG),
|
||||
|
@ -259,7 +259,7 @@ void AP_Logger::Log_Write_RSSI(AP_RSSI &rssi)
|
|||
WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
void AP_Logger::Log_Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type)
|
||||
void AP_Logger::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,22 +280,22 @@ void AP_Logger::Log_Write_Baro_instance(uint64_t time_us, uint8_t baro_instance,
|
|||
}
|
||||
|
||||
// Write a BARO packet
|
||||
void AP_Logger::Log_Write_Baro(uint64_t time_us)
|
||||
void AP_Logger::Write_Baro(uint64_t time_us)
|
||||
{
|
||||
if (time_us == 0) {
|
||||
time_us = AP_HAL::micros64();
|
||||
}
|
||||
const AP_Baro &baro = AP::baro();
|
||||
Log_Write_Baro_instance(time_us, 0, LOG_BARO_MSG);
|
||||
Write_Baro_instance(time_us, 0, LOG_BARO_MSG);
|
||||
if (baro.num_instances() > 1 && baro.healthy(1)) {
|
||||
Log_Write_Baro_instance(time_us, 1, LOG_BAR2_MSG);
|
||||
Write_Baro_instance(time_us, 1, LOG_BAR2_MSG);
|
||||
}
|
||||
if (baro.num_instances() > 2 && baro.healthy(2)) {
|
||||
Log_Write_Baro_instance(time_us, 2, LOG_BAR3_MSG);
|
||||
Write_Baro_instance(time_us, 2, LOG_BAR3_MSG);
|
||||
}
|
||||
}
|
||||
|
||||
void AP_Logger::Log_Write_IMU_instance(const uint64_t time_us, const uint8_t imu_instance, const enum LogMessages type)
|
||||
void AP_Logger::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,28 +321,28 @@ void AP_Logger::Log_Write_IMU_instance(const uint64_t time_us, const uint8_t imu
|
|||
}
|
||||
|
||||
// Write an raw accel/gyro data packet
|
||||
void AP_Logger::Log_Write_IMU()
|
||||
void AP_Logger::Write_IMU()
|
||||
{
|
||||
uint64_t time_us = AP_HAL::micros64();
|
||||
|
||||
const AP_InertialSensor &ins = AP::ins();
|
||||
|
||||
Log_Write_IMU_instance(time_us, 0, LOG_IMU_MSG);
|
||||
Write_IMU_instance(time_us, 0, LOG_IMU_MSG);
|
||||
if (ins.get_gyro_count() < 2 && ins.get_accel_count() < 2) {
|
||||
return;
|
||||
}
|
||||
|
||||
Log_Write_IMU_instance(time_us, 1, LOG_IMU2_MSG);
|
||||
Write_IMU_instance(time_us, 1, LOG_IMU2_MSG);
|
||||
|
||||
if (ins.get_gyro_count() < 3 && ins.get_accel_count() < 3) {
|
||||
return;
|
||||
}
|
||||
|
||||
Log_Write_IMU_instance(time_us, 2, LOG_IMU3_MSG);
|
||||
Write_IMU_instance(time_us, 2, LOG_IMU3_MSG);
|
||||
}
|
||||
|
||||
// Write an accel/gyro delta time data packet
|
||||
void AP_Logger::Log_Write_IMUDT_instance(const uint64_t time_us, const uint8_t imu_instance, const enum LogMessages type)
|
||||
void AP_Logger::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,18 +368,18 @@ void AP_Logger::Log_Write_IMUDT_instance(const uint64_t time_us, const uint8_t i
|
|||
WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
void AP_Logger::Log_Write_IMUDT(uint64_t time_us, uint8_t imu_mask)
|
||||
void AP_Logger::Write_IMUDT(uint64_t time_us, uint8_t imu_mask)
|
||||
{
|
||||
const AP_InertialSensor &ins = AP::ins();
|
||||
if (imu_mask & 1) {
|
||||
Log_Write_IMUDT_instance(time_us, 0, LOG_IMUDT_MSG);
|
||||
Write_IMUDT_instance(time_us, 0, LOG_IMUDT_MSG);
|
||||
}
|
||||
if ((ins.get_gyro_count() < 2 && ins.get_accel_count() < 2) || !ins.use_gyro(1)) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (imu_mask & 2) {
|
||||
Log_Write_IMUDT_instance(time_us, 1, LOG_IMUDT2_MSG);
|
||||
Write_IMUDT_instance(time_us, 1, LOG_IMUDT2_MSG);
|
||||
}
|
||||
|
||||
if ((ins.get_gyro_count() < 3 && ins.get_accel_count() < 3) || !ins.use_gyro(2)) {
|
||||
|
@ -387,11 +387,11 @@ void AP_Logger::Log_Write_IMUDT(uint64_t time_us, uint8_t imu_mask)
|
|||
}
|
||||
|
||||
if (imu_mask & 4) {
|
||||
Log_Write_IMUDT_instance(time_us, 2, LOG_IMUDT3_MSG);
|
||||
Write_IMUDT_instance(time_us, 2, LOG_IMUDT3_MSG);
|
||||
}
|
||||
}
|
||||
|
||||
void AP_Logger::Log_Write_Vibration()
|
||||
void AP_Logger::Write_Vibration()
|
||||
{
|
||||
uint64_t time_us = AP_HAL::micros64();
|
||||
const AP_InertialSensor &ins = AP::ins();
|
||||
|
@ -409,7 +409,7 @@ void AP_Logger::Log_Write_Vibration()
|
|||
WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
bool AP_Logger_Backend::Log_Write_Mission_Cmd(const AP_Mission &mission,
|
||||
bool AP_Logger_Backend::Write_Mission_Cmd(const AP_Mission &mission,
|
||||
const AP_Mission::Mission_Command &cmd)
|
||||
{
|
||||
mavlink_mission_item_int_t mav_cmd = {};
|
||||
|
@ -432,7 +432,7 @@ bool AP_Logger_Backend::Log_Write_Mission_Cmd(const AP_Mission &mission,
|
|||
return WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
void AP_Logger_Backend::Log_Write_EntireMission(const AP_Mission &mission)
|
||||
void AP_Logger_Backend::Write_EntireMission(const AP_Mission &mission)
|
||||
{
|
||||
LoggerMessageWriter_WriteEntireMission writer;
|
||||
writer.set_dataflash_backend(this);
|
||||
|
@ -440,7 +440,7 @@ void AP_Logger_Backend::Log_Write_EntireMission(const AP_Mission &mission)
|
|||
}
|
||||
|
||||
// Write a text message to the log
|
||||
bool AP_Logger_Backend::Log_Write_Message(const char *message)
|
||||
bool AP_Logger_Backend::Write_Message(const char *message)
|
||||
{
|
||||
struct log_Message pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_MESSAGE_MSG),
|
||||
|
@ -451,7 +451,7 @@ bool AP_Logger_Backend::Log_Write_Message(const char *message)
|
|||
return WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
void AP_Logger::Log_Write_Power(void)
|
||||
void AP_Logger::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 AP_Logger::Log_Write_Power(void)
|
|||
}
|
||||
|
||||
// Write an AHRS2 packet
|
||||
void AP_Logger::Log_Write_AHRS2(AP_AHRS &ahrs)
|
||||
void AP_Logger::Write_AHRS2(AP_AHRS &ahrs)
|
||||
{
|
||||
Vector3f euler;
|
||||
struct Location loc;
|
||||
|
@ -499,7 +499,7 @@ void AP_Logger::Log_Write_AHRS2(AP_AHRS &ahrs)
|
|||
}
|
||||
|
||||
// Write a POS packet
|
||||
void AP_Logger::Log_Write_POS(AP_AHRS &ahrs)
|
||||
void AP_Logger::Write_POS(AP_AHRS &ahrs)
|
||||
{
|
||||
Location loc;
|
||||
if (!ahrs.get_position(loc)) {
|
||||
|
@ -520,15 +520,15 @@ void AP_Logger::Log_Write_POS(AP_AHRS &ahrs)
|
|||
}
|
||||
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
void AP_Logger::Log_Write_EKF(AP_AHRS_NavEKF &ahrs)
|
||||
void AP_Logger::Write_EKF(AP_AHRS_NavEKF &ahrs)
|
||||
{
|
||||
// only log EKF2 if enabled
|
||||
if (ahrs.get_NavEKF2().activeCores() > 0) {
|
||||
Log_Write_EKF2(ahrs);
|
||||
Write_EKF2(ahrs);
|
||||
}
|
||||
// only log EKF3 if enabled
|
||||
if (ahrs.get_NavEKF3().activeCores() > 0) {
|
||||
Log_Write_EKF3(ahrs);
|
||||
Write_EKF3(ahrs);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -536,9 +536,9 @@ void AP_Logger::Log_Write_EKF(AP_AHRS_NavEKF &ahrs)
|
|||
/*
|
||||
write an EKF timing message
|
||||
*/
|
||||
void AP_Logger::Log_Write_EKF_Timing(const char *name, uint64_t time_us, const struct ekf_timing &timing)
|
||||
void AP_Logger::Write_EKF_Timing(const char *name, uint64_t time_us, const struct ekf_timing &timing)
|
||||
{
|
||||
Log_Write(name,
|
||||
Write(name,
|
||||
"TimeUS,Cnt,IMUMin,IMUMax,EKFMin,EKFMax,AngMin,AngMax,VMin,VMax",
|
||||
"QIffffffff",
|
||||
time_us,
|
||||
|
@ -553,7 +553,7 @@ void AP_Logger::Log_Write_EKF_Timing(const char *name, uint64_t time_us, const s
|
|||
(double)timing.delVelDT_max);
|
||||
}
|
||||
|
||||
void AP_Logger::Log_Write_EKF2(AP_AHRS_NavEKF &ahrs)
|
||||
void AP_Logger::Write_EKF2(AP_AHRS_NavEKF &ahrs)
|
||||
{
|
||||
uint64_t time_us = AP_HAL::micros64();
|
||||
// Write first EKF packet
|
||||
|
@ -887,13 +887,13 @@ void AP_Logger::Log_Write_EKF2(AP_AHRS_NavEKF &ahrs)
|
|||
struct ekf_timing timing;
|
||||
for (uint8_t i=0; i<ahrs.get_NavEKF2().activeCores(); i++) {
|
||||
ahrs.get_NavEKF2().getTimingStatistics(i, timing);
|
||||
Log_Write_EKF_Timing(i==0?"NKT1":"NKT2", time_us, timing);
|
||||
Write_EKF_Timing(i==0?"NKT1":"NKT2", time_us, timing);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void AP_Logger::Log_Write_EKF3(AP_AHRS_NavEKF &ahrs)
|
||||
void AP_Logger::Write_EKF3(AP_AHRS_NavEKF &ahrs)
|
||||
{
|
||||
uint64_t time_us = AP_HAL::micros64();
|
||||
// Write first EKF packet
|
||||
|
@ -1283,13 +1283,13 @@ void AP_Logger::Log_Write_EKF3(AP_AHRS_NavEKF &ahrs)
|
|||
struct ekf_timing timing;
|
||||
for (uint8_t i=0; i<ahrs.get_NavEKF3().activeCores(); i++) {
|
||||
ahrs.get_NavEKF3().getTimingStatistics(i, timing);
|
||||
Log_Write_EKF_Timing(i==0?"XKT1":"XKT2", time_us, timing);
|
||||
Write_EKF_Timing(i==0?"XKT1":"XKT2", time_us, timing);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
void AP_Logger::Log_Write_Radio(const mavlink_radio_t &packet)
|
||||
void AP_Logger::Write_Radio(const mavlink_radio_t &packet)
|
||||
{
|
||||
struct log_Radio pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_RADIO_MSG),
|
||||
|
@ -1306,7 +1306,7 @@ void AP_Logger::Log_Write_Radio(const mavlink_radio_t &packet)
|
|||
}
|
||||
|
||||
// Write a Camera packet
|
||||
void AP_Logger::Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const Location ¤t_loc, uint64_t timestamp_us)
|
||||
void AP_Logger::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 AP_Logger::Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs,
|
|||
}
|
||||
|
||||
// Write a Camera packet
|
||||
void AP_Logger::Log_Write_Camera(const AP_AHRS &ahrs, const Location ¤t_loc, uint64_t timestamp_us)
|
||||
void AP_Logger::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_CameraInfo(LOG_CAMERA_MSG, ahrs, current_loc, timestamp_us);
|
||||
}
|
||||
|
||||
// Write a Trigger packet
|
||||
void AP_Logger::Log_Write_Trigger(const AP_AHRS &ahrs, const Location ¤t_loc)
|
||||
void AP_Logger::Write_Trigger(const AP_AHRS &ahrs, const Location ¤t_loc)
|
||||
{
|
||||
Log_Write_CameraInfo(LOG_TRIGGER_MSG, ahrs, current_loc, 0);
|
||||
Write_CameraInfo(LOG_TRIGGER_MSG, ahrs, current_loc, 0);
|
||||
}
|
||||
|
||||
// Write an attitude packet
|
||||
void AP_Logger::Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets)
|
||||
void AP_Logger::Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets)
|
||||
{
|
||||
struct log_Attitude pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
|
||||
|
@ -1371,7 +1371,7 @@ void AP_Logger::Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets)
|
|||
}
|
||||
|
||||
// Write an attitude packet
|
||||
void AP_Logger::Log_Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets)
|
||||
void AP_Logger::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 AP_Logger::Log_Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targe
|
|||
WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
void AP_Logger::Log_Write_Current_instance(const uint64_t time_us,
|
||||
void AP_Logger::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 AP_Logger::Log_Write_Current_instance(const uint64_t time_us,
|
|||
}
|
||||
|
||||
// Write an Current data packet
|
||||
void AP_Logger::Log_Write_Current()
|
||||
void AP_Logger::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
|
||||
|
@ -1444,14 +1444,14 @@ void AP_Logger::Log_Write_Current()
|
|||
const uint64_t time_us = AP_HAL::micros64();
|
||||
const uint8_t num_instances = AP::battery().num_instances();
|
||||
for (uint8_t i = 0; i < num_instances; i++) {
|
||||
Log_Write_Current_instance(time_us,
|
||||
Write_Current_instance(time_us,
|
||||
i,
|
||||
(LogMessages)((uint8_t)LOG_CURRENT_MSG + i),
|
||||
(LogMessages)((uint8_t)LOG_CURRENT_CELLS_MSG + i));
|
||||
}
|
||||
}
|
||||
|
||||
void AP_Logger::Log_Write_Compass_instance(const uint64_t time_us, const uint8_t mag_instance, const enum LogMessages type)
|
||||
void AP_Logger::Write_Compass_instance(const uint64_t time_us, const uint8_t mag_instance, const enum LogMessages type)
|
||||
{
|
||||
const Compass &compass = AP::compass();
|
||||
|
||||
|
@ -1477,27 +1477,27 @@ void AP_Logger::Log_Write_Compass_instance(const uint64_t time_us, const uint8_t
|
|||
}
|
||||
|
||||
// Write a Compass packet
|
||||
void AP_Logger::Log_Write_Compass(uint64_t time_us)
|
||||
void AP_Logger::Write_Compass(uint64_t time_us)
|
||||
{
|
||||
if (time_us == 0) {
|
||||
time_us = AP_HAL::micros64();
|
||||
}
|
||||
const Compass &compass = AP::compass();
|
||||
if (compass.get_count() > 0) {
|
||||
Log_Write_Compass_instance(time_us, 0, LOG_COMPASS_MSG);
|
||||
Write_Compass_instance(time_us, 0, LOG_COMPASS_MSG);
|
||||
}
|
||||
|
||||
if (compass.get_count() > 1) {
|
||||
Log_Write_Compass_instance(time_us, 1, LOG_COMPASS2_MSG);
|
||||
Write_Compass_instance(time_us, 1, LOG_COMPASS2_MSG);
|
||||
}
|
||||
|
||||
if (compass.get_count() > 2) {
|
||||
Log_Write_Compass_instance(time_us, 2, LOG_COMPASS3_MSG);
|
||||
Write_Compass_instance(time_us, 2, LOG_COMPASS3_MSG);
|
||||
}
|
||||
}
|
||||
|
||||
// Write a mode packet.
|
||||
bool AP_Logger_Backend::Log_Write_Mode(uint8_t mode, uint8_t reason)
|
||||
bool AP_Logger_Backend::Write_Mode(uint8_t mode, uint8_t reason)
|
||||
{
|
||||
struct log_Mode pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_MODE_MSG),
|
||||
|
@ -1510,12 +1510,12 @@ bool AP_Logger_Backend::Log_Write_Mode(uint8_t mode, uint8_t reason)
|
|||
}
|
||||
|
||||
// Write ESC status messages
|
||||
void AP_Logger::Log_Write_ESC(void)
|
||||
void AP_Logger::Write_ESC(void)
|
||||
{
|
||||
}
|
||||
|
||||
// Write a AIRSPEED packet
|
||||
void AP_Logger::Log_Write_Airspeed(AP_Airspeed &airspeed)
|
||||
void AP_Logger::Write_Airspeed(AP_Airspeed &airspeed)
|
||||
{
|
||||
uint64_t now = AP_HAL::micros64();
|
||||
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
|
||||
|
@ -1543,7 +1543,7 @@ void AP_Logger::Log_Write_Airspeed(AP_Airspeed &airspeed)
|
|||
}
|
||||
|
||||
// Write a Yaw PID packet
|
||||
void AP_Logger::Log_Write_PID(uint8_t msg_type, const PID_Info &info)
|
||||
void AP_Logger::Write_PID(uint8_t msg_type, const PID_Info &info)
|
||||
{
|
||||
struct log_PID pkt = {
|
||||
LOG_PACKET_HEADER_INIT(msg_type),
|
||||
|
@ -1558,7 +1558,7 @@ void AP_Logger::Log_Write_PID(uint8_t msg_type, const PID_Info &info)
|
|||
WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
void AP_Logger::Log_Write_Origin(uint8_t origin_type, const Location &loc)
|
||||
void AP_Logger::Write_Origin(uint8_t origin_type, const Location &loc)
|
||||
{
|
||||
uint64_t time_us = AP_HAL::micros64();
|
||||
struct log_ORGN pkt = {
|
||||
|
@ -1572,7 +1572,7 @@ void AP_Logger::Log_Write_Origin(uint8_t origin_type, const Location &loc)
|
|||
WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
void AP_Logger::Log_Write_RPM(const AP_RPM &rpm_sensor)
|
||||
void AP_Logger::Write_RPM(const AP_RPM &rpm_sensor)
|
||||
{
|
||||
struct log_RPM pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_RPM_MSG),
|
||||
|
@ -1584,7 +1584,7 @@ void AP_Logger::Log_Write_RPM(const AP_RPM &rpm_sensor)
|
|||
}
|
||||
|
||||
// Write a rate packet
|
||||
void AP_Logger::Log_Write_Rate(const AP_AHRS_View *ahrs,
|
||||
void AP_Logger::Write_Rate(const AP_AHRS_View *ahrs,
|
||||
const AP_Motors &motors,
|
||||
const AC_AttitudeControl &attitude_control,
|
||||
const AC_PosControl &pos_control)
|
||||
|
@ -1611,7 +1611,7 @@ void AP_Logger::Log_Write_Rate(const AP_AHRS_View *ahrs,
|
|||
}
|
||||
|
||||
// Write rally points
|
||||
void AP_Logger::Log_Write_Rally(const AP_Rally &rally)
|
||||
void AP_Logger::Write_Rally(const AP_Rally &rally)
|
||||
{
|
||||
RallyLocation rally_point;
|
||||
for (uint8_t i=0; i<rally.get_rally_total(); i++) {
|
||||
|
@ -1631,7 +1631,7 @@ void AP_Logger::Log_Write_Rally(const AP_Rally &rally)
|
|||
}
|
||||
|
||||
// Write visual odometry sensor data
|
||||
void AP_Logger::Log_Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence)
|
||||
void AP_Logger::Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence)
|
||||
{
|
||||
struct log_VisualOdom pkt_visualodom = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_VISUALODOM_MSG),
|
||||
|
@ -1649,7 +1649,7 @@ void AP_Logger::Log_Write_VisualOdom(float time_delta, const Vector3f &angle_del
|
|||
}
|
||||
|
||||
// Write AOA and SSA
|
||||
void AP_Logger::Log_Write_AOA_SSA(AP_AHRS &ahrs)
|
||||
void AP_Logger::Write_AOA_SSA(AP_AHRS &ahrs)
|
||||
{
|
||||
struct log_AOA_SSA aoa_ssa = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_AOA_SSA_MSG),
|
||||
|
@ -1662,7 +1662,7 @@ void AP_Logger::Log_Write_AOA_SSA(AP_AHRS &ahrs)
|
|||
}
|
||||
|
||||
// Write beacon sensor (position) data
|
||||
void AP_Logger::Log_Write_Beacon(AP_Beacon &beacon)
|
||||
void AP_Logger::Write_Beacon(AP_Beacon &beacon)
|
||||
{
|
||||
if (!beacon.enabled()) {
|
||||
return;
|
||||
|
@ -1689,7 +1689,7 @@ void AP_Logger::Log_Write_Beacon(AP_Beacon &beacon)
|
|||
}
|
||||
|
||||
// Write proximity sensor distances
|
||||
void AP_Logger::Log_Write_Proximity(AP_Proximity &proximity)
|
||||
void AP_Logger::Write_Proximity(AP_Proximity &proximity)
|
||||
{
|
||||
// exit immediately if not enabled
|
||||
if (proximity.get_status() == AP_Proximity::Proximity_NotConnected) {
|
||||
|
@ -1726,7 +1726,7 @@ void AP_Logger::Log_Write_Proximity(AP_Proximity &proximity)
|
|||
WriteBlock(&pkt_proximity, sizeof(pkt_proximity));
|
||||
}
|
||||
|
||||
void AP_Logger::Log_Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& breadcrumb)
|
||||
void AP_Logger::Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& breadcrumb)
|
||||
{
|
||||
struct log_SRTL pkt_srtl = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_SRTL_MSG),
|
||||
|
|
|
@ -1085,7 +1085,7 @@ struct PACKED log_DSTL {
|
|||
#define ACC_UNITS "ssnnn"
|
||||
#define ACC_MULTS "FF000"
|
||||
|
||||
// see "struct sensor" in AP_Baro.h and "Log_Write_Baro":
|
||||
// see "struct sensor" in AP_Baro.h and "Write_Baro":
|
||||
#define BARO_LABELS "TimeUS,Alt,Press,Temp,CRt,SMS,Offset,GndTemp"
|
||||
#define BARO_FMT "QffcfIff"
|
||||
#define BARO_UNITS "smPOnsmO"
|
||||
|
@ -1101,7 +1101,7 @@ struct PACKED log_DSTL {
|
|||
#define GPA_UNITS "smmmn-ss"
|
||||
#define GPA_MULTS "FBBBB-CF"
|
||||
|
||||
// see "struct GPS_State" and "Log_Write_GPS":
|
||||
// see "struct GPS_State" and "Write_GPS":
|
||||
#define GPS_LABELS "TimeUS,Status,GMS,GWk,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,U"
|
||||
#define GPS_FMT "QBIHBcLLefffB"
|
||||
#define GPS_UNITS "s---SmDUmnhn-"
|
||||
|
|
|
@ -42,7 +42,7 @@ void LoggerMessageWriter_DFLogStart::process()
|
|||
case ls_blockwriter_stage_formats:
|
||||
// write log formats so the log is self-describing
|
||||
while (next_format_to_send < _dataflash_backend->num_types()) {
|
||||
if (!_dataflash_backend->Log_Write_Format(_dataflash_backend->structure(next_format_to_send))) {
|
||||
if (!_dataflash_backend->Write_Format(_dataflash_backend->structure(next_format_to_send))) {
|
||||
return; // call me again!
|
||||
}
|
||||
next_format_to_send++;
|
||||
|
@ -53,7 +53,7 @@ void LoggerMessageWriter_DFLogStart::process()
|
|||
|
||||
case ls_blockwriter_stage_units:
|
||||
while (_next_unit_to_send < _dataflash_backend->num_units()) {
|
||||
if (!_dataflash_backend->Log_Write_Unit(_dataflash_backend->unit(_next_unit_to_send))) {
|
||||
if (!_dataflash_backend->Write_Unit(_dataflash_backend->unit(_next_unit_to_send))) {
|
||||
return; // call me again!
|
||||
}
|
||||
_next_unit_to_send++;
|
||||
|
@ -63,7 +63,7 @@ void LoggerMessageWriter_DFLogStart::process()
|
|||
|
||||
case ls_blockwriter_stage_multipliers:
|
||||
while (_next_multiplier_to_send < _dataflash_backend->num_multipliers()) {
|
||||
if (!_dataflash_backend->Log_Write_Multiplier(_dataflash_backend->multiplier(_next_multiplier_to_send))) {
|
||||
if (!_dataflash_backend->Write_Multiplier(_dataflash_backend->multiplier(_next_multiplier_to_send))) {
|
||||
return; // call me again!
|
||||
}
|
||||
_next_multiplier_to_send++;
|
||||
|
@ -73,7 +73,7 @@ void LoggerMessageWriter_DFLogStart::process()
|
|||
|
||||
case ls_blockwriter_stage_format_units:
|
||||
while (_next_format_unit_to_send < _dataflash_backend->num_types()) {
|
||||
if (!_dataflash_backend->Log_Write_Format_Units(_dataflash_backend->structure(_next_format_unit_to_send))) {
|
||||
if (!_dataflash_backend->Write_Format_Units(_dataflash_backend->structure(_next_format_unit_to_send))) {
|
||||
return; // call me again!
|
||||
}
|
||||
_next_format_unit_to_send++;
|
||||
|
@ -83,7 +83,7 @@ void LoggerMessageWriter_DFLogStart::process()
|
|||
|
||||
case ls_blockwriter_stage_parms:
|
||||
while (ap) {
|
||||
if (!_dataflash_backend->Log_Write_Parameter(ap, token, type)) {
|
||||
if (!_dataflash_backend->Write_Parameter(ap, token, type)) {
|
||||
return;
|
||||
}
|
||||
ap = AP_Param::next_scalar(&token, &type);
|
||||
|
@ -144,7 +144,7 @@ void LoggerMessageWriter_WriteSysInfo::process() {
|
|||
FALLTHROUGH;
|
||||
|
||||
case ws_blockwriter_stage_firmware_string:
|
||||
if (! _dataflash_backend->Log_Write_Message(fwver.fw_string)) {
|
||||
if (! _dataflash_backend->Write_Message(fwver.fw_string)) {
|
||||
return; // call me again
|
||||
}
|
||||
stage = ws_blockwriter_stage_git_versions;
|
||||
|
@ -152,7 +152,7 @@ void LoggerMessageWriter_WriteSysInfo::process() {
|
|||
|
||||
case ws_blockwriter_stage_git_versions:
|
||||
if (fwver.middleware_name && fwver.os_name) {
|
||||
if (! _dataflash_backend->Log_Write_MessageF("%s: %s %s: %s",
|
||||
if (! _dataflash_backend->Write_MessageF("%s: %s %s: %s",
|
||||
fwver.middleware_name,
|
||||
fwver.middleware_hash_str,
|
||||
fwver.os_name,
|
||||
|
@ -160,7 +160,7 @@ void LoggerMessageWriter_WriteSysInfo::process() {
|
|||
return; // call me again
|
||||
}
|
||||
} else if (fwver.os_name) {
|
||||
if (! _dataflash_backend->Log_Write_MessageF("%s: %s",
|
||||
if (! _dataflash_backend->Write_MessageF("%s: %s",
|
||||
fwver.os_name,
|
||||
fwver.os_hash_str)) {
|
||||
return; // call me again
|
||||
|
@ -172,7 +172,7 @@ void LoggerMessageWriter_WriteSysInfo::process() {
|
|||
case ws_blockwriter_stage_system_id:
|
||||
char sysid[40];
|
||||
if (hal.util->get_system_id(sysid)) {
|
||||
if (! _dataflash_backend->Log_Write_Message(sysid)) {
|
||||
if (! _dataflash_backend->Write_Message(sysid)) {
|
||||
return; // call me again
|
||||
}
|
||||
}
|
||||
|
@ -200,7 +200,7 @@ void LoggerMessageWriter_WriteEntireMission::process() {
|
|||
FALLTHROUGH;
|
||||
|
||||
case em_blockwriter_stage_write_new_mission_message:
|
||||
if (! _dataflash_backend->Log_Write_Message("New mission")) {
|
||||
if (! _dataflash_backend->Write_Message("New mission")) {
|
||||
return; // call me again
|
||||
}
|
||||
stage = em_blockwriter_stage_write_mission_items;
|
||||
|
@ -212,7 +212,7 @@ void LoggerMessageWriter_WriteEntireMission::process() {
|
|||
// upon failure to write the mission we will re-read from
|
||||
// storage; this could be improved.
|
||||
if (_mission->read_cmd_from_storage(_mission_number_to_send,cmd)) {
|
||||
if (!_dataflash_backend->Log_Write_Mission_Cmd(*_mission, cmd)) {
|
||||
if (!_dataflash_backend->Write_Mission_Cmd(*_mission, cmd)) {
|
||||
return; // call me again
|
||||
}
|
||||
}
|
||||
|
|
|
@ -166,7 +166,7 @@ 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);
|
||||
|
||||
dataflash.Log_Write("TYP3", TYP1_LBL, TYP1_FMT,
|
||||
dataflash.Write("TYP3", TYP1_LBL, TYP1_FMT,
|
||||
AP_HAL::micros64(),
|
||||
-17, // int8_t
|
||||
42, // uint8_t
|
||||
|
@ -183,7 +183,7 @@ void AP_LoggerTest_AllTypes::Log_Write_TypeMessages_Log_Write()
|
|||
"ABCDEFGHIJKLMNOPABCDEFGHIJKLMNOPABCDEFGHIJKLMNOPABCDEFGHIJKLMNOP"
|
||||
);
|
||||
|
||||
dataflash.Log_Write("TYP4", TYP2_LBL, TYP2_FMT,
|
||||
dataflash.Write("TYP4", TYP2_LBL, TYP2_FMT,
|
||||
AP_HAL::micros64(),
|
||||
-9823, // int16_t * 100
|
||||
5436, // uint16_t * 100
|
||||
|
@ -196,7 +196,7 @@ void AP_LoggerTest_AllTypes::Log_Write_TypeMessages_Log_Write()
|
|||
);
|
||||
|
||||
// emit a message which contains NaNs:
|
||||
dataflash.Log_Write("NANS", "f,d,bf,bd", "fdfd", dataflash.quiet_nanf(), dataflash.quiet_nan(), NAN, NAN);
|
||||
dataflash.Write("NANS", "f,d,bf,bd", "fdfd", dataflash.quiet_nanf(), dataflash.quiet_nan(), NAN, NAN);
|
||||
|
||||
flush_dataflash(dataflash);
|
||||
|
||||
|
@ -210,7 +210,7 @@ void AP_LoggerTest_AllTypes::setup(void)
|
|||
log_bitmask = (uint32_t)-1;
|
||||
dataflash.Init(log_structure, ARRAY_SIZE(log_structure));
|
||||
dataflash.set_vehicle_armed(true);
|
||||
dataflash.Log_Write_Message("AP_Logger Test");
|
||||
dataflash.Write_Message("AP_Logger Test");
|
||||
|
||||
// Test
|
||||
hal.scheduler->delay(20);
|
||||
|
|
|
@ -53,7 +53,7 @@ void AP_LoggerTest::setup(void)
|
|||
log_bitmask = (uint32_t)-1;
|
||||
dataflash.Init(log_structure, ARRAY_SIZE(log_structure));
|
||||
dataflash.set_vehicle_armed(true);
|
||||
dataflash.Log_Write_Message("AP_Logger Test");
|
||||
dataflash.Write_Message("AP_Logger Test");
|
||||
|
||||
// Test
|
||||
hal.scheduler->delay(20);
|
||||
|
|
|
@ -179,7 +179,7 @@ void SoloGimbal_Parameters::handle_param_value(const mavlink_message_t *msg)
|
|||
|
||||
AP_Logger *dataflash = AP_Logger::instance();
|
||||
if (dataflash != nullptr) {
|
||||
dataflash->Log_Write_Parameter(packet.param_id, packet.param_value);
|
||||
dataflash->Write_Parameter(packet.param_id, packet.param_value);
|
||||
}
|
||||
|
||||
for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
|
||||
|
|
|
@ -563,24 +563,24 @@ void NavEKF2::check_log_write(void)
|
|||
return;
|
||||
}
|
||||
if (logging.log_compass) {
|
||||
AP_Logger::instance()->Log_Write_Compass(imuSampleTime_us);
|
||||
AP::logger().Write_Compass(imuSampleTime_us);
|
||||
logging.log_compass = false;
|
||||
}
|
||||
if (logging.log_gps) {
|
||||
AP_Logger::instance()->Log_Write_GPS(AP::gps().primary_sensor(), imuSampleTime_us);
|
||||
AP::logger().Write_GPS(AP::gps().primary_sensor(), imuSampleTime_us);
|
||||
logging.log_gps = false;
|
||||
}
|
||||
if (logging.log_baro) {
|
||||
AP_Logger::instance()->Log_Write_Baro(imuSampleTime_us);
|
||||
AP::logger().Write_Baro(imuSampleTime_us);
|
||||
logging.log_baro = false;
|
||||
}
|
||||
if (logging.log_imu) {
|
||||
AP_Logger::instance()->Log_Write_IMUDT(imuSampleTime_us, _logging_mask.get());
|
||||
AP::logger().Write_IMUDT(imuSampleTime_us, _logging_mask.get());
|
||||
logging.log_imu = false;
|
||||
}
|
||||
|
||||
// this is an example of an ad-hoc log in EKF
|
||||
// AP_Logger::instance()->Log_Write("NKA", "TimeUS,X", "Qf", AP_HAL::micros64(), (double)2.4f);
|
||||
// AP::logger().Write("NKA", "TimeUS,X", "Qf", AP_HAL::micros64(), (double)2.4f);
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -595,24 +595,24 @@ void NavEKF3::check_log_write(void)
|
|||
return;
|
||||
}
|
||||
if (logging.log_compass) {
|
||||
AP_Logger::instance()->Log_Write_Compass(imuSampleTime_us);
|
||||
AP::logger().Write_Compass(imuSampleTime_us);
|
||||
logging.log_compass = false;
|
||||
}
|
||||
if (logging.log_gps) {
|
||||
AP_Logger::instance()->Log_Write_GPS(AP::gps().primary_sensor(), imuSampleTime_us);
|
||||
AP::logger().Write_GPS(AP::gps().primary_sensor(), imuSampleTime_us);
|
||||
logging.log_gps = false;
|
||||
}
|
||||
if (logging.log_baro) {
|
||||
AP_Logger::instance()->Log_Write_Baro(imuSampleTime_us);
|
||||
AP::logger().Write_Baro(imuSampleTime_us);
|
||||
logging.log_baro = false;
|
||||
}
|
||||
if (logging.log_imu) {
|
||||
AP_Logger::instance()->Log_Write_IMUDT(imuSampleTime_us, _logging_mask.get());
|
||||
AP::logger().Write_IMUDT(imuSampleTime_us, _logging_mask.get());
|
||||
logging.log_imu = false;
|
||||
}
|
||||
|
||||
// this is an example of an ad-hoc log in EKF
|
||||
// AP_Logger::instance()->Log_Write("NKA", "TimeUS,X", "Qf", AP_HAL::micros64(), (double)2.4f);
|
||||
// AP::logger().Write("NKA", "TimeUS,X", "Qf", AP_HAL::micros64(), (double)2.4f);
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -279,7 +279,7 @@ void AP_Scheduler::update_logging()
|
|||
perf_info.update_logging();
|
||||
}
|
||||
if (_log_performance_bit != (uint32_t)-1 &&
|
||||
AP_Logger::instance()->should_log(_log_performance_bit)) {
|
||||
AP::logger().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)
|
||||
};
|
||||
AP_Logger::instance()->WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
namespace AP {
|
||||
|
|
|
@ -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) {
|
||||
AP_Logger::instance()->Log_Write_SRTL(_active, _path_points_count, _path_points_max, action, point);
|
||||
AP::logger().Write_SRTL(_active, _path_points_count, _path_points_max, action, point);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -279,7 +279,7 @@ void SoaringController::update_thermalling()
|
|||
#endif
|
||||
|
||||
// write log - save the data.
|
||||
AP_Logger::instance()->Log_Write("SOAR", "TimeUS,nettorate,dx,dy,x0,x1,x2,x3,lat,lng,alt,dx_w,dy_w", "QfffffffLLfff",
|
||||
AP::logger().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,
|
||||
|
|
|
@ -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;
|
||||
|
||||
AP_Logger::instance()->Log_Write("VAR", "TimeUS,aspd_raw,aspd_filt,alt,roll,raw,filt", "Qffffff",
|
||||
AP::logger().Write("VAR", "TimeUS,aspd_raw,aspd_filt,alt,roll,raw,filt", "Qffffff",
|
||||
AP_HAL::micros64(),
|
||||
(double)aspd,
|
||||
(double)_aspd_filt,
|
||||
|
|
|
@ -1077,7 +1077,7 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
|
|||
_update_pitch();
|
||||
|
||||
// log to AP_Logger
|
||||
AP_Logger::instance()->Log_Write(
|
||||
AP::logger().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);
|
||||
AP_Logger::instance()->Log_Write("TEC2", "TimeUS,KErr,PErr,EDelta,LF", "Qffff",
|
||||
AP::logger().Write("TEC2", "TimeUS,KErr,PErr,EDelta,LF", "Qffff",
|
||||
now,
|
||||
(double)logging.SKE_error,
|
||||
(double)logging.SPE_error,
|
||||
|
|
|
@ -370,7 +370,7 @@ void AP_Terrain::log_terrain_data()
|
|||
pending : pending,
|
||||
loaded : loaded
|
||||
};
|
||||
AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt));
|
||||
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -226,7 +226,7 @@ void AP_Tuning::check_input(uint8_t flightmode)
|
|||
*/
|
||||
void AP_Tuning::Log_Write_Parameter_Tuning(float value)
|
||||
{
|
||||
AP_Logger::instance()->Log_Write("PTUN", "TimeUS,Set,Parm,Value,CenterValue", "QBBff",
|
||||
AP::logger().Write("PTUN", "TimeUS,Set,Parm,Value,CenterValue", "QBBff",
|
||||
AP_HAL::micros64(),
|
||||
parmset,
|
||||
current_parm,
|
||||
|
|
|
@ -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)
|
||||
{
|
||||
AP_Logger::instance()->Log_Write("UCEV", "TimeUS,code,arg", "s--", "F--", "Qhq", AP_HAL::micros64(), code, argument);
|
||||
AP::logger().Write("UCEV", "TimeUS,code,arg", "s--", "F--", "Qhq", AP_HAL::micros64(), code, argument);
|
||||
}
|
||||
};
|
||||
|
||||
|
|
|
@ -726,7 +726,7 @@ void GCS_MAVLINK::handle_radio_status(mavlink_message_t *msg, AP_Logger &datafla
|
|||
|
||||
//log rssi, noise, etc if logging Performance monitoring data
|
||||
if (log_radio) {
|
||||
dataflash.Log_Write_Radio(packet);
|
||||
dataflash.Write_Radio(packet);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1173,7 +1173,7 @@ void GCS_MAVLINK::update_send()
|
|||
{
|
||||
if (!hal.scheduler->in_delay_callback()) {
|
||||
// AP_Logger will not send log data if we are armed.
|
||||
AP_Logger::instance()->handle_log_send();
|
||||
AP::logger().handle_log_send();
|
||||
}
|
||||
|
||||
if (!deferred_messages_initialised) {
|
||||
|
@ -1843,7 +1843,7 @@ void GCS::send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const cha
|
|||
{
|
||||
AP_Logger *dataflash = AP_Logger::instance();
|
||||
if (dataflash != nullptr) {
|
||||
dataflash->Log_Write_Message(text);
|
||||
dataflash->Write_Message(text);
|
||||
}
|
||||
|
||||
// add statustext message to FrSky lib queue
|
||||
|
@ -2518,7 +2518,7 @@ void GCS_MAVLINK::handle_timesync(mavlink_message_t *msg)
|
|||
#endif
|
||||
AP_Logger *df = AP_Logger::instance();
|
||||
if (df != nullptr) {
|
||||
AP_Logger::instance()->Log_Write(
|
||||
AP::logger().Write(
|
||||
"TSYN",
|
||||
"TimeUS,SysID,RTT",
|
||||
"s-s",
|
||||
|
@ -2589,7 +2589,7 @@ void GCS_MAVLINK::handle_statustext(mavlink_message_t *msg)
|
|||
|
||||
memcpy(&text[offset], packet.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
|
||||
|
||||
df->Log_Write_Message(text);
|
||||
df->Write_Message(text);
|
||||
}
|
||||
|
||||
|
||||
|
@ -2796,7 +2796,7 @@ void GCS_MAVLINK::log_vision_position_estimate_data(const uint64_t usec,
|
|||
const float pitch,
|
||||
const float yaw)
|
||||
{
|
||||
AP_Logger::instance()->Log_Write("VISP", "TimeUS,RemTimeUS,PX,PY,PZ,Roll,Pitch,Yaw",
|
||||
AP::logger().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:
|
||||
AP_Logger::instance()->handle_mavlink_msg(*this, msg);
|
||||
AP::logger().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)) {
|
||||
AP_Logger::instance()->Log_Write_EntireMission(*_mission);
|
||||
AP::logger().Write_EntireMission(*_mission);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -294,7 +294,7 @@ void GCS_MAVLINK::handle_param_set(mavlink_message_t *msg)
|
|||
|
||||
AP_Logger *AP_Logger = AP_Logger::instance();
|
||||
if (AP_Logger != nullptr) {
|
||||
AP_Logger->Log_Write_Parameter(key, vp->cast_to_float(var_type));
|
||||
AP_Logger->Write_Parameter(key, vp->cast_to_float(var_type));
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -321,7 +321,7 @@ void GCS::send_parameter_value(const char *param_name, ap_var_type param_type, f
|
|||
// also log to AP_Logger
|
||||
AP_Logger *dataflash = AP_Logger::instance();
|
||||
if (dataflash != nullptr) {
|
||||
dataflash->Log_Write_Parameter(param_name, param_value);
|
||||
dataflash->Write_Parameter(param_name, param_value);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -187,7 +187,7 @@ void Aircraft::update_position(void)
|
|||
#if 0
|
||||
// logging of raw sitl data
|
||||
Vector3f accel_ef = dcm * accel_body;
|
||||
AP_Logger::instance()->Log_Write("SITL", "TimeUS,VN,VE,VD,AN,AE,AD,PN,PE,PD", "Qfffffffff",
|
||||
AP::logger().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
|
||||
AP_Logger::instance()->Log_Write("SMOO", "TimeUS,AEx,AEy,AEz,DPx,DPy,DPz,R,P,Y,R2,P2,Y2",
|
||||
AP::logger().Write("SMOO", "TimeUS,AEx,AEy,AEz,DPx,DPy,DPz,R,P,Y,R2,P2,Y2",
|
||||
"Qffffffffffff",
|
||||
AP_HAL::micros64(),
|
||||
degrees(angle_differential.x),
|
||||
|
|
|
@ -195,7 +195,7 @@ void SITL::Log_Write_SIMSTATE()
|
|||
q3 : state.quaternion.q3,
|
||||
q4 : state.quaternion.q4,
|
||||
};
|
||||
AP_Logger::instance()->WriteBlock(&pkt, sizeof(pkt));
|
||||
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue