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

#include <sbf.h>

Inheritance diagram for GPSDriverSBF:
Collaboration diagram for GPSDriverSBF:

Public Member Functions

 GPSDriverSBF (GPSCallbackPtr callback, void *callback_user, struct vehicle_gps_position_s *gps_position, struct satellite_info_s *satellite_info, uint8_t dynamic_model)
 
virtual ~GPSDriverSBF () override
 
int receive (unsigned timeout) override
 receive & handle new data from the device More...
 
int configure (unsigned &baudrate, OutputMode output_mode) override
 
int reset (GPSRestartType restart_type) override
 Reset GPS device. More...
 
- Public Member Functions inherited from GPSBaseStationSupport
 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...
 
float getPositionUpdateRate ()
 
float getVelocityUpdateRate ()
 
void resetUpdateRates ()
 
void storeUpdateRates ()
 

Private Member Functions

int parseChar (const uint8_t b)
 Parse the binary SBF packet. More...
 
int payloadRxAdd (const uint8_t b)
 Add payload rx byte. More...
 
int payloadRxDone (void)
 Finish payload rx. More...
 
void decodeInit (void)
 Reset the parse state machine for a fresh start. More...
 
bool sendMessage (const char *msg)
 Send a message. More...
 
bool sendMessageAndWaitForAck (const char *msg, const int timeout)
 Send a message and waits for acknowledge. More...
 

Private Attributes

struct vehicle_gps_position_s_gps_position { nullptr }
 
struct satellite_info_s_satellite_info { nullptr }
 
uint8_t _dynamic_model { 7 }
 
uint64_t _last_timestamp_time { 0 }
 
bool _configured { false }
 
uint8_t _msg_status { 0 }
 
sbf_decode_state_t _decode_state { SBF_DECODE_SYNC1 }
 
uint16_t _rx_payload_index { 0 }
 
sbf_buf_t _buf
 
OutputMode _output_mode { OutputMode::GPS }
 
RTCMParsing_rtcm_parsing { nullptr }
 

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 Types inherited from GPSBaseStationSupport
enum  BaseSettingsType : uint8_t { BaseSettingsType::survey_in, BaseSettingsType::fixed_position }
 
- 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 GPSBaseStationSupport
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}
 

Detailed Description

Definition at line 308 of file sbf.h.

Constructor & Destructor Documentation

◆ GPSDriverSBF()

GPSDriverSBF::GPSDriverSBF ( GPSCallbackPtr  callback,
void *  callback_user,
struct vehicle_gps_position_s gps_position,
struct satellite_info_s satellite_info,
uint8_t  dynamic_model 
)

Definition at line 59 of file sbf.cpp.

References decodeInit().

Here is the call graph for this function:

◆ ~GPSDriverSBF()

GPSDriverSBF::~GPSDriverSBF ( )
overridevirtual

Definition at line 71 of file sbf.cpp.

Member Function Documentation

◆ configure()

◆ decodeInit()

void GPSDriverSBF::decodeInit ( void  )
private

Reset the parse state machine for a fresh start.

Definition at line 550 of file sbf.cpp.

References _decode_state, _output_mode, _rtcm_parsing, _rx_payload_index, RTCMParsing::reset(), GPSHelper::RTCM, and SBF_DECODE_SYNC1.

Referenced by configure(), GPSDriverSBF(), and parseChar().

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

◆ parseChar()

int GPSDriverSBF::parseChar ( const uint8_t  b)
private

Parse the binary SBF packet.

Definition at line 276 of file sbf.cpp.

References _decode_state, _rtcm_parsing, RTCMParsing::addByte(), decodeInit(), GPSHelper::gotRTCMMessage(), RTCMParsing::message(), RTCMParsing::messageLength(), payloadRxAdd(), payloadRxDone(), RTCM3_PREAMBLE, SBF_DEBUG, SBF_DECODE_PAYLOAD, SBF_DECODE_RTCM3, SBF_DECODE_SYNC1, SBF_DECODE_SYNC2, SBF_SYNC1, SBF_SYNC2, and SBF_TRACE_PARSER.

Referenced by receive().

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

◆ payloadRxAdd()

int GPSDriverSBF::payloadRxAdd ( const uint8_t  b)
private

Add payload rx byte.

Definition at line 350 of file sbf.cpp.

References _buf, _rx_payload_index, and sbf_buf_t::length.

Referenced by parseChar().

Here is the caller graph for this function:

◆ payloadRxDone()

int GPSDriverSBF::payloadRxDone ( void  )
private

Finish payload rx.

Definition at line 386 of file sbf.cpp.

References _buf, _gps_position, _last_timestamp_time, _msg_status, GPSHelper::_rate_count_lat_lon, GPSHelper::_rate_count_vel, _satellite_info, vehicle_gps_position_s::alt, vehicle_gps_position_s::alt_ellipsoid, vehicle_gps_position_s::c_variance_rad, sbf_payload_pvt_geodetic_t::cog, vehicle_gps_position_s::cog_rad, satellite_info_s::count, sbf_payload_vel_cov_geodetic_t::cov_ve_ve, sbf_payload_vel_cov_geodetic_t::cov_vn_vn, sbf_payload_vel_cov_geodetic_t::cov_vu_vu, sbf_buf_t::crc16, crc16(), vehicle_gps_position_s::eph, vehicle_gps_position_s::epv, sbf_payload_pvt_geodetic_t::error, f(), vehicle_gps_position_s::fix_type, gps_absolute_time, GPS_EPOCH_SECS, sbf_payload_pvt_geodetic_t::h_accuracy, vehicle_gps_position_s::hdop, sbf_payload_dop_t::hDOP, sbf_payload_pvt_geodetic_t::height, vehicle_gps_position_s::lat, sbf_payload_pvt_geodetic_t::latitude, sbf_buf_t::length, vehicle_gps_position_s::lon, sbf_payload_pvt_geodetic_t::longitude, sbf_payload_pvt_geodetic_t::mode_type, sbf_buf_t::msg_id, sbf_payload_pvt_geodetic_t::nr_sv, sbf_buf_t::payload_dop, sbf_buf_t::payload_pvt_geodetic, sbf_buf_t::payload_vel_col_geodetic, vehicle_gps_position_s::s_variance_m_s, vehicle_gps_position_s::satellites_used, SBF_ID_DOP, SBF_ID_PVTGeodetic, SBF_ID_VelCovGeodetic, SBF_TRACE_RXMSG, GPSHelper::setClock(), vehicle_gps_position_s::time_utc_usec, vehicle_gps_position_s::timestamp, satellite_info_s::timestamp, vehicle_gps_position_s::timestamp_time_relative, sbf_buf_t::TOW, sbf_payload_pvt_geodetic_t::undulation, sbf_payload_pvt_geodetic_t::v_accuracy, vehicle_gps_position_s::vdop, sbf_payload_dop_t::vDOP, sbf_payload_pvt_geodetic_t::ve, 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, sbf_payload_pvt_geodetic_t::vn, sbf_payload_pvt_geodetic_t::vu, and sbf_buf_t::WNc.

Referenced by parseChar().

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

◆ receive()

int GPSDriverSBF::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 229 of file sbf.cpp.

References _configured, gps_absolute_time, GPS_READ_BUFFER_SIZE, gps_usleep, parseChar(), GPSHelper::read(), SBF_DEBUG, SBF_PACKET_TIMEOUT, and SBF_WARN.

Referenced by configure().

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

◆ reset()

int GPSDriverSBF::reset ( GPSRestartType  restart_type)
overridevirtual

Reset GPS device.

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

Reimplemented from GPSHelper.

Definition at line 565 of file sbf.cpp.

References Cold, Hot, SBF_CONFIG_RESET_COLD, SBF_CONFIG_RESET_HOT, SBF_CONFIG_RESET_WARM, SBF_CONFIG_TIMEOUT, sendMessageAndWaitForAck(), and Warm.

Here is the call graph for this function:

◆ sendMessage()

bool GPSDriverSBF::sendMessage ( const char *  msg)
private

Send a message.

Returns
true on success, false on write error (errno set)

Definition at line 170 of file sbf.cpp.

References SBF_DEBUG, and GPSHelper::write().

Referenced by configure().

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

◆ sendMessageAndWaitForAck()

bool GPSDriverSBF::sendMessageAndWaitForAck ( const char *  msg,
const int  timeout 
)
private

Send a message and waits for acknowledge.

Returns
true on success, false on write error (errno set) or ack wait timeout

Definition at line 181 of file sbf.cpp.

References gps_absolute_time, GPS_READ_BUFFER_SIZE, GPSHelper::read(), SBF_DEBUG, SBF_WARN, and GPSHelper::write().

Referenced by configure(), and reset().

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

Member Data Documentation

◆ _buf

sbf_buf_t GPSDriverSBF::_buf
private

Definition at line 364 of file sbf.h.

Referenced by payloadRxAdd(), and payloadRxDone().

◆ _configured

bool GPSDriverSBF::_configured { false }
private

Definition at line 360 of file sbf.h.

Referenced by configure(), and receive().

◆ _decode_state

sbf_decode_state_t GPSDriverSBF::_decode_state { SBF_DECODE_SYNC1 }
private

Definition at line 362 of file sbf.h.

Referenced by decodeInit(), and parseChar().

◆ _dynamic_model

uint8_t GPSDriverSBF::_dynamic_model { 7 }
private

Definition at line 358 of file sbf.h.

Referenced by configure().

◆ _gps_position

struct vehicle_gps_position_s* GPSDriverSBF::_gps_position { nullptr }
private

Definition at line 356 of file sbf.h.

Referenced by payloadRxDone().

◆ _last_timestamp_time

uint64_t GPSDriverSBF::_last_timestamp_time { 0 }
private

Definition at line 359 of file sbf.h.

Referenced by payloadRxDone().

◆ _msg_status

uint8_t GPSDriverSBF::_msg_status { 0 }
private

Definition at line 361 of file sbf.h.

Referenced by payloadRxDone().

◆ _output_mode

OutputMode GPSDriverSBF::_output_mode { OutputMode::GPS }
private

Definition at line 365 of file sbf.h.

Referenced by configure(), and decodeInit().

◆ _rtcm_parsing

RTCMParsing* GPSDriverSBF::_rtcm_parsing { nullptr }
private

Definition at line 366 of file sbf.h.

Referenced by decodeInit(), and parseChar().

◆ _rx_payload_index

uint16_t GPSDriverSBF::_rx_payload_index { 0 }
private

Definition at line 363 of file sbf.h.

Referenced by decodeInit(), and payloadRxAdd().

◆ _satellite_info

struct satellite_info_s* GPSDriverSBF::_satellite_info { nullptr }
private

Definition at line 357 of file sbf.h.

Referenced by payloadRxDone().


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