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

#include <mtk.h>

Inheritance diagram for GPSDriverMTK:
Collaboration diagram for GPSDriverMTK:

Public Member Functions

 GPSDriverMTK (GPSCallbackPtr callback, void *callback_user, struct vehicle_gps_position_s *gps_position)
 
virtual ~GPSDriverMTK ()=default
 
int receive (unsigned timeout) override
 receive & handle new data from the device More...
 
int configure (unsigned &baudrate, OutputMode output_mode) override
 configure the device More...
 
- Public Member Functions inherited from GPSHelper
 GPSHelper (GPSCallbackPtr callback, void *callback_user)
 
virtual ~GPSHelper ()=default
 
virtual int reset (GPSRestartType restart_type)
 Reset GPS device. More...
 
float getPositionUpdateRate ()
 
float getVelocityUpdateRate ()
 
void resetUpdateRates ()
 
void storeUpdateRates ()
 

Private Member Functions

int parseChar (uint8_t b, gps_mtk_packet_t &packet)
 Parse the binary MTK packet. More...
 
void handleMessage (gps_mtk_packet_t &packet)
 Handle the package once it has arrived. More...
 
void decodeInit ()
 Reset the parse state machine for a fresh start. More...
 
void addByteToChecksum (uint8_t)
 While parsing add every byte (except the sync bytes) to the checksum. More...
 

Private Attributes

struct vehicle_gps_position_s_gps_position {nullptr}
 
mtk_decode_state_t _decode_state {MTK_DECODE_UNINIT}
 
uint8_t _mtk_revision {0}
 
unsigned _rx_count {}
 
uint8_t _rx_ck_a {}
 
uint8_t _rx_ck_b {}
 

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

Detailed Description

Definition at line 88 of file mtk.h.

Constructor & Destructor Documentation

◆ GPSDriverMTK()

GPSDriverMTK::GPSDriverMTK ( GPSCallbackPtr  callback,
void *  callback_user,
struct vehicle_gps_position_s gps_position 
)

Definition at line 50 of file mtk.cpp.

References decodeInit().

Here is the call graph for this function:

◆ ~GPSDriverMTK()

virtual GPSDriverMTK::~GPSDriverMTK ( )
virtualdefault

Member Function Documentation

◆ addByteToChecksum()

void GPSDriverMTK::addByteToChecksum ( uint8_t  b)
private

While parsing add every byte (except the sync bytes) to the checksum.

Definition at line 302 of file mtk.cpp.

References _rx_ck_a, and _rx_ck_b.

Referenced by parseChar().

Here is the caller graph for this function:

◆ configure()

int GPSDriverMTK::configure ( unsigned &  baud,
OutputMode  output_mode 
)
overridevirtual

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

Implements GPSHelper.

Definition at line 58 of file mtk.cpp.

References GPSHelper::GPS, gps_usleep, GPS_WARN, MTK_BAUDRATE, MTK_NAVTHRES_OFF, MTK_OUTPUT_5HZ, MTK_SBAS_ON, MTK_SET_BINARY, MTK_WAAS_ON, GPSHelper::setBaudrate(), and GPSHelper::write().

Here is the call graph for this function:

◆ decodeInit()

void GPSDriverMTK::decodeInit ( void  )
private

Reset the parse state machine for a fresh start.

Definition at line 156 of file mtk.cpp.

References _decode_state, _rx_ck_a, _rx_ck_b, _rx_count, and MTK_DECODE_UNINIT.

Referenced by GPSDriverMTK(), and parseChar().

Here is the caller graph for this function:

◆ handleMessage()

◆ parseChar()

int GPSDriverMTK::parseChar ( uint8_t  b,
gps_mtk_packet_t packet 
)
private

Parse the binary MTK packet.

Definition at line 164 of file mtk.cpp.

References _decode_state, _mtk_revision, _rx_ck_a, _rx_ck_b, _rx_count, addByteToChecksum(), gps_mtk_packet_t::ck_a, gps_mtk_packet_t::ck_b, decodeInit(), MTK_DECODE_GOT_CK_A, MTK_DECODE_GOT_CK_B, MTK_DECODE_UNINIT, MTK_SYNC1_V16, MTK_SYNC1_V19, and MTK_SYNC2.

Referenced by receive().

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

◆ receive()

int GPSDriverMTK::receive ( unsigned  timeout)
overridevirtual

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

Implements GPSHelper.

Definition at line 113 of file mtk.cpp.

References gps_absolute_time, GPS_READ_BUFFER_SIZE, gps_usleep, handleMessage(), parseChar(), and GPSHelper::read().

Here is the call graph for this function:

Member Data Documentation

◆ _decode_state

mtk_decode_state_t GPSDriverMTK::_decode_state {MTK_DECODE_UNINIT}
private

Definition at line 119 of file mtk.h.

Referenced by decodeInit(), and parseChar().

◆ _gps_position

struct vehicle_gps_position_s* GPSDriverMTK::_gps_position {nullptr}
private

Definition at line 118 of file mtk.h.

Referenced by handleMessage().

◆ _mtk_revision

uint8_t GPSDriverMTK::_mtk_revision {0}
private

Definition at line 120 of file mtk.h.

Referenced by handleMessage(), and parseChar().

◆ _rx_ck_a

uint8_t GPSDriverMTK::_rx_ck_a {}
private

Definition at line 122 of file mtk.h.

Referenced by addByteToChecksum(), decodeInit(), and parseChar().

◆ _rx_ck_b

uint8_t GPSDriverMTK::_rx_ck_b {}
private

Definition at line 123 of file mtk.h.

Referenced by addByteToChecksum(), decodeInit(), and parseChar().

◆ _rx_count

unsigned GPSDriverMTK::_rx_count {}
private

Definition at line 121 of file mtk.h.

Referenced by decodeInit(), and parseChar().


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