ardupilot/ArduSub/Log.cpp

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

297 lines
8.9 KiB
C++
Raw Normal View History

2016-01-14 15:30:56 -04:00
#include "Sub.h"
#if HAL_LOGGING_ENABLED
// Code to Write and Read packets from AP_Logger log memory
// Code to interact with the user to dump or erase logs
struct PACKED log_Control_Tuning {
LOG_PACKET_HEADER;
uint64_t time_us;
2016-04-05 00:17:39 -03:00
float throttle_in;
float angle_boost;
float throttle_out;
float throttle_hover;
float desired_alt;
float inav_alt;
float baro_alt;
int16_t desired_rangefinder_alt;
int16_t rangefinder_alt;
2016-05-03 01:45:37 -03:00
float terr_alt;
int16_t target_climb_rate;
int16_t climb_rate;
};
// Write a control tuning packet
2016-01-14 15:30:56 -04:00
void Sub::Log_Write_Control_Tuning()
{
// get terrain altitude
float terr_alt = 0.0f;
#if AP_TERRAIN_AVAILABLE
2024-02-21 16:12:34 -04:00
if (terrain.enabled()) {
terrain.height_above_terrain(terr_alt, true);
} else {
terr_alt = rangefinder_state.rangefinder_terrain_offset_cm * 0.01f;
}
#else
terr_alt = rangefinder_state.rangefinder_terrain_offset_cm * 0.01f;
2016-05-03 01:45:37 -03:00
#endif
struct log_Control_Tuning pkt = {
LOG_PACKET_HEADER_INIT(LOG_CONTROL_TUNING_MSG),
time_us : AP_HAL::micros64(),
2016-04-05 00:17:39 -03:00
throttle_in : attitude_control.get_throttle_in(),
angle_boost : attitude_control.angle_boost(),
throttle_out : motors.get_throttle(),
throttle_hover : motors.get_throttle_hover(),
2021-04-27 03:50:06 -03:00
desired_alt : pos_control.get_pos_target_z_cm() / 100.0f,
2021-10-20 05:30:56 -03:00
inav_alt : inertial_nav.get_position_z_up_cm() * 0.01f,
baro_alt : barometer.get_altitude(),
2024-02-21 16:12:34 -04:00
desired_rangefinder_alt : (int16_t)mode_surftrak.get_rangefinder_target_cm(),
rangefinder_alt : rangefinder_state.alt_cm,
terr_alt : terr_alt,
2021-04-27 03:50:06 -03:00
target_climb_rate : (int16_t)pos_control.get_vel_target_z_cms(),
climb_rate : climb_rate
};
logger.WriteBlock(&pkt, sizeof(pkt));
}
// Write an attitude packet
2016-01-14 15:30:56 -04:00
void Sub::Log_Write_Attitude()
{
2024-09-05 10:03:16 -03:00
ahrs.Write_Attitude(attitude_control.get_att_target_euler_rad() * RAD_TO_DEG);
2021-07-20 09:16:34 -03:00
AP::ahrs().Log_Write();
}
struct PACKED log_Data_Int16t {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t id;
int16_t data_value;
};
// Write an int16_t data packet
UNUSED_FUNCTION
void Sub::Log_Write_Data(LogDataID id, int16_t value)
{
if (should_log(MASK_LOG_ANY)) {
struct log_Data_Int16t pkt = {
LOG_PACKET_HEADER_INIT(LOG_DATA_INT16_MSG),
time_us : AP_HAL::micros64(),
id : (uint8_t)id,
data_value : value
};
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
}
}
struct PACKED log_Data_UInt16t {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t id;
uint16_t data_value;
};
// Write an uint16_t data packet
UNUSED_FUNCTION
void Sub::Log_Write_Data(LogDataID id, uint16_t value)
{
if (should_log(MASK_LOG_ANY)) {
struct log_Data_UInt16t pkt = {
LOG_PACKET_HEADER_INIT(LOG_DATA_UINT16_MSG),
time_us : AP_HAL::micros64(),
id : (uint8_t)id,
data_value : value
};
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
}
}
struct PACKED log_Data_Int32t {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t id;
int32_t data_value;
};
// Write an int32_t data packet
void Sub::Log_Write_Data(LogDataID id, int32_t value)
{
if (should_log(MASK_LOG_ANY)) {
struct log_Data_Int32t pkt = {
LOG_PACKET_HEADER_INIT(LOG_DATA_INT32_MSG),
time_us : AP_HAL::micros64(),
id : (uint8_t)id,
data_value : value
};
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
}
}
struct PACKED log_Data_UInt32t {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t id;
uint32_t data_value;
};
// Write a uint32_t data packet
void Sub::Log_Write_Data(LogDataID id, uint32_t value)
{
if (should_log(MASK_LOG_ANY)) {
struct log_Data_UInt32t pkt = {
LOG_PACKET_HEADER_INIT(LOG_DATA_UINT32_MSG),
time_us : AP_HAL::micros64(),
id : (uint8_t)id,
data_value : value
};
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
}
}
struct PACKED log_Data_Float {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t id;
float data_value;
};
// Write a float data packet
UNUSED_FUNCTION
void Sub::Log_Write_Data(LogDataID id, float value)
{
if (should_log(MASK_LOG_ANY)) {
struct log_Data_Float pkt = {
LOG_PACKET_HEADER_INIT(LOG_DATA_FLOAT_MSG),
time_us : AP_HAL::micros64(),
id : (uint8_t)id,
data_value : value
};
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
}
}
2016-05-03 01:45:37 -03:00
struct PACKED log_GuidedTarget {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t type;
float pos_target_x;
float pos_target_y;
float pos_target_z;
float vel_target_x;
float vel_target_y;
float vel_target_z;
};
// Write a Guided mode target
void Sub::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target)
{
struct log_GuidedTarget pkt = {
LOG_PACKET_HEADER_INIT(LOG_GUIDEDTARGET_MSG),
time_us : AP_HAL::micros64(),
type : target_type,
pos_target_x : pos_target.x,
pos_target_y : pos_target.y,
pos_target_z : pos_target.z,
vel_target_x : vel_target.x,
vel_target_y : vel_target.y,
vel_target_z : vel_target.z
};
logger.WriteBlock(&pkt, sizeof(pkt));
2016-05-03 01:45:37 -03:00
}
2020-03-20 02:38:04 -03:00
// @LoggerMessage: CTUN
// @Description: Control Tuning information
// @Field: TimeUS: Time since system startup
2020-03-20 02:38:04 -03:00
// @Field: ThI: throttle input
// @Field: ABst: angle boost
// @Field: ThO: throttle output
// @Field: ThH: calculated hover throttle
// @Field: DAlt: desired altitude
// @Field: Alt: achieved altitude
// @Field: BAlt: barometric altitude
// @Field: DSAlt: desired rangefinder altitude
// @Field: SAlt: achieved rangefinder altitude
2020-03-20 02:38:04 -03:00
// @Field: TAlt: terrain altitude
// @Field: DCRt: desired climb rate
// @Field: CRt: climb rate
// @LoggerMessage: D16
// @Description: Generic 16-bit-signed-integer storage
// @Field: TimeUS: Time since system startup
// @Field: Id: Data type identifier
// @Field: Value: Value
// @LoggerMessage: D32
// @Description: Generic 32-bit-signed-integer storage
// @Field: TimeUS: Time since system startup
// @Field: Id: Data type identifier
// @Field: Value: Value
// @LoggerMessage: DFLT
// @Description: Generic float storage
// @Field: TimeUS: Time since system startup
// @Field: Id: Data type identifier
// @Field: Value: Value
// @LoggerMessage: DU16
// @Description: Generic 16-bit-unsigned-integer storage
// @Field: TimeUS: Time since system startup
// @Field: Id: Data type identifier
// @Field: Value: Value
// @LoggerMessage: DU32
// @Description: Generic 32-bit-unsigned-integer storage
// @Field: TimeUS: Time since system startup
// @Field: Id: Data type identifier
// @Field: Value: Value
// @LoggerMessage: GUIP
2020-04-23 06:15:16 -03:00
// @Description: Guided mode target information
// @Field: TimeUS: Time since system startup
// @Field: Type: Type of guided mode
// @Field: pX: Target position, X-Axis
// @Field: pY: Target position, Y-Axis
// @Field: pZ: Target position, Z-Axis
// @Field: vX: Target velocity, X-Axis
// @Field: vY: Target velocity, Y-Axis
// @Field: vZ: Target velocity, Z-Axis
2017-09-05 22:02:59 -03:00
// type and unit information can be found in
// libraries/AP_Logger/Logstructure.h; search for "log_Units" for
2017-09-05 22:02:59 -03:00
// units and "Format characters" for field type information
2016-01-14 15:30:56 -04:00
const struct LogStructure Sub::log_structure[] = {
LOG_COMMON_STRUCTURES,
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
2017-09-05 22:02:59 -03:00
"CTUN", "Qfffffffccfhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00BBBBBB" },
{ LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t),
2017-09-05 22:02:59 -03:00
"D16", "QBh", "TimeUS,Id,Value", "s--", "F--" },
{ LOG_DATA_UINT16_MSG, sizeof(log_Data_UInt16t),
2017-09-05 22:02:59 -03:00
"DU16", "QBH", "TimeUS,Id,Value", "s--", "F--" },
{ LOG_DATA_INT32_MSG, sizeof(log_Data_Int32t),
2017-09-05 22:02:59 -03:00
"D32", "QBi", "TimeUS,Id,Value", "s--", "F--" },
{ LOG_DATA_UINT32_MSG, sizeof(log_Data_UInt32t),
2017-09-05 22:02:59 -03:00
"DU32", "QBI", "TimeUS,Id,Value", "s--", "F--" },
{ LOG_DATA_FLOAT_MSG, sizeof(log_Data_Float),
2017-09-05 22:02:59 -03:00
"DFLT", "QBf", "TimeUS,Id,Value", "s--", "F--" },
{ LOG_GUIDEDTARGET_MSG, sizeof(log_GuidedTarget),
"GUIP", "QBffffff", "TimeUS,Type,pX,pY,pZ,vX,vY,vZ", "s-mmmnnn", "F-000000" },
};
uint8_t Sub::get_num_log_structures() const
{
return ARRAY_SIZE(log_structure);
}
2016-01-14 15:30:56 -04:00
void Sub::Log_Write_Vehicle_Startup_Messages()
{
// only 200(?) bytes are guaranteed by AP_Logger
2023-04-03 09:11:21 -03:00
logger.Write_Mode((uint8_t)control_mode, control_mode_reason);
ahrs.Log_Write_Home_And_Origin();
gps.Write_AP_Logger_Log_Startup_messages();
}
#endif // HAL_LOGGING_ENABLED