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
|
|
|
|
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-07-08 01:28:19 -03:00
|
|
|
#if CLI_ENABLED == ENABLED
|
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
|
2015-10-25 14:03:46 -03:00
|
|
|
static const struct Menu::command log_menu_commands[] = {
|
2015-05-29 23:12:49 -03:00
|
|
|
{"dump", MENU_FUNC(dump_log)},
|
|
|
|
{"erase", MENU_FUNC(erase_logs)},
|
|
|
|
{"enable", MENU_FUNC(select_logs)},
|
|
|
|
{"disable", MENU_FUNC(select_logs)}
|
2010-12-19 12:40:33 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
// A Macro to create the Menu
|
2015-05-29 23:12:49 -03:00
|
|
|
MENU2(log_menu, "Log", log_menu_commands, FUNCTOR_BIND(&copter, &Copter::print_log_menu, bool));
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
bool Copter::print_log_menu(void)
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
2015-10-25 17:10:41 -03:00
|
|
|
cliSerial->printf("logs enabled: ");
|
2012-08-21 23:19:50 -03:00
|
|
|
|
|
|
|
if (0 == g.log_bitmask) {
|
2015-10-25 17:10:41 -03:00
|
|
|
cliSerial->printf("none");
|
2012-08-21 23:19:50 -03:00
|
|
|
}else{
|
2015-10-25 17:10:41 -03:00
|
|
|
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST) cliSerial->printf(" ATTITUDE_FAST");
|
|
|
|
if (g.log_bitmask & MASK_LOG_ATTITUDE_MED) cliSerial->printf(" ATTITUDE_MED");
|
|
|
|
if (g.log_bitmask & MASK_LOG_GPS) cliSerial->printf(" GPS");
|
|
|
|
if (g.log_bitmask & MASK_LOG_PM) cliSerial->printf(" PM");
|
|
|
|
if (g.log_bitmask & MASK_LOG_CTUN) cliSerial->printf(" CTUN");
|
|
|
|
if (g.log_bitmask & MASK_LOG_NTUN) cliSerial->printf(" NTUN");
|
|
|
|
if (g.log_bitmask & MASK_LOG_RCIN) cliSerial->printf(" RCIN");
|
|
|
|
if (g.log_bitmask & MASK_LOG_IMU) cliSerial->printf(" IMU");
|
|
|
|
if (g.log_bitmask & MASK_LOG_CMD) cliSerial->printf(" CMD");
|
|
|
|
if (g.log_bitmask & MASK_LOG_CURRENT) cliSerial->printf(" CURRENT");
|
|
|
|
if (g.log_bitmask & MASK_LOG_RCOUT) cliSerial->printf(" RCOUT");
|
|
|
|
if (g.log_bitmask & MASK_LOG_OPTFLOW) cliSerial->printf(" OPTFLOW");
|
|
|
|
if (g.log_bitmask & MASK_LOG_COMPASS) cliSerial->printf(" COMPASS");
|
|
|
|
if (g.log_bitmask & MASK_LOG_CAMERA) cliSerial->printf(" CAMERA");
|
|
|
|
if (g.log_bitmask & MASK_LOG_PID) cliSerial->printf(" PID");
|
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
|
2015-05-29 23:12:49 -03:00
|
|
|
int8_t Copter::dump_log(uint8_t argc, const Menu::arg *argv)
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
2015-05-29 23:12:49 -03:00
|
|
|
int16_t dump_log_num;
|
2013-02-22 19:15:01 -04:00
|
|
|
uint16_t dump_log_start;
|
|
|
|
uint16_t dump_log_end;
|
2012-08-21 23:19:50 -03:00
|
|
|
|
|
|
|
// check that the requested log number can be read
|
2015-05-29 23:12:49 -03:00
|
|
|
dump_log_num = argv[1].i;
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
if (dump_log_num == -2) {
|
2013-02-22 19:15:01 -04:00
|
|
|
DataFlash.DumpPageInfo(cliSerial);
|
2012-08-21 23:19:50 -03:00
|
|
|
return(-1);
|
2015-05-29 23:12:49 -03:00
|
|
|
} else if (dump_log_num <= 0) {
|
2015-10-25 17:10:41 -03:00
|
|
|
cliSerial->printf("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);
|
2015-10-20 07:36:37 -03:00
|
|
|
} else if ((argc != 2) || ((uint16_t)dump_log_num > DataFlash.get_num_logs())) {
|
2015-10-25 17:10:41 -03:00
|
|
|
cliSerial->printf("bad log number\n");
|
2012-08-21 23:19:50 -03:00
|
|
|
return(-1);
|
|
|
|
}
|
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
DataFlash.get_log_boundaries(dump_log_num, dump_log_start, dump_log_end);
|
|
|
|
Log_Read((uint16_t)dump_log_num, 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
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
int8_t Copter::erase_logs(uint8_t argc, const Menu::arg *argv)
|
2011-12-17 19:19:41 -04:00
|
|
|
{
|
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
|
|
|
}
|
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
int8_t Copter::select_logs(uint8_t argc, const Menu::arg *argv)
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
2012-08-21 23:19:50 -03:00
|
|
|
uint16_t bits;
|
|
|
|
|
|
|
|
if (argc != 2) {
|
2015-10-25 17:10:41 -03:00
|
|
|
cliSerial->printf("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.
|
|
|
|
//
|
2015-10-25 13:22:16 -03:00
|
|
|
if (!strcasecmp(argv[1].str, "all")) {
|
2012-08-21 23:19:50 -03:00
|
|
|
bits = ~0;
|
|
|
|
} else {
|
2015-10-25 13:22:16 -03:00
|
|
|
#define TARG(_s) if (!strcasecmp(argv[1].str, # _s)) bits |= MASK_LOG_ ## _s
|
2012-08-21 23:19:50 -03:00
|
|
|
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);
|
2015-05-27 01:32:05 -03:00
|
|
|
TARG(PID);
|
2012-08-21 23:19:50 -03:00
|
|
|
#undef TARG
|
|
|
|
}
|
|
|
|
|
2015-10-25 13:22:16 -03:00
|
|
|
if (!strcasecmp(argv[0].str, "enable")) {
|
2012-08-21 23:19:50 -03:00
|
|
|
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
|
|
|
}
|
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
int8_t Copter::process_logs(uint8_t argc, const Menu::arg *argv)
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
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
|
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::do_erase_logs(void)
|
2014-07-08 01:28:19 -03:00
|
|
|
{
|
2015-10-24 19:36:35 -03:00
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL, "Erasing logs\n");
|
2014-07-08 01:28:19 -03:00
|
|
|
DataFlash.EraseAll();
|
2015-10-24 19:36:35 -03:00
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL, "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-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-04-30 02:57:00 -03:00
|
|
|
time_us : hal.scheduler->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-04-30 02:57:00 -03:00
|
|
|
time_us : hal.scheduler->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
|
|
|
{
|
2015-05-23 14:51:52 -03:00
|
|
|
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();
|
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-04-30 02:57:00 -03:00
|
|
|
time_us : hal.scheduler->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
|
|
|
{
|
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),
|
2015-04-30 02:57:00 -03:00
|
|
|
time_us : hal.scheduler->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;
|
2014-01-13 08:31:43 -04:00
|
|
|
int16_t throttle_in;
|
|
|
|
int16_t angle_boost;
|
2015-05-23 14:51:52 -03:00
|
|
|
float throttle_out;
|
2014-01-13 08:31:43 -04:00
|
|
|
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
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::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),
|
2015-04-30 02:57:00 -03:00
|
|
|
time_us : hal.scheduler->micros64(),
|
2015-05-11 23:24:13 -03:00
|
|
|
throttle_in : channel_throttle->control_in,
|
2014-02-03 03:23:13 -04:00
|
|
|
angle_boost : attitude_control.angle_boost(),
|
2015-05-23 14:51:52 -03:00
|
|
|
throttle_out : motors.get_throttle(),
|
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,
|
2015-04-05 04:23:35 -03:00
|
|
|
desired_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;
|
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-04-30 02:57:00 -03:00
|
|
|
time_us : hal.scheduler->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,
|
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
|
|
|
|
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
|
|
|
{
|
2014-12-18 12:55:49 -04:00
|
|
|
Vector3f targets = attitude_control.angle_ef_targets();
|
2015-07-18 01:24:45 -03:00
|
|
|
targets.z = wrap_360_cd_float(targets.z);
|
2014-12-18 12:55:49 -04:00
|
|
|
DataFlash.Log_Write_Attitude(ahrs, targets);
|
2014-01-03 20:51:57 -04:00
|
|
|
|
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);
|
2015-05-04 03:18:46 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
2014-01-03 20:51:57 -04:00
|
|
|
sitl.Log_Write_SIMSTATE(DataFlash);
|
|
|
|
#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:05:19 -03:00
|
|
|
struct PACKED log_Rate {
|
|
|
|
LOG_PACKET_HEADER;
|
2015-04-30 02:57:00 -03:00
|
|
|
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
|
|
|
};
|
|
|
|
|
2015-03-04 02:21:01 -04:00
|
|
|
// Write an rate packet
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::Log_Write_Rate()
|
2015-03-04 02:21:01 -04:00
|
|
|
{
|
|
|
|
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();
|
2015-03-04 02:21:01 -04:00
|
|
|
struct log_Rate pkt_rate = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_RATE_MSG),
|
2015-04-30 02:57:00 -03:00
|
|
|
time_us : hal.scheduler->micros64(),
|
2015-03-04 02:21:01 -04:00
|
|
|
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(),
|
2015-03-04 02:21:01 -04:00
|
|
|
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(),
|
2015-03-04 02:21:01 -04:00
|
|
|
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()
|
2015-03-04 02:21:01 -04:00
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt_rate, sizeof(pkt_rate));
|
|
|
|
}
|
|
|
|
|
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-04-30 02:57:00 -03:00
|
|
|
time_us : hal.scheduler->micros64(),
|
2015-03-04 02:21:01 -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())
|
|
|
|
};
|
|
|
|
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_Startup {
|
2013-01-26 04:05:38 -04:00
|
|
|
LOG_PACKET_HEADER;
|
2015-04-30 02:57:00 -03:00
|
|
|
uint64_t time_us;
|
2013-01-26 04:05:38 -04:00
|
|
|
};
|
|
|
|
|
2013-04-20 02:18:22 -03:00
|
|
|
// Write Startup packet
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::Log_Write_Startup()
|
2011-06-16 14:03:26 -03:00
|
|
|
{
|
2013-01-26 04:05:38 -04:00
|
|
|
struct log_Startup pkt = {
|
2015-04-30 02:57:00 -03:00
|
|
|
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));
|
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;
|
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-04-30 02:57:00 -03:00
|
|
|
time_us : hal.scheduler->micros64(),
|
|
|
|
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-04-30 02:57:00 -03:00
|
|
|
time_us : hal.scheduler->micros64(),
|
2013-01-12 11:17:44 -04:00
|
|
|
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;
|
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-04-30 02:57:00 -03:00
|
|
|
time_us : hal.scheduler->micros64(),
|
2013-01-12 11:17:44 -04:00
|
|
|
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;
|
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-04-30 02:57:00 -03:00
|
|
|
time_us : hal.scheduler->micros64(),
|
2013-01-12 11:17:44 -04:00
|
|
|
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;
|
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-04-30 02:57:00 -03:00
|
|
|
time_us : hal.scheduler->micros64(),
|
2013-01-12 11:17:44 -04:00
|
|
|
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;
|
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-04-30 02:57:00 -03:00
|
|
|
time_us : hal.scheduler->micros64(),
|
2013-01-12 11:17:44 -04:00
|
|
|
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;
|
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-04-30 02:57:00 -03:00
|
|
|
time_us : hal.scheduler->micros64(),
|
2013-01-12 11:17:44 -04:00
|
|
|
sub_system : sub_system,
|
|
|
|
error_code : error_code,
|
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&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
|
|
|
{
|
|
|
|
DataFlash.Log_Write_Baro(barometer);
|
|
|
|
}
|
|
|
|
|
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-04-30 02:57:00 -03:00
|
|
|
time_us : hal.scheduler->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;
|
|
|
|
if (ahrs.get_NavEKF_const().getOriginLLH(ekf_orig)) {
|
|
|
|
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));
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-06-18 18:09:39 -03:00
|
|
|
struct PACKED log_Heli {
|
|
|
|
LOG_PACKET_HEADER;
|
|
|
|
uint64_t time_us;
|
|
|
|
int16_t desired_rotor_speed;
|
2015-08-11 15:32:09 -03:00
|
|
|
int16_t 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),
|
|
|
|
time_us : hal.scheduler->micros64(),
|
|
|
|
desired_rotor_speed : motors.get_desired_rotor_speed(),
|
2015-08-11 15:32:09 -03:00
|
|
|
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;
|
|
|
|
float bf_angle_x;
|
|
|
|
float bf_angle_y;
|
|
|
|
float ef_angle_x;
|
|
|
|
float ef_angle_y;
|
|
|
|
float pos_x;
|
|
|
|
float pos_y;
|
|
|
|
};
|
|
|
|
|
|
|
|
// Write an optical flow packet
|
|
|
|
void Copter::Log_Write_Precland()
|
|
|
|
{
|
|
|
|
#if PRECISION_LANDING == ENABLED
|
|
|
|
// exit immediately if not enabled
|
|
|
|
if (!precland.enabled()) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
const Vector2f &bf_angle = precland.last_bf_angle_to_target();
|
|
|
|
const Vector2f &ef_angle = precland.last_ef_angle_to_target();
|
|
|
|
const Vector3f &target_pos_ofs = precland.last_target_pos_offset();
|
|
|
|
struct log_Precland pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_PRECLAND_MSG),
|
|
|
|
time_us : hal.scheduler->micros64(),
|
|
|
|
healthy : precland.healthy(),
|
|
|
|
bf_angle_x : degrees(bf_angle.x),
|
|
|
|
bf_angle_y : degrees(bf_angle.y),
|
|
|
|
ef_angle_x : degrees(ef_angle.x),
|
|
|
|
ef_angle_y : degrees(ef_angle.y),
|
|
|
|
pos_x : target_pos_ofs.x,
|
|
|
|
pos_y : target_pos_ofs.y
|
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
#endif // PRECISION_LANDING == ENABLED
|
|
|
|
}
|
|
|
|
|
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),
|
2015-04-30 02:57:00 -03:00
|
|
|
"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),
|
2015-04-30 02:57:00 -03:00
|
|
|
"PM", "QHHIhBH", "TimeUS,NLon,NLoop,MaxT,PMT,I2CErr,INSErr" },
|
2015-03-04 02:21:01 -04:00
|
|
|
{ LOG_RATE_MSG, sizeof(log_Rate),
|
2015-04-30 02:57:00 -03:00
|
|
|
"RATE", "Qffffffffffff", "TimeUS,RDes,R,ROut,PDes,P,POut,YDes,Y,YOut,ADes,A,AOut" },
|
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_STARTUP_MSG, sizeof(log_Startup),
|
2015-04-30 02:57:00 -03:00
|
|
|
"STRT", "Q", "TimeUS" },
|
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),
|
|
|
|
"HELI", "Qhh", "TimeUS,DRRPM,ERRPM" },
|
2015-08-28 05:14:02 -03:00
|
|
|
{ LOG_PRECLAND_MSG, sizeof(log_Precland),
|
|
|
|
"PL", "QBffffff", "TimeUS,Heal,bX,bY,eX,eY,pX,pY" },
|
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
|
2011-11-25 10:13:32 -04:00
|
|
|
// Read the DataFlash log memory
|
2015-10-20 07:36:37 -03:00
|
|
|
void Copter::Log_Read(uint16_t list_entry, uint16_t start_page, uint16_t end_page)
|
2011-11-25 10:13:32 -04:00
|
|
|
{
|
2015-10-25 17:10:41 -03:00
|
|
|
cliSerial->printf("\n" FIRMWARE_STRING
|
2014-09-27 02:35:02 -03:00
|
|
|
"\nFree RAM: %u\n"
|
2015-10-24 18:45:41 -03:00
|
|
|
"\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
|
|
|
|
2015-10-25 16:50:51 -03:00
|
|
|
cliSerial->println(HAL_BOARD_NAME);
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2015-10-20 07:36:37 -03:00
|
|
|
DataFlash.LogReadProcess(list_entry, start_page, end_page,
|
2015-05-29 23:12:49 -03:00
|
|
|
FUNCTOR_BIND_MEMBER(&Copter::print_flight_mode, void, AP_HAL::BetterStream *, uint8_t),
|
2013-04-20 02:18:22 -03:00
|
|
|
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
|
|
|
|
2015-08-06 09:18:39 -03:00
|
|
|
void Copter::Log_Write_Vehicle_Startup_Messages()
|
|
|
|
{
|
|
|
|
// only 200(?) bytes are guaranteed by DataFlash
|
2015-10-26 08:23:55 -03:00
|
|
|
DataFlash.Log_Write_Message("Frame: " FRAME_CONFIG_STRING);
|
2015-08-06 09:18:39 -03:00
|
|
|
DataFlash.Log_Write_Mode(control_mode);
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2013-04-19 20:51:09 -03:00
|
|
|
// start a new log
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::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;
|
2015-08-06 09:18:39 -03:00
|
|
|
DataFlash.set_mission(&mission);
|
|
|
|
DataFlash.setVehicle_Startup_Log_Writer(FUNCTOR_BIND(&copter, &Copter::Log_Write_Vehicle_Startup_Messages, void));
|
2014-01-07 09:37:39 -04:00
|
|
|
DataFlash.StartNewLog();
|
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
|
|
|
}
|
|
|
|
|
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));
|
2015-05-29 23:12:49 -03:00
|
|
|
if (!DataFlash.CardInserted()) {
|
2015-10-24 19:36:35 -03:00
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL, "No dataflash inserted");
|
2015-05-29 23:12:49 -03:00
|
|
|
g.log_bitmask.set(0);
|
2015-08-08 03:14:02 -03:00
|
|
|
} else if (DataFlash.NeedPrep()) {
|
2015-10-24 19:36:35 -03:00
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL, "Preparing log system");
|
2015-08-08 03:14:02 -03:00
|
|
|
DataFlash.Prep();
|
2015-10-24 19:36:35 -03:00
|
|
|
gcs_send_text(MAV_SEVERITY_CRITICAL, "Prepared log system");
|
2015-08-08 03:14:02 -03:00
|
|
|
for (uint8_t i=0; i<num_gcs; i++) {
|
|
|
|
gcs[i].reset_cli_timeout();
|
|
|
|
}
|
2015-05-29 23:12:49 -03:00
|
|
|
}
|
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
|
|
|
|
|
|
|
|
#if CLI_ENABLED == ENABLED
|
|
|
|
bool Copter::print_log_menu(void) { return true; }
|
|
|
|
int8_t Copter::dump_log(uint8_t argc, const Menu::arg *argv) { return 0; }
|
|
|
|
int8_t Copter::erase_logs(uint8_t argc, const Menu::arg *argv) { return 0; }
|
|
|
|
int8_t Copter::select_logs(uint8_t argc, const Menu::arg *argv) { return 0; }
|
|
|
|
int8_t Copter::process_logs(uint8_t argc, const Menu::arg *argv) { return 0; }
|
|
|
|
void Copter::Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page) {}
|
|
|
|
#endif // CLI_ENABLED == ENABLED
|
|
|
|
|
|
|
|
void Copter::do_erase_logs(void) {}
|
|
|
|
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) {}
|
|
|
|
void Copter::Log_Write_Rate() {}
|
|
|
|
void Copter::Log_Write_MotBatt() {}
|
|
|
|
void Copter::Log_Write_Startup() {}
|
|
|
|
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() {}
|
|
|
|
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
void Copter::Log_Write_Heli() {}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#if OPTFLOW == ENABLED
|
|
|
|
void Copter::Log_Write_Optflow() {}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
void Copter::start_logging() {}
|
|
|
|
void Copter::log_init(void) {}
|
|
|
|
|
|
|
|
#endif // LOGGING_ENABLED
|