Copter: print flight mode as string

This commit is contained in:
Andrew Tridgell 2013-04-20 15:18:22 +10:00
parent 2e5834cc7f
commit 02c3083f60
4 changed files with 41 additions and 38 deletions

View File

@ -147,6 +147,7 @@ static AP_Scheduler scheduler;
// prototypes // prototypes
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////
static void update_events(void); static void update_events(void);
static void print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode);
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////
// Dataflash // Dataflash
@ -156,8 +157,8 @@ static DataFlash_APM2 DataFlash;
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 #elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
static DataFlash_APM1 DataFlash; static DataFlash_APM1 DataFlash;
#elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL #elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
//static DataFlash_File DataFlash("/tmp/APMlogs"); static DataFlash_File DataFlash("/tmp/APMlogs");
static DataFlash_SITL DataFlash; //static DataFlash_SITL DataFlash;
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4 #elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
static DataFlash_File DataFlash("/fs/microsd/APM/logs"); static DataFlash_File DataFlash("/fs/microsd/APM/logs");
#else #else

View File

@ -170,7 +170,7 @@ struct PACKED log_Current {
float current_total; float current_total;
}; };
// Write an Current data packet. Total length : 16 bytes // Write an Current data packet
static void Log_Write_Current() static void Log_Write_Current()
{ {
struct log_Current pkt = { struct log_Current pkt = {
@ -199,7 +199,7 @@ struct PACKED log_Motors {
#endif #endif
}; };
// Write an Motors packet. Total length : 12 ~ 20 bytes // Write an Motors packet
static void Log_Write_Motors() static void Log_Write_Motors()
{ {
struct log_Motors pkt = { struct log_Motors pkt = {
@ -254,7 +254,7 @@ struct PACKED log_Optflow {
int32_t pitch; int32_t pitch;
}; };
// Write an optical flow packet. Total length : 30 bytes // Write an optical flow packet
static void Log_Write_Optflow() static void Log_Write_Optflow()
{ {
#if OPTFLOW == ENABLED #if OPTFLOW == ENABLED
@ -286,7 +286,7 @@ struct PACKED log_Nav_Tuning {
int16_t lon_speed; int16_t lon_speed;
}; };
// Write an Nav Tuning packet. Total length : 24 bytes // Write an Nav Tuning packet
static void Log_Write_Nav_Tuning() static void Log_Write_Nav_Tuning()
{ {
struct log_Nav_Tuning pkt = { struct log_Nav_Tuning pkt = {
@ -316,7 +316,7 @@ struct PACKED log_Control_Tuning {
int16_t desired_climb_rate; int16_t desired_climb_rate;
}; };
// Write a control tuning packet. Total length : 26 bytes // Write a control tuning packet
static void Log_Write_Control_Tuning() static void Log_Write_Control_Tuning()
{ {
struct log_Control_Tuning pkt = { struct log_Control_Tuning pkt = {
@ -347,7 +347,7 @@ struct PACKED log_Compass {
int16_t motor_offset_z; int16_t motor_offset_z;
}; };
// Write a Compass packet. Total length : 15 bytes // Write a Compass packet
static void Log_Write_Compass() static void Log_Write_Compass()
{ {
Vector3f mag_offsets = compass.get_offsets(); Vector3f mag_offsets = compass.get_offsets();
@ -377,7 +377,7 @@ struct PACKED log_Performance {
uint32_t max_time; uint32_t max_time;
}; };
// Write a performance monitoring packet. Total length : 11 bytes // Write a performance monitoring packet
static void Log_Write_Performance() static void Log_Write_Performance()
{ {
struct log_Performance pkt = { struct log_Performance pkt = {
@ -404,7 +404,7 @@ struct PACKED log_Cmd {
int32_t waypoint_longitude; int32_t waypoint_longitude;
}; };
// Write a command processing packet. Total length : 21 bytes // Write a command processing packet
static void Log_Write_Cmd(uint8_t num, const struct Location *wp) static void Log_Write_Cmd(uint8_t num, const struct Location *wp)
{ {
struct log_Cmd pkt = { struct log_Cmd pkt = {
@ -432,7 +432,7 @@ struct PACKED log_Attitude {
uint16_t nav_yaw; uint16_t nav_yaw;
}; };
// Write an attitude packet. Total length : 16 bytes // Write an attitude packet
static void Log_Write_Attitude() static void Log_Write_Attitude()
{ {
struct log_Attitude pkt = { struct log_Attitude pkt = {
@ -462,7 +462,7 @@ struct PACKED log_INAV {
float inav_lon_from_home; float inav_lon_from_home;
}; };
// Write an INAV packet. Total length : 37 Bytes // Write an INAV packet
static void Log_Write_INAV() static void Log_Write_INAV()
{ {
Vector3f accel_corr = inertial_nav.accel_correction_ef; Vector3f accel_corr = inertial_nav.accel_correction_ef;
@ -489,7 +489,7 @@ struct PACKED log_Mode {
int16_t throttle_cruise; int16_t throttle_cruise;
}; };
// Write a mode packet. Total length : 7 bytes // Write a mode packet
static void Log_Write_Mode(uint8_t mode) static void Log_Write_Mode(uint8_t mode)
{ {
struct log_Mode pkt = { struct log_Mode pkt = {
@ -504,7 +504,7 @@ struct PACKED log_Startup {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
}; };
// Write Startup packet. Total length : 4 bytes // Write Startup packet
static void Log_Write_Startup() static void Log_Write_Startup()
{ {
struct log_Startup pkt = { struct log_Startup pkt = {
@ -636,7 +636,7 @@ struct PACKED log_PID {
float gain; float gain;
}; };
// Write an PID packet. Total length : 28 bytes // Write an PID packet
static void Log_Write_PID(uint8_t pid_id, int32_t error, int32_t p, int32_t i, int32_t d, int32_t output, float gain) static void Log_Write_PID(uint8_t pid_id, int32_t error, int32_t p, int32_t i, int32_t d, int32_t output, float gain)
{ {
struct log_PID pkt = { struct log_PID pkt = {
@ -663,7 +663,7 @@ struct PACKED log_DMP {
}; };
#if SECONDARY_DMP_ENABLED == ENABLED #if SECONDARY_DMP_ENABLED == ENABLED
// Write a DMP attitude packet. Total length : 16 bytes // Write a DMP attitude packet
static void Log_Write_DMP() static void Log_Write_DMP()
{ {
struct log_DMP pkt = { struct log_DMP pkt = {
@ -690,7 +690,7 @@ struct PACKED log_Camera {
uint16_t yaw; uint16_t yaw;
}; };
// Write a Camera packet. Total length : 26 bytes // Write a Camera packet
static void Log_Write_Camera() static void Log_Write_Camera()
{ {
#if CAMERA == ENABLED #if CAMERA == ENABLED
@ -714,7 +714,7 @@ struct PACKED log_Error {
uint8_t error_code; uint8_t error_code;
}; };
// Write an error packet. Total length : 5 bytes // Write an error packet
static void Log_Write_Error(uint8_t sub_system, uint8_t error_code) static void Log_Write_Error(uint8_t sub_system, uint8_t error_code)
{ {
struct log_Error pkt = { struct log_Error pkt = {
@ -739,7 +739,7 @@ struct PACKED log_WPNAV {
int32_t desired_pitch; int32_t desired_pitch;
}; };
// Write an WPNAV packet. Total length : 43 Bytes // Write an WPNAV packet
static void Log_Write_WPNAV() static void Log_Write_WPNAV()
{ {
Vector3f velocity = inertial_nav.get_velocity(); Vector3f velocity = inertial_nav.get_velocity();
@ -796,7 +796,7 @@ static const struct LogStructure log_structure[] PROGMEM = {
{ LOG_INAV_MSG, sizeof(log_INAV), { LOG_INAV_MSG, sizeof(log_INAV),
"INAV", "cccfffiiff", "BAlt,IAlt,IClb,ACorrX,ACorrY,ACorrZ,GLat,GLng,ILat,ILng" }, "INAV", "cccfffiiff", "BAlt,IAlt,IClb,ACorrX,ACorrY,ACorrZ,GLat,GLng,ILat,ILng" },
{ LOG_MODE_MSG, sizeof(log_Mode), { LOG_MODE_MSG, sizeof(log_Mode),
"MODE", "Bh", "Mode,ThrCrs" }, "MODE", "Mh", "Mode,ThrCrs" },
{ LOG_STARTUP_MSG, sizeof(log_Startup), { LOG_STARTUP_MSG, sizeof(log_Startup),
"STRT", "", "" }, "STRT", "", "" },
{ LOG_EVENT_MSG, sizeof(log_Event), { LOG_EVENT_MSG, sizeof(log_Event),
@ -838,7 +838,9 @@ static void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page)
DataFlash.LogReadProcess(log_num, start_page, end_page, DataFlash.LogReadProcess(log_num, start_page, end_page,
sizeof(log_structure)/sizeof(log_structure[0]), sizeof(log_structure)/sizeof(log_structure[0]),
log_structure, cliSerial); log_structure,
print_flight_mode,
cliSerial);
} }
// start a new log // start a new log

View File

@ -1249,7 +1249,7 @@ static void
print_switch(uint8_t p, uint8_t m, bool b) print_switch(uint8_t p, uint8_t m, bool b)
{ {
cliSerial->printf_P(PSTR("Pos %d:\t"),p); cliSerial->printf_P(PSTR("Pos %d:\t"),p);
print_flight_mode(m); print_flight_mode(cliSerial, m);
cliSerial->printf_P(PSTR(",\t\tSimple: ")); cliSerial->printf_P(PSTR(",\t\tSimple: "));
if(b) if(b)
cliSerial->printf_P(PSTR("ON\n")); cliSerial->printf_P(PSTR("ON\n"));

View File

@ -619,50 +619,50 @@ static void reboot_apm(void) {
// print_flight_mode - prints flight mode to serial port. // print_flight_mode - prints flight mode to serial port.
// //
static void static void
print_flight_mode(uint8_t mode) print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
{ {
switch (mode) { switch (mode) {
case STABILIZE: case STABILIZE:
cliSerial->print_P(PSTR("STABILIZE")); port->print_P(PSTR("STABILIZE"));
break; break;
case ACRO: case ACRO:
cliSerial->print_P(PSTR("ACRO")); port->print_P(PSTR("ACRO"));
break; break;
case ALT_HOLD: case ALT_HOLD:
cliSerial->print_P(PSTR("ALT_HOLD")); port->print_P(PSTR("ALT_HOLD"));
break; break;
case AUTO: case AUTO:
cliSerial->print_P(PSTR("AUTO")); port->print_P(PSTR("AUTO"));
break; break;
case GUIDED: case GUIDED:
cliSerial->print_P(PSTR("GUIDED")); port->print_P(PSTR("GUIDED"));
break; break;
case LOITER: case LOITER:
cliSerial->print_P(PSTR("LOITER")); port->print_P(PSTR("LOITER"));
break; break;
case RTL: case RTL:
cliSerial->print_P(PSTR("RTL")); port->print_P(PSTR("RTL"));
break; break;
case CIRCLE: case CIRCLE:
cliSerial->print_P(PSTR("CIRCLE")); port->print_P(PSTR("CIRCLE"));
break; break;
case POSITION: case POSITION:
cliSerial->print_P(PSTR("POSITION")); port->print_P(PSTR("POSITION"));
break; break;
case LAND: case LAND:
cliSerial->print_P(PSTR("LAND")); port->print_P(PSTR("LAND"));
break; break;
case OF_LOITER: case OF_LOITER:
cliSerial->print_P(PSTR("OF_LOITER")); port->print_P(PSTR("OF_LOITER"));
break; break;
case TOY_M: case TOY_M:
cliSerial->print_P(PSTR("TOY_M")); port->print_P(PSTR("TOY_M"));
break; break;
case TOY_A: case TOY_A:
cliSerial->print_P(PSTR("TOY_A")); port->print_P(PSTR("TOY_A"));
break; break;
default: default:
cliSerial->print_P(PSTR("---")); port->printf_P(PSTR("Mode(%u)"), (unsigned)mode);
break; break;
} }
} }