2012-04-30 04:17:14 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2013-01-14 23:03:17 -04:00
|
|
|
|
2015-05-13 00:16:45 -03:00
|
|
|
#include "Rover.h"
|
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
#if LOGGING_ENABLED == ENABLED
|
|
|
|
|
2015-03-13 08:40:06 -03:00
|
|
|
#if CLI_ENABLED == ENABLED
|
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
// 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-12 04:00:25 -03:00
|
|
|
{"dump", MENU_FUNC(dump_log)},
|
|
|
|
{"erase", MENU_FUNC(erase_logs)},
|
|
|
|
{"enable", MENU_FUNC(select_logs)},
|
|
|
|
{"disable", MENU_FUNC(select_logs)}
|
2012-04-30 04:17:14 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
// A Macro to create the Menu
|
2015-05-24 20:24:11 -03:00
|
|
|
MENU2(log_menu, "Log", log_menu_commands, FUNCTOR_BIND(&rover, &Rover::print_log_menu, bool));
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2015-05-12 04:00:25 -03:00
|
|
|
bool Rover::print_log_menu(void)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2012-11-21 02:25:11 -04:00
|
|
|
cliSerial->printf_P(PSTR("logs enabled: "));
|
2012-04-30 04:17:14 -03:00
|
|
|
|
|
|
|
if (0 == g.log_bitmask) {
|
2012-11-21 02:25:11 -04:00
|
|
|
cliSerial->printf_P(PSTR("none"));
|
2012-04-30 04:17:14 -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-11-21 02:25:11 -04:00
|
|
|
#define PLOG(_s) if (g.log_bitmask & MASK_LOG_ ## _s) cliSerial->printf_P(PSTR(" %S"), PSTR(#_s))
|
2012-04-30 04:17:14 -03:00
|
|
|
PLOG(ATTITUDE_FAST);
|
|
|
|
PLOG(ATTITUDE_MED);
|
|
|
|
PLOG(GPS);
|
|
|
|
PLOG(PM);
|
|
|
|
PLOG(CTUN);
|
|
|
|
PLOG(NTUN);
|
|
|
|
PLOG(MODE);
|
2013-01-26 04:35:18 -04:00
|
|
|
PLOG(IMU);
|
2012-04-30 04:17:14 -03:00
|
|
|
PLOG(CMD);
|
2013-01-26 04:41:38 -04:00
|
|
|
PLOG(CURRENT);
|
2013-04-18 21:23:57 -03:00
|
|
|
PLOG(SONAR);
|
2013-04-19 10:54:26 -03:00
|
|
|
PLOG(COMPASS);
|
2013-07-14 20:57:00 -03:00
|
|
|
PLOG(CAMERA);
|
2013-12-15 20:14:58 -04:00
|
|
|
PLOG(STEERING);
|
2012-04-30 04:17:14 -03:00
|
|
|
#undef PLOG
|
|
|
|
}
|
|
|
|
|
2012-11-21 02:25:11 -04:00
|
|
|
cliSerial->println();
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2013-04-17 08:34:20 -03:00
|
|
|
DataFlash.ListAvailableLogs(cliSerial);
|
2012-04-30 04:17:14 -03:00
|
|
|
return(true);
|
|
|
|
}
|
|
|
|
|
2015-05-12 04:00:25 -03:00
|
|
|
int8_t Rover::dump_log(uint8_t argc, const Menu::arg *argv)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2015-05-12 04:00:25 -03:00
|
|
|
int16_t dump_log_num;
|
2013-04-19 18:29:57 -03:00
|
|
|
uint16_t dump_log_start;
|
|
|
|
uint16_t dump_log_end;
|
|
|
|
uint16_t last_log_num;
|
|
|
|
|
|
|
|
// check that the requested log number can be read
|
2015-05-12 04:00:25 -03:00
|
|
|
dump_log_num = argv[1].i;
|
2013-04-19 18:29:57 -03:00
|
|
|
last_log_num = DataFlash.find_last_log();
|
|
|
|
|
2015-05-12 04:00:25 -03:00
|
|
|
if (dump_log_num == -2) {
|
2013-02-22 19:14:35 -04:00
|
|
|
DataFlash.DumpPageInfo(cliSerial);
|
2013-04-19 18:29:57 -03:00
|
|
|
return(-1);
|
2015-05-12 04:00:25 -03:00
|
|
|
} else if (dump_log_num <= 0) {
|
2013-04-19 18:29:57 -03:00
|
|
|
cliSerial->printf_P(PSTR("dumping all\n"));
|
|
|
|
Log_Read(0, 1, 0);
|
|
|
|
return(-1);
|
|
|
|
} else if ((argc != 2)
|
2015-05-12 04:00:25 -03:00
|
|
|
|| ((uint16_t)dump_log_num > last_log_num))
|
2013-04-19 18:29:57 -03:00
|
|
|
{
|
|
|
|
cliSerial->printf_P(PSTR("bad log number\n"));
|
|
|
|
return(-1);
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2015-05-12 04:00:25 -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-04-30 04:17:14 -03:00
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2015-05-12 04:00:25 -03:00
|
|
|
int8_t Rover::erase_logs(uint8_t argc, const Menu::arg *argv)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
|
|
|
in_mavlink_delay = true;
|
|
|
|
do_erase_logs();
|
|
|
|
in_mavlink_delay = false;
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
2015-05-12 04:00:25 -03:00
|
|
|
int8_t Rover::select_logs(uint8_t argc, const Menu::arg *argv)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
|
|
|
uint16_t bits;
|
|
|
|
|
|
|
|
if (argc != 2) {
|
2012-11-21 02:25:11 -04:00
|
|
|
cliSerial->printf_P(PSTR("missing log type\n"));
|
2012-04-30 04:17:14 -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);
|
|
|
|
TARG(MODE);
|
2013-01-26 04:35:18 -04:00
|
|
|
TARG(IMU);
|
2012-04-30 04:17:14 -03:00
|
|
|
TARG(CMD);
|
2013-01-26 04:41:38 -04:00
|
|
|
TARG(CURRENT);
|
2013-04-18 21:23:57 -03:00
|
|
|
TARG(SONAR);
|
2013-04-19 10:54:26 -03:00
|
|
|
TARG(COMPASS);
|
2013-07-14 20:57:00 -03:00
|
|
|
TARG(CAMERA);
|
2013-12-15 20:14:58 -04:00
|
|
|
TARG(STEERING);
|
2012-04-30 04:17:14 -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-12 04:00:25 -03:00
|
|
|
int8_t Rover::process_logs(uint8_t argc, const Menu::arg *argv)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
|
|
|
log_menu.run();
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
2015-03-13 08:40:06 -03:00
|
|
|
#endif // CLI_ENABLED == ENABLED
|
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::do_erase_logs(void)
|
2015-03-13 08:40:06 -03:00
|
|
|
{
|
|
|
|
cliSerial->printf_P(PSTR("\nErasing log...\n"));
|
|
|
|
DataFlash.EraseAll();
|
|
|
|
cliSerial->printf_P(PSTR("\nLog erased.\n"));
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2013-04-19 04:53:07 -03:00
|
|
|
struct PACKED log_Performance {
|
2013-01-26 05:46:16 -04:00
|
|
|
LOG_PACKET_HEADER;
|
2015-04-29 08:11:24 -03:00
|
|
|
uint64_t time_us;
|
2013-01-26 05:46:16 -04:00
|
|
|
uint32_t loop_time;
|
|
|
|
uint16_t main_loop_count;
|
2013-11-01 20:40:29 -03:00
|
|
|
uint32_t g_dt_max;
|
2013-01-26 05:46:16 -04:00
|
|
|
int16_t gyro_drift_x;
|
|
|
|
int16_t gyro_drift_y;
|
|
|
|
int16_t gyro_drift_z;
|
2013-04-26 10:40:09 -03:00
|
|
|
uint8_t i2c_lockup_count;
|
2013-11-18 00:08:53 -04:00
|
|
|
uint16_t ins_error_count;
|
2013-01-26 05:46:16 -04:00
|
|
|
};
|
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
// Write a performance monitoring packet. Total length : 19 bytes
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::Log_Write_Performance()
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2013-01-26 05:46:16 -04:00
|
|
|
struct log_Performance pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG),
|
2015-04-29 08:11:24 -03:00
|
|
|
time_us : hal.scheduler->micros64(),
|
2013-01-26 05:46:16 -04:00
|
|
|
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:53 -04:00
|
|
|
i2c_lockup_count: hal.i2c->lockup_count(),
|
|
|
|
ins_error_count : ins.error_count()
|
2013-01-26 05:46:16 -04:00
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2014-03-16 05:43:04 -03:00
|
|
|
// Write a mission command. Total length : 36 bytes
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::Log_Write_Cmd(const AP_Mission::Mission_Command &cmd)
|
2014-03-16 05:43:04 -03:00
|
|
|
{
|
|
|
|
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-12-15 20:14:58 -04:00
|
|
|
struct PACKED log_Steering {
|
|
|
|
LOG_PACKET_HEADER;
|
2015-04-29 08:11:24 -03:00
|
|
|
uint64_t time_us;
|
2013-12-15 20:14:58 -04:00
|
|
|
float demanded_accel;
|
|
|
|
float achieved_accel;
|
|
|
|
};
|
|
|
|
|
|
|
|
// Write a steering packet
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::Log_Write_Steering()
|
2013-12-15 20:14:58 -04:00
|
|
|
{
|
|
|
|
struct log_Steering pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_STEERING_MSG),
|
2015-04-29 08:11:24 -03:00
|
|
|
time_us : hal.scheduler->micros64(),
|
2013-12-15 20:14:58 -04:00
|
|
|
demanded_accel : lateral_acceleration,
|
2014-03-30 22:01:54 -03:00
|
|
|
achieved_accel : gps.ground_speed() * ins.get_gyro().z,
|
2013-12-15 20:14:58 -04:00
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
}
|
|
|
|
|
2013-04-19 04:53:07 -03:00
|
|
|
struct PACKED log_Startup {
|
2013-01-26 05:46:16 -04:00
|
|
|
LOG_PACKET_HEADER;
|
2015-04-29 08:11:24 -03:00
|
|
|
uint64_t time_us;
|
2013-01-26 05:46:16 -04:00
|
|
|
uint8_t startup_type;
|
2014-03-10 05:45:49 -03:00
|
|
|
uint16_t command_total;
|
2013-01-26 05:46:16 -04:00
|
|
|
};
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::Log_Write_Startup(uint8_t type)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2013-01-26 05:46:16 -04:00
|
|
|
struct log_Startup pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_STARTUP_MSG),
|
2015-04-29 08:11:24 -03:00
|
|
|
time_us : hal.scheduler->micros64(),
|
2013-01-26 05:46:16 -04:00
|
|
|
startup_type : type,
|
2014-03-10 05:45:49 -03:00
|
|
|
command_total : mission.num_commands()
|
2013-01-26 05:46:16 -04:00
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
|
|
|
|
// write all commands to the dataflash as well
|
2015-06-01 08:14:27 -03:00
|
|
|
if (should_log(MASK_LOG_CMD)) {
|
|
|
|
Log_Write_EntireMission();
|
|
|
|
}
|
2015-05-05 21:17:08 -03:00
|
|
|
}
|
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::Log_Write_EntireMission()
|
2015-05-05 21:17:08 -03:00
|
|
|
{
|
2015-05-13 00:59:22 -03:00
|
|
|
DataFlash.Log_Write_Message_P(PSTR("New mission"));
|
2015-05-05 21:17:08 -03:00
|
|
|
|
2014-03-10 05:45:49 -03:00
|
|
|
AP_Mission::Mission_Command cmd;
|
2014-03-12 05:24:23 -03:00
|
|
|
for (uint16_t i = 0; i < mission.num_commands(); i++) {
|
2015-05-05 21:17:08 -03:00
|
|
|
if (mission.read_cmd_from_storage(i,cmd)) {
|
2014-03-16 05:43:04 -03:00
|
|
|
Log_Write_Cmd(cmd);
|
2014-03-10 23:30:15 -03:00
|
|
|
}
|
2013-01-26 05:46:16 -04:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2013-04-19 04:53:07 -03:00
|
|
|
struct PACKED log_Control_Tuning {
|
2013-01-26 05:46:16 -04:00
|
|
|
LOG_PACKET_HEADER;
|
2015-04-29 08:11:24 -03:00
|
|
|
uint64_t time_us;
|
2013-02-07 18:21:22 -04:00
|
|
|
int16_t steer_out;
|
2013-01-26 05:46:16 -04:00
|
|
|
int16_t roll;
|
|
|
|
int16_t pitch;
|
|
|
|
int16_t throttle_out;
|
2013-04-19 04:53:07 -03:00
|
|
|
float accel_y;
|
2013-01-26 05:46:16 -04:00
|
|
|
};
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2013-01-26 05:46:16 -04:00
|
|
|
// Write a control tuning packet. Total length : 22 bytes
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::Log_Write_Control_Tuning()
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2013-01-26 05:46:16 -04:00
|
|
|
Vector3f accel = ins.get_accel();
|
|
|
|
struct log_Control_Tuning pkt = {
|
2013-04-19 04:53:07 -03:00
|
|
|
LOG_PACKET_HEADER_INIT(LOG_CTUN_MSG),
|
2015-04-29 08:11:24 -03:00
|
|
|
time_us : hal.scheduler->micros64(),
|
2013-06-03 06:33:59 -03:00
|
|
|
steer_out : (int16_t)channel_steer->servo_out,
|
2013-01-26 05:46:16 -04:00
|
|
|
roll : (int16_t)ahrs.roll_sensor,
|
|
|
|
pitch : (int16_t)ahrs.pitch_sensor,
|
2013-06-03 06:33:59 -03:00
|
|
|
throttle_out : (int16_t)channel_throttle->servo_out,
|
2013-04-19 04:53:07 -03:00
|
|
|
accel_y : accel.y
|
2013-01-26 05:46:16 -04:00
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2013-04-19 04:53:07 -03:00
|
|
|
struct PACKED log_Nav_Tuning {
|
2013-01-26 05:46:16 -04:00
|
|
|
LOG_PACKET_HEADER;
|
2015-04-29 08:11:24 -03:00
|
|
|
uint64_t time_us;
|
2013-01-26 05:46:16 -04:00
|
|
|
uint16_t yaw;
|
2013-03-01 07:32:57 -04:00
|
|
|
float wp_distance;
|
2013-01-26 05:46:16 -04:00
|
|
|
uint16_t target_bearing_cd;
|
|
|
|
uint16_t nav_bearing_cd;
|
2013-04-18 21:23:57 -03:00
|
|
|
int8_t throttle;
|
2013-01-26 05:46:16 -04:00
|
|
|
};
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2013-01-26 05:46:16 -04:00
|
|
|
// Write a navigation tuning packet. Total length : 18 bytes
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::Log_Write_Nav_Tuning()
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2013-01-26 05:46:16 -04:00
|
|
|
struct log_Nav_Tuning pkt = {
|
2013-04-19 04:53:07 -03:00
|
|
|
LOG_PACKET_HEADER_INIT(LOG_NTUN_MSG),
|
2015-04-29 08:11:24 -03:00
|
|
|
time_us : hal.scheduler->micros64(),
|
2013-01-26 05:46:16 -04:00
|
|
|
yaw : (uint16_t)ahrs.yaw_sensor,
|
2013-03-01 07:32:57 -04:00
|
|
|
wp_distance : wp_distance,
|
2013-06-16 20:50:53 -03:00
|
|
|
target_bearing_cd : (uint16_t)nav_controller->target_bearing_cd(),
|
|
|
|
nav_bearing_cd : (uint16_t)nav_controller->nav_bearing_cd(),
|
2013-06-03 06:33:59 -03:00
|
|
|
throttle : (int8_t)(100 * channel_throttle->norm_output())
|
2013-01-26 05:46:16 -04:00
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2013-04-19 04:53:07 -03:00
|
|
|
// Write an attitude packet
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::Log_Write_Attitude()
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2015-01-16 16:29:09 -04:00
|
|
|
Vector3f targets(0,0,0); // Rover does not have attitude targets, use place-holder for commonality with Dataflash Log_Write_Attitude message
|
|
|
|
|
|
|
|
DataFlash.Log_Write_Attitude(ahrs, targets);
|
|
|
|
|
2014-03-02 18:03:48 -04:00
|
|
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
2015-02-05 02:23:49 -04:00
|
|
|
#if defined(OPTFLOW) and (OPTFLOW == ENABLED)
|
2014-12-30 23:24:01 -04:00
|
|
|
DataFlash.Log_Write_EKF(ahrs,optflow.enabled());
|
|
|
|
#else
|
|
|
|
DataFlash.Log_Write_EKF(ahrs,false);
|
|
|
|
#endif
|
2014-03-02 18:03:48 -04:00
|
|
|
DataFlash.Log_Write_AHRS2(ahrs);
|
|
|
|
#endif
|
2015-05-15 01:24:55 -03:00
|
|
|
DataFlash.Log_Write_POS(ahrs);
|
2015-06-18 04:34:58 -03:00
|
|
|
|
|
|
|
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
|
|
|
|
DataFlash.Log_Write_PID(LOG_PIDY_MSG, steerController.get_pid_info());
|
|
|
|
#endif
|
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2013-04-19 04:53:07 -03:00
|
|
|
struct PACKED log_Sonar {
|
2013-04-18 21:23:57 -03:00
|
|
|
LOG_PACKET_HEADER;
|
2015-04-29 08:11:24 -03:00
|
|
|
uint64_t time_us;
|
2013-06-16 20:50:53 -03:00
|
|
|
float lateral_accel;
|
2013-04-18 21:23:57 -03:00
|
|
|
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
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::Log_Write_Sonar()
|
2013-04-18 21:23:57 -03:00
|
|
|
{
|
|
|
|
uint16_t turn_time = 0;
|
2015-05-04 23:34:02 -03:00
|
|
|
if (!is_zero(obstacle.turn_angle)) {
|
2013-04-18 22:03:43 -03:00
|
|
|
turn_time = hal.scheduler->millis() - obstacle.detected_time_ms;
|
2013-04-18 21:23:57 -03:00
|
|
|
}
|
|
|
|
struct log_Sonar pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_SONAR_MSG),
|
2015-04-29 08:11:24 -03:00
|
|
|
time_us : hal.scheduler->micros64(),
|
2013-06-16 20:50:53 -03:00
|
|
|
lateral_accel : lateral_acceleration,
|
2014-06-27 00:18:20 -03:00
|
|
|
sonar1_distance : (uint16_t)sonar.distance_cm(0),
|
|
|
|
sonar2_distance : (uint16_t)sonar.distance_cm(1),
|
2013-04-18 21:23:57 -03:00
|
|
|
detected_count : obstacle.detected_count,
|
|
|
|
turn_angle : (int8_t)obstacle.turn_angle,
|
|
|
|
turn_time : turn_time,
|
|
|
|
ground_speed : (uint16_t)(ground_speed*100),
|
2013-06-03 06:33:59 -03:00
|
|
|
throttle : (int8_t)(100 * channel_throttle->norm_output())
|
2013-04-18 21:23:57 -03:00
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
}
|
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::Log_Write_Current()
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2015-01-16 16:22:00 -04:00
|
|
|
DataFlash.Log_Write_Current(battery, channel_throttle->control_in);
|
2014-02-13 07:10:11 -04:00
|
|
|
|
|
|
|
// also write power status
|
|
|
|
DataFlash.Log_Write_Power();
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::Log_Write_RC(void)
|
2013-12-29 19:24:01 -04:00
|
|
|
{
|
|
|
|
DataFlash.Log_Write_RCIN();
|
|
|
|
DataFlash.Log_Write_RCOUT();
|
|
|
|
}
|
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::Log_Write_Baro(void)
|
2014-02-23 18:25:50 -04:00
|
|
|
{
|
|
|
|
DataFlash.Log_Write_Baro(barometer);
|
|
|
|
}
|
|
|
|
|
2015-05-13 00:16:45 -03:00
|
|
|
const LogStructure Rover::log_structure[] PROGMEM = {
|
2013-04-19 04:53:07 -03:00
|
|
|
LOG_COMMON_STRUCTURES,
|
|
|
|
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
2015-04-29 08:11:24 -03:00
|
|
|
"PM", "QIHIhhhBH", "TimeUS,LTime,MLC,gDt,GDx,GDy,GDz,I2CErr,INSErr" },
|
2013-04-19 04:53:07 -03:00
|
|
|
{ LOG_STARTUP_MSG, sizeof(log_Startup),
|
2015-04-29 08:11:24 -03:00
|
|
|
"STRT", "QBH", "TimeUS,SType,CTot" },
|
2013-04-19 04:53:07 -03:00
|
|
|
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning),
|
2015-04-29 08:11:24 -03:00
|
|
|
"CTUN", "Qhcchf", "TimeUS,Steer,Roll,Pitch,ThrOut,AccY" },
|
2013-04-19 04:53:07 -03:00
|
|
|
{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning),
|
2015-04-29 08:11:24 -03:00
|
|
|
"NTUN", "QHfHHb", "TimeUS,Yaw,WpDist,TargBrg,NavBrg,Thr" },
|
2013-04-19 04:53:07 -03:00
|
|
|
{ LOG_SONAR_MSG, sizeof(log_Sonar),
|
2015-04-29 08:11:24 -03:00
|
|
|
"SONR", "QfHHHbHCb", "TimeUS,LatAcc,S1Dist,S2Dist,DCnt,TAng,TTim,Spd,Thr" },
|
2013-12-15 20:14:58 -04:00
|
|
|
{ LOG_STEERING_MSG, sizeof(log_Steering),
|
2015-04-29 08:11:24 -03:00
|
|
|
"STER", "Qff", "TimeUS,Demanded,Achieved" },
|
2013-04-19 04:53:07 -03:00
|
|
|
};
|
|
|
|
|
2015-05-13 00:16:45 -03:00
|
|
|
void Rover::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();
|
|
|
|
}
|
|
|
|
if (g.log_bitmask != 0) {
|
|
|
|
start_logging();
|
|
|
|
}
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2015-03-13 08:40:06 -03:00
|
|
|
#if CLI_ENABLED == ENABLED
|
2012-04-30 04:17:14 -03:00
|
|
|
// Read the DataFlash log memory : Packet Parser
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2013-11-08 07:29:13 -04:00
|
|
|
cliSerial->printf_P(PSTR("\n" FIRMWARE_STRING
|
2013-01-14 23:03:17 -04:00
|
|
|
"\nFree RAM: %u\n"),
|
2013-12-28 01:02:45 -04:00
|
|
|
(unsigned)hal.util->available_memory());
|
2013-04-18 21:23:57 -03:00
|
|
|
|
|
|
|
cliSerial->println_P(PSTR(HAL_BOARD_NAME));
|
|
|
|
|
2015-05-24 20:24:11 -03:00
|
|
|
DataFlash.LogReadProcess(log_num, start_page, end_page,
|
|
|
|
FUNCTOR_BIND_MEMBER(&Rover::print_mode, void, AP_HAL::BetterStream *, uint8_t),
|
2013-04-20 02:18:42 -03:00
|
|
|
cliSerial);
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
2015-03-13 08:40:06 -03:00
|
|
|
#endif // CLI_ENABLED
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2013-04-19 10:19:37 -03:00
|
|
|
// start a new log
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::start_logging()
|
2013-04-19 10:19:37 -03:00
|
|
|
{
|
2014-01-13 23:40:10 -04:00
|
|
|
in_mavlink_delay = true;
|
2013-12-16 20:32:40 -04:00
|
|
|
DataFlash.StartNewLog();
|
2015-06-23 22:09:52 -03:00
|
|
|
DataFlash.Log_Write_SysInfo(PSTR(FIRMWARE_STRING));
|
2014-01-13 23:40:10 -04:00
|
|
|
in_mavlink_delay = false;
|
2013-04-19 10:19:37 -03:00
|
|
|
}
|
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
#else // LOGGING_ENABLED
|
|
|
|
|
|
|
|
// dummy functions
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::Log_Write_Startup(uint8_t type) {}
|
|
|
|
void Rover::Log_Write_EntireMission() {}
|
|
|
|
void Rover::Log_Write_Current() {}
|
|
|
|
void Rover::Log_Write_Nav_Tuning() {}
|
|
|
|
void Rover::Log_Write_Performance() {}
|
|
|
|
void Rover::Log_Write_Cmd(const AP_Mission::Mission_Command &cmd) {}
|
|
|
|
int8_t Rover::process_logs(uint8_t argc, const Menu::arg *argv) { return 0; }
|
|
|
|
void Rover::Log_Write_Control_Tuning() {}
|
|
|
|
void Rover::Log_Write_Sonar() {}
|
|
|
|
void Rover::Log_Write_Attitude() {}
|
|
|
|
void Rover::start_logging() {}
|
|
|
|
void Rover::Log_Write_RC(void) {}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
|
|
|
#endif // LOGGING_ENABLED
|
2013-02-28 16:40:47 -04:00
|
|
|
|