mirror of https://github.com/ArduPilot/ardupilot
Copter: print frame type in log headers
This commit is contained in:
parent
ba5e368175
commit
0335138683
|
@ -915,6 +915,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
|
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
|
||||||
send_text_P(SEVERITY_LOW, PSTR("PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION));
|
send_text_P(SEVERITY_LOW, PSTR("PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION));
|
||||||
#endif
|
#endif
|
||||||
|
send_text_P(SEVERITY_LOW, PSTR("Frame: " FRAME_CONFIG_STRING));
|
||||||
handle_param_request_list(msg);
|
handle_param_request_list(msg);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
|
@ -718,7 +718,8 @@ static void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
cliSerial->printf_P(PSTR("\n" FIRMWARE_STRING
|
cliSerial->printf_P(PSTR("\n" FIRMWARE_STRING
|
||||||
"\nFree RAM: %u\n"),
|
"\nFree RAM: %u\n"
|
||||||
|
"\nFrame: " FRAME_CONFIG_STRING "\n"),
|
||||||
(unsigned) hal.util->available_memory());
|
(unsigned) hal.util->available_memory());
|
||||||
|
|
||||||
cliSerial->println_P(PSTR(HAL_BOARD_NAME));
|
cliSerial->println_P(PSTR(HAL_BOARD_NAME));
|
||||||
|
@ -749,6 +750,7 @@ static void start_logging()
|
||||||
if (hal.util->get_system_id(sysid)) {
|
if (hal.util->get_system_id(sysid)) {
|
||||||
DataFlash.Log_Write_Message(sysid);
|
DataFlash.Log_Write_Message(sysid);
|
||||||
}
|
}
|
||||||
|
DataFlash.Log_Write_Message_P(PSTR("Frame: " FRAME_CONFIG_STRING));
|
||||||
|
|
||||||
// log the flight mode
|
// log the flight mode
|
||||||
Log_Write_Mode(control_mode);
|
Log_Write_Mode(control_mode);
|
||||||
|
|
|
@ -117,6 +117,28 @@
|
||||||
# define FRAME_CONFIG QUAD_FRAME
|
# define FRAME_CONFIG QUAD_FRAME
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if FRAME_CONFIG == QUAD_FRAME
|
||||||
|
# define FRAME_CONFIG_STRING "QUAD"
|
||||||
|
#elif FRAME_CONFIG == TRI_FRAME
|
||||||
|
# define FRAME_CONFIG_STRING "TRI"
|
||||||
|
#elif FRAME_CONFIG == HEXA_FRAME
|
||||||
|
# define FRAME_CONFIG_STRING "HEXA"
|
||||||
|
#elif FRAME_CONFIG == Y6_FRAME
|
||||||
|
# define FRAME_CONFIG_STRING "Y6"
|
||||||
|
#elif FRAME_CONFIG == OCTA_FRAME
|
||||||
|
# define FRAME_CONFIG_STRING "OCTA"
|
||||||
|
#elif FRAME_CONFIG == OCTA_QUAD_FRAME
|
||||||
|
# define FRAME_CONFIG_STRING "OCTA_QUAD"
|
||||||
|
#elif FRAME_CONFIG == HELI_FRAME
|
||||||
|
# define FRAME_CONFIG_STRING "HELI"
|
||||||
|
#elif FRAME_CONFIG == SINGLE_FRAME
|
||||||
|
# define FRAME_CONFIG_STRING "SINGLE"
|
||||||
|
#elif FRAME_CONFIG == COAX_FRAME
|
||||||
|
# define FRAME_CONFIG_STRING "COAX"
|
||||||
|
#else
|
||||||
|
# define FRAME_CONFIG_STRING "UNKNOWN"
|
||||||
|
#endif
|
||||||
|
|
||||||
/////////////////////////////////////////////////////////////////////////////////
|
/////////////////////////////////////////////////////////////////////////////////
|
||||||
// TradHeli defaults
|
// TradHeli defaults
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
|
Loading…
Reference in New Issue