ardupilot/ArduCopter/Log.cpp

455 lines
14 KiB
C++
Raw Normal View History

#include "Copter.h"
#if LOGGING_ENABLED == ENABLED
// Code to Write and Read packets from AP_Logger log memory
// Code to interact with the user to dump or erase logs
2013-04-19 20:51:09 -03:00
struct PACKED log_Control_Tuning {
LOG_PACKET_HEADER;
uint64_t time_us;
float throttle_in;
float angle_boost;
float throttle_out;
float throttle_hover;
float desired_alt;
float inav_alt;
int32_t baro_alt;
float desired_rangefinder_alt;
2016-04-27 08:37:04 -03:00
int16_t rangefinder_alt;
float terr_alt;
int16_t target_climb_rate;
int16_t climb_rate;
};
2013-04-20 02:18:22 -03:00
// Write a control tuning packet
void Copter::Log_Write_Control_Tuning()
{
// get terrain altitude
float terr_alt = 0.0f;
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
if (!terrain.height_above_terrain(terr_alt, true)) {
terr_alt = logger.quiet_nan();
}
#endif
float des_alt_m = 0.0f;
int16_t target_climb_rate_cms = 0;
if (!flightmode->has_manual_throttle()) {
des_alt_m = pos_control->get_alt_target() / 100.0f;
target_climb_rate_cms = pos_control->get_vel_target_z();
}
struct log_Control_Tuning pkt = {
LOG_PACKET_HEADER_INIT(LOG_CONTROL_TUNING_MSG),
time_us : AP_HAL::micros64(),
throttle_in : attitude_control->get_throttle_in(),
angle_boost : attitude_control->angle_boost(),
throttle_out : motors->get_throttle(),
throttle_hover : motors->get_throttle_hover(),
desired_alt : des_alt_m,
inav_alt : inertial_nav.get_altitude() / 100.0f,
baro_alt : baro_alt,
desired_rangefinder_alt : surface_tracking.logging_target_alt(),
rangefinder_alt : rangefinder_state.alt_cm,
terr_alt : terr_alt,
target_climb_rate : target_climb_rate_cms,
climb_rate : int16_t(inertial_nav.get_velocity_z()) // float -> int16_t
};
logger.WriteBlock(&pkt, sizeof(pkt));
}
2013-04-20 02:18:22 -03:00
// Write an attitude packet
void Copter::Log_Write_Attitude()
{
Vector3f targets = attitude_control->get_att_target_euler_cd();
targets.z = wrap_360_cd(targets.z);
logger.Write_Attitude(ahrs, targets);
logger.Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control);
2017-05-23 02:30:57 -03:00
if (should_log(MASK_LOG_PID)) {
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() );
2017-05-23 02:30:57 -03:00
}
}
2017-05-23 02:30:57 -03:00
// Write an EKF and POS packet
void Copter::Log_Write_EKF_POS()
{
AP::ahrs_navekf().Log_Write();
logger.Write_AHRS2(ahrs);
2015-05-04 03:18:46 -03:00
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
sitl.Log_Write_SIMSTATE();
#endif
logger.Write_POS(ahrs);
}
struct PACKED log_MotBatt {
LOG_PACKET_HEADER;
uint64_t time_us;
float lift_max;
float bat_volt;
float bat_res;
float th_limit;
};
// Write an rate packet
void Copter::Log_Write_MotBatt()
{
#if FRAME_CONFIG != HELI_FRAME
struct log_MotBatt pkt_mot = {
LOG_PACKET_HEADER_INIT(LOG_MOTBATT_MSG),
time_us : AP_HAL::micros64(),
lift_max : (float)(motors->get_lift_max()),
bat_volt : (float)(motors->get_batt_voltage_filt()),
2018-02-28 19:32:16 -04:00
bat_res : (float)(battery.get_resistance()),
th_limit : (float)(motors->get_throttle_limit())
};
logger.WriteBlock(&pkt_mot, sizeof(pkt_mot));
#endif
}
// Wrote an event packet
void Copter::Log_Write_Event(Log_Event id)
2011-11-19 20:57:10 -04:00
{
logger.Write_Event(id);
2012-11-10 02:04:23 -04:00
}
2013-04-19 20:51:09 -03:00
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 Copter::Log_Write_Data(uint8_t id, int16_t value)
2011-11-19 20:57:10 -04:00
{
2014-10-16 21:37:49 -03:00
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 : id,
data_value : value
};
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
}
2012-11-10 02:04:23 -04:00
}
2013-04-19 20:51:09 -03:00
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 Copter::Log_Write_Data(uint8_t id, uint16_t value)
2012-11-10 02:04:23 -04:00
{
2014-10-16 21:37:49 -03:00
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 : id,
data_value : value
};
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
}
2012-11-10 02:04:23 -04:00
}
2013-04-19 20:51:09 -03:00
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 Copter::Log_Write_Data(uint8_t id, int32_t value)
2012-11-10 02:04:23 -04:00
{
2014-10-16 21:37:49 -03:00
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 : id,
data_value : value
};
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
}
2011-11-19 20:57:10 -04:00
}
2013-04-19 20:51:09 -03:00
struct PACKED log_Data_UInt32t {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t id;
uint32_t data_value;
};
2012-11-10 02:04:23 -04:00
// Write a uint32_t data packet
void Copter::Log_Write_Data(uint8_t id, uint32_t value)
{
2014-10-16 21:37:49 -03:00
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 : id,
data_value : value
};
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
}
}
2012-11-10 02:04:23 -04:00
2013-04-19 20:51:09 -03:00
struct PACKED log_Data_Float {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t id;
float data_value;
};
2012-11-10 02:04:23 -04:00
// Write a float data packet
UNUSED_FUNCTION
void Copter::Log_Write_Data(uint8_t id, float value)
{
2014-10-16 21:37:49 -03:00
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 : id,
data_value : value
};
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
2012-08-21 23:19:50 -03:00
}
2011-11-19 20:57:10 -04:00
}
struct PACKED log_ParameterTuning {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t parameter; // parameter we are tuning, e.g. 39 is CH6_CIRCLE_RATE
float tuning_value; // normalized value used inside tuning() function
float tuning_min; // tuning minimum value
float tuning_max; // tuning maximum value
};
void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max)
{
struct log_ParameterTuning pkt_tune = {
LOG_PACKET_HEADER_INIT(LOG_PARAMTUNE_MSG),
time_us : AP_HAL::micros64(),
parameter : param,
tuning_value : tuning_val,
tuning_min : tune_min,
tuning_max : tune_max
};
logger.WriteBlock(&pkt_tune, sizeof(pkt_tune));
}
// logs when baro or compass becomes unhealthy
void Copter::Log_Sensor_Health()
{
// check baro
if (sensor_health.baro != barometer.healthy()) {
sensor_health.baro = barometer.healthy();
AP::logger().Write_Error(LogErrorSubsystem::BARO,
(sensor_health.baro ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY));
}
// check compass
if (sensor_health.compass != compass.healthy()) {
sensor_health.compass = compass.healthy();
AP::logger().Write_Error(LogErrorSubsystem::COMPASS, (sensor_health.compass ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY));
}
// check primary GPS
if (sensor_health.primary_gps != gps.primary_sensor()) {
sensor_health.primary_gps = gps.primary_sensor();
Log_Write_Event(DATA_GPS_PRIMARY_CHANGED);
}
}
2015-06-18 18:09:39 -03:00
struct PACKED log_Heli {
LOG_PACKET_HEADER;
uint64_t time_us;
float desired_rotor_speed;
float main_rotor_speed;
float governor_output;
float control_output;
2015-06-18 18:09:39 -03:00
};
#if FRAME_CONFIG == HELI_FRAME
// Write an helicopter packet
void Copter::Log_Write_Heli()
{
struct log_Heli pkt_heli = {
LOG_PACKET_HEADER_INIT(LOG_HELI_MSG),
time_us : AP_HAL::micros64(),
desired_rotor_speed : motors->get_desired_rotor_speed(),
main_rotor_speed : motors->get_main_rotor_speed(),
governor_output : motors->get_governor_output(),
control_output : motors->get_control_output(),
2015-06-18 18:09:39 -03:00
};
logger.WriteBlock(&pkt_heli, sizeof(pkt_heli));
2015-06-18 18:09:39 -03:00
}
#endif
// precision landing logging
struct PACKED log_Precland {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t healthy;
uint8_t target_acquired;
float pos_x;
float pos_y;
float vel_x;
float vel_y;
float meas_x;
float meas_y;
float meas_z;
uint32_t last_meas;
uint32_t ekf_outcount;
uint8_t estimator;
};
// Write a precision landing entry
void Copter::Log_Write_Precland()
{
#if PRECISION_LANDING == ENABLED
// exit immediately if not enabled
if (!precland.enabled()) {
return;
}
Vector3f target_pos_meas = Vector3f(0.0f,0.0f,0.0f);
Vector2f target_pos_rel = Vector2f(0.0f,0.0f);
Vector2f target_vel_rel = Vector2f(0.0f,0.0f);
precland.get_target_position_relative_cm(target_pos_rel);
precland.get_target_velocity_relative_cms(target_vel_rel);
precland.get_target_position_measurement_cm(target_pos_meas);
struct log_Precland pkt = {
LOG_PACKET_HEADER_INIT(LOG_PRECLAND_MSG),
time_us : AP_HAL::micros64(),
healthy : precland.healthy(),
target_acquired : precland.target_acquired(),
pos_x : target_pos_rel.x,
pos_y : target_pos_rel.y,
vel_x : target_vel_rel.x,
vel_y : target_vel_rel.y,
meas_x : target_pos_meas.x,
meas_y : target_pos_meas.y,
meas_z : target_pos_meas.z,
last_meas : precland.last_backend_los_meas_ms(),
ekf_outcount : precland.ekf_outlier_count(),
estimator : precland.estimator_type()
};
logger.WriteBlock(&pkt, sizeof(pkt));
#endif // PRECISION_LANDING == ENABLED
}
// guided target logging
2016-01-10 22:41:28 -04: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 Copter::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-01-10 22:41:28 -04:00
}
// type and unit information can be found in
// libraries/AP_Logger/Logstructure.h; search for "log_Units" for
// units and "Format characters" for field type information
const struct LogStructure Copter::log_structure[] = {
2013-04-19 20:51:09 -03:00
LOG_COMMON_STRUCTURES,
{ LOG_PARAMTUNE_MSG, sizeof(log_ParameterTuning),
"PTUN", "QBfff", "TimeUS,Param,TunVal,TunMin,TunMax", "s----", "F----" },
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
"CTUN", "Qffffffefcfhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00B0BBBB" },
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt),
"MOTB", "Qffff", "TimeUS,LiftMax,BatVolt,BatRes,ThLimit", "s-vw-", "F-00-" },
2013-04-19 20:51:09 -03:00
{ LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t),
"D16", "QBh", "TimeUS,Id,Value", "s--", "F--" },
2013-04-19 20:51:09 -03:00
{ LOG_DATA_UINT16_MSG, sizeof(log_Data_UInt16t),
"DU16", "QBH", "TimeUS,Id,Value", "s--", "F--" },
2013-04-19 20:51:09 -03:00
{ LOG_DATA_INT32_MSG, sizeof(log_Data_Int32t),
"D32", "QBi", "TimeUS,Id,Value", "s--", "F--" },
2013-04-19 20:51:09 -03:00
{ LOG_DATA_UINT32_MSG, sizeof(log_Data_UInt32t),
"DU32", "QBI", "TimeUS,Id,Value", "s--", "F--" },
2013-04-19 20:51:09 -03:00
{ LOG_DATA_FLOAT_MSG, sizeof(log_Data_Float),
"DFLT", "QBf", "TimeUS,Id,Value", "s--", "F--" },
#if FRAME_CONFIG == HELI_FRAME
2015-06-18 18:09:39 -03:00
{ LOG_HELI_MSG, sizeof(log_Heli),
"HELI", "Qffff", "TimeUS,DRRPM,ERRPM,Gov,Throt", "s----", "F----" },
#endif
#if PRECISION_LANDING == ENABLED
{ LOG_PRECLAND_MSG, sizeof(log_Precland),
"PL", "QBBfffffffIIB", "TimeUS,Heal,TAcq,pX,pY,vX,vY,mX,mY,mZ,LastMeasUS,EKFOutl,Est", "s--ddmmddms--","F--00BB00BC--" },
#endif
2016-01-10 22:41:28 -04:00
{ LOG_GUIDEDTARGET_MSG, sizeof(log_GuidedTarget),
"GUID", "QBffffff", "TimeUS,Type,pX,pY,pZ,vX,vY,vZ", "s-mmmnnn", "F-000000" },
2013-04-19 20:51:09 -03:00
};
2013-04-15 09:54:29 -03:00
void Copter::Log_Write_Vehicle_Startup_Messages()
{
// only 200(?) bytes are guaranteed by AP_Logger
logger.Write_MessageF("Frame: %s", get_frame_string());
logger.Write_Mode((uint8_t)control_mode, control_mode_reason);
ahrs.Log_Write_Home_And_Origin();
gps.Write_AP_Logger_Log_Startup_messages();
}
void Copter::log_init(void)
{
logger.Init(log_structure, ARRAY_SIZE(log_structure));
2012-08-21 23:19:50 -03:00
}
2015-07-31 20:06:20 -03:00
#else // LOGGING_ENABLED
void Copter::Log_Write_Control_Tuning() {}
void Copter::Log_Write_Performance() {}
void Copter::Log_Write_Attitude(void) {}
2017-05-23 02:30:57 -03:00
void Copter::Log_Write_EKF_POS() {}
2015-07-31 20:06:20 -03:00
void Copter::Log_Write_MotBatt() {}
void Copter::Log_Write_Event(Log_Event id) {}
2015-07-31 20:06:20 -03:00
void Copter::Log_Write_Data(uint8_t id, int32_t value) {}
void Copter::Log_Write_Data(uint8_t id, uint32_t value) {}
void Copter::Log_Write_Data(uint8_t id, int16_t value) {}
void Copter::Log_Write_Data(uint8_t id, uint16_t value) {}
void Copter::Log_Write_Data(uint8_t id, float value) {}
void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max) {}
2015-07-31 20:06:20 -03:00
void Copter::Log_Sensor_Health() {}
void Copter::Log_Write_Precland() {}
2016-07-01 02:34:48 -03:00
void Copter::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target) {}
void Copter::Log_Write_Vehicle_Startup_Messages() {}
2015-07-31 20:06:20 -03:00
#if FRAME_CONFIG == HELI_FRAME
void Copter::Log_Write_Heli() {}
#endif
void Copter::log_init(void) {}
#endif // LOGGING_ENABLED