2013-10-13 04:14:13 -03:00
//
2016-02-17 21:25:58 -04:00
# pragma once
2013-10-13 04:14:13 -03:00
# include "defines.h"
// Just so that it's completely clear...
# define ENABLED 1
# define DISABLED 0
// this avoids a very common config error
# define ENABLE ENABLED
# define DISABLE DISABLED
# ifndef MAV_SYSTEM_ID
// use 2 for antenna tracker by default
# define MAV_SYSTEM_ID 2
# endif
2014-03-02 03:00:37 -04:00
2014-10-06 05:01:54 -03:00
//////////////////////////////////////////////////////////////////////////////
// RC Channel definitions
//
# ifndef CH_YAW
# define CH_YAW CH_1 // RC input/output for yaw on channel 1
# endif
# ifndef CH_PITCH
# define CH_PITCH CH_2 // RC input/output for pitch on channel 2
# endif
2014-10-06 02:51:53 -03:00
//////////////////////////////////////////////////////////////////////////////
// yaw and pitch axis angle range defaults
//
# ifndef YAW_RANGE_DEFAULT
# define YAW_RANGE_DEFAULT 360
# endif
2016-07-01 00:40:01 -03:00
# ifndef PITCH_MIN_DEFAULT
# define PITCH_MIN_DEFAULT -90
# endif
# ifndef PITCH_MAX_DEFAULT
# define PITCH_MAX_DEFAULT 90
2014-10-06 02:51:53 -03:00
# endif
2014-09-29 07:40:25 -03:00
//////////////////////////////////////////////////////////////////////////////
// Tracking definitions
//
# ifndef TRACKING_TIMEOUT_MS
# 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
# endif
2014-10-01 10:24:06 -03:00
# ifndef TRACKING_TIMEOUT_SEC
# define TRACKING_TIMEOUT_SEC 5.0f // consider we've lost track of vehicle after 5 seconds with no position update.
# endif
2015-04-26 23:24:47 -03:00
# ifndef DISTANCE_MIN_DEFAULT
# define DISTANCE_MIN_DEFAULT 5.0f // do not track targets within 5 meters
# endif
2014-09-29 07:40:25 -03:00
2015-12-27 03:05:14 -04:00
//
2019-02-11 04:09:55 -04:00
// Logging control
2015-12-27 03:05:14 -04:00
//
2014-03-02 03:00:37 -04:00
2015-12-27 03:05:14 -04:00
// Default logging bitmask
# ifndef DEFAULT_LOG_BITMASK
# define DEFAULT_LOG_BITMASK \
MASK_LOG_ATTITUDE | \
MASK_LOG_GPS | \
MASK_LOG_RCIN | \
MASK_LOG_IMU | \
MASK_LOG_RCOUT | \
2018-01-16 16:06:27 -04:00
MASK_LOG_COMPASS | \
MASK_LOG_CURRENT
2015-12-27 03:05:14 -04:00
# endif
2024-01-29 21:32:18 -04:00
# ifndef AP_TRACKER_SET_HOME_VIA_MISSION_UPLOAD_ENABLED
# define AP_TRACKER_SET_HOME_VIA_MISSION_UPLOAD_ENABLED 1
# endif