PX4 Firmware
PX4 Autopilot Software http://px4.io
GPSBaseStationSupport Class Reference

GPS driver base class with Base Station Support. More...

#include <base_station.h>

Inheritance diagram for GPSBaseStationSupport:
Collaboration diagram for GPSBaseStationSupport:

Classes

struct  BaseSettings
 
struct  FixedPositionSettings
 
struct  SurveyInSettings
 

Public Member Functions

 GPSBaseStationSupport (GPSCallbackPtr callback, void *callback_user)
 
virtual ~GPSBaseStationSupport ()=default
 
void setSurveyInSpecs (uint32_t survey_in_acc_limit, uint32_t survey_in_min_dur)
 set survey-in specs for RTK base station setup (for finding an accurate base station position by averaging the position measurements over time). More...
 
void setBasePosition (double latitude, double longitude, float altitude, float position_accuracy)
 Set a fixed base station position. More...
 
- Public Member Functions inherited from GPSHelper
 GPSHelper (GPSCallbackPtr callback, void *callback_user)
 
virtual ~GPSHelper ()=default
 
virtual int configure (unsigned &baud, OutputMode output_mode)=0
 configure the device More...
 
virtual int receive (unsigned timeout)=0
 receive & handle new data from the device More...
 
virtual int reset (GPSRestartType restart_type)
 Reset GPS device. More...
 
float getPositionUpdateRate ()
 
float getVelocityUpdateRate ()
 
void resetUpdateRates ()
 
void storeUpdateRates ()
 

Protected Types

enum  BaseSettingsType : uint8_t { BaseSettingsType::survey_in, BaseSettingsType::fixed_position }
 

Protected Attributes

BaseSettings _base_settings
 
- Protected Attributes inherited from GPSHelper
GPSCallbackPtr _callback {nullptr}
 
void * _callback_user {}
 
uint8_t _rate_count_lat_lon {}
 
uint8_t _rate_count_vel {}
 
float _rate_lat_lon {0.0f}
 
float _rate_vel {0.0f}
 
uint64_t _interval_rate_start {0}
 

Additional Inherited Members

- Public Types inherited from GPSHelper
enum  OutputMode : uint8_t { OutputMode::GPS = 0, OutputMode::RTCM }
 
enum  Interface : uint8_t { Interface::UART = 0, Interface::SPI }
 
- Protected Member Functions inherited from GPSHelper
int read (uint8_t *buf, int buf_length, int timeout)
 read from device More...
 
int write (const void *buf, int buf_length)
 write to the device More...
 
int setBaudrate (int baudrate)
 set the Baudrate More...
 
void surveyInStatus (SurveyInStatus &status)
 
void gotRTCMMessage (uint8_t *buf, int buf_length)
 got an RTCM message from the device More...
 
void setClock (timespec &t)
 
- Static Protected Member Functions inherited from GPSHelper
static void ECEF2lla (double ecef_x, double ecef_y, double ecef_z, double &latitude, double &longitude, float &altitude)
 Convert an ECEF (Earth Centered Earth Fixed) coordinate to LLA WGS84 (Lat, Lon, Alt). More...
 

Detailed Description

GPS driver base class with Base Station Support.

Definition at line 49 of file base_station.h.

Member Enumeration Documentation

◆ BaseSettingsType

enum GPSBaseStationSupport::BaseSettingsType : uint8_t
strongprotected
Enumerator
survey_in 
fixed_position 

Definition at line 89 of file base_station.h.

Constructor & Destructor Documentation

◆ GPSBaseStationSupport()

GPSBaseStationSupport::GPSBaseStationSupport ( GPSCallbackPtr  callback,
void *  callback_user 
)
inline

Definition at line 52 of file base_station.h.

References ~GPSBaseStationSupport().

Here is the call graph for this function:

◆ ~GPSBaseStationSupport()

virtual GPSBaseStationSupport::~GPSBaseStationSupport ( )
virtualdefault

Referenced by GPSBaseStationSupport().

Here is the caller graph for this function:

Member Function Documentation

◆ setBasePosition()

void GPSBaseStationSupport::setBasePosition ( double  latitude,
double  longitude,
float  altitude,
float  position_accuracy 
)
inline

Set a fixed base station position.

This can be used if the base position is already known to avoid doing a survey-in.

Parameters
latitude[deg]
longitude[deg]
altitude[m]
position_accuracy3D position accuracy (set to 0 if unknown) [mm]

Definition at line 78 of file base_station.h.

References _base_settings, GPSBaseStationSupport::FixedPositionSettings::altitude, fixed_position, GPSBaseStationSupport::BaseSettings::fixed_position, GPSBaseStationSupport::FixedPositionSettings::latitude, GPSBaseStationSupport::FixedPositionSettings::longitude, GPSBaseStationSupport::FixedPositionSettings::position_accuracy, GPSBaseStationSupport::BaseSettings::settings, and GPSBaseStationSupport::BaseSettings::type.

◆ setSurveyInSpecs()

void GPSBaseStationSupport::setSurveyInSpecs ( uint32_t  survey_in_acc_limit,
uint32_t  survey_in_min_dur 
)
inline

set survey-in specs for RTK base station setup (for finding an accurate base station position by averaging the position measurements over time).

Parameters
survey_in_acc_limitminimum accuracy in 0.1mm
survey_in_min_durminimum duration in seconds

Definition at line 63 of file base_station.h.

References _base_settings, GPSBaseStationSupport::SurveyInSettings::acc_limit, GPSBaseStationSupport::SurveyInSettings::min_dur, GPSBaseStationSupport::BaseSettings::settings, survey_in, GPSBaseStationSupport::BaseSettings::survey_in, and GPSBaseStationSupport::BaseSettings::type.

Member Data Documentation

◆ _base_settings


The documentation for this class was generated from the following file: