2015-05-29 23:12:49 -03:00
|
|
|
#include "Copter.h"
|
|
|
|
|
2011-12-23 18:26:24 -04:00
|
|
|
#if LOGGING_ENABLED == ENABLED
|
2011-07-17 07:31:07 -03:00
|
|
|
|
2019-01-18 00:23:42 -04:00
|
|
|
// Code to Write and Read packets from AP_Logger log memory
|
2010-12-19 12:40:33 -04:00
|
|
|
// Code to interact with the user to dump or erase logs
|
|
|
|
|
2013-04-19 20:51:09 -03:00
|
|
|
struct PACKED log_Control_Tuning {
|
2013-01-12 11:17:44 -04:00
|
|
|
LOG_PACKET_HEADER;
|
2015-04-30 02:57:00 -03:00
|
|
|
uint64_t time_us;
|
2016-01-03 23:47:15 -04:00
|
|
|
float throttle_in;
|
|
|
|
float angle_boost;
|
2015-05-23 14:51:52 -03:00
|
|
|
float throttle_out;
|
2016-05-23 04:17:19 -03:00
|
|
|
float throttle_hover;
|
2014-01-13 08:31:43 -04:00
|
|
|
float desired_alt;
|
|
|
|
float inav_alt;
|
|
|
|
int32_t baro_alt;
|
2018-06-05 05:21:09 -03:00
|
|
|
float desired_rangefinder_alt;
|
2019-08-23 22:59:22 -03:00
|
|
|
float rangefinder_alt;
|
2016-04-18 03:15:56 -03:00
|
|
|
float terr_alt;
|
2016-06-04 01:30:55 -03:00
|
|
|
int16_t target_climb_rate;
|
2014-01-13 08:31:43 -04:00
|
|
|
int16_t climb_rate;
|
2013-01-12 11:17:44 -04:00
|
|
|
};
|
2011-09-06 22:22:29 -03:00
|
|
|
|
2013-04-20 02:18:22 -03:00
|
|
|
// Write a control tuning packet
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::Log_Write_Control_Tuning()
|
2011-04-21 02:15:45 -03:00
|
|
|
{
|
2016-04-18 03:15:56 -03:00
|
|
|
// get terrain altitude
|
|
|
|
float terr_alt = 0.0f;
|
2021-02-12 23:40:10 -04:00
|
|
|
#if AP_TERRAIN_AVAILABLE
|
2018-04-04 08:16:34 -03:00
|
|
|
if (!terrain.height_above_terrain(terr_alt, true)) {
|
2019-01-18 00:23:42 -04:00
|
|
|
terr_alt = logger.quiet_nan();
|
2016-08-08 00:30:55 -03:00
|
|
|
}
|
2016-04-18 03:15:56 -03:00
|
|
|
#endif
|
2018-11-20 19:54:43 -04:00
|
|
|
float des_alt_m = 0.0f;
|
|
|
|
int16_t target_climb_rate_cms = 0;
|
|
|
|
if (!flightmode->has_manual_throttle()) {
|
2021-05-11 01:42:02 -03:00
|
|
|
des_alt_m = pos_control->get_pos_target_z_cm() / 100.0f;
|
|
|
|
target_climb_rate_cms = pos_control->get_vel_target_z_cms();
|
2018-11-20 19:54:43 -04:00
|
|
|
}
|
2016-04-18 03:15:56 -03:00
|
|
|
|
2019-08-23 22:59:22 -03:00
|
|
|
// get surface tracking alts
|
2019-11-10 23:55:43 -04:00
|
|
|
float desired_rangefinder_alt;
|
|
|
|
if (!surface_tracking.get_target_dist_for_logging(desired_rangefinder_alt)) {
|
2019-08-23 22:59:22 -03:00
|
|
|
desired_rangefinder_alt = AP::logger().quiet_nan();
|
|
|
|
}
|
|
|
|
|
2013-01-12 11:17:44 -04:00
|
|
|
struct log_Control_Tuning pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_CONTROL_TUNING_MSG),
|
2015-11-19 23:04:45 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2017-01-09 03:31:26 -04: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(),
|
2018-11-20 19:54:43 -04:00
|
|
|
desired_alt : des_alt_m,
|
2021-10-20 05:29:57 -03:00
|
|
|
inav_alt : inertial_nav.get_position_z_up_cm() * 0.01f,
|
2014-01-13 08:31:43 -04:00
|
|
|
baro_alt : baro_alt,
|
2019-08-23 22:59:22 -03:00
|
|
|
desired_rangefinder_alt : desired_rangefinder_alt,
|
2019-11-10 23:55:43 -04:00
|
|
|
rangefinder_alt : surface_tracking.get_dist_for_logging(),
|
2016-04-18 03:15:56 -03:00
|
|
|
terr_alt : terr_alt,
|
2018-11-20 19:54:43 -04:00
|
|
|
target_climb_rate : target_climb_rate_cms,
|
2021-10-20 05:29:57 -03:00
|
|
|
climb_rate : int16_t(inertial_nav.get_velocity_z_up_cms()) // float -> int16_t
|
2013-01-12 11:17:44 -04:00
|
|
|
};
|
2019-01-18 00:23:42 -04:00
|
|
|
logger.WriteBlock(&pkt, sizeof(pkt));
|
2011-04-21 02:15:45 -03:00
|
|
|
}
|
|
|
|
|
2013-04-20 02:18:22 -03:00
|
|
|
// Write an attitude packet
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::Log_Write_Attitude()
|
2011-05-09 01:16:58 -03:00
|
|
|
{
|
2017-01-09 03:31:26 -04:00
|
|
|
Vector3f targets = attitude_control->get_att_target_euler_cd();
|
2016-04-27 06:35:18 -03:00
|
|
|
targets.z = wrap_360_cd(targets.z);
|
2021-01-09 04:09:35 -04:00
|
|
|
ahrs.Write_Attitude(targets);
|
|
|
|
ahrs_view->Write_Rate(*motors, *attitude_control, *pos_control);
|
2017-05-23 02:30:57 -03:00
|
|
|
if (should_log(MASK_LOG_PID)) {
|
2019-01-18 00:24:08 -04:00
|
|
|
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() );
|
2021-01-19 22:51:03 -04:00
|
|
|
if (should_log(MASK_LOG_NTUN) && (flightmode->requires_GPS() || landing_with_GPS())) {
|
|
|
|
logger.Write_PID(LOG_PIDN_MSG, pos_control->get_vel_xy_pid().get_pid_info_x());
|
|
|
|
logger.Write_PID(LOG_PIDE_MSG, pos_control->get_vel_xy_pid().get_pid_info_y());
|
|
|
|
}
|
2017-05-23 02:30:57 -03:00
|
|
|
}
|
|
|
|
}
|
2014-01-03 20:51:57 -04:00
|
|
|
|
2017-05-23 02:30:57 -03:00
|
|
|
// Write an EKF and POS packet
|
|
|
|
void Copter::Log_Write_EKF_POS()
|
|
|
|
{
|
2021-07-20 09:16:33 -03:00
|
|
|
AP::ahrs().Log_Write();
|
2011-05-09 01:16:58 -03:00
|
|
|
}
|
|
|
|
|
2013-04-19 20:51:09 -03:00
|
|
|
struct PACKED log_Data_Int16t {
|
2013-01-12 11:17:44 -04:00
|
|
|
LOG_PACKET_HEADER;
|
2015-04-30 02:57:00 -03:00
|
|
|
uint64_t time_us;
|
2013-01-12 11:17:44 -04:00
|
|
|
uint8_t id;
|
|
|
|
int16_t data_value;
|
|
|
|
};
|
|
|
|
|
|
|
|
// Write an int16_t data packet
|
2015-02-17 20:13:48 -04:00
|
|
|
UNUSED_FUNCTION
|
2019-10-25 03:06:05 -03:00
|
|
|
void Copter::Log_Write_Data(LogDataID 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)) {
|
2013-01-12 11:17:44 -04:00
|
|
|
struct log_Data_Int16t pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_DATA_INT16_MSG),
|
2015-11-19 23:04:45 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2019-10-25 03:06:05 -03:00
|
|
|
id : (uint8_t)id,
|
2013-01-12 11:17:44 -04:00
|
|
|
data_value : value
|
|
|
|
};
|
2019-01-18 00:23:42 -04:00
|
|
|
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
|
2013-01-09 08:06:40 -04:00
|
|
|
}
|
2012-11-10 02:04:23 -04:00
|
|
|
}
|
|
|
|
|
2013-04-19 20:51:09 -03:00
|
|
|
struct PACKED log_Data_UInt16t {
|
2013-01-12 11:17:44 -04:00
|
|
|
LOG_PACKET_HEADER;
|
2015-04-30 02:57:00 -03:00
|
|
|
uint64_t time_us;
|
2013-01-12 11:17:44 -04:00
|
|
|
uint8_t id;
|
|
|
|
uint16_t data_value;
|
|
|
|
};
|
|
|
|
|
|
|
|
// Write an uint16_t data packet
|
2015-02-17 20:13:48 -04:00
|
|
|
UNUSED_FUNCTION
|
2019-10-25 03:06:05 -03:00
|
|
|
void Copter::Log_Write_Data(LogDataID 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)) {
|
2013-01-12 11:17:44 -04:00
|
|
|
struct log_Data_UInt16t pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_DATA_UINT16_MSG),
|
2015-11-19 23:04:45 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2019-10-25 03:06:05 -03:00
|
|
|
id : (uint8_t)id,
|
2013-01-12 11:17:44 -04:00
|
|
|
data_value : value
|
|
|
|
};
|
2019-01-18 00:23:42 -04:00
|
|
|
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
|
2013-01-09 08:06:40 -04:00
|
|
|
}
|
2012-11-10 02:04:23 -04:00
|
|
|
}
|
|
|
|
|
2013-04-19 20:51:09 -03:00
|
|
|
struct PACKED log_Data_Int32t {
|
2013-01-12 11:17:44 -04:00
|
|
|
LOG_PACKET_HEADER;
|
2015-04-30 02:57:00 -03:00
|
|
|
uint64_t time_us;
|
2013-01-12 11:17:44 -04:00
|
|
|
uint8_t id;
|
|
|
|
int32_t data_value;
|
|
|
|
};
|
|
|
|
|
|
|
|
// Write an int32_t data packet
|
2019-10-25 03:06:05 -03:00
|
|
|
void Copter::Log_Write_Data(LogDataID 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)) {
|
2013-01-12 11:17:44 -04:00
|
|
|
struct log_Data_Int32t pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_DATA_INT32_MSG),
|
2015-11-19 23:04:45 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2019-10-25 03:06:05 -03:00
|
|
|
id : (uint8_t)id,
|
2013-01-12 11:17:44 -04:00
|
|
|
data_value : value
|
|
|
|
};
|
2019-01-18 00:23:42 -04:00
|
|
|
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
|
2013-01-09 08:06:40 -04:00
|
|
|
}
|
2011-11-19 20:57:10 -04:00
|
|
|
}
|
|
|
|
|
2013-04-19 20:51:09 -03:00
|
|
|
struct PACKED log_Data_UInt32t {
|
2013-01-12 11:17:44 -04:00
|
|
|
LOG_PACKET_HEADER;
|
2015-04-30 02:57:00 -03:00
|
|
|
uint64_t time_us;
|
2013-01-12 11:17:44 -04:00
|
|
|
uint8_t id;
|
|
|
|
uint32_t data_value;
|
|
|
|
};
|
2012-11-10 02:04:23 -04:00
|
|
|
|
2013-01-12 11:17:44 -04:00
|
|
|
// Write a uint32_t data packet
|
2019-10-25 03:06:05 -03:00
|
|
|
void Copter::Log_Write_Data(LogDataID id, uint32_t value)
|
2013-01-12 11:17:44 -04:00
|
|
|
{
|
2014-10-16 21:37:49 -03:00
|
|
|
if (should_log(MASK_LOG_ANY)) {
|
2013-01-12 11:17:44 -04:00
|
|
|
struct log_Data_UInt32t pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_DATA_UINT32_MSG),
|
2015-11-19 23:04:45 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2019-10-25 03:06:05 -03:00
|
|
|
id : (uint8_t)id,
|
2013-01-12 11:17:44 -04:00
|
|
|
data_value : value
|
|
|
|
};
|
2019-01-18 00:23:42 -04:00
|
|
|
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
|
2013-01-12 11:17:44 -04:00
|
|
|
}
|
|
|
|
}
|
2012-11-10 02:04:23 -04:00
|
|
|
|
2013-04-19 20:51:09 -03:00
|
|
|
struct PACKED log_Data_Float {
|
2013-01-12 11:17:44 -04:00
|
|
|
LOG_PACKET_HEADER;
|
2015-04-30 02:57:00 -03:00
|
|
|
uint64_t time_us;
|
2013-01-12 11:17:44 -04:00
|
|
|
uint8_t id;
|
|
|
|
float data_value;
|
|
|
|
};
|
2012-11-10 02:04:23 -04:00
|
|
|
|
2013-01-12 11:17:44 -04:00
|
|
|
// Write a float data packet
|
2015-02-17 20:13:48 -04:00
|
|
|
UNUSED_FUNCTION
|
2019-10-25 03:06:05 -03:00
|
|
|
void Copter::Log_Write_Data(LogDataID id, float value)
|
2013-01-12 11:17:44 -04:00
|
|
|
{
|
2014-10-16 21:37:49 -03:00
|
|
|
if (should_log(MASK_LOG_ANY)) {
|
2013-01-12 11:17:44 -04:00
|
|
|
struct log_Data_Float pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_DATA_FLOAT_MSG),
|
2015-11-19 23:04:45 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2019-10-25 03:06:05 -03:00
|
|
|
id : (uint8_t)id,
|
2013-01-12 11:17:44 -04:00
|
|
|
data_value : value
|
|
|
|
};
|
2019-01-18 00:23:42 -04:00
|
|
|
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
2011-11-19 20:57:10 -04:00
|
|
|
}
|
|
|
|
|
2015-04-26 21:29:04 -03:00
|
|
|
struct PACKED log_ParameterTuning {
|
|
|
|
LOG_PACKET_HEADER;
|
2015-04-30 02:57:00 -03:00
|
|
|
uint64_t time_us;
|
2015-04-26 21:29:04 -03:00
|
|
|
uint8_t parameter; // parameter we are tuning, e.g. 39 is CH6_CIRCLE_RATE
|
|
|
|
float tuning_value; // normalized value used inside tuning() function
|
2019-04-03 09:32:26 -03:00
|
|
|
float tuning_min; // tuning minimum value
|
|
|
|
float tuning_max; // tuning maximum value
|
2015-04-26 21:29:04 -03:00
|
|
|
};
|
|
|
|
|
2019-04-03 09:32:26 -03:00
|
|
|
void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max)
|
2015-04-26 21:29:04 -03:00
|
|
|
{
|
|
|
|
struct log_ParameterTuning pkt_tune = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_PARAMTUNE_MSG),
|
2015-11-19 23:04:45 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2015-04-26 21:29:04 -03:00
|
|
|
parameter : param,
|
|
|
|
tuning_value : tuning_val,
|
2019-04-03 09:32:26 -03:00
|
|
|
tuning_min : tune_min,
|
|
|
|
tuning_max : tune_max
|
2015-04-26 21:29:04 -03:00
|
|
|
};
|
|
|
|
|
2019-01-18 00:23:42 -04:00
|
|
|
logger.WriteBlock(&pkt_tune, sizeof(pkt_tune));
|
2015-04-26 21:29:04 -03:00
|
|
|
}
|
|
|
|
|
2015-07-12 10:06:21 -03:00
|
|
|
// 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();
|
2019-03-24 22:31:46 -03:00
|
|
|
AP::logger().Write_Error(LogErrorSubsystem::BARO,
|
|
|
|
(sensor_health.baro ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY));
|
2015-07-12 10:06:21 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// check compass
|
|
|
|
if (sensor_health.compass != compass.healthy()) {
|
|
|
|
sensor_health.compass = compass.healthy();
|
2019-03-24 22:31:46 -03:00
|
|
|
AP::logger().Write_Error(LogErrorSubsystem::COMPASS, (sensor_health.compass ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY));
|
2015-07-12 10:06:21 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2019-07-29 04:55:40 -03:00
|
|
|
struct PACKED log_SysIdD {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
float waveform_time;
|
|
|
|
float waveform_sample;
|
|
|
|
float waveform_freq;
|
|
|
|
float angle_x;
|
|
|
|
float angle_y;
|
|
|
|
float angle_z;
|
|
|
|
float accel_x;
|
|
|
|
float accel_y;
|
|
|
|
float accel_z;
|
|
|
|
};
|
|
|
|
|
|
|
|
// Write an rate packet
|
|
|
|
void Copter::Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z)
|
|
|
|
{
|
|
|
|
#if MODE_SYSTEMID_ENABLED == ENABLED
|
|
|
|
struct log_SysIdD pkt_sidd = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_SYSIDD_MSG),
|
|
|
|
time_us : AP_HAL::micros64(),
|
|
|
|
waveform_time : waveform_time,
|
|
|
|
waveform_sample : waveform_sample,
|
|
|
|
waveform_freq : waveform_freq,
|
|
|
|
angle_x : angle_x,
|
|
|
|
angle_y : angle_y,
|
|
|
|
angle_z : angle_z,
|
|
|
|
accel_x : accel_x,
|
|
|
|
accel_y : accel_y,
|
|
|
|
accel_z : accel_z
|
|
|
|
};
|
|
|
|
logger.WriteBlock(&pkt_sidd, sizeof(pkt_sidd));
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
|
|
|
struct PACKED log_SysIdS {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t systemID_axis;
|
|
|
|
float waveform_magnitude;
|
|
|
|
float frequency_start;
|
|
|
|
float frequency_stop;
|
|
|
|
float time_fade_in;
|
|
|
|
float time_const_freq;
|
|
|
|
float time_record;
|
|
|
|
float time_fade_out;
|
|
|
|
};
|
|
|
|
|
|
|
|
// Write an rate packet
|
|
|
|
void Copter::Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out)
|
|
|
|
{
|
|
|
|
#if MODE_SYSTEMID_ENABLED == ENABLED
|
|
|
|
struct log_SysIdS pkt_sids = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_SYSIDS_MSG),
|
|
|
|
time_us : AP_HAL::micros64(),
|
|
|
|
systemID_axis : systemID_axis,
|
|
|
|
waveform_magnitude : waveform_magnitude,
|
|
|
|
frequency_start : frequency_start,
|
|
|
|
frequency_stop : frequency_stop,
|
|
|
|
time_fade_in : time_fade_in,
|
|
|
|
time_const_freq : time_const_freq,
|
|
|
|
time_record : time_record,
|
|
|
|
time_fade_out : time_fade_out
|
|
|
|
};
|
|
|
|
logger.WriteBlock(&pkt_sids, sizeof(pkt_sids));
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2020-02-05 19:35:59 -04:00
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
2015-06-18 18:09:39 -03:00
|
|
|
struct PACKED log_Heli {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
2016-02-03 05:02:41 -04:00
|
|
|
float desired_rotor_speed;
|
|
|
|
float main_rotor_speed;
|
2018-12-08 22:57:47 -04:00
|
|
|
float governor_output;
|
|
|
|
float control_output;
|
2015-06-18 18:09:39 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
// Write an helicopter packet
|
|
|
|
void Copter::Log_Write_Heli()
|
|
|
|
{
|
|
|
|
struct log_Heli pkt_heli = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_HELI_MSG),
|
2015-11-19 23:04:45 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2017-01-09 03:31:26 -04:00
|
|
|
desired_rotor_speed : motors->get_desired_rotor_speed(),
|
|
|
|
main_rotor_speed : motors->get_main_rotor_speed(),
|
2018-12-08 22:57:47 -04:00
|
|
|
governor_output : motors->get_governor_output(),
|
|
|
|
control_output : motors->get_control_output(),
|
2015-06-18 18:09:39 -03:00
|
|
|
};
|
2019-01-18 00:23:42 -04:00
|
|
|
logger.WriteBlock(&pkt_heli, sizeof(pkt_heli));
|
2015-06-18 18:09:39 -03:00
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2022-01-25 12:28:04 -04:00
|
|
|
// guided position target logging
|
|
|
|
struct PACKED log_Guided_Position_Target {
|
2016-01-10 22:41:28 -04:00
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t type;
|
|
|
|
float pos_target_x;
|
|
|
|
float pos_target_y;
|
|
|
|
float pos_target_z;
|
2021-06-25 22:10:03 -03:00
|
|
|
uint8_t terrain;
|
2016-01-10 22:41:28 -04:00
|
|
|
float vel_target_x;
|
|
|
|
float vel_target_y;
|
|
|
|
float vel_target_z;
|
2021-05-11 01:33:13 -03:00
|
|
|
float accel_target_x;
|
|
|
|
float accel_target_y;
|
|
|
|
float accel_target_z;
|
2016-01-10 22:41:28 -04:00
|
|
|
};
|
|
|
|
|
2022-01-25 12:28:04 -04:00
|
|
|
// guided attitude target logging
|
|
|
|
struct PACKED log_Guided_Attitude_Target {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t type;
|
|
|
|
float roll;
|
|
|
|
float pitch;
|
|
|
|
float yaw;
|
|
|
|
float roll_rate;
|
|
|
|
float pitch_rate;
|
|
|
|
float yaw_rate;
|
|
|
|
float thrust;
|
|
|
|
float climb_rate;
|
|
|
|
};
|
|
|
|
|
|
|
|
// Write a Guided mode position target
|
|
|
|
// pos_target is lat, lon, alt OR offset from ekf origin in cm
|
2021-06-25 22:10:03 -03:00
|
|
|
// terrain should be 0 if pos_target.z is alt-above-ekf-origin, 1 if alt-above-terrain
|
2020-06-24 00:03:56 -03:00
|
|
|
// vel_target is cm/s
|
2022-01-25 12:28:04 -04:00
|
|
|
void Copter::Log_Write_Guided_Position_Target(ModeGuided::SubMode target_type, const Vector3f& pos_target, bool terrain_alt, const Vector3f& vel_target, const Vector3f& accel_target)
|
2016-01-10 22:41:28 -04:00
|
|
|
{
|
2022-01-25 12:28:04 -04:00
|
|
|
const log_Guided_Position_Target pkt {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_GUIDED_POSITION_TARGET_MSG),
|
2016-01-10 22:41:28 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2021-03-30 00:36:25 -03:00
|
|
|
type : (uint8_t)target_type,
|
2016-01-10 22:41:28 -04:00
|
|
|
pos_target_x : pos_target.x,
|
|
|
|
pos_target_y : pos_target.y,
|
|
|
|
pos_target_z : pos_target.z,
|
2021-06-25 22:10:03 -03:00
|
|
|
terrain : terrain_alt,
|
2016-01-10 22:41:28 -04:00
|
|
|
vel_target_x : vel_target.x,
|
|
|
|
vel_target_y : vel_target.y,
|
2021-05-11 01:33:13 -03:00
|
|
|
vel_target_z : vel_target.z,
|
|
|
|
accel_target_x : accel_target.x,
|
|
|
|
accel_target_y : accel_target.y,
|
|
|
|
accel_target_z : accel_target.z
|
2016-01-10 22:41:28 -04:00
|
|
|
};
|
2019-01-18 00:23:42 -04:00
|
|
|
logger.WriteBlock(&pkt, sizeof(pkt));
|
2016-01-10 22:41:28 -04:00
|
|
|
}
|
|
|
|
|
2022-01-25 12:28:04 -04:00
|
|
|
// Write a Guided mode attitude target
|
|
|
|
// roll, pitch and yaw are in radians
|
|
|
|
// ang_vel: angular velocity, [roll rate, pitch_rate, yaw_rate] in radians/sec
|
|
|
|
// thrust is between 0 to 1
|
|
|
|
// climb_rate is in (m/s)
|
|
|
|
void Copter::Log_Write_Guided_Attitude_Target(ModeGuided::SubMode target_type, float roll, float pitch, float yaw, const Vector3f &ang_vel, float thrust, float climb_rate)
|
|
|
|
{
|
|
|
|
const log_Guided_Attitude_Target pkt {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_GUIDED_ATTITUDE_TARGET_MSG),
|
|
|
|
time_us : AP_HAL::micros64(),
|
|
|
|
type : (uint8_t)target_type,
|
|
|
|
roll : degrees(roll), // rad to deg
|
|
|
|
pitch : degrees(pitch), // rad to deg
|
|
|
|
yaw : degrees(yaw), // rad to deg
|
|
|
|
roll_rate : degrees(ang_vel.x), // rad/s to deg/s
|
|
|
|
pitch_rate : degrees(ang_vel.y), // rad/s to deg/s
|
|
|
|
yaw_rate : degrees(ang_vel.z), // rad/s to deg/s
|
|
|
|
thrust : thrust,
|
|
|
|
climb_rate : climb_rate
|
|
|
|
};
|
|
|
|
logger.WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
}
|
|
|
|
|
2015-12-07 20:52:03 -04:00
|
|
|
// type and unit information can be found in
|
2019-01-18 00:23:42 -04:00
|
|
|
// libraries/AP_Logger/Logstructure.h; search for "log_Units" for
|
2015-12-07 20:52:03 -04:00
|
|
|
// units and "Format characters" for field type information
|
2015-10-25 14:03:46 -03:00
|
|
|
const struct LogStructure Copter::log_structure[] = {
|
2013-04-19 20:51:09 -03:00
|
|
|
LOG_COMMON_STRUCTURES,
|
2020-04-01 08:25:54 -03:00
|
|
|
|
|
|
|
// @LoggerMessage: PTUN
|
|
|
|
// @Description: Parameter Tuning information
|
|
|
|
// @URL: https://ardupilot.org/copter/docs/tuning.html#in-flight-tuning
|
2020-04-07 04:37:43 -03:00
|
|
|
// @Field: TimeUS: Time since system startup
|
2020-04-01 08:25:54 -03:00
|
|
|
// @Field: Param: Parameter being tuned
|
|
|
|
// @Field: TunVal: Normalized value used inside tuning() function
|
|
|
|
// @Field: TunMin: Tuning minimum limit
|
|
|
|
// @Field: TunMax: Tuning maximum limit
|
|
|
|
|
2015-04-26 21:29:04 -03:00
|
|
|
{ LOG_PARAMTUNE_MSG, sizeof(log_ParameterTuning),
|
2019-04-03 09:32:26 -03:00
|
|
|
"PTUN", "QBfff", "TimeUS,Param,TunVal,TunMin,TunMax", "s----", "F----" },
|
2020-03-20 02:37:55 -03:00
|
|
|
|
|
|
|
// @LoggerMessage: CTUN
|
|
|
|
// @Description: Control Tuning information
|
2020-04-07 04:37:43 -03:00
|
|
|
// @Field: TimeUS: Time since system startup
|
2020-03-20 02:37:55 -03:00
|
|
|
// @Field: ThI: throttle input
|
2020-03-20 23:42:43 -03:00
|
|
|
// @Field: ABst: angle boost
|
2020-03-20 02:37:55 -03:00
|
|
|
// @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
|
2020-03-21 10:03:33 -03:00
|
|
|
// @Field: SAlt: achieved rangefinder altitude
|
2020-03-20 02:37:55 -03:00
|
|
|
// @Field: TAlt: terrain altitude
|
|
|
|
// @Field: DCRt: desired climb rate
|
|
|
|
// @Field: CRt: climb rate
|
|
|
|
|
2020-04-02 06:12:23 -03:00
|
|
|
// @LoggerMessage: D16
|
|
|
|
// @Description: Generic 16-bit-signed-integer storage
|
2020-07-20 01:59:49 -03:00
|
|
|
// @Field: TimeUS: Time since system startup
|
|
|
|
// @Field: Id: Data type identifier
|
|
|
|
// @Field: Value: Value
|
|
|
|
|
|
|
|
// @LoggerMessage: DU16
|
|
|
|
// @Description: Generic 16-bit-unsigned-integer storage
|
2020-04-02 06:12:23 -03:00
|
|
|
// @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: DU32
|
|
|
|
// @Description: Generic 32-bit-unsigned-integer storage
|
|
|
|
// @Field: TimeUS: Time since system startup
|
|
|
|
// @Field: Id: Data type identifier
|
|
|
|
// @Field: Value: Value
|
|
|
|
|
2014-01-13 08:31:43 -04:00
|
|
|
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
|
2021-07-27 05:48:10 -03:00
|
|
|
"CTUN", "Qffffffefffhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00B000BB" , true },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t),
|
2015-12-07 20:52:03 -04:00
|
|
|
"D16", "QBh", "TimeUS,Id,Value", "s--", "F--" },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_DATA_UINT16_MSG, sizeof(log_Data_UInt16t),
|
2015-12-07 20:52:03 -04:00
|
|
|
"DU16", "QBH", "TimeUS,Id,Value", "s--", "F--" },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_DATA_INT32_MSG, sizeof(log_Data_Int32t),
|
2015-12-07 20:52:03 -04:00
|
|
|
"D32", "QBi", "TimeUS,Id,Value", "s--", "F--" },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_DATA_UINT32_MSG, sizeof(log_Data_UInt32t),
|
2015-12-07 20:52:03 -04:00
|
|
|
"DU32", "QBI", "TimeUS,Id,Value", "s--", "F--" },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_DATA_FLOAT_MSG, sizeof(log_Data_Float),
|
2015-12-07 20:52:03 -04:00
|
|
|
"DFLT", "QBf", "TimeUS,Id,Value", "s--", "F--" },
|
2020-04-01 08:25:54 -03:00
|
|
|
|
|
|
|
// @LoggerMessage: HELI
|
|
|
|
// @Description: Helicopter related messages
|
2020-04-07 04:37:43 -03:00
|
|
|
// @Field: TimeUS: Time since system startup
|
2020-04-01 08:25:54 -03:00
|
|
|
// @Field: DRRPM: Desired rotor speed
|
|
|
|
// @Field: ERRPM: Estimated rotor speed
|
|
|
|
// @Field: Gov: Governor Output
|
|
|
|
// @Field: Throt: Throttle output
|
2018-02-22 20:06:04 -04:00
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
2015-06-18 18:09:39 -03:00
|
|
|
{ LOG_HELI_MSG, sizeof(log_Heli),
|
2021-07-27 05:48:10 -03:00
|
|
|
"HELI", "Qffff", "TimeUS,DRRPM,ERRPM,Gov,Throt", "s----", "F----" , true },
|
2018-02-22 20:06:04 -04:00
|
|
|
#endif
|
2020-04-01 08:25:54 -03:00
|
|
|
|
|
|
|
// @LoggerMessage: SIDD
|
|
|
|
// @Description: System ID data
|
2020-04-07 04:37:43 -03:00
|
|
|
// @Field: TimeUS: Time since system startup
|
2020-04-01 08:25:54 -03:00
|
|
|
// @Field: Time: Time reference for waveform
|
|
|
|
// @Field: Targ: Current waveform sample
|
|
|
|
// @Field: F: Instantaneous waveform frequency
|
|
|
|
// @Field: Gx: Delta angle, X-Axis
|
|
|
|
// @Field: Gy: Delta angle, Y-Axis
|
|
|
|
// @Field: Gz: Delta angle, Z-Axis
|
|
|
|
// @Field: Ax: Delta velocity, X-Axis
|
|
|
|
// @Field: Ay: Delta velocity, Y-Axis
|
|
|
|
// @Field: Az: Delta velocity, Z-Axis
|
|
|
|
|
2019-07-29 04:55:40 -03:00
|
|
|
{ LOG_SYSIDD_MSG, sizeof(log_SysIdD),
|
2021-07-27 05:48:10 -03:00
|
|
|
"SIDD", "Qfffffffff", "TimeUS,Time,Targ,F,Gx,Gy,Gz,Ax,Ay,Az", "ss-zkkkooo", "F---------" , true },
|
2020-06-24 00:04:08 -03:00
|
|
|
|
2020-04-01 08:25:54 -03:00
|
|
|
// @LoggerMessage: SIDS
|
|
|
|
// @Description: System ID settings
|
2020-04-07 04:37:43 -03:00
|
|
|
// @Field: TimeUS: Time since system startup
|
2020-04-01 08:25:54 -03:00
|
|
|
// @Field: Ax: The axis which is being excited
|
|
|
|
// @Field: Mag: Magnitude of the chirp waveform
|
|
|
|
// @Field: FSt: Frequency at the start of chirp
|
|
|
|
// @Field: FSp: Frequency at the end of chirp
|
|
|
|
// @Field: TFin: Time to reach maximum amplitude of chirp
|
|
|
|
// @Field: TC: Time at constant frequency before chirp starts
|
|
|
|
// @Field: TR: Time taken to complete chirp waveform
|
|
|
|
// @Field: TFout: Time to reach zero amplitude after chirp finishes
|
|
|
|
|
2019-07-29 04:55:40 -03:00
|
|
|
{ LOG_SYSIDS_MSG, sizeof(log_SysIdS),
|
2021-07-27 05:48:10 -03:00
|
|
|
"SIDS", "QBfffffff", "TimeUS,Ax,Mag,FSt,FSp,TFin,TC,TR,TFout", "s--ssssss", "F--------" , true },
|
2020-06-24 00:04:08 -03:00
|
|
|
|
2022-01-25 12:28:04 -04:00
|
|
|
// @LoggerMessage: GUIP
|
|
|
|
// @Description: Guided mode position target information
|
2020-04-07 04:37:43 -03:00
|
|
|
// @Field: TimeUS: Time since system startup
|
2020-04-01 08:25:54 -03:00
|
|
|
// @Field: Type: Type of guided mode
|
|
|
|
// @Field: pX: Target position, X-Axis
|
|
|
|
// @Field: pY: Target position, Y-Axis
|
|
|
|
// @Field: pZ: Target position, Z-Axis
|
2021-06-25 22:10:03 -03:00
|
|
|
// @Field: Terrain: Target position, Z-Axis is alt above terrain
|
2020-04-01 08:25:54 -03:00
|
|
|
// @Field: vX: Target velocity, X-Axis
|
|
|
|
// @Field: vY: Target velocity, Y-Axis
|
|
|
|
// @Field: vZ: Target velocity, Z-Axis
|
2021-05-11 01:33:13 -03:00
|
|
|
// @Field: aX: Target acceleration, X-Axis
|
|
|
|
// @Field: aY: Target acceleration, Y-Axis
|
|
|
|
// @Field: aZ: Target acceleration, Z-Axis
|
2020-06-24 00:04:08 -03:00
|
|
|
|
2022-01-25 12:28:04 -04:00
|
|
|
{ LOG_GUIDED_POSITION_TARGET_MSG, sizeof(log_Guided_Position_Target),
|
|
|
|
"GUIP", "QBfffbffffff", "TimeUS,Type,pX,pY,pZ,Terrain,vX,vY,vZ,aX,aY,aZ", "s-mmm-nnnooo", "F-BBB-BBBBBB" , true },
|
|
|
|
|
|
|
|
// @LoggerMessage: GUIA
|
|
|
|
// @Description: Guided mode attitude target information
|
|
|
|
// @Field: TimeUS: Time since system startup
|
|
|
|
// @Field: Type: Type of guided mode
|
|
|
|
// @Field: Roll: Target attitude, Roll
|
|
|
|
// @Field: Pitch: Target attitude, Pitch
|
|
|
|
// @Field: Yaw: Target attitude, Yaw
|
|
|
|
// @Field: RollRt: Roll rate
|
|
|
|
// @Field: PitchRt: Pitch rate
|
|
|
|
// @Field: YawRt: Yaw rate
|
|
|
|
// @Field: Thrust: Thrust
|
|
|
|
// @Field: ClimbRt: Climb rate
|
|
|
|
|
|
|
|
{ LOG_GUIDED_ATTITUDE_TARGET_MSG, sizeof(log_Guided_Attitude_Target),
|
|
|
|
"GUIA", "QBffffffff", "TimeUS,Type,Roll,Pitch,Yaw,RollRt,PitchRt,YawRt,Thrust,ClimbRt", "s-dddkkk-n", "F-000000-0" , true },
|
2013-04-19 20:51:09 -03:00
|
|
|
};
|
2013-04-15 09:54:29 -03:00
|
|
|
|
2015-08-06 09:18:39 -03:00
|
|
|
void Copter::Log_Write_Vehicle_Startup_Messages()
|
|
|
|
{
|
2019-01-18 00:23:42 -04:00
|
|
|
// only 200(?) bytes are guaranteed by AP_Logger
|
2021-06-19 20:54:22 -03:00
|
|
|
char frame_and_type_string[30];
|
|
|
|
copter.motors->get_frame_and_type_string(frame_and_type_string, ARRAY_SIZE(frame_and_type_string));
|
|
|
|
logger.Write_MessageF("%s", frame_and_type_string);
|
2020-01-30 03:29:36 -04:00
|
|
|
logger.Write_Mode((uint8_t)flightmode->mode_number(), control_mode_reason);
|
2018-05-16 00:29:13 -03:00
|
|
|
ahrs.Log_Write_Home_And_Origin();
|
2019-01-18 00:23:42 -04:00
|
|
|
gps.Write_AP_Logger_Log_Startup_messages();
|
2015-08-06 09:18:39 -03:00
|
|
|
}
|
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::log_init(void)
|
|
|
|
{
|
2019-01-18 00:23:42 -04:00
|
|
|
logger.Init(log_structure, ARRAY_SIZE(log_structure));
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
2011-12-20 01:04:51 -04:00
|
|
|
|
2015-07-31 20:06:20 -03:00
|
|
|
#else // LOGGING_ENABLED
|
|
|
|
|
|
|
|
void Copter::Log_Write_Control_Tuning() {}
|
|
|
|
void Copter::Log_Write_Attitude(void) {}
|
2017-05-23 02:30:57 -03:00
|
|
|
void Copter::Log_Write_EKF_POS() {}
|
2019-10-25 03:06:05 -03:00
|
|
|
void Copter::Log_Write_Data(LogDataID id, int32_t value) {}
|
|
|
|
void Copter::Log_Write_Data(LogDataID id, uint32_t value) {}
|
|
|
|
void Copter::Log_Write_Data(LogDataID id, int16_t value) {}
|
|
|
|
void Copter::Log_Write_Data(LogDataID id, uint16_t value) {}
|
|
|
|
void Copter::Log_Write_Data(LogDataID id, float value) {}
|
2019-04-03 09:32:26 -03:00
|
|
|
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() {}
|
2022-01-25 12:28:04 -04:00
|
|
|
void Copter::Log_Write_Guided_Position_Target(ModeGuided::SubMode target_type, const Vector3f& pos_target, bool terrain_alt, const Vector3f& vel_target, const Vector3f& accel_target) {}
|
|
|
|
void Copter::Log_Write_Guided_Attitude_Target(ModeGuided::SubMode target_type, float roll, float pitch, float yaw, const Vector3f &ang_vel, float thrust, float climb_rate) {}
|
2019-07-29 04:55:40 -03:00
|
|
|
void Copter::Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out) {}
|
|
|
|
void Copter::Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z) {}
|
2017-06-21 01:31:42 -03:00
|
|
|
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) {}
|
|
|
|
|
2016-01-19 01:26:14 -04:00
|
|
|
#endif // LOGGING_ENABLED
|