PX4 Firmware
PX4 Autopilot Software http://px4.io
GPSHelper Class Referenceabstract

#include <gps_helper.h>

Inheritance diagram for GPSHelper:
Collaboration diagram for GPSHelper:

Public Types

enum  OutputMode : uint8_t { OutputMode::GPS = 0, OutputMode::RTCM }
 
enum  Interface : uint8_t { Interface::UART = 0, Interface::SPI }
 

Public Member Functions

 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 Member Functions

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

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...
 

Protected Attributes

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}
 

Detailed Description

Definition at line 147 of file gps_helper.h.

Member Enumeration Documentation

◆ Interface

enum GPSHelper::Interface : uint8_t
strong
Enumerator
UART 
SPI 

Definition at line 155 of file gps_helper.h.

◆ OutputMode

enum GPSHelper::OutputMode : uint8_t
strong
Enumerator
GPS 

normal GPS output

RTCM 

request RTCM output. This is used for (fixed position) base stations

Definition at line 150 of file gps_helper.h.

Constructor & Destructor Documentation

◆ GPSHelper()

GPSHelper::GPSHelper ( GPSCallbackPtr  callback,
void *  callback_user 
)

Definition at line 49 of file gps_helper.cpp.

◆ ~GPSHelper()

virtual GPSHelper::~GPSHelper ( )
virtualdefault

Member Function Documentation

◆ configure()

virtual int GPSHelper::configure ( unsigned &  baud,
OutputMode  output_mode 
)
pure virtual

configure the device

Parameters
baudInput and output parameter: if set to 0, the baudrate will be automatically detected and set to the detected baudrate. If not 0, a fixed baudrate is used.
Returns
0 on success, <0 otherwise

Implemented in GPSDriverUBX, GPSDriverEmlidReach, GPSDriverMTK, and GPSDriverAshtech.

Referenced by GPS::run().

Here is the caller graph for this function:

◆ ECEF2lla()

void GPSHelper::ECEF2lla ( double  ecef_x,
double  ecef_y,
double  ecef_z,
double &  latitude,
double &  longitude,
float &  altitude 
)
staticprotected

Convert an ECEF (Earth Centered Earth Fixed) coordinate to LLA WGS84 (Lat, Lon, Alt).

Ported from: https://stackoverflow.com/a/25428344

Parameters
ecef_xECEF X-coordinate [m]
ecef_yECEF Y-coordinate [m]
ecef_zECEF Z-coordinate [m]
latitude[deg]
longitude[deg]
altitude[m]

Definition at line 69 of file gps_helper.cpp.

References matrix::atan2(), matrix::cos(), M_PI, matrix::sin(), and matrix::sqrt().

Referenced by GPSDriverUBX::payloadRxDone().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getPositionUpdateRate()

float GPSHelper::getPositionUpdateRate ( )
inline

Definition at line 190 of file gps_helper.h.

Referenced by GPS::print_status().

Here is the caller graph for this function:

◆ getVelocityUpdateRate()

float GPSHelper::getVelocityUpdateRate ( )
inline

Definition at line 191 of file gps_helper.h.

Referenced by GPS::print_status().

Here is the caller graph for this function:

◆ gotRTCMMessage()

void GPSHelper::gotRTCMMessage ( uint8_t *  buf,
int  buf_length 
)
inlineprotected

got an RTCM message from the device

Definition at line 239 of file gps_helper.h.

References gotRTCMMessage.

Referenced by GPSDriverAshtech::parseChar(), GPSDriverSBF::parseChar(), and GPSDriverUBX::parseChar().

Here is the caller graph for this function:

◆ read()

int GPSHelper::read ( uint8_t *  buf,
int  buf_length,
int  timeout 
)
inlineprotected

read from device

Parameters
bufpointer to read buffer
buf_lengthsize of read buffer
timeouttimeout in ms
Returns
: 0 for nothing read, or poll timed out < 0 for error > 0 number of bytes read

Definition at line 206 of file gps_helper.h.

References readDeviceData.

Referenced by GPSDriverAshtech::receive(), GPSDriverMTK::receive(), GPSDriverEmlidReach::receive(), GPSDriverSBF::receive(), GPSDriverUBX::receive(), and GPSDriverSBF::sendMessageAndWaitForAck().

Here is the caller graph for this function:

◆ receive()

virtual int GPSHelper::receive ( unsigned  timeout)
pure virtual

receive & handle new data from the device

Parameters
timeout[ms]
Returns
<0 on error, otherwise a bitset: bit 0 set: got gps position update bit 1 set: got satellite info update

Implemented in GPSDriverUBX, GPSDriverSBF, GPSDriverEmlidReach, GPSDriverMTK, and GPSDriverAshtech.

Referenced by GPS::run().

Here is the caller graph for this function:

◆ reset()

virtual int GPSHelper::reset ( GPSRestartType  restart_type)
inlinevirtual

Reset GPS device.

Parameters
restart_type
Returns
<0 failure -1 not implemented 0 success

Reimplemented in GPSDriverUBX, and GPSDriverSBF.

Definition at line 188 of file gps_helper.h.

Referenced by GPS::reset_if_scheduled().

Here is the caller graph for this function:

◆ resetUpdateRates()

void GPSHelper::resetUpdateRates ( )

Definition at line 55 of file gps_helper.cpp.

References _interval_rate_start, _rate_count_lat_lon, _rate_count_vel, and gps_absolute_time.

Referenced by GPS::run().

Here is the caller graph for this function:

◆ setBaudrate()

int GPSHelper::setBaudrate ( int  baudrate)
inlineprotected

set the Baudrate

Parameters
baudrate
Returns
0 on success, <0 otherwise

Definition at line 228 of file gps_helper.h.

References setBaudrate.

Referenced by GPSDriverAshtech::configure(), GPSDriverMTK::configure(), GPSDriverEmlidReach::configure(), GPSDriverSBF::configure(), and GPSDriverUBX::configure().

Here is the caller graph for this function:

◆ setClock()

void GPSHelper::setClock ( timespec &  t)
inlineprotected

Definition at line 244 of file gps_helper.h.

References setClock.

Referenced by GPSDriverAshtech::handleMessage(), GPSDriverMTK::handleMessage(), GPSDriverSBF::payloadRxDone(), and GPSDriverUBX::payloadRxDone().

Here is the caller graph for this function:

◆ storeUpdateRates()

void GPSHelper::storeUpdateRates ( )

Definition at line 63 of file gps_helper.cpp.

References _interval_rate_start, _rate_count_lat_lon, _rate_count_vel, _rate_lat_lon, _rate_vel, and gps_absolute_time.

Referenced by GPS::run().

Here is the caller graph for this function:

◆ surveyInStatus()

void GPSHelper::surveyInStatus ( SurveyInStatus status)
inlineprotected

Definition at line 233 of file gps_helper.h.

References surveyInStatus.

Referenced by GPSDriverAshtech::configure(), GPSDriverUBX::payloadRxDone(), and GPSDriverAshtech::sendSurveyInStatusUpdate().

Here is the caller graph for this function:

◆ write()

int GPSHelper::write ( const void *  buf,
int  buf_length 
)
inlineprotected

write to the device

Parameters
buf
buf_length
Returns
num written bytes, -1 on error

Definition at line 218 of file gps_helper.h.

References writeDeviceData.

Referenced by GPSDriverAshtech::activateCorrectionOutput(), GPSDriverAshtech::configure(), GPSDriverMTK::configure(), GPSDriverSBF::sendMessage(), GPSDriverUBX::sendMessage(), GPSDriverSBF::sendMessageAndWaitForAck(), and GPSDriverAshtech::writeAckedCommand().

Here is the caller graph for this function:

Member Data Documentation

◆ _callback

GPSCallbackPtr GPSHelper::_callback {nullptr}
protected

Definition at line 261 of file gps_helper.h.

◆ _callback_user

void* GPSHelper::_callback_user {}
protected

Definition at line 262 of file gps_helper.h.

◆ _interval_rate_start

uint64_t GPSHelper::_interval_rate_start {0}
protected

Definition at line 270 of file gps_helper.h.

Referenced by resetUpdateRates(), and storeUpdateRates().

◆ _rate_count_lat_lon

◆ _rate_count_vel

◆ _rate_lat_lon

float GPSHelper::_rate_lat_lon {0.0f}
protected

Definition at line 267 of file gps_helper.h.

Referenced by storeUpdateRates().

◆ _rate_vel

float GPSHelper::_rate_vel {0.0f}
protected

Definition at line 268 of file gps_helper.h.

Referenced by storeUpdateRates().


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