ardupilot/ArduPlane/Log.cpp

562 lines
16 KiB
C++
Raw Normal View History

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2015-05-13 03:09:36 -03:00
#include "Plane.h"
#if LOGGING_ENABLED == ENABLED
#if CLI_ENABLED == ENABLED
// Code to Write and Read packets from DataFlash.log memory
// Code to interact with the user to dump or erase logs
// 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
static const struct Menu::command log_menu_commands[] PROGMEM = {
2015-05-13 03:09:36 -03:00
{"dump", MENU_FUNC(dump_log)},
{"erase", MENU_FUNC(erase_logs)},
{"enable", MENU_FUNC(select_logs)},
{"disable", MENU_FUNC(select_logs)}
};
// A Macro to create the Menu
MENU2(log_menu, "Log", log_menu_commands, FUNCTOR_BIND(&plane, &Plane::print_log_menu, bool));
2015-05-13 03:09:36 -03:00
bool Plane::print_log_menu(void)
{
2012-12-04 18:22:21 -04:00
cliSerial->println_P(PSTR("logs enabled: "));
2012-08-21 23:19:50 -03:00
if (0 == g.log_bitmask) {
2012-12-04 18:22:21 -04:00
cliSerial->println_P(PSTR("none"));
2012-08-21 23:19:50 -03:00
}else{
// 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
// the bit being set and print the name of the log option to suit.
2012-12-04 18:22:21 -04:00
#define PLOG(_s) if (g.log_bitmask & MASK_LOG_ ## _s) cliSerial->printf_P(PSTR(" %S"), PSTR(# _s))
2012-08-21 23:19:50 -03:00
PLOG(ATTITUDE_FAST);
PLOG(ATTITUDE_MED);
PLOG(GPS);
PLOG(PM);
PLOG(CTUN);
PLOG(NTUN);
PLOG(MODE);
PLOG(IMU);
2012-08-21 23:19:50 -03:00
PLOG(CMD);
PLOG(CURRENT);
2013-04-19 10:54:40 -03:00
PLOG(COMPASS);
PLOG(TECS);
PLOG(CAMERA);
2013-11-25 17:44:17 -04:00
PLOG(RC);
PLOG(SONAR);
2012-08-21 23:19:50 -03:00
#undef PLOG
}
cliSerial->println();
2012-08-21 23:19:50 -03:00
2013-04-17 08:34:56 -03:00
DataFlash.ListAvailableLogs(cliSerial);
2012-08-21 23:19:50 -03:00
return(true);
}
2015-05-13 03:09:36 -03:00
int8_t Plane::dump_log(uint8_t argc, const Menu::arg *argv)
{
2015-05-13 03:09:36 -03:00
int16_t dump_log_num;
2013-02-22 19:15:15 -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
2015-05-13 03:09:36 -03:00
dump_log_num = argv[1].i;
last_log_num = DataFlash.find_last_log();
2012-08-21 23:19:50 -03:00
2015-05-13 03:09:36 -03:00
if (dump_log_num == -2) {
2013-02-22 19:15:15 -04:00
DataFlash.DumpPageInfo(cliSerial);
2012-08-21 23:19:50 -03:00
return(-1);
2015-05-13 03:09:36 -03:00
} else if (dump_log_num <= 0) {
cliSerial->printf_P(PSTR("dumping all\n"));
2013-02-28 16:16:32 -04:00
Log_Read(0, 1, 0);
2012-08-21 23:19:50 -03:00
return(-1);
2012-12-04 18:22:21 -04:00
} else if ((argc != 2)
2015-05-13 03:09:36 -03:00
|| ((uint16_t)dump_log_num > last_log_num))
2012-12-04 18:22:21 -04:00
{
cliSerial->printf_P(PSTR("bad log number\n"));
2012-08-21 23:19:50 -03:00
return(-1);
}
2015-05-13 03:09:36 -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);
return 0;
}
2015-05-13 03:09:36 -03:00
int8_t Plane::erase_logs(uint8_t argc, const Menu::arg *argv)
{
2011-12-28 00:53:14 -04:00
in_mavlink_delay = true;
do_erase_logs();
in_mavlink_delay = false;
return 0;
}
2015-05-13 03:09:36 -03:00
int8_t Plane::select_logs(uint8_t argc, const Menu::arg *argv)
{
2014-01-13 21:52:22 -04:00
uint32_t bits;
2012-08-21 23:19:50 -03:00
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"))) {
2014-01-13 21:52:22 -04:00
bits = 0xFFFFFFFFUL;
2012-08-21 23:19:50 -03:00
} 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);
TARG(MODE);
TARG(IMU);
2012-08-21 23:19:50 -03:00
TARG(CMD);
TARG(CURRENT);
2013-04-19 10:54:40 -03:00
TARG(COMPASS);
TARG(TECS);
TARG(CAMERA);
2013-11-25 17:44:17 -04:00
TARG(RC);
TARG(SONAR);
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);
}
2015-05-13 03:09:36 -03:00
int8_t Plane::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 == ENABLED
2015-05-13 03:09:36 -03:00
void Plane::do_erase_logs(void)
{
gcs_send_text_P(SEVERITY_LOW, PSTR("Erasing logs"));
DataFlash.EraseAll();
gcs_send_text_P(SEVERITY_LOW, PSTR("Log erase complete"));
}
// Write an attitude packet
2015-05-13 03:09:36 -03:00
void Plane::Log_Write_Attitude(void)
{
Vector3f targets; // Package up the targets into a vector for commonality with Copter usage of Log_Wrote_Attitude
targets.x = nav_roll_cd;
targets.y = nav_pitch_cd;
targets.z = 0; //Plane does not have the concept of navyaw. This is a placeholder.
DataFlash.Log_Write_Attitude(ahrs, targets);
2015-05-28 00:54:50 -03:00
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
2015-05-22 18:39:50 -03:00
DataFlash.Log_Write_PID(LOG_PIDR_MSG, rollController.get_pid_info());
DataFlash.Log_Write_PID(LOG_PIDP_MSG, pitchController.get_pid_info());
DataFlash.Log_Write_PID(LOG_PIDY_MSG, steerController.get_pid_info());
2015-05-28 00:54:50 -03:00
#endif
#if AP_AHRS_NAVEKF_AVAILABLE
#if OPTFLOW == ENABLED
DataFlash.Log_Write_EKF(ahrs,optflow.enabled());
#else
DataFlash.Log_Write_EKF(ahrs,false);
#endif
2014-01-03 20:51:36 -04:00
DataFlash.Log_Write_AHRS2(ahrs);
#endif
2015-05-04 03:18:55 -03:00
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
2014-01-03 20:51:36 -04:00
sitl.Log_Write_SIMSTATE(DataFlash);
#endif
2015-05-15 01:24:46 -03:00
DataFlash.Log_Write_POS(ahrs);
}
2013-04-19 10:37:21 -03:00
struct PACKED log_Performance {
LOG_PACKET_HEADER;
uint64_t time_us;
uint32_t loop_time;
uint16_t main_loop_count;
uint32_t g_dt_max;
int16_t gyro_drift_x;
int16_t gyro_drift_y;
int16_t gyro_drift_z;
uint8_t i2c_lockup_count;
2013-11-18 00:08:40 -04:00
uint16_t ins_error_count;
};
// Write a performance monitoring packet. Total length : 19 bytes
2015-05-13 03:09:36 -03:00
void Plane::Log_Write_Performance()
{
struct log_Performance pkt = {
LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG),
time_us : hal.scheduler->micros64(),
loop_time : millis() - perf_mon_timer,
main_loop_count : mainLoop_count,
g_dt_max : G_Dt_max,
gyro_drift_x : (int16_t)(ahrs.get_gyro_drift().x * 1000),
gyro_drift_y : (int16_t)(ahrs.get_gyro_drift().y * 1000),
gyro_drift_z : (int16_t)(ahrs.get_gyro_drift().z * 1000),
2013-11-18 00:08:40 -04:00
i2c_lockup_count: hal.i2c->lockup_count(),
ins_error_count : ins.error_count()
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
2012-08-21 23:19:50 -03:00
}
// Write a mission command. Total length : 36 bytes
2015-05-13 03:09:36 -03:00
void Plane::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-19 10:37:21 -03:00
struct PACKED log_Startup {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t startup_type;
uint16_t command_total;
};
2015-05-13 03:09:36 -03:00
void Plane::Log_Write_Startup(uint8_t type)
{
// Write all current parameters
DataFlash.Log_Write_Parameters();
struct log_Startup pkt = {
LOG_PACKET_HEADER_INIT(LOG_STARTUP_MSG),
time_us : hal.scheduler->micros64(),
startup_type : type,
command_total : mission.num_commands()
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
// write all commands to the dataflash as well
if (should_log(MASK_LOG_CMD)) {
Log_Write_EntireMission();
}
}
2015-05-13 03:09:36 -03:00
void Plane::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);
}
2012-08-21 23:19:50 -03:00
}
}
2013-04-19 10:37:21 -03:00
struct PACKED log_Control_Tuning {
LOG_PACKET_HEADER;
uint64_t time_us;
int16_t nav_roll_cd;
int16_t roll;
int16_t nav_pitch_cd;
int16_t pitch;
int16_t throttle_out;
int16_t rudder_out;
2013-04-19 10:37:21 -03:00
float accel_y;
};
// Write a control tuning packet. Total length : 22 bytes
2015-05-13 03:09:36 -03:00
void Plane::Log_Write_Control_Tuning()
{
Vector3f accel = ins.get_accel();
struct log_Control_Tuning pkt = {
2013-04-19 10:37:21 -03:00
LOG_PACKET_HEADER_INIT(LOG_CTUN_MSG),
time_us : hal.scheduler->micros64(),
nav_roll_cd : (int16_t)nav_roll_cd,
roll : (int16_t)ahrs.roll_sensor,
nav_pitch_cd : (int16_t)nav_pitch_cd,
pitch : (int16_t)ahrs.pitch_sensor,
throttle_out : (int16_t)channel_throttle->servo_out,
rudder_out : (int16_t)channel_rudder->servo_out,
2013-04-19 10:37:21 -03:00
accel_y : accel.y
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
// Write a TECS tuning packet
2015-05-13 03:09:36 -03:00
void Plane::Log_Write_TECS_Tuning(void)
{
SpdHgt_Controller->log_data(DataFlash, LOG_TECS_MSG);
}
2013-04-19 10:37:21 -03:00
struct PACKED log_Nav_Tuning {
LOG_PACKET_HEADER;
uint64_t time_us;
uint16_t yaw;
float wp_distance;
int16_t target_bearing_cd;
int16_t nav_bearing_cd;
int16_t altitude_error_cm;
int16_t airspeed_cm;
float altitude;
uint32_t groundspeed_cm;
};
// Write a navigation tuning packe
2015-05-13 03:09:36 -03:00
void Plane::Log_Write_Nav_Tuning()
{
struct log_Nav_Tuning pkt = {
2013-04-19 10:37:21 -03:00
LOG_PACKET_HEADER_INIT(LOG_NTUN_MSG),
time_us : hal.scheduler->micros64(),
yaw : (uint16_t)ahrs.yaw_sensor,
wp_distance : auto_state.wp_distance,
target_bearing_cd : (int16_t)nav_controller->target_bearing_cd(),
nav_bearing_cd : (int16_t)nav_controller->nav_bearing_cd(),
altitude_error_cm : (int16_t)altitude_error_cm,
airspeed_cm : (int16_t)airspeed.get_airspeed_cm(),
altitude : barometer.get_altitude(),
2014-03-28 16:52:48 -03:00
groundspeed_cm : (uint32_t)(gps.ground_speed()*100)
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
struct PACKED log_Status {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t is_flying;
float is_flying_probability;
uint8_t armed;
uint8_t safety;
};
2015-05-13 03:09:36 -03:00
void Plane::Log_Write_Status()
{
struct log_Status pkt = {
LOG_PACKET_HEADER_INIT(LOG_STATUS_MSG)
,time_us : hal.scheduler->micros64()
,is_flying : is_flying()
,is_flying_probability : isFlyingProbability
,armed : hal.util->get_soft_armed()
,safety : hal.util->safety_switch_state()
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
struct PACKED log_Sonar {
LOG_PACKET_HEADER;
uint64_t time_us;
float distance;
float voltage;
float baro_alt;
float groundspeed;
uint8_t throttle;
uint8_t count;
float correction;
};
// Write a sonar packet
2015-05-13 03:09:36 -03:00
void Plane::Log_Write_Sonar()
{
#if RANGEFINDER_ENABLED == ENABLED
struct log_Sonar pkt = {
LOG_PACKET_HEADER_INIT(LOG_SONAR_MSG),
time_us : hal.scheduler->micros64(),
distance : (float)rangefinder.distance_cm(),
voltage : rangefinder.voltage_mv()*0.001f,
baro_alt : barometer.get_altitude(),
2014-03-28 16:52:48 -03:00
groundspeed : gps.ground_speed(),
throttle : (uint8_t)(100 * channel_throttle->norm_output()),
count : rangefinder_state.in_range_count,
correction : rangefinder_state.correction
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
#endif
}
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;
};
#if OPTFLOW == ENABLED
// Write an optical flow packet
2015-05-13 03:09:36 -03:00
void Plane::Log_Write_Optflow()
{
// 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
2013-11-27 22:19:34 -04:00
struct PACKED log_Arm_Disarm {
LOG_PACKET_HEADER;
uint64_t time_us;
2013-11-27 22:19:34 -04:00
uint8_t arm_state;
uint16_t arm_checks;
};
2015-05-13 03:09:36 -03:00
void Plane::Log_Write_Current()
{
DataFlash.Log_Write_Current(battery, channel_throttle->control_in);
2014-02-13 07:08:25 -04:00
// also write power status
DataFlash.Log_Write_Power();
}
2015-05-13 03:09:36 -03:00
void Plane::Log_Arm_Disarm() {
2013-11-27 22:19:34 -04:00
struct log_Arm_Disarm pkt = {
LOG_PACKET_HEADER_INIT(LOG_ARM_DISARM_MSG),
time_us : hal.scheduler->micros64(),
2013-11-27 22:19:34 -04:00
arm_state : arming.is_armed(),
arm_checks : arming.get_enabled_checks()
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
2013-04-19 10:54:40 -03:00
2015-05-13 03:09:36 -03:00
void Plane::Log_Write_GPS(uint8_t instance)
{
DataFlash.Log_Write_GPS(gps, instance, current_loc.alt - ahrs.get_home().alt);
}
2015-05-13 03:09:36 -03:00
void Plane::Log_Write_IMU()
{
2013-11-03 23:37:32 -04:00
DataFlash.Log_Write_IMU(ins);
}
2015-05-13 03:09:36 -03:00
void Plane::Log_Write_RC(void)
2013-11-25 17:44:17 -04:00
{
DataFlash.Log_Write_RCIN();
DataFlash.Log_Write_RCOUT();
2013-11-25 17:44:17 -04:00
}
2015-05-13 03:09:36 -03:00
void Plane::Log_Write_Baro(void)
{
DataFlash.Log_Write_Baro(barometer);
}
// Write a AIRSPEED packet
2015-05-13 03:09:36 -03:00
void Plane::Log_Write_Airspeed(void)
{
DataFlash.Log_Write_Airspeed(airspeed);
}
2013-04-19 10:37:21 -03:00
static const struct LogStructure log_structure[] PROGMEM = {
LOG_COMMON_STRUCTURES,
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
"PM", "QIHIhhhBH", "TimeUS,LTime,MLC,gDt,GDx,GDy,GDz,I2CErr,INSErr" },
2013-04-19 10:37:21 -03:00
{ LOG_STARTUP_MSG, sizeof(log_Startup),
"STRT", "QBH", "TimeUS,SType,CTot" },
2013-04-19 10:37:21 -03:00
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning),
"CTUN", "Qcccchhf", "TimeUS,NavRoll,Roll,NavPitch,Pitch,ThrOut,RdrOut,AccY" },
2013-04-19 10:37:21 -03:00
{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning),
"NTUN", "QCfccccfI", "TimeUS,Yaw,WpDist,TargBrg,NavBrg,AltErr,Arspd,Alt,GSpdCM" },
{ LOG_SONAR_MSG, sizeof(log_Sonar),
"SONR", "QffffBBf", "TimeUS,DistCM,Volt,BaroAlt,GSpd,Thr,Cnt,Corr" },
2013-11-27 22:19:34 -04:00
{ LOG_ARM_DISARM_MSG, sizeof(log_Arm_Disarm),
"ARM", "QHB", "TimeUS,ArmState,ArmChecks" },
{ LOG_ATRP_MSG, sizeof(AP_AutoTune::log_ATRP),
"ATRP", "QBBcfff", "TimeUS,Type,State,Servo,Demanded,Achieved,P" },
{ LOG_STATUS_MSG, sizeof(log_Status),
"STAT", "QBfBB", "TimeUS,isFlying,isFlyProb,Armed,Safety" },
#if OPTFLOW == ENABLED
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow),
"OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY" },
#endif
2014-01-30 06:45:41 -04:00
TECS_LOG_FORMAT(LOG_TECS_MSG)
2013-04-19 10:37:21 -03:00
};
#if CLI_ENABLED == ENABLED
// Read the DataFlash.log memory : Packet Parser
2015-05-13 03:09:36 -03:00
void Plane::Log_Read(uint16_t log_num, int16_t start_page, int16_t end_page)
{
cliSerial->printf_P(PSTR("\n" FIRMWARE_STRING
2013-01-14 23:03:08 -04:00
"\nFree RAM: %u\n"),
(unsigned)hal.util->available_memory());
2011-11-19 18:02:45 -04:00
2013-04-18 21:24:20 -03:00
cliSerial->println_P(PSTR(HAL_BOARD_NAME));
DataFlash.LogReadProcess(log_num, start_page, end_page,
FUNCTOR_BIND_MEMBER(&Plane::print_flight_mode, void, AP_HAL::BetterStream *, uint8_t),
cliSerial);
}
#endif // CLI_ENABLED
2013-04-19 10:37:21 -03:00
// start a new log
2015-05-13 03:09:36 -03:00
void Plane::start_logging()
{
2013-12-16 20:15:17 -04:00
DataFlash.StartNewLog();
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
2013-11-25 20:58:18 -04:00
// write system identifier as well if available
char sysid[40];
if (hal.util->get_system_id(sysid)) {
DataFlash.Log_Write_Message(sysid);
}
Log_Write_Startup(TYPE_GROUNDSTART_MSG);
}
2013-01-14 23:03:08 -04:00
2015-05-13 03:09:36 -03:00
/*
initialise logging subsystem
*/
void Plane::log_init(void)
{
DataFlash.Init(log_structure, sizeof(log_structure)/sizeof(log_structure[0]));
if (!DataFlash.CardInserted()) {
gcs_send_text_P(SEVERITY_LOW, PSTR("No dataflash card inserted"));
g.log_bitmask.set(0);
} else if (DataFlash.NeedErase()) {
gcs_send_text_P(SEVERITY_LOW, PSTR("ERASING LOGS"));
do_erase_logs();
for (uint8_t i=0; i<num_gcs; i++) {
gcs[i].reset_cli_timeout();
}
}
arming.set_logging_available(DataFlash.CardInserted());
}
2015-05-13 03:09:36 -03:00
#else // LOGGING_ENABLED
2015-05-13 03:09:36 -03:00
int8_t Plane::process_logs(uint8_t argc, const Menu::arg *argv)
{
2012-08-21 23:19:50 -03:00
return 0;
}
#endif // LOGGING_ENABLED