Rover: Log.cpp correct whitespace, remove tabs

This commit is contained in:
Pierre Kancir 2016-12-20 14:28:58 +01:00 committed by Randy Mackay
parent d33f67e0c4
commit 5858c84f83

View File

@ -12,10 +12,10 @@
// User enters the string in the console to call the functions on the right. // User enters the string in the console to call the functions on the right.
// See class Menu in AP_Coommon for implementation details // See class Menu in AP_Coommon for implementation details
static const struct Menu::command log_menu_commands[] = { static const struct Menu::command log_menu_commands[] = {
{"dump", MENU_FUNC(dump_log)}, {"dump", MENU_FUNC(dump_log)},
{"erase", MENU_FUNC(erase_logs)}, {"erase", MENU_FUNC(erase_logs)},
{"enable", MENU_FUNC(select_logs)}, {"enable", MENU_FUNC(select_logs)},
{"disable", MENU_FUNC(select_logs)} {"disable", MENU_FUNC(select_logs)}
}; };
// A Macro to create the Menu // A Macro to create the Menu
@ -23,37 +23,37 @@ MENU2(log_menu, "Log", log_menu_commands, FUNCTOR_BIND(&rover, &Rover::print_log
bool Rover::print_log_menu(void) bool Rover::print_log_menu(void)
{ {
cliSerial->print("logs enabled: "); cliSerial->print("logs enabled: ");
if (0 == g.log_bitmask) { if (0 == g.log_bitmask) {
cliSerial->print("none"); cliSerial->print("none");
}else{ } else {
// Macro to make the following code a bit easier on the eye. // Macro to make the following code a bit easier on the eye.
// Pass it the capitalised name of the log option, as defined // Pass it the capitalised name of the log option, as defined
// in defines.h but without the LOG_ prefix. It will check for // 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. // 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(" %s", #_s) #define PLOG(_s) if (g.log_bitmask & MASK_LOG_ ## _s) cliSerial->printf(" %s", #_s)
PLOG(ATTITUDE_FAST); PLOG(ATTITUDE_FAST);
PLOG(ATTITUDE_MED); PLOG(ATTITUDE_MED);
PLOG(GPS); PLOG(GPS);
PLOG(PM); PLOG(PM);
PLOG(CTUN); PLOG(CTUN);
PLOG(NTUN); PLOG(NTUN);
PLOG(MODE); PLOG(MODE);
PLOG(IMU); PLOG(IMU);
PLOG(CMD); PLOG(CMD);
PLOG(CURRENT); PLOG(CURRENT);
PLOG(SONAR); PLOG(SONAR);
PLOG(COMPASS); PLOG(COMPASS);
PLOG(CAMERA); PLOG(CAMERA);
PLOG(STEERING); PLOG(STEERING);
#undef PLOG #undef PLOG
} }
cliSerial->println(); cliSerial->println();
DataFlash.ListAvailableLogs(cliSerial); DataFlash.ListAvailableLogs(cliSerial);
return(true); return(true);
} }
int8_t Rover::dump_log(uint8_t argc, const Menu::arg *argv) int8_t Rover::dump_log(uint8_t argc, const Menu::arg *argv)
@ -93,63 +93,63 @@ int8_t Rover::erase_logs(uint8_t argc, const Menu::arg *argv)
int8_t Rover::select_logs(uint8_t argc, const Menu::arg *argv) int8_t Rover::select_logs(uint8_t argc, const Menu::arg *argv)
{ {
uint16_t bits; uint16_t bits;
if (argc != 2) { if (argc != 2) {
cliSerial->println("missing log type"); cliSerial->println("missing log type");
return(-1); return(-1);
} }
bits = 0; bits = 0;
// Macro to make the following code a bit easier on the eye. // Macro to make the following code a bit easier on the eye.
// Pass it the capitalised name of the log option, as defined // Pass it the capitalised name of the log option, as defined
// in defines.h but without the LOG_ prefix. It will check for // 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 // that name as the argument to the command, and set the bit in
// bits accordingly. // bits accordingly.
// //
if (!strcasecmp(argv[1].str, "all")) { if (!strcasecmp(argv[1].str, "all")) {
bits = ~0; bits = ~0;
} else { } else {
#define TARG(_s) if (!strcasecmp(argv[1].str, #_s)) bits |= MASK_LOG_ ## _s #define TARG(_s) if (!strcasecmp(argv[1].str, #_s)) bits |= MASK_LOG_ ## _s
TARG(ATTITUDE_FAST); TARG(ATTITUDE_FAST);
TARG(ATTITUDE_MED); TARG(ATTITUDE_MED);
TARG(GPS); TARG(GPS);
TARG(PM); TARG(PM);
TARG(CTUN); TARG(CTUN);
TARG(NTUN); TARG(NTUN);
TARG(MODE); TARG(MODE);
TARG(IMU); TARG(IMU);
TARG(CMD); TARG(CMD);
TARG(CURRENT); TARG(CURRENT);
TARG(SONAR); TARG(SONAR);
TARG(COMPASS); TARG(COMPASS);
TARG(CAMERA); TARG(CAMERA);
TARG(STEERING); TARG(STEERING);
#undef TARG #undef TARG
} }
if (!strcasecmp(argv[0].str, "enable")) { if (!strcasecmp(argv[0].str, "enable")) {
g.log_bitmask.set_and_save(g.log_bitmask | bits); g.log_bitmask.set_and_save(g.log_bitmask | bits);
}else{ } else {
g.log_bitmask.set_and_save(g.log_bitmask & ~bits); g.log_bitmask.set_and_save(g.log_bitmask & ~bits);
} }
return(0); return(0);
} }
int8_t Rover::process_logs(uint8_t argc, const Menu::arg *argv) int8_t Rover::process_logs(uint8_t argc, const Menu::arg *argv)
{ {
log_menu.run(); log_menu.run();
return 0; return 0;
} }
#endif // CLI_ENABLED == ENABLED #endif // CLI_ENABLED == ENABLED
void Rover::do_erase_logs(void) void Rover::do_erase_logs(void)
{ {
cliSerial->printf("\nErasing log...\n"); cliSerial->printf("\nErasing log...\n");
DataFlash.EraseAll(); DataFlash.EraseAll();
cliSerial->printf("\nLog erased.\n"); cliSerial->printf("\nLog erased.\n");
} }
@ -179,7 +179,7 @@ void Rover::Log_Write_Performance()
gyro_drift_y : (int16_t)(ahrs.get_gyro_drift().y * 1000), gyro_drift_y : (int16_t)(ahrs.get_gyro_drift().y * 1000),
gyro_drift_z : (int16_t)(ahrs.get_gyro_drift().z * 1000), gyro_drift_z : (int16_t)(ahrs.get_gyro_drift().z * 1000),
i2c_lockup_count: 0, i2c_lockup_count: 0,
ins_error_count : ins.error_count() ins_error_count : ins.error_count()
}; };
DataFlash.WriteBlock(&pkt, sizeof(pkt)); DataFlash.WriteBlock(&pkt, sizeof(pkt));
} }
@ -277,16 +277,16 @@ void Rover::Log_Write_Nav_Tuning()
// Write an attitude packet // Write an attitude packet
void Rover::Log_Write_Attitude() void Rover::Log_Write_Attitude()
{ {
Vector3f targets(0,0,0); // Rover does not have attitude targets, use place-holder for commonality with Dataflash Log_Write_Attitude message 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); DataFlash.Log_Write_Attitude(ahrs, targets);
#if AP_AHRS_NAVEKF_AVAILABLE #if AP_AHRS_NAVEKF_AVAILABLE
#if defined(OPTFLOW) and (OPTFLOW == ENABLED) #if defined(OPTFLOW) and (OPTFLOW == ENABLED)
DataFlash.Log_Write_EKF(ahrs,optflow.enabled()); DataFlash.Log_Write_EKF(ahrs, optflow.enabled());
#else #else
DataFlash.Log_Write_EKF(ahrs,false); DataFlash.Log_Write_EKF(ahrs, false);
#endif #endif
DataFlash.Log_Write_AHRS2(ahrs); DataFlash.Log_Write_AHRS2(ahrs);
#endif #endif
DataFlash.Log_Write_POS(ahrs); DataFlash.Log_Write_POS(ahrs);
@ -439,19 +439,19 @@ void Rover::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_targ
const LogStructure Rover::log_structure[] = { const LogStructure Rover::log_structure[] = {
LOG_COMMON_STRUCTURES, LOG_COMMON_STRUCTURES,
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance), { LOG_PERFORMANCE_MSG, sizeof(log_Performance),
"PM", "QIHIhhhBH", "TimeUS,LTime,MLC,gDt,GDx,GDy,GDz,I2CErr,INSErr" }, "PM", "QIHIhhhBH", "TimeUS,LTime,MLC,gDt,GDx,GDy,GDz,I2CErr,INSErr" },
{ LOG_STARTUP_MSG, sizeof(log_Startup), { LOG_STARTUP_MSG, sizeof(log_Startup),
"STRT", "QBH", "TimeUS,SType,CTot" }, "STRT", "QBH", "TimeUS,SType,CTot" },
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning), { LOG_CTUN_MSG, sizeof(log_Control_Tuning),
"CTUN", "Qhcchf", "TimeUS,Steer,Roll,Pitch,ThrOut,AccY" }, "CTUN", "Qhcchf", "TimeUS,Steer,Roll,Pitch,ThrOut,AccY" },
{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning), { LOG_NTUN_MSG, sizeof(log_Nav_Tuning),
"NTUN", "QHfHHbf", "TimeUS,Yaw,WpDist,TargBrg,NavBrg,Thr,XT" }, "NTUN", "QHfHHbf", "TimeUS,Yaw,WpDist,TargBrg,NavBrg,Thr,XT" },
{ LOG_SONAR_MSG, sizeof(log_Sonar), { LOG_SONAR_MSG, sizeof(log_Sonar),
"SONR", "QfHHHbHCb", "TimeUS,LatAcc,S1Dist,S2Dist,DCnt,TAng,TTim,Spd,Thr" }, "SONR", "QfHHHbHCb", "TimeUS,LatAcc,S1Dist,S2Dist,DCnt,TAng,TTim,Spd,Thr" },
{ LOG_ARM_DISARM_MSG, sizeof(log_Arm_Disarm), { LOG_ARM_DISARM_MSG, sizeof(log_Arm_Disarm),
"ARM", "QBH", "TimeUS,ArmState,ArmChecks" }, "ARM", "QBH", "TimeUS,ArmState,ArmChecks" },
{ LOG_STEERING_MSG, sizeof(log_Steering), { LOG_STEERING_MSG, sizeof(log_Steering),
"STER", "Qff", "TimeUS,Demanded,Achieved" }, "STER", "Qff", "TimeUS,Demanded,Achieved" },
{ LOG_GUIDEDTARGET_MSG, sizeof(log_GuidedTarget), { LOG_GUIDEDTARGET_MSG, sizeof(log_GuidedTarget),
"GUID", "QBffffff", "TimeUS,Type,pX,pY,pZ,vX,vY,vZ" }, "GUID", "QBffffff", "TimeUS,Type,pX,pY,pZ,vX,vY,vZ" },
@ -461,21 +461,21 @@ const LogStructure Rover::log_structure[] = {
void Rover::log_init(void) void Rover::log_init(void)
{ {
DataFlash.Init(log_structure, ARRAY_SIZE(log_structure)); DataFlash.Init(log_structure, ARRAY_SIZE(log_structure));
if (!DataFlash.CardInserted()) { if (!DataFlash.CardInserted()) {
gcs_send_text(MAV_SEVERITY_WARNING, "No dataflash card inserted"); gcs_send_text(MAV_SEVERITY_WARNING, "No dataflash card inserted");
} else if (DataFlash.NeedPrep()) { } else if (DataFlash.NeedPrep()) {
gcs_send_text(MAV_SEVERITY_INFO, "Preparing log system"); gcs_send_text(MAV_SEVERITY_INFO, "Preparing log system");
DataFlash.Prep(); DataFlash.Prep();
gcs_send_text(MAV_SEVERITY_INFO, "Prepared log system"); gcs_send_text(MAV_SEVERITY_INFO, "Prepared log system");
for (uint8_t i=0; i<num_gcs; i++) { for (uint8_t i=0; i < num_gcs; i++) {
gcs[i].reset_cli_timeout(); gcs[i].reset_cli_timeout();
} }
} }
if (g.log_bitmask != 0) { if (g.log_bitmask != 0) {
start_logging(); start_logging();
} }
} }
#if CLI_ENABLED == ENABLED #if CLI_ENABLED == ENABLED
@ -488,11 +488,11 @@ void Rover::Log_Read(uint16_t list_entry, uint16_t start_page, uint16_t end_page
cliSerial->println(HAL_BOARD_NAME); cliSerial->println(HAL_BOARD_NAME);
DataFlash.LogReadProcess(list_entry, start_page, end_page, DataFlash.LogReadProcess(list_entry, start_page, end_page,
FUNCTOR_BIND_MEMBER(&Rover::print_mode, void, AP_HAL::BetterStream *, uint8_t), FUNCTOR_BIND_MEMBER(&Rover::print_mode, void, AP_HAL::BetterStream *, uint8_t),
cliSerial); cliSerial);
} }
#endif // CLI_ENABLED #endif // CLI_ENABLED
void Rover::Log_Write_Vehicle_Startup_Messages() void Rover::Log_Write_Vehicle_Startup_Messages()
{ {
@ -502,7 +502,7 @@ void Rover::Log_Write_Vehicle_Startup_Messages()
} }
// start a new log // start a new log
void Rover::start_logging() void Rover::start_logging()
{ {
in_mavlink_delay = true; in_mavlink_delay = true;
DataFlash.set_mission(&mission); DataFlash.set_mission(&mission);
@ -513,7 +513,7 @@ void Rover::start_logging()
in_mavlink_delay = false; in_mavlink_delay = false;
} }
#else // LOGGING_ENABLED #else // LOGGING_ENABLED
// dummy functions // dummy functions
void Rover::Log_Write_Startup(uint8_t type) {} void Rover::Log_Write_Startup(uint8_t type) {}
@ -527,4 +527,4 @@ void Rover::Log_Write_Attitude() {}
void Rover::start_logging() {} void Rover::start_logging() {}
void Rover::Log_Write_RC(void) {} void Rover::Log_Write_RC(void) {}
#endif // LOGGING_ENABLED #endif // LOGGING_ENABLED