PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <sbf.h>
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} |
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().
|
override |
Definition at line 76 of file sbf.cpp.
References GPSBaseStationSupport::_base_settings, _configured, _dynamic_model, _output_mode, GPSBaseStationSupport::FixedPositionSettings::altitude, decodeInit(), GPSBaseStationSupport::fixed_position, GPSBaseStationSupport::BaseSettings::fixed_position, GPSBaseStationSupport::FixedPositionSettings::latitude, GPSBaseStationSupport::FixedPositionSettings::longitude, msg, receive(), GPSHelper::RTCM, SBF_CONFIG, SBF_CONFIG_BAUDRATE, SBF_CONFIG_FORCE_INPUT, SBF_CONFIG_RECEIVER_DYNAMICS, SBF_CONFIG_RESET, SBF_CONFIG_RTCM, SBF_CONFIG_RTCM_STATIC1, SBF_CONFIG_RTCM_STATIC2, SBF_CONFIG_RTCM_STATIC_COORDINATES, SBF_CONFIG_RTCM_STATIC_OFFSET, SBF_CONFIG_TIMEOUT, SBF_TX_CFG_PRT_BAUDRATE, sendMessage(), sendMessageAndWaitForAck(), GPSHelper::setBaudrate(), GPSBaseStationSupport::BaseSettings::settings, and GPSBaseStationSupport::BaseSettings::type.
|
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().
|
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().
|
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().
|
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().
|
overridevirtual |
receive & handle new data from the device
timeout | [ms] |
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().
|
overridevirtual |
Reset GPS device.
restart_type |
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.
|
private |
Send a message.
Definition at line 170 of file sbf.cpp.
References SBF_DEBUG, and GPSHelper::write().
Referenced by configure().
|
private |
Send a message and waits for acknowledge.
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().
|
private |
Definition at line 364 of file sbf.h.
Referenced by payloadRxAdd(), and payloadRxDone().
|
private |
Definition at line 360 of file sbf.h.
Referenced by configure(), and receive().
|
private |
Definition at line 362 of file sbf.h.
Referenced by decodeInit(), and parseChar().
|
private |
Definition at line 358 of file sbf.h.
Referenced by configure().
|
private |
Definition at line 356 of file sbf.h.
Referenced by payloadRxDone().
|
private |
Definition at line 359 of file sbf.h.
Referenced by payloadRxDone().
|
private |
Definition at line 361 of file sbf.h.
Referenced by payloadRxDone().
|
private |
Definition at line 365 of file sbf.h.
Referenced by configure(), and decodeInit().
|
private |
Definition at line 366 of file sbf.h.
Referenced by decodeInit(), and parseChar().
|
private |
Definition at line 363 of file sbf.h.
Referenced by decodeInit(), and payloadRxAdd().
|
private |
Definition at line 357 of file sbf.h.
Referenced by payloadRxDone().