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
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
// Code to Write and Read packets from DataFlash log memory
|
|
|
|
// Code to interact with the user to dump or erase logs
|
|
|
|
|
2014-02-02 03:58:36 -04:00
|
|
|
#if AUTOTUNE_ENABLED == ENABLED
|
2013-09-03 06:31:06 -03:00
|
|
|
struct PACKED log_AutoTune {
|
|
|
|
LOG_PACKET_HEADER;
|
2015-04-30 02:57:00 -03:00
|
|
|
uint64_t time_us;
|
2013-09-03 06:31:06 -03:00
|
|
|
uint8_t axis; // roll or pitch
|
|
|
|
uint8_t tune_step; // tuning PI or D up or down
|
2015-06-07 08:54:33 -03:00
|
|
|
float meas_target; // target achieved rotation rate
|
|
|
|
float meas_min; // maximum achieved rotation rate
|
|
|
|
float meas_max; // maximum achieved rotation rate
|
2015-03-04 02:22:05 -04:00
|
|
|
float new_gain_rp; // newly calculated gain
|
|
|
|
float new_gain_rd; // newly calculated gain
|
|
|
|
float new_gain_sp; // newly calculated gain
|
2015-06-07 08:54:33 -03:00
|
|
|
float new_ddt; // newly calculated gain
|
2013-09-03 06:31:06 -03:00
|
|
|
};
|
|
|
|
|
2014-07-09 16:14:34 -03:00
|
|
|
// Write an Autotune data packet
|
2015-06-07 08:54:33 -03:00
|
|
|
void Copter::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)
|
2013-09-03 06:31:06 -03:00
|
|
|
{
|
|
|
|
struct log_AutoTune pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_AUTOTUNE_MSG),
|
2015-11-19 23:04:45 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2013-09-03 06:31:06 -03:00
|
|
|
axis : axis,
|
|
|
|
tune_step : tune_step,
|
2015-06-07 08:54:33 -03:00
|
|
|
meas_target : meas_target,
|
|
|
|
meas_min : meas_min,
|
|
|
|
meas_max : meas_max,
|
2015-03-04 02:22:05 -04:00
|
|
|
new_gain_rp : new_gain_rp,
|
|
|
|
new_gain_rd : new_gain_rd,
|
2015-06-07 08:54:33 -03:00
|
|
|
new_gain_sp : new_gain_sp,
|
|
|
|
new_ddt : new_ddt
|
2013-09-03 06:31:06 -03:00
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
}
|
|
|
|
|
|
|
|
struct PACKED log_AutoTuneDetails {
|
|
|
|
LOG_PACKET_HEADER;
|
2015-04-30 02:57:00 -03:00
|
|
|
uint64_t time_us;
|
2015-03-04 02:22:05 -04:00
|
|
|
float angle_cd; // lean angle in centi-degrees
|
|
|
|
float rate_cds; // current rotation rate in centi-degrees / second
|
2013-09-03 06:31:06 -03:00
|
|
|
};
|
|
|
|
|
2014-07-09 16:14:34 -03:00
|
|
|
// Write an Autotune data packet
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::Log_Write_AutoTuneDetails(float angle_cd, float rate_cds)
|
2013-09-03 06:31:06 -03:00
|
|
|
{
|
|
|
|
struct log_AutoTuneDetails pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_AUTOTUNEDETAILS_MSG),
|
2015-11-19 23:04:45 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2013-09-03 06:31:06 -03:00
|
|
|
angle_cd : angle_cd,
|
|
|
|
rate_cds : rate_cds
|
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
}
|
2013-10-04 03:49:19 -03:00
|
|
|
#endif
|
2013-09-03 06:31:06 -03:00
|
|
|
|
2014-12-18 17:35:23 -04:00
|
|
|
// Write a Current data packet
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::Log_Write_Current()
|
2011-01-16 23:44:12 -04:00
|
|
|
{
|
2016-06-02 17:59:51 -03:00
|
|
|
DataFlash.Log_Write_Current(battery);
|
2014-02-13 07:10:23 -04:00
|
|
|
|
|
|
|
// also write power status
|
|
|
|
DataFlash.Log_Write_Power();
|
2011-01-16 23:44:12 -04:00
|
|
|
}
|
2011-01-29 22:36:03 -04:00
|
|
|
|
2013-04-19 20:51:09 -03:00
|
|
|
struct PACKED log_Optflow {
|
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 surface_quality;
|
2014-10-31 09:46:59 -03:00
|
|
|
float flow_x;
|
|
|
|
float flow_y;
|
|
|
|
float body_x;
|
|
|
|
float body_y;
|
2013-01-12 11:17:44 -04:00
|
|
|
};
|
|
|
|
|
2013-04-20 02:18:22 -03:00
|
|
|
// Write an optical flow packet
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::Log_Write_Optflow()
|
2011-07-21 20:14:53 -03:00
|
|
|
{
|
2012-11-18 12:16:07 -04:00
|
|
|
#if OPTFLOW == ENABLED
|
2014-07-11 23:32:40 -03:00
|
|
|
// exit immediately if not enabled
|
|
|
|
if (!optflow.enabled()) {
|
|
|
|
return;
|
|
|
|
}
|
2014-10-31 09:46:59 -03:00
|
|
|
const Vector2f &flowRate = optflow.flowRate();
|
|
|
|
const Vector2f &bodyRate = optflow.bodyRate();
|
2013-01-12 11:17:44 -04:00
|
|
|
struct log_Optflow pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_OPTFLOW_MSG),
|
2015-11-19 23:04:45 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2014-07-11 23:32:40 -03:00
|
|
|
surface_quality : optflow.quality(),
|
2014-12-07 22:19:50 -04:00
|
|
|
flow_x : flowRate.x,
|
|
|
|
flow_y : flowRate.y,
|
|
|
|
body_x : bodyRate.x,
|
|
|
|
body_y : bodyRate.y
|
2013-01-12 11:17:44 -04:00
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
2012-11-18 12:16:07 -04:00
|
|
|
#endif // OPTFLOW == ENABLED
|
2011-07-21 20:14:53 -03:00
|
|
|
}
|
2011-12-23 18:26:24 -04:00
|
|
|
|
2013-04-19 20:51:09 -03:00
|
|
|
struct PACKED log_Nav_Tuning {
|
2013-01-12 11:17:44 -04:00
|
|
|
LOG_PACKET_HEADER;
|
2015-04-30 02:57:00 -03:00
|
|
|
uint64_t time_us;
|
2014-01-13 09:00:11 -04:00
|
|
|
float desired_pos_x;
|
|
|
|
float desired_pos_y;
|
|
|
|
float pos_x;
|
|
|
|
float pos_y;
|
|
|
|
float desired_vel_x;
|
|
|
|
float desired_vel_y;
|
|
|
|
float vel_x;
|
|
|
|
float vel_y;
|
2013-05-19 10:53:35 -03:00
|
|
|
float desired_accel_x;
|
|
|
|
float desired_accel_y;
|
2013-01-12 11:17:44 -04:00
|
|
|
};
|
2011-07-21 20:14:53 -03:00
|
|
|
|
2013-04-20 02:18:22 -03:00
|
|
|
// Write an Nav Tuning packet
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::Log_Write_Nav_Tuning()
|
2011-05-23 02:53:00 -03:00
|
|
|
{
|
2017-01-09 03:31:26 -04:00
|
|
|
const Vector3f &pos_target = pos_control->get_pos_target();
|
|
|
|
const Vector3f &vel_target = pos_control->get_vel_target();
|
|
|
|
const Vector3f &accel_target = pos_control->get_accel_target();
|
2014-01-13 09:00:11 -04:00
|
|
|
const Vector3f &position = inertial_nav.get_position();
|
2013-08-12 10:43:26 -03:00
|
|
|
const Vector3f &velocity = inertial_nav.get_velocity();
|
2013-05-19 10:53:35 -03:00
|
|
|
|
2013-01-12 11:17:44 -04:00
|
|
|
struct log_Nav_Tuning pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_NAV_TUNING_MSG),
|
2015-11-19 23:04:45 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2014-01-19 10:35:55 -04:00
|
|
|
desired_pos_x : pos_target.x,
|
|
|
|
desired_pos_y : pos_target.y,
|
2014-01-13 09:00:11 -04:00
|
|
|
pos_x : position.x,
|
|
|
|
pos_y : position.y,
|
2014-01-19 10:35:55 -04:00
|
|
|
desired_vel_x : vel_target.x,
|
|
|
|
desired_vel_y : vel_target.y,
|
2014-01-13 09:00:11 -04:00
|
|
|
vel_x : velocity.x,
|
|
|
|
vel_y : velocity.y,
|
2014-01-19 10:35:55 -04:00
|
|
|
desired_accel_x : accel_target.x,
|
|
|
|
desired_accel_y : accel_target.y
|
2013-01-12 11:17:44 -04:00
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
2011-05-23 02:53:00 -03:00
|
|
|
}
|
|
|
|
|
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;
|
2016-04-27 08:37:04 -03:00
|
|
|
int16_t desired_rangefinder_alt;
|
|
|
|
int16_t 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;
|
|
|
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
2016-08-08 00:30:55 -03:00
|
|
|
if (terrain.height_above_terrain(terr_alt, true)) {
|
|
|
|
terr_alt = 0.0f;
|
|
|
|
}
|
2016-04-18 03:15:56 -03:00
|
|
|
#endif
|
|
|
|
|
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(),
|
|
|
|
desired_alt : pos_control->get_alt_target() / 100.0f,
|
2015-02-10 08:28:30 -04:00
|
|
|
inav_alt : inertial_nav.get_altitude() / 100.0f,
|
2014-01-13 08:31:43 -04:00
|
|
|
baro_alt : baro_alt,
|
2016-04-27 08:37:04 -03:00
|
|
|
desired_rangefinder_alt : (int16_t)target_rangefinder_alt,
|
2016-05-07 04:55:40 -03:00
|
|
|
rangefinder_alt : rangefinder_state.alt_cm,
|
2016-04-18 03:15:56 -03:00
|
|
|
terr_alt : terr_alt,
|
2017-01-09 03:31:26 -04:00
|
|
|
target_climb_rate : (int16_t)pos_control->get_vel_target_z(),
|
2014-01-13 08:31:43 -04:00
|
|
|
climb_rate : climb_rate
|
2013-01-12 11:17:44 -04:00
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
2011-04-21 02:15:45 -03:00
|
|
|
}
|
|
|
|
|
2013-04-19 20:51:09 -03:00
|
|
|
struct PACKED log_Performance {
|
2013-01-12 03:15:23 -04:00
|
|
|
LOG_PACKET_HEADER;
|
2015-04-30 02:57:00 -03:00
|
|
|
uint64_t time_us;
|
2013-01-12 03:15:23 -04:00
|
|
|
uint16_t num_long_running;
|
|
|
|
uint16_t num_loops;
|
|
|
|
uint32_t max_time;
|
2013-04-29 09:30:22 -03:00
|
|
|
int16_t pm_test;
|
2013-04-26 10:39:22 -03:00
|
|
|
uint8_t i2c_lockup_count;
|
2013-11-17 23:16:21 -04:00
|
|
|
uint16_t ins_error_count;
|
2016-04-21 03:42:25 -03:00
|
|
|
uint32_t log_dropped;
|
2017-03-26 18:12:11 -03:00
|
|
|
uint32_t mem_avail;
|
2013-01-12 03:15:23 -04:00
|
|
|
};
|
|
|
|
|
2013-04-20 02:18:22 -03:00
|
|
|
// Write a performance monitoring packet
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::Log_Write_Performance()
|
2011-05-09 01:16:58 -03:00
|
|
|
{
|
2013-01-12 03:15:23 -04:00
|
|
|
struct log_Performance pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG),
|
2015-11-19 23:04:45 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2013-01-12 03:15:23 -04:00
|
|
|
num_long_running : perf_info_get_num_long_running(),
|
|
|
|
num_loops : perf_info_get_num_loops(),
|
2013-04-26 10:39:22 -03:00
|
|
|
max_time : perf_info_get_max_time(),
|
2013-04-29 09:30:22 -03:00
|
|
|
pm_test : pmTest1,
|
2016-07-22 14:36:26 -03:00
|
|
|
i2c_lockup_count : 0,
|
2016-04-21 03:42:25 -03:00
|
|
|
ins_error_count : ins.error_count(),
|
|
|
|
log_dropped : DataFlash.num_dropped() - perf_info_get_num_dropped(),
|
2017-03-26 18:12:11 -03:00
|
|
|
hal.util->available_memory()
|
2013-01-12 03:15:23 -04:00
|
|
|
};
|
2016-04-21 03:42:25 -03:00
|
|
|
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
|
2011-05-09 01:16:58 -03:00
|
|
|
}
|
2010-12-19 12:40:33 -04: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);
|
2014-12-18 12:55:49 -04:00
|
|
|
DataFlash.Log_Write_Attitude(ahrs, targets);
|
2017-05-23 02:30:57 -03:00
|
|
|
DataFlash.Log_Write_Rate(ahrs, *motors, *attitude_control, *pos_control);
|
|
|
|
if (should_log(MASK_LOG_PID)) {
|
|
|
|
DataFlash.Log_Write_PID(LOG_PIDR_MSG, attitude_control->get_rate_roll_pid().get_pid_info());
|
|
|
|
DataFlash.Log_Write_PID(LOG_PIDP_MSG, attitude_control->get_rate_pitch_pid().get_pid_info());
|
|
|
|
DataFlash.Log_Write_PID(LOG_PIDY_MSG, attitude_control->get_rate_yaw_pid().get_pid_info());
|
|
|
|
DataFlash.Log_Write_PID(LOG_PIDA_MSG, g.pid_accel_z.get_pid_info() );
|
|
|
|
}
|
|
|
|
}
|
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()
|
|
|
|
{
|
2017-08-22 00:14:37 -03:00
|
|
|
DataFlash.Log_Write_EKF(ahrs);
|
2014-01-03 20:51:57 -04:00
|
|
|
DataFlash.Log_Write_AHRS2(ahrs);
|
2015-05-04 03:18:46 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
2015-11-16 00:10:50 -04:00
|
|
|
sitl.Log_Write_SIMSTATE(&DataFlash);
|
2014-01-03 20:51:57 -04:00
|
|
|
#endif
|
2015-05-15 01:24:51 -03:00
|
|
|
DataFlash.Log_Write_POS(ahrs);
|
2011-05-09 01:16:58 -03:00
|
|
|
}
|
|
|
|
|
2015-03-18 09:08:30 -03:00
|
|
|
struct PACKED log_MotBatt {
|
|
|
|
LOG_PACKET_HEADER;
|
2015-04-30 02:57:00 -03:00
|
|
|
uint64_t time_us;
|
2015-03-18 09:08:30 -03:00
|
|
|
float lift_max;
|
|
|
|
float bat_volt;
|
|
|
|
float bat_res;
|
|
|
|
float th_limit;
|
|
|
|
};
|
|
|
|
|
2015-03-04 02:21:01 -04:00
|
|
|
// Write an rate packet
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::Log_Write_MotBatt()
|
2015-03-04 02:21:01 -04:00
|
|
|
{
|
2015-07-15 04:27:45 -03:00
|
|
|
#if FRAME_CONFIG != HELI_FRAME
|
2015-03-18 09:08:30 -03:00
|
|
|
struct log_MotBatt pkt_mot = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_MOTBATT_MSG),
|
2015-11-19 23:04:45 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2017-01-09 03:31:26 -04:00
|
|
|
lift_max : (float)(motors->get_lift_max()),
|
|
|
|
bat_volt : (float)(motors->get_batt_voltage_filt()),
|
|
|
|
bat_res : (float)(motors->get_batt_resistance()),
|
|
|
|
th_limit : (float)(motors->get_throttle_limit())
|
2015-03-04 02:21:01 -04:00
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt_mot, sizeof(pkt_mot));
|
2015-07-15 04:27:45 -03:00
|
|
|
#endif
|
2015-03-04 02:21:01 -04:00
|
|
|
}
|
|
|
|
|
2013-04-19 20:51:09 -03:00
|
|
|
struct PACKED log_Event {
|
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;
|
|
|
|
};
|
2012-11-10 02:04:23 -04:00
|
|
|
|
2013-01-12 11:17:44 -04:00
|
|
|
// Wrote an event packet
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::Log_Write_Event(uint8_t id)
|
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_Event pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_EVENT_MSG),
|
2015-11-19 23:04:45 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2015-04-30 02:57:00 -03:00
|
|
|
id : id
|
2013-01-12 11:17:44 -04:00
|
|
|
};
|
2015-11-02 05:28:02 -04:00
|
|
|
DataFlash.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_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
|
2015-05-29 23:12:49 -03:00
|
|
|
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)) {
|
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(),
|
2013-01-12 11:17:44 -04:00
|
|
|
id : id,
|
|
|
|
data_value : value
|
|
|
|
};
|
2016-04-21 03:43:27 -03:00
|
|
|
DataFlash.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
|
2015-05-29 23:12:49 -03:00
|
|
|
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)) {
|
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(),
|
2013-01-12 11:17:44 -04:00
|
|
|
id : id,
|
|
|
|
data_value : value
|
|
|
|
};
|
2016-04-21 03:43:27 -03:00
|
|
|
DataFlash.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
|
2015-05-29 23:12:49 -03:00
|
|
|
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)) {
|
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(),
|
2013-01-12 11:17:44 -04:00
|
|
|
id : id,
|
|
|
|
data_value : value
|
|
|
|
};
|
2016-04-21 03:43:27 -03:00
|
|
|
DataFlash.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
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::Log_Write_Data(uint8_t 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(),
|
2013-01-12 11:17:44 -04:00
|
|
|
id : id,
|
|
|
|
data_value : value
|
|
|
|
};
|
2016-04-21 03:43:27 -03:00
|
|
|
DataFlash.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
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::Log_Write_Data(uint8_t 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(),
|
2013-01-12 11:17:44 -04:00
|
|
|
id : id,
|
|
|
|
data_value : value
|
|
|
|
};
|
2016-04-21 03:43:27 -03:00
|
|
|
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
2011-11-19 20:57:10 -04:00
|
|
|
}
|
|
|
|
|
2013-04-19 20:51:09 -03:00
|
|
|
struct PACKED log_Error {
|
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 sub_system;
|
|
|
|
uint8_t error_code;
|
|
|
|
};
|
|
|
|
|
2013-04-20 02:18:22 -03:00
|
|
|
// Write an error packet
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::Log_Write_Error(uint8_t sub_system, uint8_t error_code)
|
2012-12-29 23:08:25 -04:00
|
|
|
{
|
2013-01-12 11:17:44 -04:00
|
|
|
struct log_Error pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_ERROR_MSG),
|
2015-11-19 23:04:45 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2013-01-12 11:17:44 -04:00
|
|
|
sub_system : sub_system,
|
|
|
|
error_code : error_code,
|
|
|
|
};
|
2016-04-21 03:43:27 -03:00
|
|
|
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
|
2012-12-29 23:08:25 -04:00
|
|
|
}
|
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::Log_Write_Baro(void)
|
2014-02-18 16:38:20 -04:00
|
|
|
{
|
2016-05-04 01:01:58 -03:00
|
|
|
if (!ahrs.have_ekf_logging()) {
|
|
|
|
DataFlash.Log_Write_Baro(barometer);
|
|
|
|
}
|
2014-02-18 16:38:20 -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
|
|
|
|
int16_t control_in; // raw tune input value
|
|
|
|
int16_t tuning_low; // tuning low end value
|
|
|
|
int16_t tuning_high; // tuning high end value
|
|
|
|
};
|
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high)
|
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,
|
|
|
|
control_in : control_in,
|
|
|
|
tuning_low : tune_low,
|
|
|
|
tuning_high : tune_high
|
|
|
|
};
|
|
|
|
|
|
|
|
DataFlash.WriteBlock(&pkt_tune, sizeof(pkt_tune));
|
|
|
|
}
|
|
|
|
|
2015-07-05 05:25:28 -03:00
|
|
|
// log EKF origin and ahrs home to dataflash
|
|
|
|
void Copter::Log_Write_Home_And_Origin()
|
|
|
|
{
|
|
|
|
// log ekf origin if set
|
|
|
|
Location ekf_orig;
|
2016-03-03 02:56:41 -04:00
|
|
|
if (ahrs.get_origin(ekf_orig)) {
|
2015-07-05 05:25:28 -03:00
|
|
|
DataFlash.Log_Write_Origin(LogOriginType::ekf_origin, ekf_orig);
|
|
|
|
}
|
|
|
|
|
|
|
|
// log ahrs home if set
|
|
|
|
if (ap.home_state != HOME_UNSET) {
|
|
|
|
DataFlash.Log_Write_Origin(LogOriginType::ahrs_home, ahrs.get_home());
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
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();
|
|
|
|
Log_Write_Error(ERROR_SUBSYSTEM_BARO, (sensor_health.baro ? ERROR_CODE_ERROR_RESOLVED : ERROR_CODE_UNHEALTHY));
|
|
|
|
}
|
|
|
|
|
|
|
|
// check compass
|
|
|
|
if (sensor_health.compass != compass.healthy()) {
|
|
|
|
sensor_health.compass = compass.healthy();
|
|
|
|
Log_Write_Error(ERROR_SUBSYSTEM_COMPASS, (sensor_health.compass ? ERROR_CODE_ERROR_RESOLVED : ERROR_CODE_UNHEALTHY));
|
|
|
|
}
|
2017-03-08 20:16:25 -04:00
|
|
|
|
|
|
|
// 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-07-12 10:06:21 -03:00
|
|
|
}
|
|
|
|
|
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;
|
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),
|
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(),
|
2015-06-18 18:09:39 -03:00
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt_heli, sizeof(pkt_heli));
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2015-08-28 05:14:02 -03:00
|
|
|
// precision landing logging
|
|
|
|
struct PACKED log_Precland {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t healthy;
|
2016-07-15 14:21:10 -03:00
|
|
|
uint8_t target_acquired;
|
2015-08-28 05:14:02 -03:00
|
|
|
float pos_x;
|
|
|
|
float pos_y;
|
2016-07-15 14:21:10 -03:00
|
|
|
float vel_x;
|
|
|
|
float vel_y;
|
2015-08-28 05:14:02 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
// Write an optical flow packet
|
|
|
|
void Copter::Log_Write_Precland()
|
|
|
|
{
|
|
|
|
#if PRECISION_LANDING == ENABLED
|
|
|
|
// exit immediately if not enabled
|
|
|
|
if (!precland.enabled()) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2016-07-15 14:21:10 -03:00
|
|
|
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);
|
|
|
|
|
2015-08-28 05:14:02 -03:00
|
|
|
struct log_Precland pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_PRECLAND_MSG),
|
2015-11-19 23:04:45 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2015-08-28 05:14:02 -03:00
|
|
|
healthy : precland.healthy(),
|
2016-07-15 14:21:10 -03:00
|
|
|
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
|
2015-08-28 05:14:02 -03:00
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
#endif // PRECISION_LANDING == ENABLED
|
|
|
|
}
|
|
|
|
|
2016-01-10 22:41:28 -04:00
|
|
|
// precision landing logging
|
|
|
|
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
|
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
}
|
|
|
|
|
2016-08-02 02:41:39 -03:00
|
|
|
// precision landing logging
|
|
|
|
struct PACKED log_Throw {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
uint8_t stage;
|
|
|
|
float velocity;
|
|
|
|
float velocity_z;
|
|
|
|
float accel;
|
|
|
|
float ef_accel_z;
|
|
|
|
uint8_t throw_detect;
|
|
|
|
uint8_t attitude_ok;
|
|
|
|
uint8_t height_ok;
|
|
|
|
uint8_t pos_ok;
|
|
|
|
};
|
|
|
|
|
|
|
|
// Write a Throw mode details
|
|
|
|
void Copter::Log_Write_Throw(ThrowModeStage stage, float velocity, float velocity_z, float accel, float ef_accel_z, bool throw_detect, bool attitude_ok, bool height_ok, bool pos_ok)
|
|
|
|
{
|
|
|
|
struct log_Throw pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_THROW_MSG),
|
|
|
|
time_us : AP_HAL::micros64(),
|
|
|
|
stage : (uint8_t)stage,
|
|
|
|
velocity : velocity,
|
|
|
|
velocity_z : velocity_z,
|
|
|
|
accel : accel,
|
|
|
|
ef_accel_z : ef_accel_z,
|
|
|
|
throw_detect : throw_detect,
|
|
|
|
attitude_ok : attitude_ok,
|
|
|
|
height_ok : height_ok,
|
|
|
|
pos_ok : pos_ok
|
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
}
|
|
|
|
|
2016-08-16 09:09:17 -03:00
|
|
|
// Write proximity sensor distances
|
|
|
|
void Copter::Log_Write_Proximity()
|
|
|
|
{
|
|
|
|
#if PROXIMITY_ENABLED == ENABLED
|
2017-07-14 14:00:13 -03:00
|
|
|
DataFlash.Log_Write_Proximity(g2.proximity);
|
2016-08-16 09:09:17 -03:00
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2016-10-27 01:40:55 -03:00
|
|
|
// Write beacon position and distances
|
|
|
|
void Copter::Log_Write_Beacon()
|
|
|
|
{
|
|
|
|
// exit immediately if feature is disabled
|
|
|
|
if (!g2.beacon.enabled()) {
|
|
|
|
return;
|
|
|
|
}
|
2017-04-18 11:43:30 -03:00
|
|
|
DataFlash.Log_Write_Beacon(g2.beacon);
|
2016-10-27 01:40:55 -03:00
|
|
|
}
|
|
|
|
|
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,
|
2014-03-21 03:44:06 -03:00
|
|
|
#if AUTOTUNE_ENABLED == ENABLED
|
2013-09-03 06:31:06 -03:00
|
|
|
{ LOG_AUTOTUNE_MSG, sizeof(log_AutoTune),
|
2015-06-07 08:54:33 -03:00
|
|
|
"ATUN", "QBBfffffff", "TimeUS,Axis,TuneStep,Targ,Min,Max,RP,RD,SP,ddt" },
|
2013-09-03 06:31:06 -03:00
|
|
|
{ LOG_AUTOTUNEDETAILS_MSG, sizeof(log_AutoTuneDetails),
|
2015-04-30 02:57:00 -03:00
|
|
|
"ATDE", "Qff", "TimeUS,Angle,Rate" },
|
2013-10-04 03:49:19 -03:00
|
|
|
#endif
|
2015-04-26 21:29:04 -03:00
|
|
|
{ LOG_PARAMTUNE_MSG, sizeof(log_ParameterTuning),
|
2015-04-30 02:57:00 -03:00
|
|
|
"PTUN", "QBfHHH", "TimeUS,Param,TunVal,CtrlIn,TunLo,TunHi" },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow),
|
2015-04-30 02:57:00 -03:00
|
|
|
"OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY" },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_NAV_TUNING_MSG, sizeof(log_Nav_Tuning),
|
2015-04-30 02:57:00 -03:00
|
|
|
"NTUN", "Qffffffffff", "TimeUS,DPosX,DPosY,PosX,PosY,DVelX,DVelY,VelX,VelY,DAccX,DAccY" },
|
2014-01-13 08:31:43 -04:00
|
|
|
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
|
2016-05-23 04:17:19 -03:00
|
|
|
"CTUN", "Qffffffeccfhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt" },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
2017-03-26 18:12:11 -03:00
|
|
|
"PM", "QHHIhBHII", "TimeUS,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,LogDrop,Mem" },
|
2015-03-18 09:08:30 -03:00
|
|
|
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt),
|
2015-04-30 02:57:00 -03:00
|
|
|
"MOTB", "Qffff", "TimeUS,LiftMax,BatVolt,BatRes,ThLimit" },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_EVENT_MSG, sizeof(log_Event),
|
2015-04-30 02:57:00 -03:00
|
|
|
"EV", "QB", "TimeUS,Id" },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t),
|
2015-04-30 02:57:00 -03:00
|
|
|
"D16", "QBh", "TimeUS,Id,Value" },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_DATA_UINT16_MSG, sizeof(log_Data_UInt16t),
|
2015-04-30 02:57:00 -03:00
|
|
|
"DU16", "QBH", "TimeUS,Id,Value" },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_DATA_INT32_MSG, sizeof(log_Data_Int32t),
|
2015-04-30 02:57:00 -03:00
|
|
|
"D32", "QBi", "TimeUS,Id,Value" },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_DATA_UINT32_MSG, sizeof(log_Data_UInt32t),
|
2015-04-30 02:57:00 -03:00
|
|
|
"DU32", "QBI", "TimeUS,Id,Value" },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_DATA_FLOAT_MSG, sizeof(log_Data_Float),
|
2015-04-30 02:57:00 -03:00
|
|
|
"DFLT", "QBf", "TimeUS,Id,Value" },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_ERROR_MSG, sizeof(log_Error),
|
2015-04-30 02:57:00 -03:00
|
|
|
"ERR", "QBB", "TimeUS,Subsys,ECode" },
|
2015-06-18 18:09:39 -03:00
|
|
|
{ LOG_HELI_MSG, sizeof(log_Heli),
|
2016-02-03 05:02:41 -04:00
|
|
|
"HELI", "Qff", "TimeUS,DRRPM,ERRPM" },
|
2015-08-28 05:14:02 -03:00
|
|
|
{ LOG_PRECLAND_MSG, sizeof(log_Precland),
|
2016-07-15 14:21:10 -03:00
|
|
|
"PL", "QBBffff", "TimeUS,Heal,TAcq,pX,pY,vX,vY" },
|
2016-01-10 22:41:28 -04:00
|
|
|
{ LOG_GUIDEDTARGET_MSG, sizeof(log_GuidedTarget),
|
|
|
|
"GUID", "QBffffff", "TimeUS,Type,pX,pY,pZ,vX,vY,vZ" },
|
2016-08-02 02:41:39 -03:00
|
|
|
{ LOG_THROW_MSG, sizeof(log_Throw),
|
|
|
|
"THRO", "QBffffbbbb", "TimeUS,Stage,Vel,VelZ,Acc,AccEfZ,Throw,AttOk,HgtOk,PosOk" },
|
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()
|
|
|
|
{
|
|
|
|
// only 200(?) bytes are guaranteed by DataFlash
|
2017-05-01 02:27:15 -03:00
|
|
|
DataFlash.Log_Write_MessageF("Frame: %s", get_frame_string());
|
2016-01-25 19:50:12 -04:00
|
|
|
DataFlash.Log_Write_Mode(control_mode, control_mode_reason);
|
2017-01-02 19:50:17 -04:00
|
|
|
#if AC_RALLY
|
2016-07-02 03:54:25 -03:00
|
|
|
DataFlash.Log_Write_Rally(rally);
|
2017-01-02 19:50:17 -04:00
|
|
|
#endif
|
2017-03-13 19:43:16 -03:00
|
|
|
Log_Write_Home_And_Origin();
|
2016-08-01 08:58:39 -03:00
|
|
|
gps.Write_DataFlash_Log_Startup_messages();
|
2015-08-06 09:18:39 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::log_init(void)
|
|
|
|
{
|
2015-07-06 12:30:40 -03:00
|
|
|
DataFlash.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_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) {}
|
|
|
|
void Copter::Log_Write_AutoTuneDetails(float angle_cd, float rate_cds) {}
|
|
|
|
void Copter::Log_Write_Current() {}
|
|
|
|
void Copter::Log_Write_Nav_Tuning() {}
|
|
|
|
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(uint8_t id) {}
|
|
|
|
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_Error(uint8_t sub_system, uint8_t error_code) {}
|
|
|
|
void Copter::Log_Write_Baro(void) {}
|
|
|
|
void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high) {}
|
|
|
|
void Copter::Log_Write_Home_And_Origin() {}
|
|
|
|
void Copter::Log_Sensor_Health() {}
|
2017-06-21 01:31:42 -03:00
|
|
|
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) {}
|
2017-06-21 01:31:42 -03:00
|
|
|
void Copter::Log_Write_Throw(ThrowModeStage stage, float velocity, float velocity_z, float accel, float ef_accel_z, bool throw_detect, bool attitude_ok, bool height_ok, bool pos_ok) {}
|
2017-01-01 21:30:11 -04:00
|
|
|
void Copter::Log_Write_Proximity() {}
|
|
|
|
void Copter::Log_Write_Beacon() {}
|
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
|
|
|
|
|
|
|
|
#if OPTFLOW == ENABLED
|
|
|
|
void Copter::Log_Write_Optflow() {}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
void Copter::log_init(void) {}
|
|
|
|
|
2016-01-19 01:26:14 -04:00
|
|
|
#endif // LOGGING_ENABLED
|