mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
ArduCopter Logging: DISABLED means DISABLED again; CONFIG_LOGGING added
CONFIG_LOGGING selects LOGGING_SIMPLE and LOGGING_VERBOSE. Verbose logging is the default, implemented in Log.pde. Simple logging is optional, but the default for the 1280 build, implemented in Log_simple.pde
This commit is contained in:
parent
8bf6afe3d4
commit
74530de4bb
@ -1,6 +1,6 @@
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
#if LOGGING_ENABLED == ENABLED && CONFIG_LOGGING == LOGGING_VERBOSE
|
||||
|
||||
// Code to Write and Read packets from DataFlash log memory
|
||||
// Code to interact with the user to dump or erase logs
|
||||
@ -1119,3 +1119,29 @@ static int Log_Read_Process(int start_page, int end_page)
|
||||
}
|
||||
|
||||
#endif // LOGGING_ENABLED
|
||||
|
||||
#if LOGGING_ENABLED == DISABLED
|
||||
|
||||
static void Log_Write_Startup() {}
|
||||
static void Log_Read_Startup() {}
|
||||
static void Log_Read(int start_page, int end_page) {}
|
||||
static void Log_Write_Cmd(byte num, struct Location *wp) {}
|
||||
static void Log_Write_Mode(byte mode) {}
|
||||
static void start_new_log() {}
|
||||
static void Log_Write_Raw() {}
|
||||
static void Log_Write_GPS() {}
|
||||
static void Log_Write_Current() {}
|
||||
static void Log_Write_Attitude() {}
|
||||
static void Log_Write_Data(int8_t _type, float _data){}
|
||||
static void Log_Write_Data(int8_t _type, int32_t _data){}
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
static void Log_Write_Optflow() {}
|
||||
#endif
|
||||
static void Log_Write_Nav_Tuning() {}
|
||||
static void Log_Write_Control_Tuning() {}
|
||||
static void Log_Write_Motors() {}
|
||||
static void Log_Write_Performance() {}
|
||||
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) { return 0; }
|
||||
static void do_erase_logs(void (*delay_cb)(unsigned long)) {}
|
||||
|
||||
#endif
|
||||
|
@ -1,6 +1,6 @@
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#if LOGGING_ENABLED == DISABLED
|
||||
#if LOGGING_ENABLED == ENABLED && CONFIG_LOGGING == LOGGING_SIMPLE
|
||||
|
||||
// Code to Write and Read packets from DataFlash log memory
|
||||
// Code to interact with the user to dump or erase logs
|
||||
|
@ -673,21 +673,21 @@
|
||||
// Dataflash logging control
|
||||
//
|
||||
|
||||
// Logging must be disabled for 1280 build.
|
||||
#if defined( __AVR_ATmega1280__ )
|
||||
# if LOGGING_ENABLED == ENABLED
|
||||
// If logging was enabled in APM_Config or command line, warn the user.
|
||||
# warning "Logging is not supported on ATmega1280"
|
||||
# undef LOGGING_ENABLED
|
||||
# ifndef CONFIG_LOGGING
|
||||
# define CONFIG_LOGGING LOGGING_SIMPLE
|
||||
# elif CONFIG_LOGGING != LOGGING_SIMPLE
|
||||
# warning "Simple Logging is the only officially supported mode on mega 1280"
|
||||
# endif
|
||||
# ifndef LOGGING_ENABLED
|
||||
# define LOGGING_ENABLED DISABLED
|
||||
# endif
|
||||
#elif !defined(LOGGING_ENABLED)
|
||||
// Logging is enabled by default for all other builds.
|
||||
# define LOGGING_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef CONFIG_LOGGING
|
||||
# define CONFIG_LOGGING LOGGING_VERBOSE
|
||||
#endif
|
||||
|
||||
#ifndef LOGGING_ENABLED
|
||||
# define LOGGING_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef LOG_ATTITUDE_FAST
|
||||
# define LOG_ATTITUDE_FAST DISABLED
|
||||
|
@ -358,4 +358,7 @@ enum gcs_severity {
|
||||
#define AP_BARO_BMP085 1
|
||||
#define AP_BARO_MS5611 2
|
||||
|
||||
#define LOGGING_SIMPLE 1
|
||||
#define LOGGING_VERBOSE 2
|
||||
|
||||
#endif // _DEFINES_H
|
||||
|
Loading…
Reference in New Issue
Block a user