ardupilot/libraries/AP_Logger/LogFile.cpp

969 lines
32 KiB
C++
Raw Normal View History

#include <stdlib.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <AP_Motors/AP_Motors.h>
#include <AC_AttitudeControl/AC_AttitudeControl.h>
#include <AC_AttitudeControl/AC_PosControl.h>
#include <AP_RSSI/AP_RSSI.h>
2019-06-13 23:58:15 -03:00
#include <AP_GPS/AP_GPS.h>
#include "AP_Logger.h"
#include "AP_Logger_File.h"
#include "AP_Logger_MAVLink.h"
#include "LoggerMessageWriter.h"
extern const AP_HAL::HAL& hal;
/*
2015-06-25 10:53:20 -03:00
write a structure format to the log - should be in frontend
*/
void AP_Logger_Backend::Fill_Format(const struct LogStructure *s, struct log_Format &pkt)
{
memset(&pkt, 0, sizeof(pkt));
pkt.head1 = HEAD_BYTE1;
pkt.head2 = HEAD_BYTE2;
pkt.msgid = LOG_FORMAT_MSG;
2015-12-23 12:06:58 -04:00
pkt.type = s->msg_type;
pkt.length = s->msg_len;
strncpy(pkt.name, s->name, sizeof(pkt.name));
strncpy(pkt.format, s->format, sizeof(pkt.format));
strncpy(pkt.labels, s->labels, sizeof(pkt.labels));
}
2015-12-07 20:51:46 -04:00
/*
Pack a LogStructure packet into a structure suitable to go to the logfile:
*/
void AP_Logger_Backend::Fill_Format_Units(const struct LogStructure *s, struct log_Format_Units &pkt)
2015-12-07 20:51:46 -04:00
{
memset(&pkt, 0, sizeof(pkt));
pkt.head1 = HEAD_BYTE1;
pkt.head2 = HEAD_BYTE2;
pkt.msgid = LOG_FORMAT_UNITS_MSG;
pkt.time_us = AP_HAL::micros64();
pkt.format_type = s->msg_type;
strncpy(pkt.units, s->units, sizeof(pkt.units));
strncpy(pkt.multipliers, s->multipliers, sizeof(pkt.multipliers));
}
/*
write a structure format to the log
*/
bool AP_Logger_Backend::Write_Format(const struct LogStructure *s)
{
struct log_Format pkt;
Fill_Format(s, pkt);
return WriteCriticalBlock(&pkt, sizeof(pkt));
}
2015-12-07 20:51:46 -04:00
/*
write a unit definition
*/
bool AP_Logger_Backend::Write_Unit(const struct UnitStructure *s)
2015-12-07 20:51:46 -04:00
{
struct log_Unit pkt = {
LOG_PACKET_HEADER_INIT(LOG_UNIT_MSG),
time_us : AP_HAL::micros64(),
type : s->ID,
unit : { }
};
strncpy(pkt.unit, s->unit, sizeof(pkt.unit));
return WriteCriticalBlock(&pkt, sizeof(pkt));
}
/*
write a unit-multiplier definition
*/
bool AP_Logger_Backend::Write_Multiplier(const struct MultiplierStructure *s)
2015-12-07 20:51:46 -04:00
{
struct log_Format_Multiplier pkt = {
LOG_PACKET_HEADER_INIT(LOG_MULT_MSG),
time_us : AP_HAL::micros64(),
type : s->ID,
multiplier : s->multiplier,
};
return WriteCriticalBlock(&pkt, sizeof(pkt));
}
/*
write the units for a format to the log
*/
bool AP_Logger_Backend::Write_Format_Units(const struct LogStructure *s)
2015-12-07 20:51:46 -04:00
{
struct log_Format_Units pkt;
Fill_Format_Units(s, pkt);
2015-12-07 20:51:46 -04:00
return WriteCriticalBlock(&pkt, sizeof(pkt));
}
/*
write a parameter to the log
*/
bool AP_Logger_Backend::Write_Parameter(const char *name, float value)
{
struct log_Parameter pkt = {
LOG_PACKET_HEADER_INIT(LOG_PARAMETER_MSG),
time_us : AP_HAL::micros64(),
name : {},
value : value
};
strncpy(pkt.name, name, sizeof(pkt.name));
return WriteCriticalBlock(&pkt, sizeof(pkt));
}
/*
write a parameter to the log
*/
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 Write_Parameter(name, ap->cast_to_float(type));
}
// Write an GPS packet
void AP_Logger::Write_GPS(uint8_t i, uint64_t time_us)
{
const AP_GPS &gps = AP::gps();
if (time_us == 0) {
time_us = AP_HAL::micros64();
}
const struct Location &loc = gps.location(i);
struct log_GPS pkt = {
LOG_PACKET_HEADER_INIT((uint8_t)(LOG_GPS_MSG+i)),
time_us : time_us,
status : (uint8_t)gps.status(i),
gps_week_ms : gps.time_week_ms(i),
gps_week : gps.time_week(i),
num_sats : gps.num_sats(i),
hdop : gps.get_hdop(i),
latitude : loc.lat,
longitude : loc.lng,
altitude : loc.alt,
ground_speed : gps.ground_speed(i),
ground_course : gps.ground_course(i),
vel_z : gps.velocity(i).z,
used : (uint8_t)(gps.primary_sensor() == i)
};
WriteBlock(&pkt, sizeof(pkt));
2016-05-12 13:50:13 -03:00
/* write auxiliary accuracy information as well */
float hacc = 0, vacc = 0, sacc = 0;
gps.horizontal_accuracy(i, hacc);
gps.vertical_accuracy(i, vacc);
gps.speed_accuracy(i, sacc);
struct log_GPA pkt2 = {
LOG_PACKET_HEADER_INIT((uint8_t)(LOG_GPA_MSG+i)),
time_us : time_us,
vdop : gps.get_vdop(i),
2017-04-16 19:56:55 -03:00
hacc : (uint16_t)MIN((hacc*100), UINT16_MAX),
vacc : (uint16_t)MIN((vacc*100), UINT16_MAX),
sacc : (uint16_t)MIN((sacc*100), UINT16_MAX),
have_vv : (uint8_t)gps.have_vertical_velocity(i),
sample_ms : gps.last_message_time_ms(i),
delta_ms : gps.last_message_delta_time_ms(i)
};
WriteBlock(&pkt2, sizeof(pkt2));
}
// Write an RCIN packet
void AP_Logger::Write_RCIN(void)
{
uint16_t values[14] = {};
rc().get_radio_in(values, ARRAY_SIZE(values));
struct log_RCIN pkt = {
LOG_PACKET_HEADER_INIT(LOG_RCIN_MSG),
time_us : AP_HAL::micros64(),
chan1 : values[0],
chan2 : values[1],
chan3 : values[2],
chan4 : values[3],
chan5 : values[4],
chan6 : values[5],
chan7 : values[6],
chan8 : values[7],
chan9 : values[8],
chan10 : values[9],
chan11 : values[10],
chan12 : values[11],
chan13 : values[12],
chan14 : values[13]
};
WriteBlock(&pkt, sizeof(pkt));
}
// Write an SERVO packet
void AP_Logger::Write_RCOUT(void)
{
struct log_RCOUT pkt = {
LOG_PACKET_HEADER_INIT(LOG_RCOUT_MSG),
time_us : AP_HAL::micros64(),
chan1 : hal.rcout->read(0),
chan2 : hal.rcout->read(1),
chan3 : hal.rcout->read(2),
chan4 : hal.rcout->read(3),
chan5 : hal.rcout->read(4),
chan6 : hal.rcout->read(5),
chan7 : hal.rcout->read(6),
chan8 : hal.rcout->read(7),
chan9 : hal.rcout->read(8),
chan10 : hal.rcout->read(9),
chan11 : hal.rcout->read(10),
chan12 : hal.rcout->read(11),
chan13 : hal.rcout->read(12),
chan14 : hal.rcout->read(13)
};
WriteBlock(&pkt, sizeof(pkt));
}
// Write an RSSI packet
void AP_Logger::Write_RSSI()
{
AP_RSSI *rssi = AP::rssi();
if (rssi == nullptr) {
return;
}
struct log_RSSI pkt = {
LOG_PACKET_HEADER_INIT(LOG_RSSI_MSG),
time_us : AP_HAL::micros64(),
RXRSSI : rssi->read_receiver_rssi()
};
WriteBlock(&pkt, sizeof(pkt));
}
void AP_Logger::Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type)
{
2018-03-05 16:36:23 -04:00
AP_Baro &baro = AP::baro();
float climbrate = baro.get_climb_rate();
2016-05-13 17:01:43 -03:00
float drift_offset = baro.get_baro_drift_offset();
float ground_temp = baro.get_ground_temperature();
struct log_BARO pkt = {
2018-04-09 03:04:17 -03:00
LOG_PACKET_HEADER_INIT(type),
time_us : time_us,
altitude : baro.get_altitude(baro_instance),
pressure : baro.get_pressure(baro_instance),
temperature : (int16_t)(baro.get_temperature(baro_instance) * 100 + 0.5f),
climbrate : climbrate,
sample_time_ms: baro.get_last_update(baro_instance),
2016-05-13 17:01:43 -03:00
drift_offset : drift_offset,
ground_temp : ground_temp,
};
WriteBlock(&pkt, sizeof(pkt));
}
// Write a BARO packet
void AP_Logger::Write_Baro(uint64_t time_us)
{
if (time_us == 0) {
time_us = AP_HAL::micros64();
}
2018-03-05 16:36:23 -04:00
const AP_Baro &baro = AP::baro();
Write_Baro_instance(time_us, 0, LOG_BARO_MSG);
2015-01-05 17:37:23 -04:00
if (baro.num_instances() > 1 && baro.healthy(1)) {
Write_Baro_instance(time_us, 1, LOG_BAR2_MSG);
2015-01-05 17:37:23 -04:00
}
if (baro.num_instances() > 2 && baro.healthy(2)) {
Write_Baro_instance(time_us, 2, LOG_BAR3_MSG);
}
}
void AP_Logger::Write_IMU_instance(const uint64_t time_us, const uint8_t imu_instance, const enum LogMessages type)
{
2018-03-10 05:36:33 -04:00
const AP_InertialSensor &ins = AP::ins();
const Vector3f &gyro = ins.get_gyro(imu_instance);
const Vector3f &accel = ins.get_accel(imu_instance);
struct log_IMU pkt = {
LOG_PACKET_HEADER_INIT(type),
time_us : time_us,
gyro_x : gyro.x,
gyro_y : gyro.y,
gyro_z : gyro.z,
accel_x : accel.x,
accel_y : accel.y,
accel_z : accel.z,
gyro_error : ins.get_gyro_error_count(imu_instance),
accel_error : ins.get_accel_error_count(imu_instance),
temperature : ins.get_temperature(imu_instance),
gyro_health : (uint8_t)ins.get_gyro_health(imu_instance),
accel_health : (uint8_t)ins.get_accel_health(imu_instance),
gyro_rate : ins.get_gyro_rate_hz(imu_instance),
accel_rate : ins.get_accel_rate_hz(imu_instance),
};
WriteBlock(&pkt, sizeof(pkt));
}
// Write an raw accel/gyro data packet
void AP_Logger::Write_IMU()
{
uint64_t time_us = AP_HAL::micros64();
2018-03-10 05:36:33 -04:00
const AP_InertialSensor &ins = AP::ins();
Write_IMU_instance(time_us, 0, LOG_IMU_MSG);
if (ins.get_gyro_count() < 2 && ins.get_accel_count() < 2) {
return;
}
Write_IMU_instance(time_us, 1, LOG_IMU2_MSG);
if (ins.get_gyro_count() < 3 && ins.get_accel_count() < 3) {
return;
}
Write_IMU_instance(time_us, 2, LOG_IMU3_MSG);
}
2015-06-13 10:06:49 -03:00
// Write an accel/gyro delta time data packet
void AP_Logger::Write_IMUDT_instance(const uint64_t time_us, const uint8_t imu_instance, const enum LogMessages type)
2015-06-13 10:06:49 -03:00
{
2018-03-10 05:36:33 -04:00
const AP_InertialSensor &ins = AP::ins();
2015-06-13 10:06:49 -03:00
float delta_t = ins.get_delta_time();
float delta_vel_t = ins.get_delta_velocity_dt(imu_instance);
float delta_ang_t = ins.get_delta_angle_dt(imu_instance);
2015-06-13 10:06:49 -03:00
Vector3f delta_angle, delta_velocity;
ins.get_delta_angle(imu_instance, delta_angle);
ins.get_delta_velocity(imu_instance, delta_velocity);
2015-06-13 10:06:49 -03:00
struct log_IMUDT pkt = {
LOG_PACKET_HEADER_INIT(type),
2015-06-13 10:06:49 -03:00
time_us : time_us,
delta_time : delta_t,
delta_vel_dt : delta_vel_t,
delta_ang_dt : delta_ang_t,
2015-06-13 10:06:49 -03:00
delta_ang_x : delta_angle.x,
delta_ang_y : delta_angle.y,
delta_ang_z : delta_angle.z,
delta_vel_x : delta_velocity.x,
delta_vel_y : delta_velocity.y,
delta_vel_z : delta_velocity.z
};
WriteBlock(&pkt, sizeof(pkt));
}
void AP_Logger::Write_IMUDT(uint64_t time_us, uint8_t imu_mask)
{
2018-03-10 05:36:33 -04:00
const AP_InertialSensor &ins = AP::ins();
if (imu_mask & 1) {
Write_IMUDT_instance(time_us, 0, LOG_IMUDT_MSG);
}
if ((ins.get_gyro_count() < 2 && ins.get_accel_count() < 2) || !ins.use_gyro(1)) {
2015-06-13 10:06:49 -03:00
return;
}
if (imu_mask & 2) {
Write_IMUDT_instance(time_us, 1, LOG_IMUDT2_MSG);
}
2015-06-13 10:06:49 -03:00
if ((ins.get_gyro_count() < 3 && ins.get_accel_count() < 3) || !ins.use_gyro(2)) {
2015-06-13 10:06:49 -03:00
return;
}
if (imu_mask & 4) {
Write_IMUDT_instance(time_us, 2, LOG_IMUDT3_MSG);
}
2015-06-13 10:06:49 -03:00
}
void AP_Logger::Write_Vibration()
2015-06-11 10:26:45 -03:00
{
uint64_t time_us = AP_HAL::micros64();
2018-03-10 05:36:33 -04:00
const AP_InertialSensor &ins = AP::ins();
const Vector3f vibration = ins.get_vibration_levels();
2015-06-11 10:26:45 -03:00
struct log_Vibe pkt = {
LOG_PACKET_HEADER_INIT(LOG_VIBE_MSG),
time_us : time_us,
vibe_x : vibration.x,
vibe_y : vibration.y,
vibe_z : vibration.z,
clipping_0 : ins.get_accel_clip_count(0),
clipping_1 : ins.get_accel_clip_count(1),
clipping_2 : ins.get_accel_clip_count(2)
};
WriteBlock(&pkt, sizeof(pkt));
}
bool AP_Logger_Backend::Write_Mission_Cmd(const AP_Mission &mission,
const AP_Mission::Mission_Command &cmd)
{
mavlink_mission_item_int_t mav_cmd = {};
AP_Mission::mission_cmd_to_mavlink_int(cmd,mav_cmd);
struct log_Cmd pkt = {
LOG_PACKET_HEADER_INIT(LOG_CMD_MSG),
time_us : AP_HAL::micros64(),
command_total : mission.num_commands(),
sequence : mav_cmd.seq,
command : mav_cmd.command,
param1 : mav_cmd.param1,
param2 : mav_cmd.param2,
param3 : mav_cmd.param3,
param4 : mav_cmd.param4,
latitude : mav_cmd.x,
longitude : mav_cmd.y,
altitude : mav_cmd.z,
frame : mav_cmd.frame
};
return WriteBlock(&pkt, sizeof(pkt));
}
void AP_Logger_Backend::Write_EntireMission()
{
LoggerMessageWriter_WriteEntireMission writer;
writer.set_logger_backend(this);
writer.process();
}
// Write a text message to the log
bool AP_Logger_Backend::Write_Message(const char *message)
{
struct log_Message pkt = {
LOG_PACKET_HEADER_INIT(LOG_MESSAGE_MSG),
time_us : AP_HAL::micros64(),
msg : {}
};
strncpy(pkt.msg, message, sizeof(pkt.msg));
return WriteCriticalBlock(&pkt, sizeof(pkt));
}
void AP_Logger::Write_Power(void)
2014-02-13 07:07:32 -04:00
{
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
uint8_t safety_and_armed = uint8_t(hal.util->safety_switch_state());
if (hal.util->get_soft_armed()) {
// encode armed state in bit 3
safety_and_armed |= 1U<<2;
}
2014-02-13 07:07:32 -04:00
struct log_POWR pkt = {
LOG_PACKET_HEADER_INIT(LOG_POWR_MSG),
time_us : AP_HAL::micros64(),
Vcc : hal.analogin->board_voltage(),
Vservo : hal.analogin->servorail_voltage(),
flags : hal.analogin->power_status_flags(),
safety_and_arm : safety_and_armed
2014-02-13 07:07:32 -04:00
};
WriteBlock(&pkt, sizeof(pkt));
#endif
}
2014-01-03 01:01:08 -04:00
// Write an AHRS2 packet
void AP_Logger::Write_AHRS2(AP_AHRS &ahrs)
2014-01-03 01:01:08 -04:00
{
Vector3f euler;
struct Location loc;
Quaternion quat;
if (!ahrs.get_secondary_attitude(euler) || !ahrs.get_secondary_position(loc) || !ahrs.get_secondary_quaternion(quat)) {
2014-01-03 01:01:08 -04:00
return;
}
struct log_AHRS pkt = {
LOG_PACKET_HEADER_INIT(LOG_AHR2_MSG),
time_us : AP_HAL::micros64(),
2014-01-03 01:01:08 -04:00
roll : (int16_t)(degrees(euler.x)*100),
pitch : (int16_t)(degrees(euler.y)*100),
yaw : (uint16_t)(wrap_360_cd(degrees(euler.z)*100)),
alt : loc.alt*1.0e-2f,
lat : loc.lat,
lng : loc.lng,
q1 : quat.q1,
q2 : quat.q2,
q3 : quat.q3,
q4 : quat.q4,
2014-01-03 01:01:08 -04:00
};
WriteBlock(&pkt, sizeof(pkt));
}
// Write a POS packet
void AP_Logger::Write_POS(AP_AHRS &ahrs)
{
Location loc;
if (!ahrs.get_position(loc)) {
return;
}
float home, origin;
ahrs.get_relative_position_D_home(home);
struct log_POS pkt = {
LOG_PACKET_HEADER_INIT(LOG_POS_MSG),
time_us : AP_HAL::micros64(),
lat : loc.lat,
lng : loc.lng,
alt : loc.alt*1.0e-2f,
rel_home_alt : -home,
2017-07-21 23:27:45 -03:00
rel_origin_alt : ahrs.get_relative_position_D_origin(origin) ? -origin : quiet_nanf(),
};
WriteBlock(&pkt, sizeof(pkt));
}
#if AP_AHRS_NAVEKF_AVAILABLE
2016-07-14 02:08:43 -03:00
/*
write an EKF timing message
*/
void AP_Logger::Write_EKF_Timing(const char *name, uint64_t time_us, const struct ekf_timing &timing)
{
Write(name,
"TimeUS,Cnt,IMUMin,IMUMax,EKFMin,EKFMax,AngMin,AngMax,VMin,VMax",
"QIffffffff",
time_us,
timing.count,
(double)timing.dtIMUavg_min,
(double)timing.dtIMUavg_max,
(double)timing.dtEKFavg_min,
(double)timing.dtEKFavg_max,
(double)timing.delAngDT_min,
(double)timing.delAngDT_max,
(double)timing.delVelDT_min,
(double)timing.delVelDT_max);
}
#endif
void AP_Logger::Write_Radio(const mavlink_radio_t &packet)
{
struct log_Radio pkt = {
LOG_PACKET_HEADER_INIT(LOG_RADIO_MSG),
time_us : AP_HAL::micros64(),
rssi : packet.rssi,
remrssi : packet.remrssi,
txbuf : packet.txbuf,
noise : packet.noise,
remnoise : packet.remnoise,
rxerrors : packet.rxerrors,
fixed : packet.fixed
};
WriteBlock(&pkt, sizeof(pkt));
}
// Write a Camera packet
void AP_Logger::Write_CameraInfo(enum LogMessages msg, const Location &current_loc, uint64_t timestamp_us)
{
const AP_AHRS &ahrs = AP::ahrs();
int32_t altitude, altitude_rel, altitude_gps;
if (current_loc.relative_alt) {
altitude = current_loc.alt+ahrs.get_home().alt;
altitude_rel = current_loc.alt;
} else {
altitude = current_loc.alt;
altitude_rel = current_loc.alt - ahrs.get_home().alt;
}
const AP_GPS &gps = AP::gps();
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
altitude_gps = gps.location().alt;
} else {
altitude_gps = 0;
}
struct log_Camera pkt = {
LOG_PACKET_HEADER_INIT(static_cast<uint8_t>(msg)),
time_us : timestamp_us?timestamp_us:AP_HAL::micros64(),
gps_time : gps.time_week_ms(),
gps_week : gps.time_week(),
latitude : current_loc.lat,
longitude : current_loc.lng,
altitude : altitude,
altitude_rel: altitude_rel,
altitude_gps: altitude_gps,
roll : (int16_t)ahrs.roll_sensor,
pitch : (int16_t)ahrs.pitch_sensor,
yaw : (uint16_t)ahrs.yaw_sensor
};
2015-10-06 01:13:40 -03:00
WriteCriticalBlock(&pkt, sizeof(pkt));
}
// Write a Camera packet
void AP_Logger::Write_Camera(const Location &current_loc, uint64_t timestamp_us)
{
Write_CameraInfo(LOG_CAMERA_MSG, current_loc, timestamp_us);
}
// Write a Trigger packet
void AP_Logger::Write_Trigger(const Location &current_loc)
{
Write_CameraInfo(LOG_TRIGGER_MSG, current_loc, 0);
}
// Write an attitude packet
void AP_Logger::Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets)
{
struct log_Attitude pkt = {
LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
time_us : AP_HAL::micros64(),
control_roll : (int16_t)targets.x,
roll : (int16_t)ahrs.roll_sensor,
control_pitch : (int16_t)targets.y,
pitch : (int16_t)ahrs.pitch_sensor,
2019-01-13 00:24:05 -04:00
control_yaw : (uint16_t)wrap_360_cd(targets.z),
yaw : (uint16_t)wrap_360_cd(ahrs.yaw_sensor),
error_rp : (uint16_t)(ahrs.get_error_rp() * 100),
error_yaw : (uint16_t)(ahrs.get_error_yaw() * 100)
};
WriteBlock(&pkt, sizeof(pkt));
}
// Write an attitude packet
void AP_Logger::Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets)
{
struct log_Attitude pkt = {
LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
time_us : AP_HAL::micros64(),
control_roll : (int16_t)targets.x,
roll : (int16_t)ahrs.roll_sensor,
control_pitch : (int16_t)targets.y,
pitch : (int16_t)ahrs.pitch_sensor,
control_yaw : (uint16_t)wrap_360_cd(targets.z),
yaw : (uint16_t)wrap_360_cd(ahrs.yaw_sensor),
error_rp : (uint16_t)(ahrs.get_error_rp() * 100),
error_yaw : (uint16_t)(ahrs.get_error_yaw() * 100)
};
WriteBlock(&pkt, sizeof(pkt));
}
void AP_Logger::Write_Current_instance(const uint64_t time_us,
const uint8_t battery_instance,
const enum LogMessages type,
const enum LogMessages celltype)
{
2018-01-16 15:09:47 -04:00
AP_BattMonitor &battery = AP::battery();
float temp;
bool has_temp = battery.get_temperature(temp, battery_instance);
struct log_Current pkt = {
LOG_PACKET_HEADER_INIT(type),
time_us : time_us,
voltage : battery.voltage(battery_instance),
voltage_resting : battery.voltage_resting_estimate(battery_instance),
current_amps : battery.current_amps(battery_instance),
current_total : battery.consumed_mah(battery_instance),
2017-12-05 05:54:11 -04:00
consumed_wh : battery.consumed_wh(battery_instance),
temperature : (int16_t)(has_temp ? (temp * 100) : 0),
resistance : battery.get_resistance(battery_instance)
};
WriteBlock(&pkt, sizeof(pkt));
// individual cell voltages
if (battery.has_cell_voltages(battery_instance)) {
const AP_BattMonitor::cells &cells = battery.get_cell_voltages(battery_instance);
struct log_Current_Cells cell_pkt = {
LOG_PACKET_HEADER_INIT(celltype),
time_us : time_us,
voltage : battery.voltage(battery_instance)
};
for (uint8_t i = 0; i < ARRAY_SIZE(cells.cells); i++) {
cell_pkt.cell_voltages[i] = cells.cells[i] + 1;
}
WriteBlock(&cell_pkt, sizeof(cell_pkt));
// check battery structure can hold all cells
static_assert(ARRAY_SIZE(cells.cells) == (sizeof(cell_pkt.cell_voltages) / sizeof(cell_pkt.cell_voltages[0])),
"Battery cell number doesn't match in library and log structure");
}
}
// Write an Current data packet
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
// LOG_COMPASS_MSG follows the last LOG_CURRENT_CELLSx_MSG
static_assert(((LOG_CURRENT_MSG + AP_BATT_MONITOR_MAX_INSTANCES) == LOG_CURRENT_CELLS_MSG) &&
((LOG_CURRENT_CELLS_MSG + AP_BATT_MONITOR_MAX_INSTANCES) == LOG_COMPASS_MSG),
"The number of batt monitors has changed without updating the log "
"table entries. Please add new enums for LOG_CURRENT_MSG, LOG_CURRENT_CELLS_MSG "
"directly following the highest indexed fields. Don't forget to update the log "
"description table as well.");
const uint64_t time_us = AP_HAL::micros64();
2018-01-16 15:09:47 -04:00
const uint8_t num_instances = AP::battery().num_instances();
for (uint8_t i = 0; i < num_instances; i++) {
Write_Current_instance(time_us,
i,
(LogMessages)((uint8_t)LOG_CURRENT_MSG + i),
(LogMessages)((uint8_t)LOG_CURRENT_CELLS_MSG + i));
}
}
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();
const Vector3f &mag_field = compass.get_field(mag_instance);
const Vector3f &mag_offsets = compass.get_offsets(mag_instance);
const Vector3f &mag_motor_offsets = compass.get_motor_offsets(mag_instance);
struct log_Compass pkt = {
LOG_PACKET_HEADER_INIT(type),
time_us : time_us,
mag_x : (int16_t)mag_field.x,
mag_y : (int16_t)mag_field.y,
mag_z : (int16_t)mag_field.z,
offset_x : (int16_t)mag_offsets.x,
offset_y : (int16_t)mag_offsets.y,
offset_z : (int16_t)mag_offsets.z,
motor_offset_x : (int16_t)mag_motor_offsets.x,
motor_offset_y : (int16_t)mag_motor_offsets.y,
motor_offset_z : (int16_t)mag_motor_offsets.z,
health : (uint8_t)compass.healthy(mag_instance),
SUS : compass.last_update_usec(mag_instance)
};
WriteBlock(&pkt, sizeof(pkt));
}
// Write a Compass packet
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) {
Write_Compass_instance(time_us, 0, LOG_COMPASS_MSG);
}
if (compass.get_count() > 1) {
Write_Compass_instance(time_us, 1, LOG_COMPASS2_MSG);
}
if (compass.get_count() > 2) {
Write_Compass_instance(time_us, 2, LOG_COMPASS3_MSG);
}
}
// Write a mode packet.
bool AP_Logger_Backend::Write_Mode(uint8_t mode, uint8_t reason)
{
struct log_Mode pkt = {
LOG_PACKET_HEADER_INIT(LOG_MODE_MSG),
time_us : AP_HAL::micros64(),
mode : mode,
2016-01-25 19:45:27 -04:00
mode_num : mode,
mode_reason : reason
};
return WriteCriticalBlock(&pkt, sizeof(pkt));
}
// Write ESC status messages
2019-02-11 01:48:39 -04:00
// id starts from 0
// rpm is eRPM (rpm * 100)
// voltage is in centi-volts
// current is in centi-amps
// temperature is in centi-degrees Celsius
// current_tot is in centi-amp hours
void AP_Logger::Write_ESC(uint8_t id, uint64_t time_us, int32_t rpm, uint16_t voltage, uint16_t current, int16_t temperature, uint16_t current_tot)
{
2019-02-11 01:48:39 -04:00
// sanity check id
if (id >= 8) {
return;
}
struct log_Esc pkt = {
LOG_PACKET_HEADER_INIT(uint8_t(LOG_ESC1_MSG+id)),
time_us : time_us,
rpm : rpm,
voltage : voltage,
current : current,
temperature : temperature,
current_tot : current_tot
};
WriteBlock(&pkt, sizeof(pkt));
}
2015-05-21 22:42:08 -03:00
// Write a Yaw PID packet
void AP_Logger::Write_PID(uint8_t msg_type, const PID_Info &info)
2015-05-21 22:42:08 -03:00
{
struct log_PID pkt = {
LOG_PACKET_HEADER_INIT(msg_type),
time_us : AP_HAL::micros64(),
desired : info.desired,
actual : info.actual,
2015-05-21 22:42:08 -03:00
P : info.P,
I : info.I,
D : info.D,
FF : info.FF
2015-05-21 22:42:08 -03:00
};
WriteBlock(&pkt, sizeof(pkt));
}
2015-07-03 08:49:45 -03:00
void AP_Logger::Write_Origin(uint8_t origin_type, const Location &loc)
2015-07-03 08:49:45 -03:00
{
uint64_t time_us = AP_HAL::micros64();
2015-07-03 08:49:45 -03:00
struct log_ORGN pkt = {
LOG_PACKET_HEADER_INIT(LOG_ORGN_MSG),
time_us : time_us,
origin_type : origin_type,
latitude : loc.lat,
longitude : loc.lng,
altitude : loc.alt
};
WriteBlock(&pkt, sizeof(pkt));
}
2015-08-07 07:34:14 -03:00
void AP_Logger::Write_RPM(const AP_RPM &rpm_sensor)
2015-08-07 07:34:14 -03:00
{
struct log_RPM pkt = {
LOG_PACKET_HEADER_INIT(LOG_RPM_MSG),
time_us : AP_HAL::micros64(),
2015-08-07 07:34:14 -03:00
rpm1 : rpm_sensor.get_rpm(0),
rpm2 : rpm_sensor.get_rpm(1)
};
WriteBlock(&pkt, sizeof(pkt));
}
2017-04-18 11:43:03 -03:00
// Write a rate packet
void AP_Logger::Write_Rate(const AP_AHRS_View *ahrs,
const AP_Motors &motors,
const AC_AttitudeControl &attitude_control,
const AC_PosControl &pos_control)
{
const Vector3f &rate_targets = attitude_control.rate_bf_targets();
const Vector3f &accel_target = pos_control.get_accel_target();
struct log_Rate pkt_rate = {
LOG_PACKET_HEADER_INIT(LOG_RATE_MSG),
time_us : AP_HAL::micros64(),
2016-06-18 07:47:45 -03:00
control_roll : degrees(rate_targets.x),
roll : degrees(ahrs->get_gyro().x),
roll_out : motors.get_roll(),
2016-06-18 07:47:45 -03:00
control_pitch : degrees(rate_targets.y),
pitch : degrees(ahrs->get_gyro().y),
pitch_out : motors.get_pitch(),
2016-06-18 07:47:45 -03:00
control_yaw : degrees(rate_targets.z),
yaw : degrees(ahrs->get_gyro().z),
yaw_out : motors.get_yaw(),
control_accel : (float)accel_target.z,
accel : (float)(-(ahrs->get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f),
accel_out : motors.get_throttle()
};
WriteBlock(&pkt_rate, sizeof(pkt_rate));
}
2016-07-03 23:14:26 -03:00
// Write visual odometry sensor data
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),
time_us : AP_HAL::micros64(),
time_delta : time_delta,
angle_delta_x : angle_delta.x,
angle_delta_y : angle_delta.y,
angle_delta_z : angle_delta.z,
position_delta_x : position_delta.x,
position_delta_y : position_delta.y,
position_delta_z : position_delta.z,
confidence : confidence
};
WriteBlock(&pkt_visualodom, sizeof(log_VisualOdom));
}
2017-04-09 08:17:17 -03:00
// Write AOA and SSA
void AP_Logger::Write_AOA_SSA(AP_AHRS &ahrs)
2017-04-09 08:17:17 -03:00
{
struct log_AOA_SSA aoa_ssa = {
LOG_PACKET_HEADER_INIT(LOG_AOA_SSA_MSG),
time_us : AP_HAL::micros64(),
AOA : ahrs.getAOA(),
SSA : ahrs.getSSA()
};
WriteBlock(&aoa_ssa, sizeof(aoa_ssa));
}
2017-04-18 11:43:03 -03:00
// Write beacon sensor (position) data
void AP_Logger::Write_Beacon(AP_Beacon &beacon)
2017-04-18 11:43:03 -03:00
{
if (!beacon.enabled()) {
return;
}
2017-04-18 11:43:03 -03:00
// position
Vector3f pos;
float accuracy = 0.0f;
beacon.get_vehicle_position_ned(pos, accuracy);
struct log_Beacon pkt_beacon = {
LOG_PACKET_HEADER_INIT(LOG_BEACON_MSG),
time_us : AP_HAL::micros64(),
health : (uint8_t)beacon.healthy(),
count : (uint8_t)beacon.count(),
dist0 : beacon.beacon_distance(0),
dist1 : beacon.beacon_distance(1),
dist2 : beacon.beacon_distance(2),
dist3 : beacon.beacon_distance(3),
posx : pos.x,
posy : pos.y,
posz : pos.z
};
WriteBlock(&pkt_beacon, sizeof(pkt_beacon));
}
// Write proximity sensor distances
void AP_Logger::Write_Proximity(AP_Proximity &proximity)
{
// exit immediately if not enabled
if (proximity.get_status() == AP_Proximity::Proximity_NotConnected) {
return;
}
AP_Proximity::Proximity_Distance_Array dist_array {};
proximity.get_horizontal_distances(dist_array);
float dist_up;
if (!proximity.get_upward_distance(dist_up)) {
dist_up = 0.0f;
}
float close_ang = 0.0f, close_dist = 0.0f;
proximity.get_closest_object(close_ang, close_dist);
struct log_Proximity pkt_proximity = {
LOG_PACKET_HEADER_INIT(LOG_PROXIMITY_MSG),
time_us : AP_HAL::micros64(),
health : (uint8_t)proximity.get_status(),
dist0 : dist_array.distance[0],
dist45 : dist_array.distance[1],
dist90 : dist_array.distance[2],
dist135 : dist_array.distance[3],
dist180 : dist_array.distance[4],
dist225 : dist_array.distance[5],
dist270 : dist_array.distance[6],
dist315 : dist_array.distance[7],
distup : dist_up,
closest_angle : close_ang,
closest_dist : close_dist
};
WriteBlock(&pkt_proximity, sizeof(pkt_proximity));
}
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),
time_us : AP_HAL::micros64(),
active : active,
num_points : num_points,
max_points : max_points,
action : action,
N : breadcrumb.x,
E : breadcrumb.y,
D : breadcrumb.z
};
WriteBlock(&pkt_srtl, sizeof(pkt_srtl));
}
2019-06-08 01:59:04 -03:00
void AP_Logger::Write_OA(uint8_t algorithm, const Location& final_dest, const Location& oa_dest)
{
struct log_OA pkt = {
LOG_PACKET_HEADER_INIT(LOG_OA_MSG),
time_us : AP_HAL::micros64(),
algorithm : algorithm,
final_lat : final_dest.lat,
final_lng : final_dest.lng,
oa_lat : oa_dest.lat,
oa_lng : oa_dest.lng,
};
WriteBlock(&pkt, sizeof(pkt));
}