Public Member Functions | Public Attributes | Private Types | Private Member Functions | Private Attributes | List of all members
io_comm_rx::RxMessage Class Reference

Can search buffer for messages, read/parse them, and so on. More...

#include <rx_message.hpp>

Public Member Functions

bool diagnostics_complete (uint32_t id)
 Wether all blocks have arrived for Diagnostics Message. More...
 
bool found ()
 Has an NMEA message, SBF block or command reply been found in the buffer? More...
 
uint16_t getBlockLength ()
 Gets the length of the SBF block. More...
 
std::size_t getCount ()
 Returns the count_ variable. More...
 
const uint8_t * getEndBuffer ()
 Gets the end position in the read buffer. More...
 
const uint8_t * getPosBuffer ()
 Gets the current position in the read buffer. More...
 
bool gnss_gpsfix_complete (uint32_t id)
 Wether all blocks from GNSS have arrived for GpsFix Message. More...
 
bool gnss_navsatfix_complete (uint32_t id)
 Wether all blocks from GNSS have arrived for NavSatFix Message. More...
 
bool gnss_pose_complete (uint32_t id)
 Wether all blocks from GNSS have arrived for Pose Message. More...
 
bool ins_gpsfix_complete (uint32_t id)
 Wether all blocks from INS have arrived for GpsFix Message. More...
 
bool ins_localization_complete (uint32_t id)
 Wether all blocks have arrived for Localization Message. More...
 
bool ins_navsatfix_complete (uint32_t id)
 Wether all blocks from INS have arrived for NavSatFix Message. More...
 
bool ins_pose_complete (uint32_t id)
 Wether all blocks from INS have arrived for Pose Message. More...
 
bool isConnectionDescriptor ()
 
bool isErrorMessage ()
 
bool isMessage (const uint16_t ID)
 Determines whether data_ points to the SBF block with ID "ID", e.g. 5003. More...
 
bool isMessage (std::string ID)
 
bool isNMEA ()
 Determines whether data_ currently points to an NMEA message. More...
 
bool isResponse ()
 Determines whether data_ currently points to an NMEA message. More...
 
bool isSBF ()
 Determines whether data_ currently points to an SBF block. More...
 
std::string messageID ()
 
std::size_t messageSize ()
 
void newData (Timestamp recvTimestamp, const uint8_t *data, std::size_t &size)
 Put new data. More...
 
void next ()
 Goes to the start of the next message based on the calculated length of current message. More...
 
template<typename M >
void publish (const std::string &topic, const M &msg)
 Publishing function. More...
 
void publishTf (const LocalizationUtmMsg &msg)
 Publishing function. More...
 
bool read (std::string message_key, bool search=false)
 Performs the CRC check (if SBF) and publishes ROS messages. More...
 
 RxMessage (ROSaicNodeBase *node, Settings *settings)
 Constructor of the RxMessage class. More...
 
const uint8_t * search ()
 Searches the buffer for the beginning of the next message (NMEA or SBF) More...
 

Public Attributes

bool found_
 Whether or not a message has been found. More...
 

Private Types

typedef std::unordered_map< std::string, RxID_EnumRxIDMap
 
typedef std::unordered_map< uint16_t, TypeOfPVT_EnumTypeOfPVTMap
 

Private Member Functions

bool allTrue (std::vector< bool > &vec, uint32_t id)
 Wether all elements are true. More...
 
DiagnosticArrayMsg DiagnosticArrayCallback ()
 "Callback" function when constructing DiagnosticArrayMsg messages More...
 
GPSFixMsg GPSFixCallback ()
 "Callback" function when constructing GPSFix messages More...
 
ImuMsg ImuCallback ()
 "Callback" function when constructing ImuMsg messages More...
 
LocalizationUtmMsg LocalizationUtmCallback ()
 "Callback" function when constructing LocalizationUtmMsg messages More...
 
NavSatFixMsg NavSatFixCallback ()
 "Callback" function when constructing NavSatFix messages More...
 
PoseWithCovarianceStampedMsg PoseWithCovarianceStampedCallback ()
 "Callback" function when constructing PoseWithCovarianceStamped messages More...
 
Timestamp timestampSBF (const uint8_t *data, bool use_gnss_time)
 Calculates the timestamp, in the Unix Epoch time format This is either done using the TOW as transmitted with the SBF block (if "use_gnss" is true), or using the current time. More...
 
Timestamp timestampSBF (uint32_t tow, uint16_t wnc, bool use_gnss_time)
 Calculates the timestamp, in the Unix Epoch time format This is either done using the TOW as transmitted with the SBF block (if "use_gnss" is true), or using the current time. More...
 
TwistWithCovarianceStampedMsg TwistCallback (bool fromIns=false)
 "Callback" function when constructing TwistWithCovarianceStampedMsg messages More...
 
void wait (Timestamp time_obj)
 Waits according to time when reading from file. More...
 

Private Attributes

bool attcoveuler_has_arrived_gpsfix_ = false
 
bool attcoveuler_has_arrived_pose_ = false
 
bool atteuler_has_arrived_gpsfix_ = false
 
bool atteuler_has_arrived_pose_ = false
 
bool channelstatus_has_arrived_gpsfix_ = false
 
std::size_t count_
 Number of unread bytes in the buffer. More...
 
uint32_t count_gpsfix_ = 0
 Number of times the GPSFixMsg message has been published. More...
 
bool crc_check_
 Whether the CRC check as evaluated in the read() method was successful or not is stored here. More...
 
int8_t current_leap_seconds_ = -128
 Current leap seconds as received, do not use value is -128. More...
 
const uint8_t * data_
 Pointer to the buffer of messages. More...
 
bool dop_has_arrived_gpsfix_ = false
 For GPSFix: Whether the DOP block of the current epoch has arrived or not. More...
 
std::shared_ptr< std::string > fixedUtmZone_
 Fixed UTM zone. More...
 
bool insnavgeod_has_arrived_gpsfix_ = false
 
bool insnavgeod_has_arrived_localization_ = false
 
bool insnavgeod_has_arrived_navsatfix_ = false
 
bool insnavgeod_has_arrived_pose_ = false
 
AttCovEulerMsg last_attcoveuler_
 Since GPSFix etc. need AttCovEuler, incoming AttCovEuler blocks need to be stored. More...
 
AttEulerMsg last_atteuler_
 Since GPSFix etc. need AttEuler, incoming AttEuler blocks need to be stored. More...
 
ChannelStatus last_channelstatus_
 Since GPSFix needs ChannelStatus, incoming ChannelStatus blocks need to be stored. More...
 
DOP last_dop_
 Since GPSFix needs DOP, incoming DOP blocks need to be stored. More...
 
ExtSensorMeasMsg last_extsensmeas_
 Since Imu needs ExtSensorMeas, incoming ExtSensorMeas blocks need to be stored. More...
 
INSNavGeodMsg last_insnavgeod_
 Since NavSatFix, GPSFix, Imu and Pose. need INSNavGeod, incoming INSNavGeod blocks need to be stored. More...
 
MeasEpochMsg last_measepoch_
 Since GPSFix needs MeasEpoch (for SNRs), incoming MeasEpoch blocks need to be stored. More...
 
PosCovGeodeticMsg last_poscovgeodetic_
 Since NavSatFix etc. need PosCovGeodetic, incoming PosCovGeodetic blocks need to be stored. More...
 
PVTGeodeticMsg last_pvtgeodetic_
 Since NavSatFix etc. need PVTGeodetic, incoming PVTGeodetic blocks need to be stored. More...
 
QualityInd last_qualityind_
 Since DiagnosticArray needs QualityInd, incoming QualityInd blocks need to be stored. More...
 
ReceiverSetup last_receiversetup_
 Since DiagnosticArray needs ReceiverSetup, incoming ReceiverSetup blocks need to be stored. More...
 
ReceiverStatus last_receiverstatus_
 Since DiagnosticArray needs ReceiverStatus, incoming ReceiverStatus blocks need to be stored. More...
 
VelCovGeodeticMsg last_velcovgeodetic_
 Since GPSFix needs VelCovGeodetic, incoming VelCovGeodetic blocks need to be stored. More...
 
bool measepoch_has_arrived_gpsfix_ = false
 
std::size_t message_size_
 Helps to determine size of response message / NMEA message / SBF block. More...
 
ROSaicNodeBasenode_
 Pointer to the node. More...
 
bool poscovgeodetic_has_arrived_gpsfix_ = false
 
bool poscovgeodetic_has_arrived_navsatfix_ = false
 
bool poscovgeodetic_has_arrived_pose_ = false
 
bool pvtgeodetic_has_arrived_gpsfix_ = false
 
bool pvtgeodetic_has_arrived_navsatfix_ = false
 
bool pvtgeodetic_has_arrived_pose_ = false
 
bool qualityind_has_arrived_diagnostics_ = false
 
bool receiverstatus_has_arrived_diagnostics_ = false
 
Timestamp recvTimestamp_
 Timestamp of receiving buffer. More...
 
RxIDMap rx_id_map
 All instances of the RxMessage class shall have access to the map without reinitializing it, hence static. More...
 
Settingssettings_
 Settings struct. More...
 
TypeOfPVTMap type_of_pvt_map
 All instances of the RxMessage class shall have access to the map without reinitializing it, hence static. More...
 
Timestamp unix_time_
 
bool velcovgeodetic_has_arrived_gpsfix_ = false
 

Detailed Description

Can search buffer for messages, read/parse them, and so on.

Definition at line 201 of file rx_message.hpp.

Member Typedef Documentation

◆ RxIDMap

typedef std::unordered_map<std::string, RxID_Enum> io_comm_rx::RxMessage::RxIDMap
private

Shorthand for the map responsible for matching ROS message identifiers to an enum value

Definition at line 562 of file rx_message.hpp.

◆ TypeOfPVTMap

typedef std::unordered_map<uint16_t, TypeOfPVT_Enum> io_comm_rx::RxMessage::TypeOfPVTMap
private

Shorthand for the map responsible for matching PVTGeodetic's Mode field to an enum value

Definition at line 552 of file rx_message.hpp.

Constructor & Destructor Documentation

◆ RxMessage()

io_comm_rx::RxMessage::RxMessage ( ROSaicNodeBase node,
Settings settings 
)
inline

Constructor of the RxMessage class.

One can always provide a non-const value where a const one was expected. The const-ness of the argument just means the function promises not to change it.. Recall: static_cast by the way can remove or add const-ness, no other C++ cast is capable of removing it (not even reinterpret_cast)

Parameters
[in]dataPointer to the buffer that is about to be analyzed
[in]sizeSize of the buffer (as handed over by async_read_some)

Pair of iterators to facilitate initialization of the map

Pair of iterators to facilitate initialization of the map

Definition at line 214 of file rx_message.hpp.

Member Function Documentation

◆ allTrue()

bool io_comm_rx::RxMessage::allTrue ( std::vector< bool > &  vec,
uint32_t  id 
)
private

Wether all elements are true.

Definition at line 3128 of file rx_message.cpp.

◆ DiagnosticArrayCallback()

DiagnosticArrayMsg io_comm_rx::RxMessage::DiagnosticArrayCallback ( )
private

"Callback" function when constructing DiagnosticArrayMsg messages

Returns
A ROS message DiagnosticArrayMsg just created

Definition at line 187 of file rx_message.cpp.

◆ diagnostics_complete()

bool io_comm_rx::RxMessage::diagnostics_complete ( uint32_t  id)

Wether all blocks have arrived for Diagnostics Message.

Definition at line 3115 of file rx_message.cpp.

◆ found()

bool io_comm_rx::RxMessage::found ( )

Has an NMEA message, SBF block or command reply been found in the buffer?

Returns
True if a message with the correct header & length has been found

Definition at line 1582 of file rx_message.cpp.

◆ getBlockLength()

uint16_t io_comm_rx::RxMessage::getBlockLength ( )

Gets the length of the SBF block.

It determines the length from the header of the SBF block. The block length thus includes the header length.

Returns
The length of the SBF block

Definition at line 1801 of file rx_message.cpp.

◆ getCount()

std::size_t io_comm_rx::RxMessage::getCount ( )
inline

Returns the count_ variable.

Returns
The variable count_

Definition at line 327 of file rx_message.hpp.

◆ getEndBuffer()

const uint8_t * io_comm_rx::RxMessage::getEndBuffer ( )

Gets the end position in the read buffer.

Returns
A pointer pointing to just after the read buffer (matches search()'s final pointer in case no valid message is found)

Definition at line 1799 of file rx_message.cpp.

◆ getPosBuffer()

const uint8_t * io_comm_rx::RxMessage::getPosBuffer ( )

Gets the current position in the read buffer.

Returns
The current position of the read buffer

Definition at line 1797 of file rx_message.cpp.

◆ gnss_gpsfix_complete()

bool io_comm_rx::RxMessage::gnss_gpsfix_complete ( uint32_t  id)

Wether all blocks from GNSS have arrived for GpsFix Message.

Definition at line 3067 of file rx_message.cpp.

◆ gnss_navsatfix_complete()

bool io_comm_rx::RxMessage::gnss_navsatfix_complete ( uint32_t  id)

Wether all blocks from GNSS have arrived for NavSatFix Message.

Definition at line 3088 of file rx_message.cpp.

◆ gnss_pose_complete()

bool io_comm_rx::RxMessage::gnss_pose_complete ( uint32_t  id)

Wether all blocks from GNSS have arrived for Pose Message.

Definition at line 3101 of file rx_message.cpp.

◆ GPSFixCallback()

GPSFixMsg io_comm_rx::RxMessage::GPSFixCallback ( )
private

"Callback" function when constructing GPSFix messages

Returns
A smart pointer to the ROS message GPSFix just created

Note that the field "dip" denotes the local magnetic inclination in degrees (positive when the magnetic field points downwards (into the Earth)). This quantity cannot be calculated by most Septentrio receivers. We assume that for the ROS field "err_time", we are requested to provide the 2 sigma uncertainty on the clock bias estimate in square meters, not the clock drift estimate (latter would be "2*std::sqrt(last_velcovgeodetic_.Cov_DtDt)"). The "err_track" entry is calculated via the Gaussian error propagation formula from the eastward and the northward velocities. For the formula's usage we have to assume that the eastward and the northward velocities are independent variables. Note that elevations and azimuths of visible satellites are taken from the ChannelStatus block, which provides 1 degree precision, while the SatVisibility block could provide hundredths of degrees precision. Change if imperative for your application... Definition of "visible satellite" adopted here: We define a visible satellite as being !up to! "in sync" mode with the receiver, which corresponds to last_measepoch_.N (signal-to-noise ratios are thereby available for these), though not last_channelstatus_.N, which also includes those "in search". In case certain values appear unphysical, please consult the firmware, since those most likely refer to Do-Not-Use values.

Definition at line 1101 of file rx_message.cpp.

◆ ImuCallback()

ImuMsg io_comm_rx::RxMessage::ImuCallback ( )
private

"Callback" function when constructing ImuMsg messages

Returns
A ROS message ImuMsg just created

Definition at line 294 of file rx_message.cpp.

◆ ins_gpsfix_complete()

bool io_comm_rx::RxMessage::ins_gpsfix_complete ( uint32_t  id)

Wether all blocks from INS have arrived for GpsFix Message.

Definition at line 3080 of file rx_message.cpp.

◆ ins_localization_complete()

bool io_comm_rx::RxMessage::ins_localization_complete ( uint32_t  id)

Wether all blocks have arrived for Localization Message.

Definition at line 3122 of file rx_message.cpp.

◆ ins_navsatfix_complete()

bool io_comm_rx::RxMessage::ins_navsatfix_complete ( uint32_t  id)

Wether all blocks from INS have arrived for NavSatFix Message.

Definition at line 3095 of file rx_message.cpp.

◆ ins_pose_complete()

bool io_comm_rx::RxMessage::ins_pose_complete ( uint32_t  id)

Wether all blocks from INS have arrived for Pose Message.

Definition at line 3109 of file rx_message.cpp.

◆ isConnectionDescriptor()

bool io_comm_rx::RxMessage::isConnectionDescriptor ( )

Determines whether data_ currently points to a connection descriptor (right after initiating a TCP connection)

Definition at line 1741 of file rx_message.cpp.

◆ isErrorMessage()

bool io_comm_rx::RxMessage::isErrorMessage ( )

Determines whether data_ currently points to an error message reply from the Rx

Definition at line 1759 of file rx_message.cpp.

◆ isMessage() [1/2]

bool io_comm_rx::RxMessage::isMessage ( const uint16_t  ID)

Determines whether data_ points to the SBF block with ID "ID", e.g. 5003.

Definition at line 1656 of file rx_message.cpp.

◆ isMessage() [2/2]

bool io_comm_rx::RxMessage::isMessage ( std::string  ID)

Determines whether data_ points to the NMEA message with ID "ID", e.g. "$GPGGA"

Definition at line 1667 of file rx_message.cpp.

◆ isNMEA()

bool io_comm_rx::RxMessage::isNMEA ( )

Determines whether data_ currently points to an NMEA message.

Definition at line 1706 of file rx_message.cpp.

◆ isResponse()

bool io_comm_rx::RxMessage::isResponse ( )

Determines whether data_ currently points to an NMEA message.

Definition at line 1724 of file rx_message.cpp.

◆ isSBF()

bool io_comm_rx::RxMessage::isSBF ( )

Determines whether data_ currently points to an SBF block.

Definition at line 1689 of file rx_message.cpp.

◆ LocalizationUtmCallback()

LocalizationUtmMsg io_comm_rx::RxMessage::LocalizationUtmCallback ( )
private

"Callback" function when constructing LocalizationUtmMsg messages

Returns
A ROS message LocalizationUtmMsg just created

Localization in UTM coordinates. Yaw angle is converted from true north to grid north. Linear velocity of twist in body frame as per msg definition. Angular velocity not available, thus according autocovariances are set to -1.0.

Definition at line 629 of file rx_message.cpp.

◆ messageID()

std::string io_comm_rx::RxMessage::messageID ( )

Returns the message ID of the message where data_ is pointing at at the moment, SBF identifiers embellished with inverted commas, e.g. "5003"

Definition at line 1777 of file rx_message.cpp.

◆ messageSize()

std::size_t io_comm_rx::RxMessage::messageSize ( )

Determines size of the message (also command reply) that data_ is currently pointing at

Definition at line 1617 of file rx_message.cpp.

◆ NavSatFixCallback()

NavSatFixMsg io_comm_rx::RxMessage::NavSatFixCallback ( )
private

"Callback" function when constructing NavSatFix messages

Returns
A smart pointer to the ROS message NavSatFix just created

The position_covariance array is populated in row-major order, where the basis of the corresponding matrix is ENU (so Cov_lonlon is in location 11 of the matrix). The B2b signal type of BeiDou is not checked for usage, since the SignalInfo field of the PVTGeodetic block does not disclose it. For that, one would need to go to the ObsInfo field of the MeasEpochChannelType1 sub-block.

Definition at line 906 of file rx_message.cpp.

◆ newData()

void io_comm_rx::RxMessage::newData ( Timestamp  recvTimestamp,
const uint8_t *  data,
std::size_t &  size 
)
inline

Put new data.

Parameters
[in]recvTimestampTimestamp of receiving buffer
[in]dataPointer to the buffer that is about to be analyzed
[in]sizeSize of the buffer (as handed over by async_read_some)

Definition at line 289 of file rx_message.hpp.

◆ next()

void io_comm_rx::RxMessage::next ( )

Goes to the start of the next message based on the calculated length of current message.

This method won't make data_ jump to the next message if the current one is an NMEA message or a command reply. In that case, search() will check the bytes one by one for the new message's sync bytes ($P, $G or $R).

Definition at line 1821 of file rx_message.cpp.

◆ PoseWithCovarianceStampedCallback()

PoseWithCovarianceStampedMsg io_comm_rx::RxMessage::PoseWithCovarianceStampedCallback ( )
private

"Callback" function when constructing PoseWithCovarianceStamped messages

Returns
A smart pointer to the ROS message PoseWithCovarianceStamped just created

Definition at line 55 of file rx_message.cpp.

◆ publish()

template<typename M >
void io_comm_rx::RxMessage::publish ( const std::string &  topic,
const M &  msg 
)

Publishing function.

Parameters
[in]topicString of topic
[in]msgROS message to be published

If GNSS time is used, Publishing is only done with valid leap seconds

Definition at line 1864 of file rx_message.cpp.

◆ publishTf()

void io_comm_rx::RxMessage::publishTf ( const LocalizationUtmMsg msg)

Publishing function.

Parameters
[in]msgLocalization message

If GNSS time is used, Publishing is only done with valid leap seconds

Definition at line 1886 of file rx_message.cpp.

◆ read()

bool io_comm_rx::RxMessage::read ( std::string  message_key,
bool  search = false 
)

Performs the CRC check (if SBF) and publishes ROS messages.

Returns
True if read was successful, false otherwise

Note that putting the default in the definition's argument list instead of the declaration's is an added extra that is not available for function templates, hence no search = false here. Also note that the SBF block header part of the SBF-echoing ROS messages have ID fields that only show the block number as found in the firmware (e.g. 4007 for PVTGeodetic), without the revision number. NMEA 0183 messages are at most 82 characters long in principle, but most Septentrio Rxs by default increase precision on lat/lon s.t. the maximum allowed e.g. for GGA seems to be 89 on a mosaic-x5. Luckily, when parsing we do not care since we just search for <LF><CR>.

Definition at line 1917 of file rx_message.cpp.

◆ search()

const uint8_t * io_comm_rx::RxMessage::search ( )

Searches the buffer for the beginning of the next message (NMEA or SBF)

Returns
A pointer to the start of the next message.

Definition at line 1598 of file rx_message.cpp.

◆ timestampSBF() [1/2]

Timestamp io_comm_rx::RxMessage::timestampSBF ( const uint8_t *  data,
bool  use_gnss_time 
)
private

Calculates the timestamp, in the Unix Epoch time format This is either done using the TOW as transmitted with the SBF block (if "use_gnss" is true), or using the current time.

Parameters
[in]dataPointer to the buffer
[in]use_gnssIf true, the TOW as transmitted with the SBF block is used, otherwise the current time
Returns
Timestamp object containing seconds and nanoseconds since last epoch

Definition at line 1541 of file rx_message.cpp.

◆ timestampSBF() [2/2]

Timestamp io_comm_rx::RxMessage::timestampSBF ( uint32_t  tow,
uint16_t  wnc,
bool  use_gnss_time 
)
private

Calculates the timestamp, in the Unix Epoch time format This is either done using the TOW as transmitted with the SBF block (if "use_gnss" is true), or using the current time.

Parameters
[in]tow(Time of Week) Number of milliseconds that elapsed since the beginning of the current GPS week as transmitted by the SBF block
[in]wnc(Week Number Counter) counts the number of complete weeks elapsed since January 6, 1980
[in]use_gnssIf true, the TOW as transmitted with the SBF block is used, otherwise the current time
Returns
Timestamp object containing seconds and nanoseconds since last epoch

If the current time shall be employed, it is calculated via the time(NULL) function found in the <ctime> library At the time of writing the code (2020), the GPS time was ahead of UTC time by 18 (leap) seconds. Adapt the settings_->leap_seconds ROSaic parameter accordingly as soon as the next leap second is inserted into the UTC time.

Definition at line 1555 of file rx_message.cpp.

◆ TwistCallback()

TwistWithCovarianceStampedMsg io_comm_rx::RxMessage::TwistCallback ( bool  fromIns = false)
private

"Callback" function when constructing TwistWithCovarianceStampedMsg messages

Parameters
[in]fromInsWether to contruct message from INS data
Returns
A ROS message TwistWithCovarianceStampedMsg just created

Definition at line 408 of file rx_message.cpp.

◆ wait()

void io_comm_rx::RxMessage::wait ( Timestamp  time_obj)
private

Waits according to time when reading from file.

Definition at line 3043 of file rx_message.cpp.

Member Data Documentation

◆ attcoveuler_has_arrived_gpsfix_

bool io_comm_rx::RxMessage::attcoveuler_has_arrived_gpsfix_ = false
private

For GPSFix: Whether the AttCovEuler block of the current epoch has arrived or not

Definition at line 610 of file rx_message.hpp.

◆ attcoveuler_has_arrived_pose_

bool io_comm_rx::RxMessage::attcoveuler_has_arrived_pose_ = false
private

For PoseWithCovarianceStamped: Whether the AttCovEuler block of the current epoch has arrived or not

Definition at line 641 of file rx_message.hpp.

◆ atteuler_has_arrived_gpsfix_

bool io_comm_rx::RxMessage::atteuler_has_arrived_gpsfix_ = false
private

For GPSFix: Whether the AttEuler block of the current epoch has arrived or not

Definition at line 606 of file rx_message.hpp.

◆ atteuler_has_arrived_pose_

bool io_comm_rx::RxMessage::atteuler_has_arrived_pose_ = false
private

For PoseWithCovarianceStamped: Whether the AttEuler block of the current epoch has arrived or not

Definition at line 637 of file rx_message.hpp.

◆ channelstatus_has_arrived_gpsfix_

bool io_comm_rx::RxMessage::channelstatus_has_arrived_gpsfix_ = false
private

For GPSFix: Whether the ChannelStatus block of the current epoch has arrived or not

Definition at line 583 of file rx_message.hpp.

◆ count_

std::size_t io_comm_rx::RxMessage::count_
private

Number of unread bytes in the buffer.

Definition at line 454 of file rx_message.hpp.

◆ count_gpsfix_

uint32_t io_comm_rx::RxMessage::count_gpsfix_ = 0
private

Number of times the GPSFixMsg message has been published.

Definition at line 471 of file rx_message.hpp.

◆ crc_check_

bool io_comm_rx::RxMessage::crc_check_
private

Whether the CRC check as evaluated in the read() method was successful or not is stored here.

Definition at line 460 of file rx_message.hpp.

◆ current_leap_seconds_

int8_t io_comm_rx::RxMessage::current_leap_seconds_ = -128
private

Current leap seconds as received, do not use value is -128.

Definition at line 579 of file rx_message.hpp.

◆ data_

const uint8_t* io_comm_rx::RxMessage::data_
private

Pointer to the buffer of messages.

Definition at line 449 of file rx_message.hpp.

◆ dop_has_arrived_gpsfix_

bool io_comm_rx::RxMessage::dop_has_arrived_gpsfix_ = false
private

For GPSFix: Whether the DOP block of the current epoch has arrived or not.

Definition at line 590 of file rx_message.hpp.

◆ fixedUtmZone_

std::shared_ptr<std::string> io_comm_rx::RxMessage::fixedUtmZone_
private

Fixed UTM zone.

Definition at line 730 of file rx_message.hpp.

◆ found_

bool io_comm_rx::RxMessage::found_

Whether or not a message has been found.

Definition at line 393 of file rx_message.hpp.

◆ insnavgeod_has_arrived_gpsfix_

bool io_comm_rx::RxMessage::insnavgeod_has_arrived_gpsfix_ = false
private

For GPSFix: Whether the INSNavGeod block of the current epoch has arrived or not

Definition at line 614 of file rx_message.hpp.

◆ insnavgeod_has_arrived_localization_

bool io_comm_rx::RxMessage::insnavgeod_has_arrived_localization_ = false
private

For Localization: Whether the INSNavGeod block of the current epoch has arrived or not

Definition at line 657 of file rx_message.hpp.

◆ insnavgeod_has_arrived_navsatfix_

bool io_comm_rx::RxMessage::insnavgeod_has_arrived_navsatfix_ = false
private

For NavSatFix: Whether the INSNavGeod block of the current epoch has arrived or not

Definition at line 626 of file rx_message.hpp.

◆ insnavgeod_has_arrived_pose_

bool io_comm_rx::RxMessage::insnavgeod_has_arrived_pose_ = false
private

For PoseWithCovarianceStamped: Whether the INSNavGeod block of the current epoch has arrived or not

Definition at line 645 of file rx_message.hpp.

◆ last_attcoveuler_

AttCovEulerMsg io_comm_rx::RxMessage::last_attcoveuler_
private

Since GPSFix etc. need AttCovEuler, incoming AttCovEuler blocks need to be stored.

Definition at line 495 of file rx_message.hpp.

◆ last_atteuler_

AttEulerMsg io_comm_rx::RxMessage::last_atteuler_
private

Since GPSFix etc. need AttEuler, incoming AttEuler blocks need to be stored.

Definition at line 489 of file rx_message.hpp.

◆ last_channelstatus_

ChannelStatus io_comm_rx::RxMessage::last_channelstatus_
private

Since GPSFix needs ChannelStatus, incoming ChannelStatus blocks need to be stored.

Definition at line 513 of file rx_message.hpp.

◆ last_dop_

DOP io_comm_rx::RxMessage::last_dop_
private

Since GPSFix needs DOP, incoming DOP blocks need to be stored.

Definition at line 524 of file rx_message.hpp.

◆ last_extsensmeas_

ExtSensorMeasMsg io_comm_rx::RxMessage::last_extsensmeas_
private

Since Imu needs ExtSensorMeas, incoming ExtSensorMeas blocks need to be stored.

Definition at line 507 of file rx_message.hpp.

◆ last_insnavgeod_

INSNavGeodMsg io_comm_rx::RxMessage::last_insnavgeod_
private

Since NavSatFix, GPSFix, Imu and Pose. need INSNavGeod, incoming INSNavGeod blocks need to be stored.

Definition at line 501 of file rx_message.hpp.

◆ last_measepoch_

MeasEpochMsg io_comm_rx::RxMessage::last_measepoch_
private

Since GPSFix needs MeasEpoch (for SNRs), incoming MeasEpoch blocks need to be stored.

Definition at line 519 of file rx_message.hpp.

◆ last_poscovgeodetic_

PosCovGeodeticMsg io_comm_rx::RxMessage::last_poscovgeodetic_
private

Since NavSatFix etc. need PosCovGeodetic, incoming PosCovGeodetic blocks need to be stored.

Definition at line 483 of file rx_message.hpp.

◆ last_pvtgeodetic_

PVTGeodeticMsg io_comm_rx::RxMessage::last_pvtgeodetic_
private

Since NavSatFix etc. need PVTGeodetic, incoming PVTGeodetic blocks need to be stored.

Definition at line 477 of file rx_message.hpp.

◆ last_qualityind_

QualityInd io_comm_rx::RxMessage::last_qualityind_
private

Since DiagnosticArray needs QualityInd, incoming QualityInd blocks need to be stored.

Definition at line 542 of file rx_message.hpp.

◆ last_receiversetup_

ReceiverSetup io_comm_rx::RxMessage::last_receiversetup_
private

Since DiagnosticArray needs ReceiverSetup, incoming ReceiverSetup blocks need to be stored.

Definition at line 548 of file rx_message.hpp.

◆ last_receiverstatus_

ReceiverStatus io_comm_rx::RxMessage::last_receiverstatus_
private

Since DiagnosticArray needs ReceiverStatus, incoming ReceiverStatus blocks need to be stored.

Definition at line 536 of file rx_message.hpp.

◆ last_velcovgeodetic_

VelCovGeodeticMsg io_comm_rx::RxMessage::last_velcovgeodetic_
private

Since GPSFix needs VelCovGeodetic, incoming VelCovGeodetic blocks need to be stored.

Definition at line 530 of file rx_message.hpp.

◆ measepoch_has_arrived_gpsfix_

bool io_comm_rx::RxMessage::measepoch_has_arrived_gpsfix_ = false
private

For GPSFix: Whether the MeasEpoch block of the current epoch has arrived or not

Definition at line 587 of file rx_message.hpp.

◆ message_size_

std::size_t io_comm_rx::RxMessage::message_size_
private

Helps to determine size of response message / NMEA message / SBF block.

Definition at line 466 of file rx_message.hpp.

◆ node_

ROSaicNodeBase* io_comm_rx::RxMessage::node_
private

Pointer to the node.

Definition at line 439 of file rx_message.hpp.

◆ poscovgeodetic_has_arrived_gpsfix_

bool io_comm_rx::RxMessage::poscovgeodetic_has_arrived_gpsfix_ = false
private

For GPSFix: Whether the PosCovGeodetic block of the current epoch has arrived or not

Definition at line 598 of file rx_message.hpp.

◆ poscovgeodetic_has_arrived_navsatfix_

bool io_comm_rx::RxMessage::poscovgeodetic_has_arrived_navsatfix_ = false
private

For NavSatFix: Whether the PosCovGeodetic block of the current epoch has arrived or not

Definition at line 622 of file rx_message.hpp.

◆ poscovgeodetic_has_arrived_pose_

bool io_comm_rx::RxMessage::poscovgeodetic_has_arrived_pose_ = false
private

For PoseWithCovarianceStamped: Whether the PosCovGeodetic block of the current epoch has arrived or not

Definition at line 633 of file rx_message.hpp.

◆ pvtgeodetic_has_arrived_gpsfix_

bool io_comm_rx::RxMessage::pvtgeodetic_has_arrived_gpsfix_ = false
private

For GPSFix: Whether the PVTGeodetic block of the current epoch has arrived or not

Definition at line 594 of file rx_message.hpp.

◆ pvtgeodetic_has_arrived_navsatfix_

bool io_comm_rx::RxMessage::pvtgeodetic_has_arrived_navsatfix_ = false
private

For NavSatFix: Whether the PVTGeodetic block of the current epoch has arrived or not

Definition at line 618 of file rx_message.hpp.

◆ pvtgeodetic_has_arrived_pose_

bool io_comm_rx::RxMessage::pvtgeodetic_has_arrived_pose_ = false
private

For PoseWithCovarianceStamped: Whether the PVTGeodetic block of the current epoch has arrived or not

Definition at line 629 of file rx_message.hpp.

◆ qualityind_has_arrived_diagnostics_

bool io_comm_rx::RxMessage::qualityind_has_arrived_diagnostics_ = false
private

For DiagnosticArray: Whether the QualityInd block of the current epoch has arrived or not

Definition at line 653 of file rx_message.hpp.

◆ receiverstatus_has_arrived_diagnostics_

bool io_comm_rx::RxMessage::receiverstatus_has_arrived_diagnostics_ = false
private

For DiagnosticArray: Whether the ReceiverStatus block of the current epoch has arrived or not

Definition at line 649 of file rx_message.hpp.

◆ recvTimestamp_

Timestamp io_comm_rx::RxMessage::recvTimestamp_
private

Timestamp of receiving buffer.

Definition at line 444 of file rx_message.hpp.

◆ rx_id_map

RxIDMap io_comm_rx::RxMessage::rx_id_map
private

All instances of the RxMessage class shall have access to the map without reinitializing it, hence static.

This map is for mapping ROS message, SBF and NMEA identifiers to an enumeration and makes the switch-case formalism in rx_message.hpp more explicit.

Definition at line 572 of file rx_message.hpp.

◆ settings_

Settings* io_comm_rx::RxMessage::settings_
private

Settings struct.

Definition at line 725 of file rx_message.hpp.

◆ type_of_pvt_map

TypeOfPVTMap io_comm_rx::RxMessage::type_of_pvt_map
private

All instances of the RxMessage class shall have access to the map without reinitializing it, hence static.

Definition at line 558 of file rx_message.hpp.

◆ unix_time_

Timestamp io_comm_rx::RxMessage::unix_time_
private

When reading from an SBF file, the ROS publishing frequency is governed by the time stamps found in the SBF blocks therein.

Definition at line 576 of file rx_message.hpp.

◆ velcovgeodetic_has_arrived_gpsfix_

bool io_comm_rx::RxMessage::velcovgeodetic_has_arrived_gpsfix_ = false
private

For GPSFix: Whether the VelCovGeodetic block of the current epoch has arrived or not

Definition at line 602 of file rx_message.hpp.


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


septentrio_gnss_driver
Author(s): Tibor Dome
autogenerated on Sat Mar 11 2023 03:12:56