//1#pragma once23#include "defines.h"45#ifndef MAV_SYSTEM_ID6// use 2 for antenna tracker by default7# define MAV_SYSTEM_ID 28#endif91011//////////////////////////////////////////////////////////////////////////////12// RC Channel definitions13//14#ifndef CH_YAW15# define CH_YAW CH_1 // RC input/output for yaw on channel 116#endif17#ifndef CH_PITCH18# define CH_PITCH CH_2 // RC input/output for pitch on channel 219#endif202122//////////////////////////////////////////////////////////////////////////////23// yaw and pitch axis angle range defaults24//25#ifndef YAW_RANGE_DEFAULT26# define YAW_RANGE_DEFAULT 36027#endif28#ifndef PITCH_MIN_DEFAULT29# define PITCH_MIN_DEFAULT -9030#endif31#ifndef PITCH_MAX_DEFAULT32# define PITCH_MAX_DEFAULT 9033#endif3435//////////////////////////////////////////////////////////////////////////////36// Tracking definitions37//38#ifndef TRACKING_TIMEOUT_MS39# 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 leds40#endif41#ifndef TRACKING_TIMEOUT_SEC42# define TRACKING_TIMEOUT_SEC 5.0f // consider we've lost track of vehicle after 5 seconds with no position update.43#endif44#ifndef DISTANCE_MIN_DEFAULT45# define DISTANCE_MIN_DEFAULT 5.0f // do not track targets within 5 meters46#endif4748//49// Logging control50//5152// Default logging bitmask53#ifndef DEFAULT_LOG_BITMASK54# define DEFAULT_LOG_BITMASK \55MASK_LOG_ATTITUDE | \56MASK_LOG_GPS | \57MASK_LOG_RCIN | \58MASK_LOG_IMU | \59MASK_LOG_RCOUT | \60MASK_LOG_COMPASS | \61MASK_LOG_CURRENT62#endif6364#ifndef AP_TRACKER_SET_HOME_VIA_MISSION_UPLOAD_ENABLED65#define AP_TRACKER_SET_HOME_VIA_MISSION_UPLOAD_ENABLED 166#endif676869