2011-03-19 07:20:11 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2010-12-19 12:40:33 -04:00
|
|
|
|
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-07-08 01:28:19 -03:00
|
|
|
#if CLI_ENABLED == ENABLED
|
2010-12-19 12:40:33 -04:00
|
|
|
// These are function definitions so the Menu can be constructed before the functions
|
|
|
|
// are defined below. Order matters to the compiler.
|
2011-07-17 07:30:21 -03:00
|
|
|
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);
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
// 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}
|
2010-12-19 12:40:33 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
// A Macro to create the Menu
|
|
|
|
MENU2(log_menu, "Log", log_menu_commands, print_log_menu);
|
|
|
|
|
|
|
|
static bool
|
|
|
|
print_log_menu(void)
|
|
|
|
{
|
2012-11-21 02:08:03 -04:00
|
|
|
cliSerial->printf_P(PSTR("logs enabled: "));
|
2012-08-21 23:19:50 -03:00
|
|
|
|
|
|
|
if (0 == g.log_bitmask) {
|
2012-11-21 02:08:03 -04:00
|
|
|
cliSerial->printf_P(PSTR("none"));
|
2012-08-21 23:19:50 -03:00
|
|
|
}else{
|
2012-11-21 02:08:03 -04:00
|
|
|
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"));
|
2013-01-12 11:17:44 -04:00
|
|
|
if (g.log_bitmask & MASK_LOG_IMU) cliSerial->printf_P(PSTR(" IMU"));
|
2012-11-21 02:08:03 -04:00
|
|
|
if (g.log_bitmask & MASK_LOG_CMD) cliSerial->printf_P(PSTR(" CMD"));
|
2013-01-26 04:20:41 -04:00
|
|
|
if (g.log_bitmask & MASK_LOG_CURRENT) cliSerial->printf_P(PSTR(" CURRENT"));
|
2013-11-27 07:17:16 -04:00
|
|
|
if (g.log_bitmask & MASK_LOG_RCOUT) cliSerial->printf_P(PSTR(" RCOUT"));
|
2012-11-21 02:08:03 -04:00
|
|
|
if (g.log_bitmask & MASK_LOG_OPTFLOW) cliSerial->printf_P(PSTR(" OPTFLOW"));
|
2013-02-09 02:24:02 -04:00
|
|
|
if (g.log_bitmask & MASK_LOG_COMPASS) cliSerial->printf_P(PSTR(" COMPASS"));
|
2012-12-06 11:57:08 -04:00
|
|
|
if (g.log_bitmask & MASK_LOG_CAMERA) cliSerial->printf_P(PSTR(" CAMERA"));
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
|
|
|
|
2012-11-21 02:08:03 -04: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);
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
|
|
|
|
2014-08-01 02:57:28 -03:00
|
|
|
#if CLI_ENABLED == ENABLED
|
2010-12-19 12:40:33 -04:00
|
|
|
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) {
|
2012-11-21 02:08:03 -04:00
|
|
|
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);
|
2013-07-07 22:24:01 -03:00
|
|
|
} else if ((argc != 2) || ((uint16_t)dump_log <= (last_log_num - DataFlash.get_num_logs())) || (static_cast<uint16_t>(dump_log) > last_log_num)) {
|
2012-11-21 02:08:03 -04:00
|
|
|
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);
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
2014-08-01 02:57:28 -03:00
|
|
|
#endif
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2011-12-17 19:19:41 -04:00
|
|
|
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;
|
2011-11-25 10:13:32 -04:00
|
|
|
return 0;
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
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) {
|
2012-11-21 02:08:03 -04:00
|
|
|
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);
|
2013-01-12 11:17:44 -04:00
|
|
|
TARG(IMU);
|
2012-08-21 23:19:50 -03:00
|
|
|
TARG(CMD);
|
2013-01-26 04:20:41 -04:00
|
|
|
TARG(CURRENT);
|
2013-11-27 07:17:16 -04:00
|
|
|
TARG(RCOUT);
|
2012-08-21 23:19:50 -03:00
|
|
|
TARG(OPTFLOW);
|
2013-02-09 02:24:02 -04:00
|
|
|
TARG(COMPASS);
|
2012-12-06 11:57:08 -04:00
|
|
|
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);
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
|
|
|
|
2011-07-17 07:32:00 -03:00
|
|
|
static int8_t
|
2010-12-19 12:40:33 -04:00
|
|
|
process_logs(uint8_t argc, const Menu::arg *argv)
|
|
|
|
{
|
2012-08-21 23:19:50 -03:00
|
|
|
log_menu.run();
|
|
|
|
return 0;
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
2014-07-08 01:28:19 -03:00
|
|
|
#endif // CLI_ENABLED
|
|
|
|
|
|
|
|
static void do_erase_logs(void)
|
|
|
|
{
|
2015-01-14 22:37:43 -04:00
|
|
|
gcs_send_text_P(SEVERITY_HIGH, PSTR("Erasing logs\n"));
|
2014-07-08 01:28:19 -03:00
|
|
|
DataFlash.EraseAll();
|
2015-01-14 22:37:43 -04:00
|
|
|
gcs_send_text_P(SEVERITY_HIGH, PSTR("Log erase complete\n"));
|
2014-07-08 01:28:19 -03:00
|
|
|
}
|
2010-12-19 12:40:33 -04:00
|
|
|
|
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-03-04 02:22:05 -04:00
|
|
|
uint32_t time_ms;
|
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-03-04 02:22:05 -04:00
|
|
|
float rate_target; // target achieved rotation rate
|
2013-09-03 06:31:06 -03:00
|
|
|
float rate_min; // maximum achieved rotation rate
|
|
|
|
float rate_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
|
2013-09-03 06:31:06 -03:00
|
|
|
};
|
|
|
|
|
2014-07-09 16:14:34 -03:00
|
|
|
// Write an Autotune data packet
|
2015-03-04 02:22:05 -04:00
|
|
|
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)
|
2013-09-03 06:31:06 -03:00
|
|
|
{
|
|
|
|
struct log_AutoTune pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_AUTOTUNE_MSG),
|
2015-03-04 02:22:05 -04:00
|
|
|
time_ms : hal.scheduler->millis(),
|
2013-09-03 06:31:06 -03:00
|
|
|
axis : axis,
|
|
|
|
tune_step : tune_step,
|
2015-03-04 02:22:05 -04:00
|
|
|
rate_target : rate_target,
|
2013-09-03 06:31:06 -03:00
|
|
|
rate_min : rate_min,
|
|
|
|
rate_max : rate_max,
|
2015-03-04 02:22:05 -04:00
|
|
|
new_gain_rp : new_gain_rp,
|
|
|
|
new_gain_rd : new_gain_rd,
|
|
|
|
new_gain_sp : new_gain_sp
|
2013-09-03 06:31:06 -03:00
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
}
|
|
|
|
|
|
|
|
struct PACKED log_AutoTuneDetails {
|
|
|
|
LOG_PACKET_HEADER;
|
2015-03-04 02:22:05 -04:00
|
|
|
uint32_t time_ms;
|
|
|
|
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-03-04 02:22:05 -04:00
|
|
|
static void 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-03-04 02:22:05 -04:00
|
|
|
time_ms : hal.scheduler->millis(),
|
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
|
2011-07-17 07:32:00 -03:00
|
|
|
static void Log_Write_Current()
|
2011-01-16 23:44:12 -04:00
|
|
|
{
|
2014-12-18 17:35:23 -04:00
|
|
|
DataFlash.Log_Write_Current(battery, g.rc_3.servo_out);
|
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;
|
2014-07-11 23:32:40 -03:00
|
|
|
uint32_t time_ms;
|
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
|
2011-07-21 20:14:53 -03:00
|
|
|
static void Log_Write_Optflow()
|
|
|
|
{
|
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),
|
2014-07-11 23:32:40 -03:00
|
|
|
time_ms : hal.scheduler->millis(),
|
|
|
|
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;
|
2014-01-13 09:00:11 -04:00
|
|
|
uint32_t time_ms;
|
|
|
|
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
|
2011-07-17 07:32:00 -03:00
|
|
|
static void Log_Write_Nav_Tuning()
|
2011-05-23 02:53:00 -03:00
|
|
|
{
|
2014-01-21 22:42:16 -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),
|
2014-01-13 09:00:11 -04:00
|
|
|
time_ms : hal.scheduler->millis(),
|
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;
|
2014-01-13 08:31:43 -04:00
|
|
|
uint32_t time_ms;
|
|
|
|
int16_t throttle_in;
|
|
|
|
int16_t angle_boost;
|
|
|
|
int16_t 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-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
|
2011-07-17 07:32:00 -03:00
|
|
|
static void Log_Write_Control_Tuning()
|
2011-04-21 02:15:45 -03:00
|
|
|
{
|
2013-01-12 11:17:44 -04:00
|
|
|
struct log_Control_Tuning pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_CONTROL_TUNING_MSG),
|
2014-01-13 08:31:43 -04:00
|
|
|
time_ms : hal.scheduler->millis(),
|
2013-01-12 11:17:44 -04:00
|
|
|
throttle_in : g.rc_3.control_in,
|
2014-02-03 03:23:13 -04:00
|
|
|
angle_boost : attitude_control.angle_boost(),
|
2013-01-12 11:17:44 -04:00
|
|
|
throttle_out : g.rc_3.servo_out,
|
2014-01-10 03:20:31 -04:00
|
|
|
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,
|
|
|
|
desired_sonar_alt : (int16_t)target_sonar_alt,
|
|
|
|
sonar_alt : sonar_alt,
|
|
|
|
desired_climb_rate : desired_climb_rate,
|
|
|
|
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;
|
|
|
|
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;
|
2013-01-12 03:15:23 -04:00
|
|
|
};
|
|
|
|
|
2013-04-20 02:18:22 -03:00
|
|
|
// Write a performance monitoring packet
|
2011-07-17 07:32:00 -03:00
|
|
|
static void 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),
|
|
|
|
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,
|
2013-11-17 23:16:21 -04:00
|
|
|
i2c_lockup_count : hal.i2c->lockup_count(),
|
2015-03-12 10:24:40 -03:00
|
|
|
ins_error_count : ins.error_count()
|
2013-01-12 03:15:23 -04:00
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
2011-05-09 01:16:58 -03:00
|
|
|
}
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2014-03-16 05:41:59 -03:00
|
|
|
// 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
|
2011-07-17 07:32:00 -03:00
|
|
|
static void Log_Write_Attitude()
|
2011-05-09 01:16:58 -03:00
|
|
|
{
|
2014-12-18 12:55:49 -04:00
|
|
|
Vector3f targets = attitude_control.angle_ef_targets();
|
|
|
|
DataFlash.Log_Write_Attitude(ahrs, targets);
|
2014-01-03 20:51:57 -04:00
|
|
|
|
|
|
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
2014-12-30 13:31:16 -04:00
|
|
|
#if OPTFLOW == ENABLED
|
2014-12-23 16:40:31 -04:00
|
|
|
DataFlash.Log_Write_EKF(ahrs,optflow.enabled());
|
2014-12-30 13:31:16 -04:00
|
|
|
#else
|
|
|
|
DataFlash.Log_Write_EKF(ahrs,false);
|
|
|
|
#endif
|
2014-01-03 20:51:57 -04:00
|
|
|
DataFlash.Log_Write_AHRS2(ahrs);
|
|
|
|
#endif
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
|
|
|
sitl.Log_Write_SIMSTATE(DataFlash);
|
|
|
|
#endif
|
2011-05-09 01:16:58 -03:00
|
|
|
}
|
|
|
|
|
2015-03-18 09:05:19 -03:00
|
|
|
struct PACKED log_Rate {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint32_t time_ms;
|
|
|
|
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-03-04 02:21:01 -04:00
|
|
|
// Write an rate packet
|
|
|
|
static void Log_Write_Rate()
|
|
|
|
{
|
|
|
|
const Vector3f &rate_targets = attitude_control.rate_bf_targets();
|
|
|
|
struct log_Rate pkt_rate = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_RATE_MSG),
|
|
|
|
time_ms : hal.scheduler->millis(),
|
|
|
|
control_roll : (float)rate_targets.x,
|
|
|
|
roll : (float)(ahrs.get_gyro().x * AC_ATTITUDE_CONTROL_DEGX100),
|
|
|
|
roll_out : (float)(motors.get_roll()),
|
|
|
|
control_pitch : (float)rate_targets.y,
|
|
|
|
pitch : (float)(ahrs.get_gyro().y * AC_ATTITUDE_CONTROL_DEGX100),
|
|
|
|
pitch_out : (float)(motors.get_pitch()),
|
|
|
|
control_yaw : (float)rate_targets.z,
|
|
|
|
yaw : (float)(ahrs.get_gyro().z * AC_ATTITUDE_CONTROL_DEGX100),
|
|
|
|
yaw_out : (float)(motors.get_yaw())
|
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt_rate, sizeof(pkt_rate));
|
|
|
|
}
|
|
|
|
|
2015-03-18 09:08:30 -03:00
|
|
|
struct PACKED log_MotBatt {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint32_t time_ms;
|
|
|
|
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-03-18 09:08:30 -03:00
|
|
|
static void Log_Write_MotBatt()
|
2015-03-04 02:21:01 -04:00
|
|
|
{
|
2015-03-18 09:08:30 -03:00
|
|
|
struct log_MotBatt pkt_mot = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_MOTBATT_MSG),
|
2015-03-04 02:21:01 -04:00
|
|
|
time_ms : hal.scheduler->millis(),
|
|
|
|
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;
|
|
|
|
};
|
|
|
|
|
2013-04-20 02:18:22 -03:00
|
|
|
// Write Startup packet
|
2011-07-17 07:32:00 -03:00
|
|
|
static void Log_Write_Startup()
|
2011-06-16 14:03:26 -03:00
|
|
|
{
|
2013-01-26 04:05:38 -04:00
|
|
|
struct log_Startup pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_STARTUP_MSG)
|
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
2011-06-16 14:03:26 -03:00
|
|
|
}
|
|
|
|
|
2013-04-19 20:51:09 -03:00
|
|
|
struct PACKED log_Event {
|
2013-01-12 11:17:44 -04:00
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint8_t id;
|
|
|
|
};
|
2012-11-10 02:04:23 -04:00
|
|
|
|
2013-01-12 11:17:44 -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)) {
|
2013-01-12 11:17:44 -04:00
|
|
|
struct log_Event pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_EVENT_MSG),
|
|
|
|
id : id
|
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&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;
|
|
|
|
uint8_t id;
|
|
|
|
int16_t data_value;
|
|
|
|
};
|
|
|
|
|
|
|
|
// Write an int16_t data packet
|
2015-02-17 20:13:48 -04:00
|
|
|
UNUSED_FUNCTION
|
2013-01-12 11:17:44 -04:00
|
|
|
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)) {
|
2013-01-12 11:17:44 -04:00
|
|
|
struct log_Data_Int16t pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_DATA_INT16_MSG),
|
|
|
|
id : id,
|
|
|
|
data_value : value
|
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&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;
|
|
|
|
uint8_t id;
|
|
|
|
uint16_t data_value;
|
|
|
|
};
|
|
|
|
|
|
|
|
// Write an uint16_t data packet
|
2015-02-17 20:13:48 -04:00
|
|
|
UNUSED_FUNCTION
|
2013-01-12 11:17:44 -04:00
|
|
|
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)) {
|
2013-01-12 11:17:44 -04:00
|
|
|
struct log_Data_UInt16t pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_DATA_UINT16_MSG),
|
|
|
|
id : id,
|
|
|
|
data_value : value
|
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&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;
|
|
|
|
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)) {
|
2013-01-12 11:17:44 -04:00
|
|
|
struct log_Data_Int32t pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_DATA_INT32_MSG),
|
|
|
|
id : id,
|
|
|
|
data_value : value
|
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&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;
|
|
|
|
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
|
|
|
|
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)) {
|
2013-01-12 11:17:44 -04:00
|
|
|
struct log_Data_UInt32t pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_DATA_UINT32_MSG),
|
|
|
|
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 {
|
2013-01-12 11:17:44 -04:00
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
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
|
2013-01-12 11:17:44 -04:00
|
|
|
static void Log_Write_Data(uint8_t id, float value)
|
|
|
|
{
|
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),
|
|
|
|
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 {
|
2013-01-12 11:17:44 -04:00
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint8_t sub_system;
|
|
|
|
uint8_t error_code;
|
|
|
|
};
|
|
|
|
|
2013-04-20 02:18:22 -03:00
|
|
|
// Write an error packet
|
2012-12-29 23:08:25 -04:00
|
|
|
static void Log_Write_Error(uint8_t sub_system, uint8_t error_code)
|
|
|
|
{
|
2013-01-12 11:17:44 -04:00
|
|
|
struct log_Error pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_ERROR_MSG),
|
|
|
|
sub_system : sub_system,
|
|
|
|
error_code : error_code,
|
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
2012-12-29 23:08:25 -04:00
|
|
|
}
|
|
|
|
|
2014-02-18 16:38:20 -04:00
|
|
|
static void Log_Write_Baro(void)
|
|
|
|
{
|
|
|
|
DataFlash.Log_Write_Baro(barometer);
|
|
|
|
}
|
|
|
|
|
2013-04-19 20:51:09 -03:00
|
|
|
static const struct LogStructure log_structure[] PROGMEM = {
|
|
|
|
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-03-04 02:22:05 -04:00
|
|
|
"ATUN", "IBBffffff", "TimeMS,Axis,TuneStep,RateTarg,RateMin,RateMax,RP,RD,SP" },
|
2013-09-03 06:31:06 -03:00
|
|
|
{ LOG_AUTOTUNEDETAILS_MSG, sizeof(log_AutoTuneDetails),
|
2015-03-04 02:22:05 -04:00
|
|
|
"ATDE", "Iff", "TimeMS,Angle,Rate" },
|
2013-10-04 03:49:19 -03:00
|
|
|
#endif
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow),
|
2014-10-31 09:46:59 -03:00
|
|
|
"OF", "IBffff", "TimeMS,Qual,flowX,flowY,bodyX,bodyY" },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_NAV_TUNING_MSG, sizeof(log_Nav_Tuning),
|
2014-01-13 09:00:11 -04:00
|
|
|
"NTUN", "Iffffffffff", "TimeMS,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),
|
|
|
|
"CTUN", "Ihhhffecchh", "TimeMS,ThrIn,AngBst,ThrOut,DAlt,Alt,BarAlt,DSAlt,SAlt,DCRt,CRt" },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
2015-03-12 10:24:40 -03:00
|
|
|
"PM", "HHIhBH", "NLon,NLoop,MaxT,PMT,I2CErr,INSErr" },
|
2015-03-04 02:21:01 -04:00
|
|
|
{ LOG_RATE_MSG, sizeof(log_Rate),
|
|
|
|
"RATE", "Ifffffffff", "TimeMS,RllDes,Rll,RllOut,PitDes,Pit,PitOut,YawDes,Yaw,YawOut" },
|
2015-03-18 09:08:30 -03:00
|
|
|
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt),
|
|
|
|
"MOTB", "Iffff", "TimeMS,LiftMax,BatVolt,BatRes,ThLimit" },
|
2013-04-19 20:51:09 -03:00
|
|
|
{ LOG_STARTUP_MSG, sizeof(log_Startup),
|
|
|
|
"STRT", "", "" },
|
|
|
|
{ LOG_EVENT_MSG, sizeof(log_Event),
|
|
|
|
"EV", "B", "Id" },
|
|
|
|
{ LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t),
|
|
|
|
"D16", "Bh", "Id,Value" },
|
|
|
|
{ LOG_DATA_UINT16_MSG, sizeof(log_Data_UInt16t),
|
|
|
|
"DU16", "BH", "Id,Value" },
|
|
|
|
{ LOG_DATA_INT32_MSG, sizeof(log_Data_Int32t),
|
|
|
|
"D32", "Bi", "Id,Value" },
|
|
|
|
{ LOG_DATA_UINT32_MSG, sizeof(log_Data_UInt32t),
|
|
|
|
"DU32", "BI", "Id,Value" },
|
|
|
|
{ LOG_DATA_FLOAT_MSG, sizeof(log_Data_Float),
|
|
|
|
"DFLT", "Bf", "Id,Value" },
|
|
|
|
{ LOG_ERROR_MSG, sizeof(log_Error),
|
|
|
|
"ERR", "BB", "Subsys,ECode" },
|
|
|
|
};
|
2013-04-15 09:54:29 -03:00
|
|
|
|
2014-08-01 02:46:28 -03:00
|
|
|
#if CLI_ENABLED == ENABLED
|
2011-11-25 10:13:32 -04:00
|
|
|
// 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)
|
2011-11-25 10:13:32 -04:00
|
|
|
{
|
2013-11-08 07:29:29 -04:00
|
|
|
cliSerial->printf_P(PSTR("\n" FIRMWARE_STRING
|
2014-09-27 02:35:02 -03:00
|
|
|
"\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
|
|
|
|
2015-01-14 22:37:43 -04:00
|
|
|
DataFlash.LogReadProcess(log_num, start_page, end_page,
|
2013-04-20 02:18:22 -03:00
|
|
|
print_flight_mode,
|
|
|
|
cliSerial);
|
2011-11-25 10:13:32 -04:00
|
|
|
}
|
2014-08-01 02:46:28 -03:00
|
|
|
#endif // CLI_ENABLED
|
2011-06-16 14:03:26 -03:00
|
|
|
|
2013-04-19 20:51:09 -03:00
|
|
|
// start a new log
|
|
|
|
static void start_logging()
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
2014-01-07 09:37:39 -04:00
|
|
|
if (g.log_bitmask != 0) {
|
|
|
|
if (!ap.logging_started) {
|
|
|
|
ap.logging_started = true;
|
2014-01-13 23:37:48 -04:00
|
|
|
in_mavlink_delay = true;
|
2014-01-07 09:37:39 -04:00
|
|
|
DataFlash.StartNewLog();
|
2014-01-13 23:37:48 -04:00
|
|
|
in_mavlink_delay = false;
|
2014-01-07 09:37:39 -04:00
|
|
|
DataFlash.Log_Write_Message_P(PSTR(FIRMWARE_STRING));
|
|
|
|
|
2014-01-14 00:38:51 -04:00
|
|
|
#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);
|
|
|
|
}
|
2014-09-27 02:35:02 -03:00
|
|
|
DataFlash.Log_Write_Message_P(PSTR("Frame: " FRAME_CONFIG_STRING));
|
2014-01-07 09:37:39 -04:00
|
|
|
|
|
|
|
// log the flight mode
|
2014-12-22 16:11:31 -04:00
|
|
|
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);
|
2013-05-03 02:49:01 -03:00
|
|
|
}
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
|
|
|
|
2011-12-23 18:26:24 -04:00
|
|
|
#else // LOGGING_ENABLED
|
2011-12-20 01:04:51 -04:00
|
|
|
|
2013-01-26 04:05:38 -04:00
|
|
|
static void Log_Write_Startup() {}
|
2014-02-02 03:58:36 -04:00
|
|
|
#if AUTOTUNE_ENABLED == ENABLED
|
2015-03-04 02:22:05 -04:00
|
|
|
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) {}
|
2013-10-04 03:49:19 -03:00
|
|
|
#endif
|
2013-01-26 04:05:38 -04:00
|
|
|
static void Log_Write_Current() {}
|
|
|
|
static void Log_Write_Attitude() {}
|
2015-03-04 02:21:01 -04:00
|
|
|
static void Log_Write_Rate() {}
|
2015-03-18 09:08:30 -03:00
|
|
|
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() {}
|
2014-03-16 05:41:59 -03:00
|
|
|
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) {}
|
2014-04-29 20:48:50 -03:00
|
|
|
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;
|
|
|
|
}
|
2011-12-20 01:04:51 -04:00
|
|
|
|
2011-12-23 18:26:24 -04:00
|
|
|
#endif // LOGGING_DISABLED
|