ardupilot/ArduCopter/Log.pde

775 lines
24 KiB
Plaintext
Raw Normal View History

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#if LOGGING_ENABLED == ENABLED
// Code to Write and Read packets from DataFlash log memory
// Code to interact with the user to dump or erase logs
#if CLI_ENABLED == ENABLED
// These are function definitions so the Menu can be constructed before the functions
// are defined below. Order matters to the compiler.
static bool print_log_menu(void);
2012-08-21 23:19:50 -03:00
static int8_t dump_log(uint8_t argc, const Menu::arg *argv);
static int8_t erase_logs(uint8_t argc, const Menu::arg *argv);
static int8_t select_logs(uint8_t argc, const Menu::arg *argv);
// Creates a constant array of structs representing menu options
// and stores them in Flash memory, not RAM.
// User enters the string in the console to call the functions on the right.
// See class Menu in AP_Coommon for implementation details
const struct Menu::command log_menu_commands[] PROGMEM = {
2012-08-21 23:19:50 -03:00
{"dump", dump_log},
{"erase", erase_logs},
{"enable", select_logs},
{"disable", select_logs}
};
// A Macro to create the Menu
MENU2(log_menu, "Log", log_menu_commands, print_log_menu);
static bool
print_log_menu(void)
{
cliSerial->printf_P(PSTR("logs enabled: "));
2012-08-21 23:19:50 -03:00
if (0 == g.log_bitmask) {
cliSerial->printf_P(PSTR("none"));
2012-08-21 23:19:50 -03:00
}else{
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST) cliSerial->printf_P(PSTR(" ATTITUDE_FAST"));
if (g.log_bitmask & MASK_LOG_ATTITUDE_MED) cliSerial->printf_P(PSTR(" ATTITUDE_MED"));
if (g.log_bitmask & MASK_LOG_GPS) cliSerial->printf_P(PSTR(" GPS"));
if (g.log_bitmask & MASK_LOG_PM) cliSerial->printf_P(PSTR(" PM"));
if (g.log_bitmask & MASK_LOG_CTUN) cliSerial->printf_P(PSTR(" CTUN"));
if (g.log_bitmask & MASK_LOG_NTUN) cliSerial->printf_P(PSTR(" NTUN"));
2013-11-27 03:46:25 -04:00
if (g.log_bitmask & MASK_LOG_RCIN) cliSerial->printf_P(PSTR(" RCIN"));
if (g.log_bitmask & MASK_LOG_IMU) cliSerial->printf_P(PSTR(" IMU"));
if (g.log_bitmask & MASK_LOG_CMD) cliSerial->printf_P(PSTR(" CMD"));
if (g.log_bitmask & MASK_LOG_CURRENT) cliSerial->printf_P(PSTR(" CURRENT"));
if (g.log_bitmask & MASK_LOG_RCOUT) cliSerial->printf_P(PSTR(" RCOUT"));
if (g.log_bitmask & MASK_LOG_OPTFLOW) cliSerial->printf_P(PSTR(" OPTFLOW"));
if (g.log_bitmask & MASK_LOG_COMPASS) cliSerial->printf_P(PSTR(" COMPASS"));
if (g.log_bitmask & MASK_LOG_CAMERA) cliSerial->printf_P(PSTR(" CAMERA"));
2012-08-21 23:19:50 -03:00
}
cliSerial->println();
2012-08-21 23:19:50 -03:00
2013-04-17 08:34:42 -03:00
DataFlash.ListAvailableLogs(cliSerial);
2012-08-21 23:19:50 -03:00
return(true);
}
2014-08-01 02:57:28 -03:00
#if CLI_ENABLED == ENABLED
static int8_t
dump_log(uint8_t argc, const Menu::arg *argv)
{
2012-08-21 23:19:50 -03:00
int16_t dump_log;
2013-02-22 19:15:01 -04:00
uint16_t dump_log_start;
uint16_t dump_log_end;
uint16_t last_log_num;
2012-08-21 23:19:50 -03:00
// check that the requested log number can be read
dump_log = argv[1].i;
last_log_num = DataFlash.find_last_log();
if (dump_log == -2) {
2013-02-22 19:15:01 -04:00
DataFlash.DumpPageInfo(cliSerial);
2012-08-21 23:19:50 -03:00
return(-1);
} else if (dump_log <= 0) {
cliSerial->printf_P(PSTR("dumping all\n"));
2013-02-28 16:16:48 -04:00
Log_Read(0, 1, 0);
2012-08-21 23:19:50 -03:00
return(-1);
} else if ((argc != 2) || ((uint16_t)dump_log <= (last_log_num - DataFlash.get_num_logs())) || (static_cast<uint16_t>(dump_log) > last_log_num)) {
cliSerial->printf_P(PSTR("bad log number\n"));
2012-08-21 23:19:50 -03:00
return(-1);
}
DataFlash.get_log_boundaries(dump_log, dump_log_start, dump_log_end);
2013-04-17 08:34:42 -03:00
Log_Read((uint16_t)dump_log, dump_log_start, dump_log_end);
2012-08-21 23:19:50 -03:00
return (0);
}
2014-08-01 02:57:28 -03:00
#endif
static int8_t
erase_logs(uint8_t argc, const Menu::arg *argv)
{
2011-12-28 00:53:05 -04:00
in_mavlink_delay = true;
do_erase_logs();
in_mavlink_delay = false;
return 0;
}
static int8_t
select_logs(uint8_t argc, const Menu::arg *argv)
{
2012-08-21 23:19:50 -03:00
uint16_t bits;
if (argc != 2) {
cliSerial->printf_P(PSTR("missing log type\n"));
2012-08-21 23:19:50 -03:00
return(-1);
}
bits = 0;
// Macro to make the following code a bit easier on the eye.
// Pass it the capitalised name of the log option, as defined
// in defines.h but without the LOG_ prefix. It will check for
// that name as the argument to the command, and set the bit in
// bits accordingly.
//
if (!strcasecmp_P(argv[1].str, PSTR("all"))) {
bits = ~0;
} else {
#define TARG(_s) if (!strcasecmp_P(argv[1].str, PSTR(# _s))) bits |= MASK_LOG_ ## _s
TARG(ATTITUDE_FAST);
TARG(ATTITUDE_MED);
TARG(GPS);
TARG(PM);
TARG(CTUN);
TARG(NTUN);
2013-11-27 03:46:25 -04:00
TARG(RCIN);
TARG(IMU);
2012-08-21 23:19:50 -03:00
TARG(CMD);
TARG(CURRENT);
TARG(RCOUT);
2012-08-21 23:19:50 -03:00
TARG(OPTFLOW);
TARG(COMPASS);
TARG(CAMERA);
2012-08-21 23:19:50 -03:00
#undef TARG
}
if (!strcasecmp_P(argv[0].str, PSTR("enable"))) {
g.log_bitmask.set_and_save(g.log_bitmask | bits);
}else{
g.log_bitmask.set_and_save(g.log_bitmask & ~bits);
}
return(0);
}
static int8_t
process_logs(uint8_t argc, const Menu::arg *argv)
{
2012-08-21 23:19:50 -03:00
log_menu.run();
return 0;
}
#endif // CLI_ENABLED
static void do_erase_logs(void)
{
gcs_send_text_P(SEVERITY_HIGH, PSTR("Erasing logs\n"));
DataFlash.EraseAll();
gcs_send_text_P(SEVERITY_HIGH, PSTR("Log erase complete\n"));
}
2014-02-02 03:58:36 -04:00
#if AUTOTUNE_ENABLED == ENABLED
struct PACKED log_AutoTune {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t axis; // roll or pitch
uint8_t tune_step; // tuning PI or D up or down
float rate_target; // target achieved rotation rate
float rate_min; // maximum achieved rotation rate
float rate_max; // maximum achieved rotation rate
float new_gain_rp; // newly calculated gain
float new_gain_rd; // newly calculated gain
float new_gain_sp; // newly calculated gain
};
2014-07-09 16:14:34 -03:00
// Write an Autotune data packet
static void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float rate_target, float rate_min, float rate_max, float new_gain_rp, float new_gain_rd, float new_gain_sp)
{
struct log_AutoTune pkt = {
LOG_PACKET_HEADER_INIT(LOG_AUTOTUNE_MSG),
time_us : hal.scheduler->micros64(),
axis : axis,
tune_step : tune_step,
rate_target : rate_target,
rate_min : rate_min,
rate_max : rate_max,
new_gain_rp : new_gain_rp,
new_gain_rd : new_gain_rd,
new_gain_sp : new_gain_sp
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
struct PACKED log_AutoTuneDetails {
LOG_PACKET_HEADER;
uint64_t time_us;
float angle_cd; // lean angle in centi-degrees
float rate_cds; // current rotation rate in centi-degrees / second
};
2014-07-09 16:14:34 -03:00
// Write an Autotune data packet
static void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds)
{
struct log_AutoTuneDetails pkt = {
LOG_PACKET_HEADER_INIT(LOG_AUTOTUNEDETAILS_MSG),
time_us : hal.scheduler->micros64(),
angle_cd : angle_cd,
rate_cds : rate_cds
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
#endif
// Write a Current data packet
static void Log_Write_Current()
{
DataFlash.Log_Write_Current(battery, (int16_t)(motors.get_throttle()));
2014-02-13 07:10:23 -04:00
// also write power status
DataFlash.Log_Write_Power();
}
2013-04-19 20:51:09 -03:00
struct PACKED log_Optflow {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t surface_quality;
float flow_x;
float flow_y;
float body_x;
float body_y;
};
2013-04-20 02:18:22 -03:00
// Write an optical flow packet
static void Log_Write_Optflow()
{
#if OPTFLOW == ENABLED
// exit immediately if not enabled
if (!optflow.enabled()) {
return;
}
const Vector2f &flowRate = optflow.flowRate();
const Vector2f &bodyRate = optflow.bodyRate();
struct log_Optflow pkt = {
LOG_PACKET_HEADER_INIT(LOG_OPTFLOW_MSG),
time_us : hal.scheduler->micros64(),
surface_quality : optflow.quality(),
flow_x : flowRate.x,
flow_y : flowRate.y,
body_x : bodyRate.x,
body_y : bodyRate.y
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
#endif // OPTFLOW == ENABLED
}
2013-04-19 20:51:09 -03:00
struct PACKED log_Nav_Tuning {
LOG_PACKET_HEADER;
uint64_t time_us;
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;
float desired_accel_x;
float desired_accel_y;
};
2013-04-20 02:18:22 -03:00
// Write an Nav Tuning packet
static void Log_Write_Nav_Tuning()
{
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();
const Vector3f &position = inertial_nav.get_position();
const Vector3f &velocity = inertial_nav.get_velocity();
struct log_Nav_Tuning pkt = {
LOG_PACKET_HEADER_INIT(LOG_NAV_TUNING_MSG),
time_us : hal.scheduler->micros64(),
desired_pos_x : pos_target.x,
desired_pos_y : pos_target.y,
pos_x : position.x,
pos_y : position.y,
desired_vel_x : vel_target.x,
desired_vel_y : vel_target.y,
vel_x : velocity.x,
vel_y : velocity.y,
desired_accel_x : accel_target.x,
desired_accel_y : accel_target.y
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
2013-04-19 20:51:09 -03:00
struct PACKED log_Control_Tuning {
LOG_PACKET_HEADER;
uint64_t time_us;
int16_t throttle_in;
int16_t angle_boost;
float throttle_out;
float desired_alt;
float inav_alt;
int32_t baro_alt;
int16_t desired_sonar_alt;
int16_t sonar_alt;
int16_t desired_climb_rate;
int16_t climb_rate;
};
2013-04-20 02:18:22 -03:00
// Write a control tuning packet
static void Log_Write_Control_Tuning()
{
struct log_Control_Tuning pkt = {
LOG_PACKET_HEADER_INIT(LOG_CONTROL_TUNING_MSG),
time_us : hal.scheduler->micros64(),
throttle_in : channel_throttle->control_in,
angle_boost : attitude_control.angle_boost(),
throttle_out : motors.get_throttle(),
2014-01-10 03:20:31 -04:00
desired_alt : pos_control.get_alt_target() / 100.0f,
inav_alt : inertial_nav.get_altitude() / 100.0f,
baro_alt : baro_alt,
desired_sonar_alt : (int16_t)target_sonar_alt,
sonar_alt : sonar_alt,
2015-04-05 04:23:35 -03:00
desired_climb_rate : (int16_t)pos_control.get_vel_target_z(),
climb_rate : climb_rate
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
2013-04-19 20:51:09 -03:00
struct PACKED log_Performance {
LOG_PACKET_HEADER;
uint64_t time_us;
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;
uint8_t i2c_lockup_count;
2013-11-17 23:16:21 -04:00
uint16_t ins_error_count;
};
2013-04-20 02:18:22 -03:00
// Write a performance monitoring packet
static void Log_Write_Performance()
{
struct log_Performance pkt = {
LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG),
time_us : hal.scheduler->micros64(),
num_long_running : perf_info_get_num_long_running(),
num_loops : perf_info_get_num_loops(),
max_time : perf_info_get_max_time(),
2013-04-29 09:30:22 -03:00
pm_test : pmTest1,
2013-11-17 23:16:21 -04:00
i2c_lockup_count : hal.i2c->lockup_count(),
ins_error_count : ins.error_count()
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
// Write a mission command. Total length : 36 bytes
static void Log_Write_Cmd(const AP_Mission::Mission_Command &cmd)
{
mavlink_mission_item_t mav_cmd = {};
AP_Mission::mission_cmd_to_mavlink(cmd,mav_cmd);
DataFlash.Log_Write_MavCmd(mission.num_commands(),mav_cmd);
}
2013-04-20 02:18:22 -03:00
// Write an attitude packet
static void Log_Write_Attitude()
{
Vector3f targets = attitude_control.angle_ef_targets();
DataFlash.Log_Write_Attitude(ahrs, targets);
#if AP_AHRS_NAVEKF_AVAILABLE
#if OPTFLOW == ENABLED
DataFlash.Log_Write_EKF(ahrs,optflow.enabled());
#else
DataFlash.Log_Write_EKF(ahrs,false);
#endif
DataFlash.Log_Write_AHRS2(ahrs);
#endif
2015-05-04 03:18:46 -03:00
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
sitl.Log_Write_SIMSTATE(DataFlash);
#endif
2015-05-15 01:24:51 -03:00
DataFlash.Log_Write_POS(ahrs);
}
2015-03-18 09:05:19 -03:00
struct PACKED log_Rate {
LOG_PACKET_HEADER;
uint64_t time_us;
2015-03-18 09:05:19 -03:00
float control_roll;
float roll;
float roll_out;
float control_pitch;
float pitch;
float pitch_out;
float control_yaw;
float yaw;
float yaw_out;
2015-04-05 04:23:35 -03:00
float control_accel;
float accel;
float accel_out;
2015-03-18 09:05:19 -03:00
};
// Write an rate packet
static void Log_Write_Rate()
{
const Vector3f &rate_targets = attitude_control.rate_bf_targets();
2015-04-05 04:23:35 -03:00
const Vector3f &accel_target = pos_control.get_accel_target();
struct log_Rate pkt_rate = {
LOG_PACKET_HEADER_INIT(LOG_RATE_MSG),
time_us : hal.scheduler->micros64(),
control_roll : (float)rate_targets.x,
roll : (float)(ahrs.get_gyro().x * AC_ATTITUDE_CONTROL_DEGX100),
2015-05-25 08:23:45 -03:00
roll_out : motors.get_roll(),
control_pitch : (float)rate_targets.y,
pitch : (float)(ahrs.get_gyro().y * AC_ATTITUDE_CONTROL_DEGX100),
2015-05-25 08:23:45 -03:00
pitch_out : motors.get_pitch(),
control_yaw : (float)rate_targets.z,
yaw : (float)(ahrs.get_gyro().z * AC_ATTITUDE_CONTROL_DEGX100),
2015-05-25 08:23:45 -03:00
yaw_out : motors.get_yaw(),
2015-04-05 04:23:35 -03:00
control_accel : (float)accel_target.z,
accel : (float)(-(ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f),
2015-05-25 08:23:45 -03:00
accel_out : motors.get_throttle()
};
DataFlash.WriteBlock(&pkt_rate, sizeof(pkt_rate));
}
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
static void Log_Write_MotBatt()
{
struct log_MotBatt pkt_mot = {
LOG_PACKET_HEADER_INIT(LOG_MOTBATT_MSG),
time_us : hal.scheduler->micros64(),
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())
};
DataFlash.WriteBlock(&pkt_mot, sizeof(pkt_mot));
}
2013-04-19 20:51:09 -03:00
struct PACKED log_Startup {
2013-01-26 04:05:38 -04:00
LOG_PACKET_HEADER;
uint64_t time_us;
2013-01-26 04:05:38 -04:00
};
2013-04-20 02:18:22 -03:00
// Write Startup packet
static void Log_Write_Startup()
{
2013-01-26 04:05:38 -04:00
struct log_Startup pkt = {
LOG_PACKET_HEADER_INIT(LOG_STARTUP_MSG),
time_us : hal.scheduler->micros64()
2013-01-26 04:05:38 -04:00
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
Log_Write_EntireMission();
}
static void Log_Write_EntireMission()
{
DataFlash.Log_Write_Message_P(PSTR("New mission"));
AP_Mission::Mission_Command cmd;
for (uint16_t i = 0; i < mission.num_commands(); i++) {
if (mission.read_cmd_from_storage(i,cmd)) {
Log_Write_Cmd(cmd);
}
}
}
2013-04-19 20:51:09 -03:00
struct PACKED log_Event {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t id;
};
2012-11-10 02:04:23 -04:00
// Wrote an event packet
static void 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)) {
struct log_Event pkt = {
LOG_PACKET_HEADER_INIT(LOG_EVENT_MSG),
time_us : hal.scheduler->micros64(),
id : id
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
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
static void 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 : hal.scheduler->micros64(),
id : id,
data_value : value
};
DataFlash.WriteBlock(&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
static void 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 : hal.scheduler->micros64(),
id : id,
data_value : value
};
DataFlash.WriteBlock(&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
static void 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 : hal.scheduler->micros64(),
id : id,
data_value : value
};
DataFlash.WriteBlock(&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
static void 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 : hal.scheduler->micros64(),
id : id,
data_value : value
};
DataFlash.WriteBlock(&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
static void 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 : hal.scheduler->micros64(),
id : id,
data_value : value
};
DataFlash.WriteBlock(&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 {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t sub_system;
uint8_t error_code;
};
2013-04-20 02:18:22 -03:00
// Write an error packet
static void Log_Write_Error(uint8_t sub_system, uint8_t error_code)
{
struct log_Error pkt = {
LOG_PACKET_HEADER_INIT(LOG_ERROR_MSG),
time_us : hal.scheduler->micros64(),
sub_system : sub_system,
error_code : error_code,
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
static void Log_Write_Baro(void)
{
DataFlash.Log_Write_Baro(barometer);
}
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
int16_t control_in; // raw tune input value
int16_t tuning_low; // tuning low end value
int16_t tuning_high; // tuning high end value
};
static void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high)
{
struct log_ParameterTuning pkt_tune = {
LOG_PACKET_HEADER_INIT(LOG_PARAMTUNE_MSG),
time_us : hal.scheduler->micros64(),
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));
}
2013-04-19 20:51:09 -03:00
static const struct LogStructure log_structure[] PROGMEM = {
LOG_COMMON_STRUCTURES,
#if AUTOTUNE_ENABLED == ENABLED
{ LOG_AUTOTUNE_MSG, sizeof(log_AutoTune),
"ATUN", "QBBffffff", "TimeUS,Axis,TuneStep,RateTarg,RateMin,RateMax,RP,RD,SP" },
{ LOG_AUTOTUNEDETAILS_MSG, sizeof(log_AutoTuneDetails),
"ATDE", "Qff", "TimeUS,Angle,Rate" },
#endif
{ LOG_PARAMTUNE_MSG, sizeof(log_ParameterTuning),
"PTUN", "QBfHHH", "TimeUS,Param,TunVal,CtrlIn,TunLo,TunHi" },
2013-04-19 20:51:09 -03:00
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow),
"OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY" },
2013-04-19 20:51:09 -03:00
{ LOG_NAV_TUNING_MSG, sizeof(log_Nav_Tuning),
"NTUN", "Qffffffffff", "TimeUS,DPosX,DPosY,PosX,PosY,DVelX,DVelY,VelX,VelY,DAccX,DAccY" },
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
"CTUN", "Qhhfffecchh", "TimeUS,ThrIn,AngBst,ThrOut,DAlt,Alt,BarAlt,DSAlt,SAlt,DCRt,CRt" },
2013-04-19 20:51:09 -03:00
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
"PM", "QHHIhBH", "TimeUS,NLon,NLoop,MaxT,PMT,I2CErr,INSErr" },
{ LOG_RATE_MSG, sizeof(log_Rate),
"RATE", "Qffffffffffff", "TimeUS,RDes,R,ROut,PDes,P,POut,YDes,Y,YOut,ADes,A,AOut" },
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt),
"MOTB", "Qffff", "TimeUS,LiftMax,BatVolt,BatRes,ThLimit" },
2013-04-19 20:51:09 -03:00
{ LOG_STARTUP_MSG, sizeof(log_Startup),
"STRT", "Q", "TimeUS" },
2013-04-19 20:51:09 -03:00
{ LOG_EVENT_MSG, sizeof(log_Event),
"EV", "QB", "TimeUS,Id" },
2013-04-19 20:51:09 -03:00
{ LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t),
"D16", "QBh", "TimeUS,Id,Value" },
2013-04-19 20:51:09 -03:00
{ LOG_DATA_UINT16_MSG, sizeof(log_Data_UInt16t),
"DU16", "QBH", "TimeUS,Id,Value" },
2013-04-19 20:51:09 -03:00
{ LOG_DATA_INT32_MSG, sizeof(log_Data_Int32t),
"D32", "QBi", "TimeUS,Id,Value" },
2013-04-19 20:51:09 -03:00
{ LOG_DATA_UINT32_MSG, sizeof(log_Data_UInt32t),
"DU32", "QBI", "TimeUS,Id,Value" },
2013-04-19 20:51:09 -03:00
{ LOG_DATA_FLOAT_MSG, sizeof(log_Data_Float),
"DFLT", "QBf", "TimeUS,Id,Value" },
2013-04-19 20:51:09 -03:00
{ LOG_ERROR_MSG, sizeof(log_Error),
"ERR", "QBB", "TimeUS,Subsys,ECode" },
2013-04-19 20:51:09 -03:00
};
2013-04-15 09:54:29 -03:00
2014-08-01 02:46:28 -03:00
#if CLI_ENABLED == ENABLED
// Read the DataFlash log memory
2013-04-17 08:34:42 -03:00
static void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page)
{
cliSerial->printf_P(PSTR("\n" FIRMWARE_STRING
"\nFree RAM: %u\n"
"\nFrame: " FRAME_CONFIG_STRING "\n"),
2013-12-28 01:02:32 -04:00
(unsigned) hal.util->available_memory());
2012-08-21 23:19:50 -03:00
2013-02-22 19:15:01 -04:00
cliSerial->println_P(PSTR(HAL_BOARD_NAME));
2012-08-21 23:19:50 -03:00
DataFlash.LogReadProcess(log_num, start_page, end_page,
2013-04-20 02:18:22 -03:00
print_flight_mode,
cliSerial);
}
2014-08-01 02:46:28 -03:00
#endif // CLI_ENABLED
2013-04-19 20:51:09 -03:00
// start a new log
static void start_logging()
{
2014-01-07 09:37:39 -04:00
if (g.log_bitmask != 0) {
if (!ap.logging_started) {
ap.logging_started = true;
in_mavlink_delay = true;
2014-01-07 09:37:39 -04:00
DataFlash.StartNewLog();
in_mavlink_delay = false;
2014-01-07 09:37:39 -04:00
DataFlash.Log_Write_Message_P(PSTR(FIRMWARE_STRING));
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
DataFlash.Log_Write_Message_P(PSTR("PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION));
#endif
2014-01-07 09:37:39 -04:00
// write system identifier as well if available
char sysid[40];
if (hal.util->get_system_id(sysid)) {
DataFlash.Log_Write_Message(sysid);
}
DataFlash.Log_Write_Message_P(PSTR("Frame: " FRAME_CONFIG_STRING));
2014-01-07 09:37:39 -04:00
// log the flight mode
DataFlash.Log_Write_Mode(control_mode);
2013-11-25 21:00:45 -04:00
}
2014-01-07 09:37:39 -04:00
// enable writes
DataFlash.EnableWrites(true);
}
}
#else // LOGGING_ENABLED
2013-01-26 04:05:38 -04:00
static void Log_Write_Startup() {}
static void Log_Write_EntireMission() {}
2014-02-02 03:58:36 -04:00
#if AUTOTUNE_ENABLED == ENABLED
static void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float rate_target, float rate_min, float rate_max, float new_gain_rp, float new_gain_rd, float new_gain_sp) {}
static void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds) {}
#endif
2013-01-26 04:05:38 -04:00
static void Log_Write_Current() {}
static void Log_Write_Attitude() {}
static void Log_Write_Rate() {}
static void Log_Write_MotBatt() {}
2013-01-26 04:05:38 -04:00
static void Log_Write_Data(uint8_t id, int16_t value){}
static void Log_Write_Data(uint8_t id, uint16_t value){}
static void Log_Write_Data(uint8_t id, int32_t value){}
static void Log_Write_Data(uint8_t id, uint32_t value){}
static void Log_Write_Data(uint8_t id, float value){}
static void Log_Write_Event(uint8_t id){}
static void Log_Write_Optflow() {}
static void Log_Write_Nav_Tuning() {}
static void Log_Write_Control_Tuning() {}
static void Log_Write_Performance() {}
static void Log_Write_Cmd(const AP_Mission::Mission_Command &cmd) {}
2013-01-26 04:05:38 -04:00
static void Log_Write_Error(uint8_t sub_system, uint8_t error_code) {}
static void Log_Write_Baro(void) {}
2012-08-21 23:19:50 -03:00
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) {
return 0;
}
#endif // LOGGING_DISABLED