Static Public Member Functions | List of all members
sick_scan_xd::Utils Class Reference

#include <utils.h>

Static Public Member Functions

static void flattenString (std::string &s)
 
static std::string flattenToString (const sick_scan_xd::SickLocColaTelegramMsg &cola_telegram)
 
static std::string flattenToString (const sick_scan_xd::SickLocResultPortTelegramMsg &telegram)
 
static std::string flattenToString (const std_msgs::Header *header)
 
template<typename T >
static std::string flattenToString (const T &x)
 
static bool identicalByStream (const SickLocColaTelegramMsg &x, const SickLocColaTelegramMsg &y)
 
static bool identicalByStream (const SickLocResultPortTelegramMsg &x, const SickLocResultPortTelegramMsg &y)
 
template<typename T >
static bool identicalByStream (const std::vector< T > &x, const std::vector< T > &y)
 
template<typename T >
static bool identicalByStream (const T &x, const T &y)
 
static double normalizeAngle (double angle)
 
static void replaceAll (std::string &str, const std::string &from, const std::string &to)
 
static std::vector< std::string > splitSpaces (const std::string &s)
 
static std::string toAsciiString (const uint8_t *binary_data, int length)
 
static std::string toHexString (const std::vector< uint8_t > &binary_data)
 

Detailed Description

class Utils implements utility functions for SIM Localization.

Definition at line 120 of file test/emulator/include/sick_scan/utils.h.

Member Function Documentation

◆ flattenString()

void sick_scan_xd::Utils::flattenString ( std::string &  s)
static

Shortcut to replace linefeeds by colon-separators

Definition at line 128 of file utils.cpp.

◆ flattenToString() [1/4]

static std::string sick_scan_xd::Utils::flattenToString ( const sick_scan_xd::SickLocColaTelegramMsg cola_telegram)
inlinestatic

Shortcut to print a SickLocColaTelegramMsg in flatten format, replacing linefeeds by colon-separators

Definition at line 177 of file test/emulator/include/sick_scan/utils.h.

◆ flattenToString() [2/4]

static std::string sick_scan_xd::Utils::flattenToString ( const sick_scan_xd::SickLocResultPortTelegramMsg telegram)
inlinestatic

Shortcut to print a SickLocColaTelegramMsg in flatten format, replacing linefeeds by colon-separators

Definition at line 194 of file test/emulator/include/sick_scan/utils.h.

◆ flattenToString() [3/4]

static std::string sick_scan_xd::Utils::flattenToString ( const std_msgs::Header header)
inlinestatic

Shortcut to print (msg_header.stamp.sec,msg_header.stamp.nsec) on ROS1 resp. (msg_header.stamp.sec,msg_header.stamp.nanosec) on ROS2

Definition at line 167 of file test/emulator/include/sick_scan/utils.h.

◆ flattenToString() [4/4]

template<typename T >
static std::string sick_scan_xd::Utils::flattenToString ( const T &  x)
inlinestatic

Shortcut to print a type in flatten format, replacing linefeeds by colon-separators

Definition at line 157 of file test/emulator/include/sick_scan/utils.h.

◆ identicalByStream() [1/4]

static bool sick_scan_xd::Utils::identicalByStream ( const SickLocColaTelegramMsg x,
const SickLocColaTelegramMsg y 
)
inlinestatic

Compares two SickLocColaTelegramMsg by streaming them to strings. Returns true, if string representation of x and y is identical, otherwise false. The message headers with timestamp and frame_id are ignored.

Definition at line 263 of file test/emulator/include/sick_scan/utils.h.

◆ identicalByStream() [2/4]

static bool sick_scan_xd::Utils::identicalByStream ( const SickLocResultPortTelegramMsg x,
const SickLocResultPortTelegramMsg y 
)
inlinestatic

Compares two SickLocResultPortTelegramMsgs by streaming them to strings. Returns true, if string representation of x and y is identical, otherwise false. The message headers with timestamp and frame_id are ignored.

Definition at line 244 of file test/emulator/include/sick_scan/utils.h.

◆ identicalByStream() [3/4]

template<typename T >
static bool sick_scan_xd::Utils::identicalByStream ( const std::vector< T > &  x,
const std::vector< T > &  y 
)
inlinestatic

Compares two vectors by streaming them to strings. Returns true, if string representation of x and y is identical, otherwise false.

Definition at line 227 of file test/emulator/include/sick_scan/utils.h.

◆ identicalByStream() [4/4]

template<typename T >
static bool sick_scan_xd::Utils::identicalByStream ( const T &  x,
const T &  y 
)
inlinestatic

Compares two objects by streaming them to strings. Returns true, if string representation of x and y is identical, otherwise false.

Definition at line 214 of file test/emulator/include/sick_scan/utils.h.

◆ normalizeAngle()

static double sick_scan_xd::Utils::normalizeAngle ( double  angle)
inlinestatic

Returns the normalized angle, i.e. the angle in the range -PI to +PI.

Parameters
[in]angleangle in radians
Returns
normalized angle in radians

Definition at line 273 of file test/emulator/include/sick_scan/utils.h.

◆ replaceAll()

void sick_scan_xd::Utils::replaceAll ( std::string &  str,
const std::string &  from,
const std::string &  to 
)
static

Replaces all substrings of a string by another string. https://stackoverflow.com/questions/3418231/replace-part-of-a-string-with-another-string/3418285

Definition at line 111 of file utils.cpp.

◆ splitSpaces()

std::vector< std::string > sick_scan_xd::Utils::splitSpaces ( const std::string &  s)
static

Splits a string into its space separated substrings

Definition at line 139 of file utils.cpp.

◆ toAsciiString()

std::string sick_scan_xd::Utils::toAsciiString ( const uint8_t *  binary_data,
int  length 
)
static

Converts and returns binary data to ascii string with non-ascii data represented as "\x<hexvalue>"

Parameters
[in]binary_databinary input data
Returns
hex string

Definition at line 86 of file utils.cpp.

◆ toHexString()

std::string sick_scan_xd::Utils::toHexString ( const std::vector< uint8_t > &  binary_data)
static

Converts and returns binary data to hex string

Parameters
[in]binary_databinary input data
Returns
hex string

Definition at line 69 of file utils.cpp.


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


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:21