Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_GPS/AP_GPS_config.h
Views: 1798
#pragma once12#include <AP_HAL/AP_HAL_Boards.h>3#include <GCS_MAVLink/GCS_config.h>45#ifndef AP_GPS_ENABLED6#define AP_GPS_ENABLED 17#endif89#if AP_GPS_ENABLED10/**11maximum number of GPS instances available on this platform. If more12than 1 then redundant sensors may be available13*/14#ifndef GPS_MAX_RECEIVERS15#define GPS_MAX_RECEIVERS 2 // maximum number of physical GPS sensors allowed - does not include virtual GPS created by blending receiver data16#endif1718#if !defined(GPS_MAX_INSTANCES)19#if GPS_MAX_RECEIVERS > 120#define GPS_MAX_INSTANCES (GPS_MAX_RECEIVERS + 1) // maximum number of GPS instances including the 'virtual' GPS created by blending receiver data21#else22#define GPS_MAX_INSTANCES 123#endif // GPS_MAX_RECEIVERS > 124#endif // GPS_MAX_INSTANCES2526#if GPS_MAX_RECEIVERS <= 1 && GPS_MAX_INSTANCES > 127#error "GPS_MAX_INSTANCES should be 1 for GPS_MAX_RECEIVERS <= 1"28#endif29#endif3031#ifndef AP_GPS_BACKEND_DEFAULT_ENABLED32#define AP_GPS_BACKEND_DEFAULT_ENABLED AP_GPS_ENABLED33#endif3435#if !defined(AP_GPS_BLENDED_ENABLED) && defined(GPS_MAX_INSTANCES)36#define AP_GPS_BLENDED_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED && GPS_MAX_INSTANCES > GPS_MAX_RECEIVERS37#endif3839#ifndef AP_GPS_BLENDED_ENABLED40#define AP_GPS_BLENDED_ENABLED 041#endif4243#if AP_GPS_BLENDED_ENABLED44#define GPS_BLENDED_INSTANCE GPS_MAX_RECEIVERS // the virtual blended GPS is always the highest instance (2)45#endif4647#ifndef AP_GPS_DRONECAN_ENABLED48#define AP_GPS_DRONECAN_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS49#endif5051#ifndef AP_GPS_ERB_ENABLED52#define AP_GPS_ERB_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED53#endif5455#ifndef AP_GPS_GSOF_ENABLED56#define AP_GPS_GSOF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED57#endif5859#ifndef AP_GPS_MAV_ENABLED60#define AP_GPS_MAV_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED && HAL_GCS_ENABLED61#endif6263#ifndef HAL_MSP_GPS_ENABLED64#define HAL_MSP_GPS_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED && HAL_MSP_SENSORS_ENABLED65#endif6667#ifndef AP_GPS_NMEA_ENABLED68#define AP_GPS_NMEA_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED69#endif7071#ifndef AP_GPS_NMEA_UNICORE_ENABLED72#define AP_GPS_NMEA_UNICORE_ENABLED AP_GPS_NMEA_ENABLED73#endif7475#ifndef AP_GPS_NOVA_ENABLED76#define AP_GPS_NOVA_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED77#endif7879#ifndef AP_GPS_SBF_ENABLED80#define AP_GPS_SBF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED81#endif8283#ifndef AP_GPS_SBP_ENABLED84#define AP_GPS_SBP_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED85#endif8687#ifndef AP_GPS_SBP2_ENABLED88#define AP_GPS_SBP2_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED89#endif9091#ifndef AP_GPS_SIRF_ENABLED92#define AP_GPS_SIRF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED93#endif9495#ifndef AP_GPS_UBLOX_ENABLED96#define AP_GPS_UBLOX_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED97#endif9899#ifndef AP_GPS_RTCM_DECODE_ENABLED100#define AP_GPS_RTCM_DECODE_ENABLED BOARD_FLASH_SIZE > 1024101#endif102103#ifndef HAL_GPS_COM_PORT_DEFAULT104#define HAL_GPS_COM_PORT_DEFAULT 1105#endif106107108#ifndef AP_GPS_GPS_RAW_INT_SENDING_ENABLED109#define AP_GPS_GPS_RAW_INT_SENDING_ENABLED HAL_GCS_ENABLED && AP_GPS_ENABLED110#endif111112#ifndef AP_GPS_GPS2_RAW_SENDING_ENABLED113#define AP_GPS_GPS2_RAW_SENDING_ENABLED HAL_GCS_ENABLED && AP_GPS_ENABLED && GPS_MAX_RECEIVERS > 1114#endif115116#ifndef AP_GPS_GPS_RTK_SENDING_ENABLED117#define AP_GPS_GPS_RTK_SENDING_ENABLED HAL_GCS_ENABLED && AP_GPS_ENABLED && (AP_GPS_SBF_ENABLED || AP_GPS_ERB_ENABLED)118#endif119120#ifndef AP_GPS_GPS2_RTK_SENDING_ENABLED121#define AP_GPS_GPS2_RTK_SENDING_ENABLED HAL_GCS_ENABLED && AP_GPS_ENABLED && GPS_MAX_RECEIVERS > 1 && (AP_GPS_SBF_ENABLED || AP_GPS_ERB_ENABLED)122#endif123124125