mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 23:48:31 -04:00
461 lines
13 KiB
Plaintext
461 lines
13 KiB
Plaintext
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
#if LOGGING_ENABLED == ENABLED
|
|
|
|
// Code to Write and Read packets from DataFlash log memory
|
|
// Code to interact with the user to dump or erase logs
|
|
|
|
// These are function definitions so the Menu can be constructed before the functions
|
|
// are defined below. Order matters to the compiler.
|
|
static int8_t dump_log(uint8_t argc, const Menu::arg *argv);
|
|
static int8_t erase_logs(uint8_t argc, const Menu::arg *argv);
|
|
static int8_t select_logs(uint8_t argc, const Menu::arg *argv);
|
|
|
|
// Creates a constant array of structs representing menu options
|
|
// and stores them in Flash memory, not RAM.
|
|
// User enters the string in the console to call the functions on the right.
|
|
// See class Menu in AP_Coommon for implementation details
|
|
static const struct Menu::command log_menu_commands[] PROGMEM = {
|
|
{"dump", dump_log},
|
|
{"erase", erase_logs},
|
|
{"enable", select_logs},
|
|
{"disable", select_logs}
|
|
};
|
|
|
|
// A Macro to create the Menu
|
|
MENU2(log_menu, "Log", log_menu_commands, print_log_menu);
|
|
|
|
static bool
|
|
print_log_menu(void)
|
|
{
|
|
cliSerial->printf_P(PSTR("logs enabled: "));
|
|
|
|
if (0 == g.log_bitmask) {
|
|
cliSerial->printf_P(PSTR("none"));
|
|
}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.
|
|
#define PLOG(_s) if (g.log_bitmask & MASK_LOG_ ## _s) cliSerial->printf_P(PSTR(" %S"), PSTR(#_s))
|
|
PLOG(ATTITUDE_FAST);
|
|
PLOG(ATTITUDE_MED);
|
|
PLOG(GPS);
|
|
PLOG(PM);
|
|
PLOG(CTUN);
|
|
PLOG(NTUN);
|
|
PLOG(MODE);
|
|
PLOG(IMU);
|
|
PLOG(CMD);
|
|
PLOG(CURRENT);
|
|
PLOG(SONAR);
|
|
#undef PLOG
|
|
}
|
|
|
|
cliSerial->println();
|
|
|
|
DataFlash.ListAvailableLogs(cliSerial);
|
|
return(true);
|
|
}
|
|
|
|
static int8_t
|
|
dump_log(uint8_t argc, const Menu::arg *argv)
|
|
{
|
|
int16_t dump_log;
|
|
uint16_t dump_log_start;
|
|
uint16_t dump_log_end;
|
|
uint16_t last_log_num;
|
|
|
|
// 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) {
|
|
DataFlash.DumpPageInfo(cliSerial);
|
|
return(-1);
|
|
} else if (dump_log <= 0) {
|
|
cliSerial->printf_P(PSTR("dumping all\n"));
|
|
Log_Read(0, 1, 0);
|
|
return(-1);
|
|
} else if ((argc != 2) || (dump_log <= (last_log_num - DataFlash.get_num_logs())) || (dump_log > last_log_num)) {
|
|
cliSerial->printf_P(PSTR("bad log number\n"));
|
|
return(-1);
|
|
}
|
|
|
|
DataFlash.get_log_boundaries(dump_log, dump_log_start, dump_log_end);
|
|
Log_Read((uint16_t)dump_log, dump_log_start, dump_log_end);
|
|
return 0;
|
|
}
|
|
|
|
|
|
static void do_erase_logs(void)
|
|
{
|
|
cliSerial->printf_P(PSTR("\nErasing log...\n"));
|
|
DataFlash.EraseAll();
|
|
cliSerial->printf_P(PSTR("\nLog erased.\n"));
|
|
}
|
|
|
|
static int8_t
|
|
erase_logs(uint8_t argc, const Menu::arg *argv)
|
|
{
|
|
in_mavlink_delay = true;
|
|
do_erase_logs();
|
|
in_mavlink_delay = false;
|
|
return 0;
|
|
}
|
|
|
|
static int8_t
|
|
select_logs(uint8_t argc, const Menu::arg *argv)
|
|
{
|
|
uint16_t bits;
|
|
|
|
if (argc != 2) {
|
|
cliSerial->printf_P(PSTR("missing log type\n"));
|
|
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);
|
|
TARG(MODE);
|
|
TARG(IMU);
|
|
TARG(CMD);
|
|
TARG(CURRENT);
|
|
TARG(SONAR);
|
|
#undef TARG
|
|
}
|
|
|
|
if (!strcasecmp_P(argv[0].str, PSTR("enable"))) {
|
|
g.log_bitmask.set_and_save(g.log_bitmask | bits);
|
|
}else{
|
|
g.log_bitmask.set_and_save(g.log_bitmask & ~bits);
|
|
}
|
|
return(0);
|
|
}
|
|
|
|
static int8_t
|
|
process_logs(uint8_t argc, const Menu::arg *argv)
|
|
{
|
|
log_menu.run();
|
|
return 0;
|
|
}
|
|
|
|
// print_latlon - prints an latitude or longitude value held in an int32_t
|
|
// probably this should be moved to AP_Common
|
|
void print_latlon(AP_HAL::BetterStream *s, int32_t lat_or_lon)
|
|
{
|
|
int32_t dec_portion, frac_portion;
|
|
int32_t abs_lat_or_lon = labs(lat_or_lon);
|
|
|
|
// extract decimal portion (special handling of negative numbers to ensure we round towards zero)
|
|
dec_portion = abs_lat_or_lon / T7;
|
|
|
|
// extract fractional portion
|
|
frac_portion = abs_lat_or_lon - dec_portion*T7;
|
|
|
|
// print output including the minus sign
|
|
if( lat_or_lon < 0 ) {
|
|
s->printf_P(PSTR("-"));
|
|
}
|
|
s->printf_P(PSTR("%ld.%07ld"),(long)dec_portion,(long)frac_portion);
|
|
}
|
|
|
|
struct PACKED log_Performance {
|
|
LOG_PACKET_HEADER;
|
|
uint32_t loop_time;
|
|
uint16_t main_loop_count;
|
|
int16_t g_dt_max;
|
|
uint8_t renorm_count;
|
|
uint8_t renorm_blowup;
|
|
uint8_t gps_fix_count;
|
|
int16_t gyro_drift_x;
|
|
int16_t gyro_drift_y;
|
|
int16_t gyro_drift_z;
|
|
int16_t pm_test;
|
|
};
|
|
|
|
// Write a performance monitoring packet. Total length : 19 bytes
|
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
static void Log_Write_Performance()
|
|
{
|
|
struct log_Performance pkt = {
|
|
LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG),
|
|
loop_time : millis()- perf_mon_timer,
|
|
main_loop_count : mainLoop_count,
|
|
g_dt_max : G_Dt_max,
|
|
renorm_count : ahrs.renorm_range_count,
|
|
renorm_blowup : ahrs.renorm_blowup_count,
|
|
gps_fix_count : gps_fix_count,
|
|
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),
|
|
pm_test : pmTest1
|
|
};
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
}
|
|
#endif
|
|
|
|
struct PACKED log_Cmd {
|
|
LOG_PACKET_HEADER;
|
|
uint8_t command_total;
|
|
uint8_t command_number;
|
|
uint8_t waypoint_id;
|
|
uint8_t waypoint_options;
|
|
uint8_t waypoint_param1;
|
|
int32_t waypoint_altitude;
|
|
int32_t waypoint_latitude;
|
|
int32_t waypoint_longitude;
|
|
};
|
|
|
|
// Write a command processing packet. Total length : 19 bytes
|
|
static void Log_Write_Cmd(uint8_t num, const struct Location *wp)
|
|
{
|
|
struct log_Cmd pkt = {
|
|
LOG_PACKET_HEADER_INIT(LOG_CMD_MSG),
|
|
command_total : g.command_total,
|
|
command_number : num,
|
|
waypoint_id : wp->id,
|
|
waypoint_options : wp->options,
|
|
waypoint_param1 : wp->p1,
|
|
waypoint_altitude : wp->alt,
|
|
waypoint_latitude : wp->lat,
|
|
waypoint_longitude : wp->lng
|
|
};
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
}
|
|
|
|
struct PACKED log_Startup {
|
|
LOG_PACKET_HEADER;
|
|
uint8_t startup_type;
|
|
uint8_t command_total;
|
|
};
|
|
|
|
static void Log_Write_Startup(uint8_t type)
|
|
{
|
|
struct log_Startup pkt = {
|
|
LOG_PACKET_HEADER_INIT(LOG_STARTUP_MSG),
|
|
startup_type : type,
|
|
command_total : g.command_total
|
|
};
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
// write all commands to the dataflash as well
|
|
struct Location cmd;
|
|
for (uint8_t i = 0; i <= g.command_total; i++) {
|
|
cmd = get_cmd_with_index(i);
|
|
Log_Write_Cmd(i, &cmd);
|
|
}
|
|
}
|
|
|
|
struct PACKED log_Control_Tuning {
|
|
LOG_PACKET_HEADER;
|
|
int16_t steer_out;
|
|
int16_t roll;
|
|
int16_t pitch;
|
|
int16_t throttle_out;
|
|
float accel_y;
|
|
};
|
|
|
|
// Write a control tuning packet. Total length : 22 bytes
|
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
static void Log_Write_Control_Tuning()
|
|
{
|
|
Vector3f accel = ins.get_accel();
|
|
struct log_Control_Tuning pkt = {
|
|
LOG_PACKET_HEADER_INIT(LOG_CTUN_MSG),
|
|
steer_out : (int16_t)g.channel_steer.servo_out,
|
|
roll : (int16_t)ahrs.roll_sensor,
|
|
pitch : (int16_t)ahrs.pitch_sensor,
|
|
throttle_out : (int16_t)g.channel_throttle.servo_out,
|
|
accel_y : accel.y
|
|
};
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
}
|
|
#endif
|
|
|
|
struct PACKED log_Nav_Tuning {
|
|
LOG_PACKET_HEADER;
|
|
uint16_t yaw;
|
|
float wp_distance;
|
|
uint16_t target_bearing_cd;
|
|
uint16_t nav_bearing_cd;
|
|
int16_t nav_gain_scalar;
|
|
int8_t throttle;
|
|
};
|
|
|
|
// Write a navigation tuning packet. Total length : 18 bytes
|
|
static void Log_Write_Nav_Tuning()
|
|
{
|
|
struct log_Nav_Tuning pkt = {
|
|
LOG_PACKET_HEADER_INIT(LOG_NTUN_MSG),
|
|
yaw : (uint16_t)ahrs.yaw_sensor,
|
|
wp_distance : wp_distance,
|
|
target_bearing_cd : (uint16_t)target_bearing,
|
|
nav_bearing_cd : (uint16_t)nav_bearing,
|
|
nav_gain_scalar : (int16_t)(nav_gain_scaler*1000),
|
|
throttle : (int8_t)(100 * g.channel_throttle.norm_output())
|
|
};
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
}
|
|
|
|
struct PACKED log_Attitude {
|
|
LOG_PACKET_HEADER;
|
|
int16_t roll;
|
|
int16_t pitch;
|
|
uint16_t yaw;
|
|
};
|
|
|
|
|
|
// Write an attitude packet
|
|
void Log_Write_Attitude()
|
|
{
|
|
struct log_Attitude pkt = {
|
|
LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
|
|
roll : (int16_t)ahrs.roll_sensor,
|
|
pitch : (int16_t)ahrs.pitch_sensor,
|
|
yaw : (uint16_t)ahrs.yaw_sensor
|
|
};
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
}
|
|
|
|
struct log_Mode {
|
|
LOG_PACKET_HEADER;
|
|
uint8_t mode;
|
|
};
|
|
|
|
// Write a mode packet. Total length : 7 bytes
|
|
static void Log_Write_Mode()
|
|
{
|
|
struct log_Mode pkt = {
|
|
LOG_PACKET_HEADER_INIT(LOG_MODE_MSG),
|
|
mode : (uint8_t)control_mode
|
|
};
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
}
|
|
|
|
|
|
struct PACKED log_Sonar {
|
|
LOG_PACKET_HEADER;
|
|
int16_t nav_steer;
|
|
uint16_t sonar1_distance;
|
|
uint16_t sonar2_distance;
|
|
uint16_t detected_count;
|
|
int8_t turn_angle;
|
|
uint16_t turn_time;
|
|
uint16_t ground_speed;
|
|
int8_t throttle;
|
|
};
|
|
|
|
// Write a sonar packet
|
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
static void Log_Write_Sonar()
|
|
{
|
|
uint16_t turn_time = 0;
|
|
if (obstacle.turn_angle != 0) {
|
|
turn_time = hal.scheduler->millis() - obstacle.detected_time_ms;
|
|
}
|
|
struct log_Sonar pkt = {
|
|
LOG_PACKET_HEADER_INIT(LOG_SONAR_MSG),
|
|
nav_steer : (int16_t)nav_steer_cd,
|
|
sonar1_distance : (uint16_t)sonar.distance_cm(),
|
|
sonar2_distance : (uint16_t)sonar2.distance_cm(),
|
|
detected_count : obstacle.detected_count,
|
|
turn_angle : (int8_t)obstacle.turn_angle,
|
|
turn_time : turn_time,
|
|
ground_speed : (uint16_t)(ground_speed*100),
|
|
throttle : (int8_t)(100 * g.channel_throttle.norm_output())
|
|
};
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
}
|
|
#endif
|
|
|
|
struct PACKED log_Current {
|
|
LOG_PACKET_HEADER;
|
|
int16_t throttle_in;
|
|
int16_t battery_voltage;
|
|
int16_t current_amps;
|
|
float current_total;
|
|
};
|
|
|
|
static void Log_Write_Current()
|
|
{
|
|
struct log_Current pkt = {
|
|
LOG_PACKET_HEADER_INIT(LOG_CURRENT_MSG),
|
|
throttle_in : g.channel_throttle.control_in,
|
|
battery_voltage : (int16_t)(battery_voltage1 * 100.0),
|
|
current_amps : (int16_t)(current_amps1 * 100.0),
|
|
current_total : current_total1
|
|
};
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
}
|
|
|
|
static const struct LogStructure log_structure[] PROGMEM = {
|
|
LOG_COMMON_STRUCTURES,
|
|
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),
|
|
"ATT", "ccC", "Roll,Pitch,Yaw" },
|
|
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
|
"PM", "IHhBBBhhhh", "LTime,MLC,gDt,RNCnt,RNBl,GPScnt,GDx,GDy,GDz,PMT" },
|
|
{ LOG_CMD_MSG, sizeof(log_Cmd),
|
|
"CMD", "BBBBBeLL", "CTot,CNum,CId,COpt,Prm1,Alt,Lat,Lng" },
|
|
{ LOG_STARTUP_MSG, sizeof(log_Startup),
|
|
"STRT", "BB", "SType,CTot" },
|
|
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning),
|
|
"CTUN", "hcchf", "Steer,Roll,Pitch,ThrOut,AccY" },
|
|
{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning),
|
|
"NTUN", "HfHHhb", "Yaw,WpDist,TargBrg,NavBrg,NavGain,Thr" },
|
|
{ LOG_SONAR_MSG, sizeof(log_Sonar),
|
|
"SONR", "hHHHbHCb", "NavStr,S1Dist,S2Dist,DCnt,TAng,TTim,Spd,Thr" },
|
|
{ LOG_CURRENT_MSG, sizeof(log_Current),
|
|
"CURR", "hhhf", "Thr,Volt,Curr,CurrTot" },
|
|
{ LOG_MODE_MSG, sizeof(log_Mode),
|
|
"MODE", "B", "Mode" },
|
|
};
|
|
|
|
|
|
static int8_t setup_show (uint8_t argc, const Menu::arg *argv);
|
|
|
|
// Read the DataFlash log memory : Packet Parser
|
|
static void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page)
|
|
{
|
|
cliSerial->printf_P(PSTR("\n" THISFIRMWARE
|
|
"\nFree RAM: %u\n"),
|
|
(unsigned) memcheck_available_memory());
|
|
|
|
cliSerial->println_P(PSTR(HAL_BOARD_NAME));
|
|
|
|
DataFlash.LogReadProcess(log_num, start_page, end_page,
|
|
sizeof(log_structure)/sizeof(log_structure[0]),
|
|
log_structure, cliSerial);
|
|
}
|
|
|
|
#else // LOGGING_ENABLED
|
|
|
|
// dummy functions
|
|
static void Log_Write_Startup(uint8_t type) {}
|
|
static void Log_Write_Cmd(uint8_t num, const struct Location *wp) {}
|
|
static void Log_Write_Current() {}
|
|
static void Log_Write_Nav_Tuning() {}
|
|
static void Log_Write_Performance() {}
|
|
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) { return 0; }
|
|
static void Log_Write_Control_Tuning() {}
|
|
static void Log_Write_Sonar() {}
|
|
|
|
|
|
#endif // LOGGING_ENABLED
|
|
|