VARTest: fixed build

This commit is contained in:
Andrew Tridgell 2014-03-24 12:03:56 +11:00
parent 271ba3a6bc
commit 9b92e25cdc
3 changed files with 1 additions and 83 deletions

View File

@ -87,7 +87,7 @@ const AP_Param::Info var_info[] PROGMEM = {
GSCALAR(reverse_ch1_elevon, "ELEVON_CH1_REV", ELEVON_CH1_REVERSE), GSCALAR(reverse_ch1_elevon, "ELEVON_CH1_REV", ELEVON_CH1_REVERSE),
GSCALAR(reverse_ch2_elevon, "ELEVON_CH2_REV", ELEVON_CH2_REVERSE), GSCALAR(reverse_ch2_elevon, "ELEVON_CH2_REV", ELEVON_CH2_REVERSE),
GSCALAR(num_resets, "SYS_NUM_RESETS", 0), GSCALAR(num_resets, "SYS_NUM_RESETS", 0),
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK), GSCALAR(log_bitmask, "LOG_BITMASK", 0),
GSCALAR(log_last_filenumber, "LOG_LASTFILE", 0), GSCALAR(log_last_filenumber, "LOG_LASTFILE", 0),
GSCALAR(reset_switch_chan, "RST_SWITCH_CH", 0), GSCALAR(reset_switch_chan, "RST_SWITCH_CH", 0),
GSCALAR(airspeed_cruise, "TRIM_ARSPD_CM", AIRSPEED_CRUISE_CM), GSCALAR(airspeed_cruise, "TRIM_ARSPD_CM", AIRSPEED_CRUISE_CM),

View File

@ -656,62 +656,6 @@
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// Dataflash logging control
//
#ifndef LOGGING_ENABLED
# define LOGGING_ENABLED ENABLED
#endif
#ifndef LOG_ATTITUDE_FAST
# define LOG_ATTITUDE_FAST DISABLED
#endif
#ifndef LOG_ATTITUDE_MED
# define LOG_ATTITUDE_MED ENABLED
#endif
#ifndef LOG_GPS
# define LOG_GPS ENABLED
#endif
#ifndef LOG_PM
# define LOG_PM ENABLED
#endif
#ifndef LOG_CTUN
# define LOG_CTUN DISABLED
#endif
#ifndef LOG_NTUN
# define LOG_NTUN DISABLED
#endif
#ifndef LOG_MODE
# define LOG_MODE ENABLED
#endif
#ifndef LOG_RAW
# define LOG_RAW DISABLED
#endif
#ifndef LOG_CMD
# define LOG_CMD ENABLED
#endif
#ifndef LOG_CUR
# define LOG_CUR DISABLED
#endif
// calculate the default log_bitmask
#define LOGBIT(_s) (LOG_##_s ? MASK_LOG_##_s : 0)
#define DEFAULT_LOG_BITMASK \
LOGBIT(ATTITUDE_FAST) | \
LOGBIT(ATTITUDE_MED) | \
LOGBIT(GPS) | \
LOGBIT(PM) | \
LOGBIT(CTUN) | \
LOGBIT(NTUN) | \
LOGBIT(MODE) | \
LOGBIT(RAW) | \
LOGBIT(CMD) | \
LOGBIT(CUR)
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Navigation defaults // Navigation defaults
// //

View File

@ -125,32 +125,6 @@ enum ap_message {
MSG_RETRY_DEFERRED // this must be last MSG_RETRY_DEFERRED // this must be last
}; };
// Logging parameters
#define LOG_INDEX_MSG 0xF0
#define LOG_ATTITUDE_MSG 0x01
#define LOG_MODE_MSG 0X03
#define LOG_CONTROL_TUNING_MSG 0X04
#define LOG_NAV_TUNING_MSG 0X05
#define LOG_PERFORMANCE_MSG 0X06
#define LOG_RAW_MSG 0x07
#define LOG_CMD_MSG 0x08
#define LOG_CURRENT_MSG 0x09
#define LOG_STARTUP_MSG 0x0A
#define TYPE_AIRSTART_MSG 0x00
#define TYPE_GROUNDSTART_MSG 0x01
#define MAX_NUM_LOGS 100
#define MASK_LOG_ATTITUDE_FAST (1<<0)
#define MASK_LOG_ATTITUDE_MED (1<<1)
#define MASK_LOG_GPS (1<<2)
#define MASK_LOG_PM (1<<3)
#define MASK_LOG_CTUN (1<<4)
#define MASK_LOG_NTUN (1<<5)
#define MASK_LOG_MODE (1<<6)
#define MASK_LOG_RAW (1<<7)
#define MASK_LOG_CMD (1<<8)
#define MASK_LOG_CUR (1<<9)
// Waypoint Modes // Waypoint Modes
// ---------------- // ----------------
#define ABS_WP 0 #define ABS_WP 0