6 // Just so that it's completely clear...
10 // this avoids a very common config error
11 #define ENABLE ENABLED
12 #define DISABLE DISABLED
15 // use 2 for antenna tracker by default
16 # define MAV_SYSTEM_ID 2
20 //////////////////////////////////////////////////////////////////////////////
21 // RC Channel definitions
24 # define CH_YAW CH_1 // RC input/output for yaw on channel 1
27 # define CH_PITCH CH_2 // RC input/output for pitch on channel 2
31 //////////////////////////////////////////////////////////////////////////////
32 // yaw and pitch axis angle range defaults
34 #ifndef YAW_RANGE_DEFAULT
35 # define YAW_RANGE_DEFAULT 360
37 #ifndef PITCH_MIN_DEFAULT
38 # define PITCH_MIN_DEFAULT -90
40 #ifndef PITCH_MAX_DEFAULT
41 # define PITCH_MAX_DEFAULT 90
44 //////////////////////////////////////////////////////////////////////////////
45 // Tracking definitions
47 #ifndef TRACKING_TIMEOUT_MS
48 # define TRACKING_TIMEOUT_MS 5000 // consider we've lost track of vehicle after 5 seconds with no position update. Used to update armed/disarmed status leds
50 #ifndef TRACKING_TIMEOUT_SEC
51 # define TRACKING_TIMEOUT_SEC 5.0f // consider we've lost track of vehicle after 5 seconds with no position update.
53 #ifndef DISTANCE_MIN_DEFAULT
54 # define DISTANCE_MIN_DEFAULT 5.0f // do not track targets within 5 meters
61 // Default logging bitmask
62 #ifndef DEFAULT_LOG_BITMASK
63 # define DEFAULT_LOG_BITMASK \
73 #ifndef AP_TRACKER_SET_HOME_VIA_MISSION_UPLOAD_ENABLED
74 #define AP_TRACKER_SET_HOME_VIA_MISSION_UPLOAD_ENABLED 1