Functions | Variables
parsing_utilities Namespace Reference

Functions

double convertAutoCovariance (double val)
 
double convertCovariance (double val)
 
double convertDMSToDegrees (double dms)
 Converts latitude or longitude from the DMS notation (in the without-colon-delimiter format), to the pure degree notation. More...
 
Eigen::Quaterniond convertEulerToQuaternion (double roll, double pitch, double yaw)
 Transforms Euler angles to a quaternion. More...
 
QuaternionMsg convertEulerToQuaternionMsg (double roll, double pitch, double yaw)
 Convert Eigen quaternion to a QuaternionMsg. More...
 
std::string convertUserPeriodToRxCommand (uint32_t period_user)
 Transforms the input polling period [milliseconds] into a std::string number that can be appended to either sec or msec for Rx commands. More...
 
double convertUTCDoubleToSeconds (double utc_double)
 Converts UTC time from the without-colon-delimiter format to the number-of-seconds-since-midnight format. More...
 
std::time_t convertUTCtoUnix (double utc_double)
 Converts UTC time from the without-colon-delimiter format to Unix Epoch time (a number-of-seconds-since-1970/01/01 format) More...
 
template<class T >
deg2rad (T deg)
 
template<class T >
deg2radSq (T deg)
 
uint16_t getCrc (const std::vector< uint8_t > &message)
 Get the CRC of the SBF message. More...
 
uint16_t getId (const std::vector< uint8_t > &message)
 Get the ID of the SBF message. More...
 
uint16_t getLength (const std::vector< uint8_t > &message)
 Get the length of the SBF message. More...
 
uint32_t getTow (const std::vector< uint8_t > &message)
 Get the time of week in ms of the SBF message. More...
 
uint16_t getWnc (const std::vector< uint8_t > &message)
 Get the GPS week counter of the SBF message. More...
 
bool parseDouble (const std::string &string, double &value)
 Interprets the contents of "string" as a floating point number of type double. More...
 
double parseDouble (const uint8_t *buffer)
 Converts an 8-byte-buffer into a double. More...
 
bool parseFloat (const std::string &string, float &value)
 Interprets the contents of "string" as a floating point number of type float. More...
 
float parseFloat (const uint8_t *buffer)
 Converts a 4-byte-buffer into a float. More...
 
bool parseInt16 (const std::string &string, int16_t &value, int32_t base=10)
 Interprets the contents of "string" as a integer number of type int16_t. More...
 
int16_t parseInt16 (const uint8_t *buffer)
 Converts a 2-byte-buffer into a signed 16-bit integer. More...
 
bool parseInt32 (const std::string &string, int32_t &value, int32_t base=10)
 Interprets the contents of "string" as a integer number of type int32_t. More...
 
int32_t parseInt32 (const uint8_t *buffer)
 Converts a 4-byte-buffer into a signed 32-bit integer. More...
 
bool parseUInt16 (const std::string &string, uint16_t &value, int32_t base=10)
 Interprets the contents of "string" as a unsigned integer number of type uint16_t. More...
 
uint16_t parseUInt16 (const uint8_t *buffer)
 Converts a 2-byte-buffer into an unsigned 16-bit integer. More...
 
bool parseUInt32 (const std::string &string, uint32_t &value, int32_t base=10)
 Interprets the contents of "string" as a unsigned integer number of type uint32_t. More...
 
uint32_t parseUInt32 (const uint8_t *buffer)
 Converts a 4-byte-buffer into an unsigned 32-bit integer. More...
 
bool parseUInt8 (const std::string &string, uint8_t &value, int32_t base=10)
 Interprets the contents of "string" as a unsigned integer number of type uint8_t. More...
 
Eigen::Quaterniond q_enu_ecef (double lat, double lon)
 Generates the quaternion to rotate from local ENU to ECEF. More...
 
Eigen::Quaterniond q_ned_ecef (double lat, double lon)
 Generates the quaternion to rotate from local NED to ECEF. More...
 
QuaternionMsg quaternionToQuaternionMsg (const Eigen::Quaterniond &q)
 Transforms Euler angles to a QuaternionMsg. More...
 
Eigen::Matrix3d R_enu_ecef (double lat, double lon)
 Generates the matrix to rotate from local ENU to ECEF. More...
 
Eigen::Matrix3d R_ned_ecef (double lat, double lon)
 Generates the matrix to rotate from local NED to ECEF. More...
 
template<class T >
rad2deg (T rad)
 
Eigen::Matrix3d rpyToRot (double roll, double pitch, double yaw)
 
void setQuaternionNaN (QuaternionMsg &quaternion)
 
void setVector3NaN (Vector3Msg &v)
 
template<class T >
square (T val)
 
double wrapAngle180to180 (double angle)
 Wraps an angle between -180 and 180 degrees. More...
 

Variables

const double pihalf = boost::math::constants::half_pi<double>()
 

Function Documentation

◆ convertAutoCovariance()

double parsing_utilities::convertAutoCovariance ( double  val)
inline

Definition at line 524 of file parsing_utilities.hpp.

◆ convertCovariance()

double parsing_utilities::convertCovariance ( double  val)
inline

Definition at line 529 of file parsing_utilities.hpp.

◆ convertDMSToDegrees()

double parsing_utilities::convertDMSToDegrees ( double  dms)

Converts latitude or longitude from the DMS notation (in the without-colon-delimiter format), to the pure degree notation.

Note that DMS stands for "Degrees, Minutes, Seconds".

Parameters
[in]dmsRepresents latitude or longitude in the DMS notation (in the without-colon-delimiter format)
Returns
Represents latitude or longitude in the pure degree notation

Recall: One degree is divided into 60 minutes (of arc), and in turn one minute into 60 seconds (of arc). Use of the degrees-minutes-seconds system is also called DMS notation.

Definition at line 235 of file parsing_utilities.cpp.

◆ convertEulerToQuaternion()

Eigen::Quaterniond parsing_utilities::convertEulerToQuaternion ( double  roll,
double  pitch,
double  yaw 
)
inline

Transforms Euler angles to a quaternion.

Parameters
[in]yawYaw, i.e. heading, about the z-axis [rad]
[in]pitchPitch about the new y-axis [rad]
[in]rollRoll about the new y-axis [rad]
Returns
quaternion The rotational sequence convention we adopt here (and Septentrio receivers' pitch, roll, yaw definition too) is the yaw-pitch-roll sequence, i.e. the 3-2-1 sequence: The body first does yaw around the z-axis, then pitches around the new y-axis and finally rolls around the new x-axis.

Definition at line 326 of file parsing_utilities.hpp.

◆ convertEulerToQuaternionMsg()

QuaternionMsg parsing_utilities::convertEulerToQuaternionMsg ( double  roll,
double  pitch,
double  yaw 
)
inline

Convert Eigen quaternion to a QuaternionMsg.

Parameters
[in]qEigen quaternion
Returns
ROS message representing a quaternion

Definition at line 366 of file parsing_utilities.hpp.

◆ convertUserPeriodToRxCommand()

std::string parsing_utilities::convertUserPeriodToRxCommand ( uint32_t  period_user)

Transforms the input polling period [milliseconds] into a std::string number that can be appended to either sec or msec for Rx commands.

Parameters
[in]period_userPolling period in milliseconds as specified by the ROSaic user
Returns
Number to be appended to either msec, sec or min when sending commands to the Rx

Definition at line 291 of file parsing_utilities.cpp.

◆ convertUTCDoubleToSeconds()

double parsing_utilities::convertUTCDoubleToSeconds ( double  utc_double)

Converts UTC time from the without-colon-delimiter format to the number-of-seconds-since-midnight format.

Parameters
[in]utc_doubleRrepresents UTC time in the without-colon-delimiter format
Returns
Represents UTC time in the number-of-seconds-since-midnight format

The UTC precision in NMEA messages is down to a tenth of a second, naturally in both the without-colon-delimiter and the number-of-seconds-since-midnight formats.

Definition at line 221 of file parsing_utilities.cpp.

◆ convertUTCtoUnix()

time_t parsing_utilities::convertUTCtoUnix ( double  utc_double)

Converts UTC time from the without-colon-delimiter format to Unix Epoch time (a number-of-seconds-since-1970/01/01 format)

Note that the type "std::time_t" is usually 32 bits, which also leads to the "Year 2038 Problem".

Parameters
[in]utc_doubleRepresents UTC time in the without-colon-delimiter format
Returns
The time_t variable representing Unix Epoch time

Time information (hours, minutes, seconds) is extracted from the given double and augmented with the date, which is taken from the current system time on the host computer (i.e. current UTC+some_shift time via time(0)). The date ambiguity is resolved by adding/subtracting a day to the current date if the host time is more than 12 hours behind/ahead the NMEA time (i.e. UTC time). Recall time(0), time(NULL): If argument is a null pointer, the parameter is not used (the function still returns the current calendar time of type time_t). Otherwise, the return value is the same as the one stored in the location pointed by the argument. Note that the function assumes that utc_double has two significant digits after the decimal point, i.e. hhmmss.ss, yet it does not round the number of seconds to the nearest unsigned integer, but instead disregards ss. This is since we use this function for the "header.stamp.sec" field of ROS messages, while "header.stamp.nsec" is taken care of separately.

Definition at line 258 of file parsing_utilities.cpp.

◆ deg2rad()

template<class T >
T parsing_utilities::deg2rad ( deg)
inline

Definition at line 74 of file parsing_utilities.hpp.

◆ deg2radSq()

template<class T >
T parsing_utilities::deg2radSq ( deg)
inline

Definition at line 83 of file parsing_utilities.hpp.

◆ getCrc()

uint16_t parsing_utilities::getCrc ( const std::vector< uint8_t > &  message)

Get the CRC of the SBF message.

Parameters
bufferA pointer to a buffer containing an SBF message
Returns
SBF message CRC

Definition at line 305 of file parsing_utilities.cpp.

◆ getId()

uint16_t parsing_utilities::getId ( const std::vector< uint8_t > &  message)

Get the ID of the SBF message.

Parameters
bufferA pointer to a buffer containing an SBF message
Returns
SBF message ID

Definition at line 310 of file parsing_utilities.cpp.

◆ getLength()

uint16_t parsing_utilities::getLength ( const std::vector< uint8_t > &  message)

Get the length of the SBF message.

Parameters
bufferA pointer to a buffer containing an SBF message
Returns
SBF message length

Definition at line 320 of file parsing_utilities.cpp.

◆ getTow()

uint32_t parsing_utilities::getTow ( const std::vector< uint8_t > &  message)

Get the time of week in ms of the SBF message.

Parameters
[in]bufferA pointer to a buffer containing an SBF message
Returns
SBF time of week in ms

Definition at line 325 of file parsing_utilities.cpp.

◆ getWnc()

uint16_t parsing_utilities::getWnc ( const std::vector< uint8_t > &  message)

Get the GPS week counter of the SBF message.

Parameters
bufferA pointer to a buffer containing an SBF message
Returns
SBF GPS week counter

Definition at line 330 of file parsing_utilities.cpp.

◆ parseDouble() [1/2]

bool parsing_utilities::parseDouble ( const std::string &  string,
double &  value 
)

Interprets the contents of "string" as a floating point number of type double.

It stores the "string"'s value in "value" and returns whether or not all went well.

Parameters
[in]stringThe string whose content should be interpreted as a floating point number
[out]valueThe double variable that should be overwritten by the floating point number found in "string"
Returns
True if all went fine, false if not

It checks whether an error occurred (via errno) and whether junk characters exist within "string", and returns true if the latter two tests are negative or when the string is empty, false otherwise.

Definition at line 61 of file parsing_utilities.cpp.

◆ parseDouble() [2/2]

double parsing_utilities::parseDouble ( const uint8_t *  buffer)

Converts an 8-byte-buffer into a double.

Parameters
[in]bufferA pointer to a buffer containing 8 bytes of data
Returns
The double extracted from the data in the buffer

Definition at line 49 of file parsing_utilities.cpp.

◆ parseFloat() [1/2]

bool parsing_utilities::parseFloat ( const std::string &  string,
float &  value 
)

Interprets the contents of "string" as a floating point number of type float.

It stores the "string"'s value in "value" and returns whether or not all went well.

Parameters
[in]stringThe string whose content should be interpreted as a floating point number
[out]valueThe float variable that should be overwritten by the floating point number found in "string"
Returns
True if all went fine, false if not

It checks whether an error occurred (via errno) and whether junk characters exist within "string", and returns true if the latter two tests are negative or when the string is empty, false otherwise.

Definition at line 78 of file parsing_utilities.cpp.

◆ parseFloat() [2/2]

float parsing_utilities::parseFloat ( const uint8_t *  buffer)

Converts a 4-byte-buffer into a float.

Parameters
[in]bufferA pointer to a buffer containing 4 bytes of data
Returns
The float extracted from the data in the buffer

Definition at line 66 of file parsing_utilities.cpp.

◆ parseInt16() [1/2]

bool parsing_utilities::parseInt16 ( const std::string &  string,
int16_t &  value,
int32_t  base = 10 
)

Interprets the contents of "string" as a integer number of type int16_t.

It stores the "string"'s value in "value" and returns whether or not all went well.

Parameters
[in]stringThe string whose content should be interpreted as an integer number
[out]valueThe int16_t variable that should be overwritten by the integer number found in "string"
[in]baseThe numerical base of the integer in the string, default being 10
Returns
True if all went fine, false if not

It checks whether an error occurred (via errno) and whether junk characters exist within "string", and returns true if the latter two tests are negative or when the string is empty, false otherwise.

Definition at line 102 of file parsing_utilities.cpp.

◆ parseInt16() [2/2]

int16_t parsing_utilities::parseInt16 ( const uint8_t *  buffer)

Converts a 2-byte-buffer into a signed 16-bit integer.

Parameters
[in]bufferA pointer to a buffer containing 2 bytes of data
Returns
The int16_t value extracted from the data in the buffer

The function assumes that the bytes in the buffer are already arranged with the same endianness as the local platform. It copies the elements in the range [buffer,buffer + 2) into the range beginning at reinterpret_cast<uint8_t*>(&x). Recall: data_type *var_name = reinterpret_cast <data_type *>(pointer_variable) converts the pointer type, no return type

Definition at line 90 of file parsing_utilities.cpp.

◆ parseInt32() [1/2]

bool parsing_utilities::parseInt32 ( const std::string &  string,
int32_t &  value,
int32_t  base = 10 
)

Interprets the contents of "string" as a integer number of type int32_t.

It stores the "string"'s value in "value" and returns whether or not all went well.

Parameters
[in]stringThe string whose content should be interpreted as an integer number
[out]valueThe int32_t variable that should be overwritten by the integer number found in "string"
[in]baseThe numerical base of the integer in the string, default being 10
Returns
True if all went fine, false if not

It checks whether an error occurred (via errno) and whether junk characters exist within "string", and returns true if the latter two tests are negative or when the string is empty, false otherwise.

Definition at line 135 of file parsing_utilities.cpp.

◆ parseInt32() [2/2]

int32_t parsing_utilities::parseInt32 ( const uint8_t *  buffer)

Converts a 4-byte-buffer into a signed 32-bit integer.

Parameters
[in]bufferA pointer to a buffer containing 4 bytes of data
Returns
The int32_t value extracted from the data in the buffer

Definition at line 123 of file parsing_utilities.cpp.

◆ parseUInt16() [1/2]

bool parsing_utilities::parseUInt16 ( const std::string &  string,
uint16_t &  value,
int32_t  base = 10 
)

Interprets the contents of "string" as a unsigned integer number of type uint16_t.

It stores the "string"'s value in "value" and returns whether or not all went well.

Parameters
[in]stringThe string whose content should be interpreted as an integer number
[out]valueThe uint16_t variable that should be overwritten by the integer number found in "string"
[in]baseThe numerical base of the integer in the string, default being 10
Returns
True if all went fine, false if not

It checks whether an error occurred (via errno) and whether junk characters exist within "string", and returns true if the latter two tests are negative or when the string is empty, false otherwise.

Definition at line 178 of file parsing_utilities.cpp.

◆ parseUInt16() [2/2]

uint16_t parsing_utilities::parseUInt16 ( const uint8_t *  buffer)

Converts a 2-byte-buffer into an unsigned 16-bit integer.

Parameters
[in]bufferA pointer to a buffer containing 2 bytes of data
Returns
The uint16_t value extracted from the data in the buffer

Definition at line 166 of file parsing_utilities.cpp.

◆ parseUInt32() [1/2]

bool parsing_utilities::parseUInt32 ( const std::string &  string,
uint32_t &  value,
int32_t  base = 10 
)

Interprets the contents of "string" as a unsigned integer number of type uint32_t.

It stores the "string"'s value in "value" and returns whether or not all went well.

Parameters
[in]stringThe string whose content should be interpreted as an integer number
[out]valueThe uint32_t variable that should be overwritten by the integer number found in "string"
[in]baseThe numerical base of the integer in the string, default being 10
Returns
True if all went fine, false if not

It checks whether an error occurred (via errno) and whether junk characters exist within "string", and returns true if the latter two tests are negative or when the string is empty, false otherwise.

Definition at line 210 of file parsing_utilities.cpp.

◆ parseUInt32() [2/2]

uint32_t parsing_utilities::parseUInt32 ( const uint8_t *  buffer)

Converts a 4-byte-buffer into an unsigned 32-bit integer.

Parameters
[in]bufferA pointer to a buffer containing 4 bytes of data
Returns
The uint32_t value extracted from the data in the buffer

Definition at line 198 of file parsing_utilities.cpp.

◆ parseUInt8()

bool parsing_utilities::parseUInt8 ( const std::string &  string,
uint8_t &  value,
int32_t  base = 10 
)

Interprets the contents of "string" as a unsigned integer number of type uint8_t.

It stores the "string"'s value in "value" and returns whether or not all went well.

Parameters
[in]stringThe string whose content should be interpreted as an integer number
[out]valueThe uint8_t variable that should be overwritten by the integer number found in "string"
[in]baseThe numerical base of the integer in the string, default being 10
Returns
True if all went fine, false if not

It checks whether an error occurred (via errno) and whether junk characters exist within "string", and returns true if the latter two tests are negative or when the string is empty, false otherwise.

Definition at line 146 of file parsing_utilities.cpp.

◆ q_enu_ecef()

Eigen::Quaterniond parsing_utilities::q_enu_ecef ( double  lat,
double  lon 
)
inline

Generates the quaternion to rotate from local ENU to ECEF.

Parameters
[in]latgedoetic latitude [rad]
[in]longeodetic longitude [rad]
Returns
quaternion

Definition at line 392 of file parsing_utilities.hpp.

◆ q_ned_ecef()

Eigen::Quaterniond parsing_utilities::q_ned_ecef ( double  lat,
double  lon 
)
inline

Generates the quaternion to rotate from local NED to ECEF.

Parameters
[in]latgeodetic latitude [rad]
[in]longeodetic longitude [rad]
Returns
rotation matrix

Definition at line 408 of file parsing_utilities.hpp.

◆ quaternionToQuaternionMsg()

QuaternionMsg parsing_utilities::quaternionToQuaternionMsg ( const Eigen::Quaterniond &  q)
inline

Transforms Euler angles to a QuaternionMsg.

Parameters
[in]yawYaw, i.e. heading, about the z-axis [rad]
[in]pitchPitch about the new y-axis [rad]
[in]rollRoll about the new x-axis [rad]
Returns
ROS message representing a quaternion

Definition at line 348 of file parsing_utilities.hpp.

◆ R_enu_ecef()

Eigen::Matrix3d parsing_utilities::R_enu_ecef ( double  lat,
double  lon 
)
inline

Generates the matrix to rotate from local ENU to ECEF.

Parameters
[in]latgeodetic latitude [rad]
[in]longeodetic longitude [rad]
Returns
rotation matrix

Definition at line 424 of file parsing_utilities.hpp.

◆ R_ned_ecef()

Eigen::Matrix3d parsing_utilities::R_ned_ecef ( double  lat,
double  lon 
)
inline

Generates the matrix to rotate from local NED to ECEF.

Parameters
[in]latgeodetic latitude [rad]
[in]longeodetic longitude [rad]
Returns
rotation matrix

Definition at line 452 of file parsing_utilities.hpp.

◆ rad2deg()

template<class T >
T parsing_utilities::rad2deg ( rad)
inline

Definition at line 93 of file parsing_utilities.hpp.

◆ rpyToRot()

Eigen::Matrix3d parsing_utilities::rpyToRot ( double  roll,
double  pitch,
double  yaw 
)
inline

Definition at line 101 of file parsing_utilities.hpp.

◆ setQuaternionNaN()

void parsing_utilities::setQuaternionNaN ( QuaternionMsg quaternion)
inline

Definition at line 371 of file parsing_utilities.hpp.

◆ setVector3NaN()

void parsing_utilities::setVector3NaN ( Vector3Msg v)
inline

Definition at line 379 of file parsing_utilities.hpp.

◆ square()

template<class T >
T parsing_utilities::square ( val)
inline

Definition at line 65 of file parsing_utilities.hpp.

◆ wrapAngle180to180()

double parsing_utilities::wrapAngle180to180 ( double  angle)
inline

Wraps an angle between -180 and 180 degrees.

Parameters
[in]angleThe angle to be wrapped

Definition at line 122 of file parsing_utilities.hpp.

Variable Documentation

◆ pihalf

const double parsing_utilities::pihalf = boost::math::constants::half_pi<double>()

Definition at line 59 of file parsing_utilities.hpp.



septentrio_gnss_driver
Author(s): Tibor Dome, Thomas Emter
autogenerated on Sat May 10 2025 03:03:11