mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: use config.h pattern and only include log structures if enabled
This commit is contained in:
parent
00329ae443
commit
71b00e0f75
|
@ -22,10 +22,6 @@
|
|||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_ERB_ENABLED
|
||||
#define AP_GPS_ERB_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_ERB_ENABLED
|
||||
class AP_GPS_ERB : public AP_GPS_Backend
|
||||
{
|
||||
|
|
|
@ -22,10 +22,6 @@
|
|||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_GSOF_ENABLED
|
||||
#define AP_GPS_GSOF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_GSOF_ENABLED
|
||||
class AP_GPS_GSOF : public AP_GPS_Backend
|
||||
{
|
||||
|
|
|
@ -46,10 +46,6 @@
|
|||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_NMEA_ENABLED
|
||||
#define AP_GPS_NMEA_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_NMEA_ENABLED
|
||||
/// NMEA parser
|
||||
///
|
||||
|
|
|
@ -22,10 +22,6 @@
|
|||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_NOVA_ENABLED
|
||||
#define AP_GPS_NOVA_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_NOVA_ENABLED
|
||||
class AP_GPS_NOVA : public AP_GPS_Backend
|
||||
{
|
||||
|
|
|
@ -22,10 +22,6 @@
|
|||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_SBF_ENABLED
|
||||
#define AP_GPS_SBF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_SBF_ENABLED
|
||||
|
||||
#define SBF_DISK_ACTIVITY (1 << 7)
|
||||
|
|
|
@ -24,10 +24,6 @@
|
|||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_SBP_ENABLED
|
||||
#define AP_GPS_SBP_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_SBP_ENABLED
|
||||
class AP_GPS_SBP : public AP_GPS_Backend
|
||||
{
|
||||
|
|
|
@ -24,10 +24,6 @@
|
|||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_SBP2_ENABLED
|
||||
#define AP_GPS_SBP2_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_SBP2_ENABLED
|
||||
class AP_GPS_SBP2 : public AP_GPS_Backend
|
||||
{
|
||||
|
|
|
@ -25,10 +25,6 @@
|
|||
#include "AP_GPS.h"
|
||||
#include "GPS_Backend.h"
|
||||
|
||||
#ifndef AP_GPS_SIRF_ENABLED
|
||||
#define AP_GPS_SIRF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_GPS_SIRF_ENABLED
|
||||
|
||||
#define SIRF_SET_BINARY "$PSRF100,0,38400,8,1,0*3C\r\n"
|
||||
|
|
|
@ -0,0 +1,37 @@
|
|||
#pragma once
|
||||
|
||||
#ifndef AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#define AP_GPS_BACKEND_DEFAULT_ENABLED 1
|
||||
#endif
|
||||
|
||||
#ifndef AP_GPS_ERB_ENABLED
|
||||
#define AP_GPS_ERB_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_GPS_GSOF_ENABLED
|
||||
#define AP_GPS_GSOF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_GPS_NMEA_ENABLED
|
||||
#define AP_GPS_NMEA_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_GPS_NOVA_ENABLED
|
||||
#define AP_GPS_NOVA_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_GPS_SBF_ENABLED
|
||||
#define AP_GPS_SBF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_GPS_SBP_ENABLED
|
||||
#define AP_GPS_SBP_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_GPS_SBP2_ENABLED
|
||||
#define AP_GPS_SBP2_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_GPS_SIRF_ENABLED
|
||||
#define AP_GPS_SIRF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
|
@ -21,10 +21,7 @@
|
|||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <AP_RTC/JitterCorrection.h>
|
||||
#include "AP_GPS.h"
|
||||
|
||||
#ifndef AP_GPS_BACKEND_DEFAULT_ENABLED
|
||||
#define AP_GPS_BACKEND_DEFAULT_ENABLED 1
|
||||
#endif
|
||||
#include "AP_GPS_config.h"
|
||||
|
||||
#ifndef AP_GPS_DEBUG_LOGGING_ENABLED
|
||||
// enable this to log all bytes from the GPS. Also needs a call to
|
||||
|
|
|
@ -211,4 +211,4 @@ struct PACKED log_GPS_RAWS {
|
|||
"GRXH", "QdHbBB", "TimeUS,rcvTime,week,leapS,numMeas,recStat", "s-----", "F-----" , true }, \
|
||||
{ LOG_GPS_RAWS_MSG, sizeof(log_GPS_RAWS), \
|
||||
"GRXS", "QddfBBBHBBBBB", "TimeUS,prMes,cpMes,doMes,gnss,sv,freq,lock,cno,prD,cpD,doD,trk", "s------------", "F------------" , true }, \
|
||||
LOG_STRUCTURE_FROM_GPS_SBP,
|
||||
LOG_STRUCTURE_FROM_GPS_SBP
|
||||
|
|
|
@ -1,6 +1,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <AP_Logger/LogStructure.h>
|
||||
#include "AP_GPS_config.h"
|
||||
|
||||
#define LOG_IDS_FROM_GPS_SBP \
|
||||
LOG_MSG_SBPHEALTH, \
|
||||
|
@ -68,6 +69,7 @@ struct PACKED log_SbpEvent {
|
|||
uint8_t quality;
|
||||
};
|
||||
|
||||
#if AP_GPS_SBP_ENABLED
|
||||
#define LOG_STRUCTURE_FROM_GPS_SBP \
|
||||
{ LOG_MSG_SBPHEALTH, sizeof(log_SbpHealth), \
|
||||
"SBPH", "QIII", "TimeUS,CrcError,LastInject,IARhyp", "s---", "F---" , true }, \
|
||||
|
@ -76,4 +78,7 @@ struct PACKED log_SbpEvent {
|
|||
{ LOG_MSG_SBPRAWM, sizeof(log_SbpRAWM), \
|
||||
"SBRM", "QQQQQQQQQQQQQQQ", "TimeUS,msg_flag,1,2,3,4,5,6,7,8,9,10,11,12,13", "s??????????????", "F??????????????" , true }, \
|
||||
{ LOG_MSG_SBPEVENT, sizeof(log_SbpEvent), \
|
||||
"SBRE", "QHIiBB", "TimeUS,GWk,GMS,ns_residual,level,quality", "s?????", "F?????" }
|
||||
"SBRE", "QHIiBB", "TimeUS,GWk,GMS,ns_residual,level,quality", "s?????", "F?????" },
|
||||
#else
|
||||
#define LOG_STRUCTURE_FROM_GPS_SBP
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue