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

Driver class for Emlid Reach Populates caller provided vehicle_gps_position_s Some ERB messages are cached and correlated by timestamp before publishing it. More...

#include <emlid_reach.h>

Inheritance diagram for GPSDriverEmlidReach:
Collaboration diagram for GPSDriverEmlidReach:

Public Member Functions

 GPSDriverEmlidReach (GPSCallbackPtr callback, void *callback_user, struct vehicle_gps_position_s *gps_position, struct satellite_info_s *satellite_info)
 
virtual ~GPSDriverEmlidReach ()=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 Types

enum  ERB_State {
  ERB_State::init = 0, ERB_State::got_sync_1, ERB_State::got_sync_2, ERB_State::got_id,
  ERB_State::got_len_1, ERB_State::got_len_2, ERB_State::got_payload, ERB_State::got_CK_A
}
 

Private Member Functions

int erbParseChar (uint8_t b)
 Feed ERB parser with received bytes from serial. More...
 
int handleErbSentence ()
 ERB sentence into vehicle_gps_position_s or satellite_info_s, to be used by GPSHelper. More...
 
void computeNedVelocity ()
 
bool testConnection ()
 

Private Attributes

ERB_State _erb_decode_state
 NMEA parser state machine. More...
 
erb_message_t _erb_buff {}
 Buffer used by parser to build ERB sentences. More...
 
uint16_t _erb_buff_cnt {}
 
erb_checksum_t _erb_checksum {}
 Buffer used by parser to build ERB checksum. More...
 
uint8_t _erb_checksum_cnt {}
 
struct vehicle_gps_position_s_gps_position {nullptr}
 Pointer provided by caller, ie gps.cpp. More...
 
struct satellite_info_s_satellite_info {nullptr}
 Pointer provided by caller, gps.cpp. More...
 
bool _testing_connection {false}
 
unsigned _sentence_cnt {0}
 counts decoded sentence when testing connection More...
 
uint16_t _erb_payload_len {0}
 
uint32_t _last_POS_timeGPS {0}
 
uint32_t _last_VEL_timeGPS {0}
 
bool _POS_received {false}
 
bool _VEL_received {false}
 
uint8_t _fix_type {0}
 
uint8_t _fix_status {0}
 
uint8_t _satellites_used {0}
 
float _hdop {0}
 
float _vdop {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...
 
- 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

Driver class for Emlid Reach Populates caller provided vehicle_gps_position_s Some ERB messages are cached and correlated by timestamp before publishing it.

Definition at line 139 of file emlid_reach.h.

Member Enumeration Documentation

◆ ERB_State

enum GPSDriverEmlidReach::ERB_State
strongprivate
Enumerator
init 
got_sync_1 
got_sync_2 
got_id 
got_len_1 
got_len_2 
got_payload 
got_CK_A 

Definition at line 154 of file emlid_reach.h.

Constructor & Destructor Documentation

◆ GPSDriverEmlidReach()

GPSDriverEmlidReach::GPSDriverEmlidReach ( GPSCallbackPtr  callback,
void *  callback_user,
struct vehicle_gps_position_s gps_position,
struct satellite_info_s satellite_info 
)

Definition at line 73 of file emlid_reach.cpp.

◆ ~GPSDriverEmlidReach()

virtual GPSDriverEmlidReach::~GPSDriverEmlidReach ( )
virtualdefault

Member Function Documentation

◆ computeNedVelocity()

void GPSDriverEmlidReach::computeNedVelocity ( )
private

◆ configure()

int GPSDriverEmlidReach::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 81 of file emlid_reach.cpp.

References _erb_buff_cnt, _erb_decode_state, _erb_payload_len, _sentence_cnt, GPSHelper::GPS, GPS_WARN, init, GPSHelper::setBaudrate(), and testConnection().

Here is the call graph for this function:

◆ erbParseChar()

int GPSDriverEmlidReach::erbParseChar ( uint8_t  b)
private

Feed ERB parser with received bytes from serial.

Returns
len of decoded message, 0 if not completed, -1 if error

Definition at line 178 of file emlid_reach.cpp.

References _erb_buff, _erb_buff_cnt, _erb_checksum, _erb_decode_state, _erb_payload_len, erb_checksum_t::ck_a, erb_checksum_t::ck_b, ERB_HEADER_LEN, ERB_ID_RTK, ERB_ID_SPACE_INFO, ERB_ID_VERSION, ERB_SENTENCE_MAX_LEN, ERB_SYNC_1, ERB_SYNC_2, got_CK_A, got_id, got_len_1, got_len_2, got_payload, got_sync_1, got_sync_2, and init.

Referenced by receive().

Here is the caller graph for this function:

◆ handleErbSentence()

int GPSDriverEmlidReach::handleErbSentence ( )
private

ERB sentence into vehicle_gps_position_s or satellite_info_s, to be used by GPSHelper.

Returns
1 if gps_position updated, 2 for satellite_info_s (can be bit OR), 0 for nothing

Definition at line 276 of file emlid_reach.cpp.

References _erb_buff, _fix_status, _fix_type, _gps_position, _hdop, _last_POS_timeGPS, _last_VEL_timeGPS, _POS_received, GPSHelper::_rate_count_lat_lon, GPSHelper::_rate_count_vel, _satellites_used, _vdop, _VEL_received, erb_geodic_position_t::accHorizontal, erb_geodic_position_t::accVertical, vehicle_gps_position_s::alt, vehicle_gps_position_s::alt_ellipsoid, erb_geodic_position_t::altElipsoid, erb_geodic_position_t::altMeanSeaLevel, vehicle_gps_position_s::cog_rad, erb_payload_t::dop, erb_dop_t::dopHorizontal, erb_dop_t::dopVertical, vehicle_gps_position_s::eph, vehicle_gps_position_s::epv, ERB_ID_DOPS, ERB_ID_GEODIC_POSITION, ERB_ID_NAV_STATUS, ERB_ID_RTK, ERB_ID_SPACE_INFO, ERB_ID_VELOCITY_NED, ERB_ID_VERSION, f(), vehicle_gps_position_s::fix_type, erb_navigation_status_t::fixStatus, erb_navigation_status_t::fixType, erb_payload_t::geodic_position, gps_absolute_time, GPS_PI, vehicle_gps_position_s::hdop, erb_message_t::header, erb_ned_velocity_t::heading, erb_header_t::id, vehicle_gps_position_s::lat, erb_geodic_position_t::latitude, vehicle_gps_position_s::lon, erb_geodic_position_t::longitude, erb_payload_t::navigation_status, erb_payload_t::ned_velocity, erb_navigation_status_t::numSatUsed, erb_message_t::payload, vehicle_gps_position_s::s_variance_m_s, vehicle_gps_position_s::satellites_used, erb_ned_velocity_t::speed, erb_ned_velocity_t::speedAccuracy, erb_geodic_position_t::timeGPS, erb_ned_velocity_t::timeGPS, vehicle_gps_position_s::timestamp, vehicle_gps_position_s::vdop, vehicle_gps_position_s::vel_d_m_s, vehicle_gps_position_s::vel_e_m_s, vehicle_gps_position_s::vel_m_s, vehicle_gps_position_s::vel_n_m_s, vehicle_gps_position_s::vel_ned_valid, erb_ned_velocity_t::velD, erb_ned_velocity_t::velE, and erb_ned_velocity_t::velN.

Referenced by receive().

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

◆ receive()

int GPSDriverEmlidReach::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 128 of file emlid_reach.cpp.

References _sentence_cnt, _testing_connection, erbParseChar(), gps_absolute_time, GPS_READ_BUFFER_SIZE, handleErbSentence(), and GPSHelper::read().

Referenced by testConnection().

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

◆ testConnection()

bool GPSDriverEmlidReach::testConnection ( )
private

Definition at line 118 of file emlid_reach.cpp.

References _sentence_cnt, _testing_connection, AUTO_DETECT_MAX_READ_SENTENCE, and receive().

Referenced by configure().

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

Member Data Documentation

◆ _erb_buff

erb_message_t GPSDriverEmlidReach::_erb_buff {}
private

Buffer used by parser to build ERB sentences.

Definition at line 170 of file emlid_reach.h.

Referenced by erbParseChar(), and handleErbSentence().

◆ _erb_buff_cnt

uint16_t GPSDriverEmlidReach::_erb_buff_cnt {}
private

Definition at line 171 of file emlid_reach.h.

Referenced by configure(), and erbParseChar().

◆ _erb_checksum

erb_checksum_t GPSDriverEmlidReach::_erb_checksum {}
private

Buffer used by parser to build ERB checksum.

Definition at line 174 of file emlid_reach.h.

Referenced by erbParseChar().

◆ _erb_checksum_cnt

uint8_t GPSDriverEmlidReach::_erb_checksum_cnt {}
private

Definition at line 175 of file emlid_reach.h.

◆ _erb_decode_state

ERB_State GPSDriverEmlidReach::_erb_decode_state
private

NMEA parser state machine.

Definition at line 167 of file emlid_reach.h.

Referenced by configure(), and erbParseChar().

◆ _erb_payload_len

uint16_t GPSDriverEmlidReach::_erb_payload_len {0}
private

Definition at line 186 of file emlid_reach.h.

Referenced by configure(), and erbParseChar().

◆ _fix_status

uint8_t GPSDriverEmlidReach::_fix_status {0}
private

Definition at line 196 of file emlid_reach.h.

Referenced by handleErbSentence().

◆ _fix_type

uint8_t GPSDriverEmlidReach::_fix_type {0}
private

Definition at line 195 of file emlid_reach.h.

Referenced by handleErbSentence().

◆ _gps_position

struct vehicle_gps_position_s* GPSDriverEmlidReach::_gps_position {nullptr}
private

Pointer provided by caller, ie gps.cpp.

Definition at line 178 of file emlid_reach.h.

Referenced by handleErbSentence().

◆ _hdop

float GPSDriverEmlidReach::_hdop {0}
private

Definition at line 198 of file emlid_reach.h.

Referenced by handleErbSentence().

◆ _last_POS_timeGPS

uint32_t GPSDriverEmlidReach::_last_POS_timeGPS {0}
private

Definition at line 188 of file emlid_reach.h.

Referenced by handleErbSentence().

◆ _last_VEL_timeGPS

uint32_t GPSDriverEmlidReach::_last_VEL_timeGPS {0}
private

Definition at line 189 of file emlid_reach.h.

Referenced by handleErbSentence().

◆ _POS_received

bool GPSDriverEmlidReach::_POS_received {false}
private

Definition at line 190 of file emlid_reach.h.

Referenced by handleErbSentence().

◆ _satellite_info

struct satellite_info_s* GPSDriverEmlidReach::_satellite_info {nullptr}
private

Pointer provided by caller, gps.cpp.

Definition at line 180 of file emlid_reach.h.

◆ _satellites_used

uint8_t GPSDriverEmlidReach::_satellites_used {0}
private

Definition at line 197 of file emlid_reach.h.

Referenced by handleErbSentence().

◆ _sentence_cnt

unsigned GPSDriverEmlidReach::_sentence_cnt {0}
private

counts decoded sentence when testing connection

Definition at line 184 of file emlid_reach.h.

Referenced by configure(), receive(), and testConnection().

◆ _testing_connection

bool GPSDriverEmlidReach::_testing_connection {false}
private

Definition at line 182 of file emlid_reach.h.

Referenced by receive(), and testConnection().

◆ _vdop

float GPSDriverEmlidReach::_vdop {0}
private

Definition at line 199 of file emlid_reach.h.

Referenced by handleErbSentence().

◆ _VEL_received

bool GPSDriverEmlidReach::_VEL_received {false}
private

Definition at line 191 of file emlid_reach.h.

Referenced by handleErbSentence().


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