uncrustify ArduCopter/Log.pde

This commit is contained in:
uncrustify 2012-08-21 19:19:50 -07:00 committed by Pat Hickey
parent 0f0811d597
commit dfc77d37ca

View File

@ -5,9 +5,9 @@
// Code to Write and Read packets from DataFlash log memory // Code to Write and Read packets from DataFlash log memory
// Code to interact with the user to dump or erase logs // Code to interact with the user to dump or erase logs
#define HEAD_BYTE1 0xA3 // Decimal 163 #define HEAD_BYTE1 0xA3 // Decimal 163
#define HEAD_BYTE2 0x95 // Decimal 149 #define HEAD_BYTE2 0x95 // Decimal 149
#define END_BYTE 0xBA // Decimal 186 #define END_BYTE 0xBA // Decimal 186
// These are function definitions so the Menu can be constructed before the functions // These are function definitions so the Menu can be constructed before the functions
@ -22,15 +22,15 @@ static int8_t select_logs(uint8_t argc, const Menu::arg *argv);
// printf_P is a version of print_f that reads from flash memory // printf_P is a version of print_f that reads from flash memory
//static int8_t help_log(uint8_t argc, const Menu::arg *argv) //static int8_t help_log(uint8_t argc, const Menu::arg *argv)
/*{ /*{
Serial.printf_P(PSTR("\n" * Serial.printf_P(PSTR("\n"
"Commands:\n" * "Commands:\n"
" dump <n>" * " dump <n>"
" erase (all logs)\n" * " erase (all logs)\n"
" enable <name> | all\n" * " enable <name> | all\n"
" disable <name> | all\n" * " disable <name> | all\n"
"\n")); * "\n"));
return 0; * return 0;
}*/ * }*/
// Creates a constant array of structs representing menu options // Creates a constant array of structs representing menu options
// and stores them in Flash memory, not RAM. // and stores them in Flash memory, not RAM.
@ -95,7 +95,7 @@ print_log_menu(void)
}else{ }else{
Serial.printf_P(PSTR("\n%u logs\n"), (unsigned)num_logs); Serial.printf_P(PSTR("\n%u logs\n"), (unsigned)num_logs);
for(int16_t i=num_logs;i>=1;i--) { for(int16_t i=num_logs; i>=1; i--) {
int16_t last_log_start = log_start, last_log_end = log_end; int16_t last_log_start = log_start, last_log_end = log_end;
temp = last_log_num-i+1; temp = last_log_num-i+1;
DataFlash.get_log_boundaries(temp, log_start, log_end); DataFlash.get_log_boundaries(temp, log_start, log_end);
@ -141,9 +141,9 @@ dump_log(uint8_t argc, const Menu::arg *argv)
DataFlash.get_log_boundaries(dump_log, dump_log_start, dump_log_end); DataFlash.get_log_boundaries(dump_log, dump_log_start, dump_log_end);
/*Serial.printf_P(PSTR("Dumping Log number %d, start %d, end %d\n"), /*Serial.printf_P(PSTR("Dumping Log number %d, start %d, end %d\n"),
dump_log, * dump_log,
dump_log_start, * dump_log_start,
dump_log_end); * dump_log_end);
*/ */
Log_Read(dump_log_start, dump_log_end); Log_Read(dump_log_start, dump_log_end);
//Serial.printf_P(PSTR("Done\n")); //Serial.printf_P(PSTR("Done\n"));
@ -187,7 +187,7 @@ select_logs(uint8_t argc, const Menu::arg *argv)
if (!strcasecmp_P(argv[1].str, PSTR("all"))) { if (!strcasecmp_P(argv[1].str, PSTR("all"))) {
bits = ~0; bits = ~0;
} else { } else {
#define TARG(_s) if (!strcasecmp_P(argv[1].str, PSTR(#_s))) bits |= MASK_LOG_ ## _s #define TARG(_s) if (!strcasecmp_P(argv[1].str, PSTR(# _s))) bits |= MASK_LOG_ ## _s
TARG(ATTITUDE_FAST); TARG(ATTITUDE_FAST);
TARG(ATTITUDE_MED); TARG(ATTITUDE_MED);
TARG(GPS); TARG(GPS);
@ -287,7 +287,7 @@ static void Log_Read_GPS()
(long)temp8); // 8 ground course (long)temp8); // 8 ground course
} }
#if INERTIAL_NAV == ENABLED #if INERTIAL_NAV == ENABLED
static void Log_Write_Raw() static void Log_Write_Raw()
{ {
Vector3f accel = imu.get_accel(); Vector3f accel = imu.get_accel();
@ -314,14 +314,14 @@ static void Log_Write_Raw()
static void Log_Read_Raw() static void Log_Read_Raw()
{ {
/* /*
float logvar; * float logvar;
Serial.printf_P(PSTR("RAW,")); * Serial.printf_P(PSTR("RAW,"));
for (int16_t y = 0; y < 9; y++) { * for (int16_t y = 0; y < 9; y++) {
logvar = get_float(DataFlash.ReadLong()); * logvar = get_float(DataFlash.ReadLong());
Serial.print(logvar); * Serial.print(logvar);
Serial.print(", "); * Serial.print(", ");
} * }
Serial.println(" "); * Serial.println(" ");
*/ */
float vx = get_float(DataFlash.ReadLong()); float vx = get_float(DataFlash.ReadLong());
@ -340,7 +340,7 @@ static void Log_Read_Raw()
(int)sz); (int)sz);
} }
#else #else
static void Log_Write_Raw() static void Log_Write_Raw()
{ {
Vector3f gyro = imu.get_gyro(); Vector3f gyro = imu.get_gyro();
@ -373,7 +373,7 @@ static void Log_Read_Raw()
} }
Serial.println(" "); Serial.println(" ");
} }
#endif #endif
// Write an Current data packet. Total length : 16 bytes // Write an Current data packet. Total length : 16 bytes
@ -418,52 +418,52 @@ static void Log_Write_Motors()
DataFlash.WriteByte(LOG_MOTORS_MSG); DataFlash.WriteByte(LOG_MOTORS_MSG);
#if FRAME_CONFIG == TRI_FRAME #if FRAME_CONFIG == TRI_FRAME
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//1 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]); //1
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//2 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]); //2
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//3 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]); //3
DataFlash.WriteInt(g.rc_4.radio_out);//4 DataFlash.WriteInt(g.rc_4.radio_out); //4
#elif FRAME_CONFIG == HEXA_FRAME #elif FRAME_CONFIG == HEXA_FRAME
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//1 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]); //1
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//2 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]); //2
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]);//3 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]); //3
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//4 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]); //4
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_5]);//5 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_5]); //5
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_6]);//6 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_6]); //6
#elif FRAME_CONFIG == Y6_FRAME #elif FRAME_CONFIG == Y6_FRAME
//left //left
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//1 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]); //1
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]);//2 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]); //2
//right //right
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_5]);//3 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_5]); //3
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//4 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]); //4
//back //back
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_6]);//5 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_6]); //5
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//6 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]); //6
#elif FRAME_CONFIG == OCTA_FRAME || FRAME_CONFIG == OCTA_QUAD_FRAME #elif FRAME_CONFIG == OCTA_FRAME || FRAME_CONFIG == OCTA_QUAD_FRAME
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//1 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]); //1
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//2 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]); //2
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]);//3 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]); //3
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//4 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]); //4
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_5]);//5 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_5]); //5
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_6]); //6 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_6]); //6
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_7]);//7 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_7]); //7
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_8]);//8 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_8]); //8
#elif FRAME_CONFIG == HELI_FRAME #elif FRAME_CONFIG == HELI_FRAME
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//1 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]); //1
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//2 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]); //2
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]);//3 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]); //3
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//4 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]); //4
DataFlash.WriteInt(motors.ext_gyro_gain);//5 DataFlash.WriteInt(motors.ext_gyro_gain); //5
#else // quads #else // quads
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//1 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]); //1
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//2 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]); //2
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]);//3 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]); //3
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//4 DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]); //4
#endif #endif
DataFlash.WriteByte(END_BYTE); DataFlash.WriteByte(END_BYTE);
@ -549,8 +549,8 @@ static void Log_Write_Optflow()
DataFlash.WriteInt((int)optflow.surface_quality); DataFlash.WriteInt((int)optflow.surface_quality);
DataFlash.WriteInt((int)optflow.x_cm); DataFlash.WriteInt((int)optflow.x_cm);
DataFlash.WriteInt((int)optflow.y_cm); DataFlash.WriteInt((int)optflow.y_cm);
DataFlash.WriteLong(optflow.vlat);//optflow_offset.lat + optflow.lat); DataFlash.WriteLong(optflow.vlat); //optflow_offset.lat + optflow.lat);
DataFlash.WriteLong(optflow.vlon);//optflow_offset.lng + optflow.lng); DataFlash.WriteLong(optflow.vlon); //optflow_offset.lng + optflow.lng);
DataFlash.WriteLong(of_roll); DataFlash.WriteLong(of_roll);
DataFlash.WriteLong(of_pitch); DataFlash.WriteLong(of_pitch);
DataFlash.WriteByte(END_BYTE); DataFlash.WriteByte(END_BYTE);
@ -614,7 +614,7 @@ static void Log_Read_Nav_Tuning()
Serial.printf_P(PSTR("NTUN, ")); Serial.printf_P(PSTR("NTUN, "));
for(int8_t i = 1; i < 10; i++ ){ for(int8_t i = 1; i < 10; i++ ) {
temp = DataFlash.ReadInt(); temp = DataFlash.ReadInt();
Serial.printf("%d, ", (int)temp); Serial.printf("%d, ", (int)temp);
} }
@ -640,7 +640,7 @@ static void Log_Write_Control_Tuning()
DataFlash.WriteInt(climb_rate_actual); // 7 DataFlash.WriteInt(climb_rate_actual); // 7
DataFlash.WriteInt(g.rc_3.servo_out); // 8 DataFlash.WriteInt(g.rc_3.servo_out); // 8
DataFlash.WriteInt(g.pi_alt_hold.get_integrator()); // 9 DataFlash.WriteInt(g.pi_alt_hold.get_integrator()); // 9
DataFlash.WriteInt(g.pid_throttle.get_integrator());// 10 DataFlash.WriteInt(g.pid_throttle.get_integrator()); // 10
DataFlash.WriteByte(END_BYTE); DataFlash.WriteByte(END_BYTE);
} }
@ -652,7 +652,7 @@ static void Log_Read_Control_Tuning()
Serial.printf_P(PSTR("CTUN, ")); Serial.printf_P(PSTR("CTUN, "));
for(uint8_t i = 1; i < 10; i++ ){ for(uint8_t i = 1; i < 10; i++ ) {
temp = DataFlash.ReadInt(); temp = DataFlash.ReadInt();
Serial.printf("%d, ", (int)temp); Serial.printf("%d, ", (int)temp);
} }
@ -842,7 +842,7 @@ static void Log_Read_Data()
int8_t temp1 = DataFlash.ReadByte(); int8_t temp1 = DataFlash.ReadByte();
int8_t temp2 = DataFlash.ReadByte(); int8_t temp2 = DataFlash.ReadByte();
if(temp2 == 1){ if(temp2 == 1) {
float temp3 = get_float(DataFlash.ReadLong()); float temp3 = get_float(DataFlash.ReadLong());
Serial.printf_P(PSTR("DATA: %d, %1.6f\n"), (int)temp1, temp3); Serial.printf_P(PSTR("DATA: %d, %1.6f\n"), (int)temp1, temp3);
}else{ }else{
@ -902,17 +902,17 @@ static void Log_Read(int16_t start_page, int16_t end_page)
Serial.printf_P(PSTR("\n" THISFIRMWARE Serial.printf_P(PSTR("\n" THISFIRMWARE
"\nFree RAM: %u\n"), "\nFree RAM: %u\n"),
(unsigned)memcheck_available_memory()); (unsigned) memcheck_available_memory());
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 #if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
Serial.printf_P(PSTR("APM 2\n")); Serial.printf_P(PSTR("APM 2\n"));
#elif CONFIG_APM_HARDWARE == APM2_BETA_HARDWARE #elif CONFIG_APM_HARDWARE == APM2_BETA_HARDWARE
Serial.printf_P(PSTR("APM 2Beta\n")); Serial.printf_P(PSTR("APM 2Beta\n"));
#else #else
Serial.printf_P(PSTR("APM 1\n")); Serial.printf_P(PSTR("APM 1\n"));
#endif #endif
if(start_page > end_page){ if(start_page > end_page) {
packet_count = Log_Read_Process(start_page, DataFlash.df_NumPages); packet_count = Log_Read_Process(start_page, DataFlash.df_NumPages);
packet_count += Log_Read_Process(1, end_page); packet_count += Log_Read_Process(1, end_page);
} else { } else {
@ -932,12 +932,12 @@ static int16_t Log_Read_Process(int16_t start_page, int16_t end_page)
DataFlash.StartRead(start_page); DataFlash.StartRead(start_page);
while (page < end_page && page != -1){ while (page < end_page && page != -1) {
data = DataFlash.ReadByte(); data = DataFlash.ReadByte();
// This is a state machine to read the packets // This is a state machine to read the packets
switch(log_step){ switch(log_step) {
case 0: case 0:
if(data == HEAD_BYTE1) // Head byte 1 if(data == HEAD_BYTE1) // Head byte 1
log_step++; log_step++;
@ -954,7 +954,7 @@ static int16_t Log_Read_Process(int16_t start_page, int16_t end_page)
case 2: case 2:
log_step = 0; log_step = 0;
switch(data){ switch(data) {
case LOG_ATTITUDE_MSG: case LOG_ATTITUDE_MSG:
Log_Read_Attitude(); Log_Read_Attitude();
break; break;
@ -1013,7 +1013,7 @@ static int16_t Log_Read_Process(int16_t start_page, int16_t end_page)
} }
break; break;
case 3: case 3:
if(data == END_BYTE){ if(data == END_BYTE) {
packet_count++; packet_count++;
}else{ }else{
Serial.printf_P(PSTR("Error Reading END_BYTE: %d\n"),data); Serial.printf_P(PSTR("Error Reading END_BYTE: %d\n"),data);
@ -1029,23 +1029,42 @@ static int16_t Log_Read_Process(int16_t start_page, int16_t end_page)
#else // LOGGING_ENABLED #else // LOGGING_ENABLED
static void Log_Write_Startup() {} static void Log_Write_Startup() {
static void Log_Read_Startup() {} }
static void Log_Read(int16_t start_page, int16_t end_page) {} static void Log_Read_Startup() {
static void Log_Write_Cmd(byte num, struct Location *wp) {} }
static void Log_Write_Mode(byte mode) {} static void Log_Read(int16_t start_page, int16_t end_page) {
static void Log_Write_Raw() {} }
static void Log_Write_GPS() {} static void Log_Write_Cmd(byte num, struct Location *wp) {
static void Log_Write_Current() {} }
static void Log_Write_Attitude() {} static void Log_Write_Mode(byte mode) {
static void Log_Write_Data(int8_t _type, float _data){} }
static void Log_Write_Data(int8_t _type, int32_t _data){} static void Log_Write_Raw() {
static void Log_Write_Optflow() {} }
static void Log_Write_Nav_Tuning() {} static void Log_Write_GPS() {
static void Log_Write_Control_Tuning() {} }
static void Log_Write_Motors() {} static void Log_Write_Current() {
static void Log_Write_Performance() {} }
static void Log_Write_PID() {} static void Log_Write_Attitude() {
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) { return 0; } }
static void Log_Write_Data(int8_t _type, float _data){
}
static void Log_Write_Data(int8_t _type, int32_t _data){
}
static void Log_Write_Optflow() {
}
static void Log_Write_Nav_Tuning() {
}
static void Log_Write_Control_Tuning() {
}
static void Log_Write_Motors() {
}
static void Log_Write_Performance() {
}
static void Log_Write_PID() {
}
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) {
return 0;
}
#endif // LOGGING_DISABLED #endif // LOGGING_DISABLED