mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: remove check for GPS_RTK_AVAILABLE
This commit is contained in:
parent
c75c1d84d9
commit
e31595c60c
|
@ -54,7 +54,6 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
|||
// @User: Advanced
|
||||
AP_GROUPINFO("AUTO_SWITCH", 3, AP_GPS, _auto_switch, 1),
|
||||
|
||||
#if GPS_RTK_AVAILABLE
|
||||
// @Param: MIN_DGPS
|
||||
// @DisplayName: Minimum Lock Type Accepted for DGPS
|
||||
// @Description: Sets the minimum type of differential GPS corrections required before allowing to switch into DGPS mode.
|
||||
|
@ -62,7 +61,6 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
|||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("MIN_DGPS", 4, AP_GPS, _min_dgps, 100),
|
||||
#endif
|
||||
|
||||
// @Param: SBAS_MODE
|
||||
// @DisplayName: SBAS Mode
|
||||
|
@ -87,23 +85,19 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
|||
// @Values: 0:send to first GPS, 1:send to 2nd GPS, 127:send to all
|
||||
AP_GROUPINFO("INJECT_TO", 7, AP_GPS, _inject_to, GPS_RTK_INJECT_TO_ALL),
|
||||
|
||||
#if GPS_RTK_AVAILABLE
|
||||
// @Param: SBP_LOGMASK
|
||||
// @DisplayName: Swift Binary Protocol Logging Mask
|
||||
// @Description: Masked with the SBP msg_type field to determine whether SBR1/SBR2 data is logged
|
||||
// @Values: 0x0000:None, 0xFFFF:All, 0xFF00:External only
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SBP_LOGMASK", 8, AP_GPS, _sbp_logmask, 0xFF00),
|
||||
#endif
|
||||
|
||||
#if GPS_RTK_AVAILABLE
|
||||
// @Param: RAW_DATA
|
||||
// @DisplayName: Raw data logging
|
||||
// @Description: Enable logging of RXM raw data from uBlox which includes carrier phase and pseudo range information. This allows for post processing of dataflash logs for more precise positioning. Note that this requires a raw capable uBlox such as the 6P or 6T.
|
||||
// @Values: 0:Disabled,1:log at 1MHz,5:log at 5MHz
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("RAW_DATA", 9, AP_GPS, _raw_data, 0),
|
||||
#endif
|
||||
|
||||
// @Param: GNSS_MODE
|
||||
// @DisplayName: GNSS system configuration
|
||||
|
@ -204,7 +198,6 @@ AP_GPS::detect_instance(uint8_t instance)
|
|||
state[instance].status = NO_GPS;
|
||||
state[instance].hdop = 9999;
|
||||
|
||||
#if GPS_RTK_AVAILABLE
|
||||
// by default the sbf/trimble gps outputs no data on its port, until configured.
|
||||
if (_type[instance] == GPS_TYPE_SBF) {
|
||||
hal.console->print(" SBF ");
|
||||
|
@ -213,7 +206,6 @@ AP_GPS::detect_instance(uint8_t instance)
|
|||
hal.console->print(" GSOF ");
|
||||
new_gps = new AP_GPS_GSOF(*this, state[instance], _port[instance]);
|
||||
}
|
||||
#endif // GPS_RTK_AVAILABLE
|
||||
|
||||
// record the time when we started detection. This is used to try
|
||||
// to avoid initialising a uBlox as a NMEA GPS
|
||||
|
@ -267,13 +259,11 @@ AP_GPS::detect_instance(uint8_t instance)
|
|||
hal.console->print(" MTK ");
|
||||
new_gps = new AP_GPS_MTK(*this, state[instance], _port[instance]);
|
||||
}
|
||||
#if GPS_RTK_AVAILABLE
|
||||
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) &&
|
||||
AP_GPS_SBP::_detect(dstate->sbp_detect_state, data)) {
|
||||
hal.console->print(" SBP ");
|
||||
new_gps = new AP_GPS_SBP(*this, state[instance], _port[instance]);
|
||||
}
|
||||
#endif // HAL_CPU_CLASS
|
||||
#if !defined(GPS_SKIP_SIRF_NMEA)
|
||||
// save a bit of code space on a 1280
|
||||
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SIRF) &&
|
||||
|
@ -306,21 +296,16 @@ found_gps:
|
|||
AP_GPS::GPS_Status
|
||||
AP_GPS::highest_supported_status(uint8_t instance) const
|
||||
{
|
||||
#if GPS_RTK_AVAILABLE
|
||||
if (drivers[instance] != NULL)
|
||||
return drivers[instance]->highest_supported_status();
|
||||
#endif
|
||||
return AP_GPS::GPS_OK_FIX_3D;
|
||||
}
|
||||
|
||||
AP_GPS::GPS_Status
|
||||
AP_GPS::highest_supported_status(void) const
|
||||
{
|
||||
#if GPS_RTK_AVAILABLE
|
||||
|
||||
if (drivers[primary_instance] != NULL)
|
||||
return drivers[primary_instance]->highest_supported_status();
|
||||
#endif
|
||||
return AP_GPS::GPS_OK_FIX_3D;
|
||||
}
|
||||
|
||||
|
@ -568,7 +553,6 @@ AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
|
|||
0);
|
||||
}
|
||||
|
||||
#if GPS_RTK_AVAILABLE
|
||||
void
|
||||
AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan)
|
||||
{
|
||||
|
@ -584,4 +568,3 @@ AP_GPS::send_mavlink_gps2_rtk(mavlink_channel_t chan)
|
|||
drivers[1]->send_mavlink_gps_rtk(chan);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -32,7 +32,6 @@
|
|||
than 1 then redundent sensors may be available
|
||||
*/
|
||||
#define GPS_MAX_INSTANCES 2
|
||||
#define GPS_RTK_AVAILABLE 1
|
||||
#define GPS_RTK_INJECT_TO_ALL 127
|
||||
|
||||
class DataFlash_Class;
|
||||
|
@ -334,10 +333,8 @@ public:
|
|||
void send_mavlink_gps_raw(mavlink_channel_t chan);
|
||||
void send_mavlink_gps2_raw(mavlink_channel_t chan);
|
||||
|
||||
#if GPS_RTK_AVAILABLE
|
||||
void send_mavlink_gps_rtk(mavlink_channel_t chan);
|
||||
void send_mavlink_gps2_rtk(mavlink_channel_t chan);
|
||||
#endif
|
||||
|
||||
private:
|
||||
struct GPS_timing {
|
||||
|
@ -371,9 +368,7 @@ private:
|
|||
struct MTK19_detect_state mtk19_detect_state;
|
||||
struct SIRF_detect_state sirf_detect_state;
|
||||
struct NMEA_detect_state nmea_detect_state;
|
||||
#if GPS_RTK_AVAILABLE
|
||||
struct SBP_detect_state sbp_detect_state;
|
||||
#endif
|
||||
} detect_state[GPS_MAX_INSTANCES];
|
||||
|
||||
struct {
|
||||
|
|
|
@ -23,8 +23,6 @@
|
|||
#include "AP_GPS_GSOF.h"
|
||||
#include <DataFlash/DataFlash.h>
|
||||
|
||||
#if GPS_RTK_AVAILABLE
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#define gsof_DEBUGGING 0
|
||||
|
@ -353,4 +351,3 @@ AP_GPS_GSOF::inject_data(uint8_t *data, uint8_t len)
|
|||
Debug("GSOF: Not enough TXSPACE");
|
||||
}
|
||||
}
|
||||
#endif // GPS_RTK_AVAILABLE
|
||||
|
|
|
@ -23,8 +23,6 @@
|
|||
#include "AP_GPS_SBF.h"
|
||||
#include <DataFlash/DataFlash.h>
|
||||
|
||||
#if GPS_RTK_AVAILABLE
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#define SBF_DEBUGGING 0
|
||||
|
@ -297,6 +295,3 @@ AP_GPS_SBF::inject_data(uint8_t *data, uint8_t len)
|
|||
Debug("SBF: Not enough TXSPACE");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#endif // GPS_RTK_AVAILABLE
|
||||
|
|
|
@ -25,8 +25,6 @@
|
|||
#include "AP_GPS_SBP.h"
|
||||
#include <DataFlash/DataFlash.h>
|
||||
|
||||
#if GPS_RTK_AVAILABLE
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#define SBP_DEBUGGING 1
|
||||
|
@ -518,5 +516,3 @@ AP_GPS_SBP::logging_log_raw_sbp(uint16_t msg_type,
|
|||
|
||||
|
||||
#endif // SBP_HW_LOGGING
|
||||
|
||||
#endif // GPS_RTK_AVAILABLE
|
||||
|
|
|
@ -39,7 +39,6 @@ public:
|
|||
|
||||
virtual void inject_data(uint8_t *data, uint8_t len) { return; }
|
||||
|
||||
#if GPS_RTK_AVAILABLE
|
||||
// Highest status supported by this GPS.
|
||||
// Allows external system to identify type of receiver connected.
|
||||
virtual AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D; }
|
||||
|
@ -48,7 +47,6 @@ public:
|
|||
virtual void send_mavlink_gps_rtk(mavlink_channel_t chan) { return ; }
|
||||
|
||||
virtual void send_mavlink_gps2_rtk(mavlink_channel_t chan) { return ; }
|
||||
#endif
|
||||
|
||||
protected:
|
||||
AP_HAL::UARTDriver *port; ///< UART we are attached to
|
||||
|
|
Loading…
Reference in New Issue