Classes | Functions | Variables
labust::tools Namespace Reference

Classes

class  Bits2LatLon
class  LatLon2Bits
class  OutlierRejection
class  RosbagReader
struct  wait_until_ms
struct  watchdog

Functions

template<class Iterator >
void binaryToHex (const Iterator &start, const Iterator &end, std::string *data)
template<class Iterator , class Stream >
void binaryToHex (const Iterator &start, const Iterator &end, Stream &data)
std::string chomp (std::string &main, const char token= ',')
template<class VectorType , class Packable >
bool decodePackable (const std::vector< VectorType > &binary, Packable *data)
std::pair< double, double > deg2meter (double difflat, double difflon, double lat)
template<class Point , class Iterator >
void disableAxisToVector (Point &point, const Iterator &vec)
Eigen::Vector3d ecef2geodetic (const Eigen::Vector3d &xyz)
Eigen::Vector3d ecef2ned (const Eigen::Vector3d &xyz, const Eigen::Vector3d &geo)
template<class Packable >
void encodePackable (const Packable &data, std::vector< char > *binary)
template<class T >
void eulerZYXFromQuaternion (const T &q, double &roll, double &pitch, double &yaw)
template<class T , class V >
void eulerZYXFromQuaternion (const T &q, V &vect)
void eulerZYXFromQuaternion (const geometry_msgs::Quaternion &q, double &roll, double &pitch, double &yaw)
Eigen::Vector3d geodetic2ecef (const Eigen::Vector3d &geo)
unsigned char getChecksum (const unsigned char *const data, size_t len)
template<class Derived >
std::pair< int, int > getMatrixParam (const ros::NodeHandle &nh, const std::string &name, const Eigen::MatrixBase< Derived > &matrix)
template<class Derived >
std::pair< int, int > getMatrixParam_fixedsize (const ros::NodeHandle &nh, const std::string &name, const Eigen::MatrixBase< Derived > &matrix)
template<class Derived >
std::pair< int, int > getMatrixParam_variablesize (const ros::NodeHandle &nh, const std::string &name, const Eigen::MatrixBase< Derived > &matrix)
template<class Iterator >
void hexToBinary (const std::string &data, const Iterator &start, const Iterator &end)
template<class IteratorIn , class OutVector >
void hexToBinary (const IteratorIn &instart, const IteratorIn &inend, OutVector *out)
template<class Model >
void loadDynamicsParams (const ros::NodeHandle &nh, Model &model)
template<class Derived >
void matrixExtender (const ros::NodeHandle &nh, const std::string &name, Eigen::MatrixBase< Derived > &matrix)
std::pair< double, double > meter2deg (double x, double y, double lat)
double mpdlat (double lat)
double mpdlon (double lat)
Eigen::Vector3d ned2ecef (const Eigen::Vector3d &ned, const Eigen::Vector3d &geo)
Eigen::Matrix3d nedrot (const Eigen::Vector3d &geo)
 Returns the rotation matrix between ECEF and NED frame.
template<class Point , class Iterator >
void nedToVector (const Point &point, Iterator &vec, int offset=0)
Eigen::Matrix3d nwurot (const Eigen::Vector3d &geo)
 Returns the rotation matrix between ECEF and NWU frame.
template<class Point , class Iterator >
void pointToVector (const Point &point, Iterator &vec, int offset=0)
template<class T >
void quaternionFromEulerZYX (double roll, double pitch, double yaw, Eigen::Quaternion< T > &q)
template<class T >
void quaternionFromEulerZYX (double roll, double pitch, double yaw, T &q)
template<class Point , class Iterator >
void rpyToVector (const Point &point, Iterator &vec, int offset=0)
void sleep (size_t ms)
std::string time_signature ()
template<class MyType >
std::string to_string (MyType value)
double unix_time ()
std::string unix_time_string (bool microseconds=false)
template<class Point , class Iterator >
void vectorToDisableAxis (const Iterator &vec, Point &point)
template<class Point , class Iterator >
void vectorToNED (const Iterator &vec, Point &point, int offset=0)
template<class Point , class Iterator >
void vectorToPoint (const Iterator &vec, Point &point, int offset=0)
template<class Point , class Iterator >
void vectorToRPY (const Iterator &vec, Point &point, int offset=0)
template<class Derived , class XmlRpcVal >
Eigen::MatrixBase< Derived >
::Scalar 
xmlRpcConvert (XmlRpcVal &data, bool intType)

Variables

static const double a = 6378137
 Semi-major axis of the local geodetic datum ellipsoid.
static const double b = a*(1-f)
 Semi-minor axis of the local geodetic datum ellipsoid.
static const double deg2rad = M_PI/180
 Constants for quick projection.
static const double ecsq = (a*a - b*b)/(b*b)
 Secondary eccentricity squared.
static const double esq = 2*f-f*f
 First eccentricity squared.
static const double f = 1/298.257223563
 Flattening of the local geodetic datum ellipsoid.
static const double rad2deg = 180/M_PI
static const double radius = 6378137
static const double ratio = 0.99664719

Detailed Description

Todo:
Add Vincenty formula: http://en.wikipedia.org/wiki/Vincenty's_formulae

Function Documentation

template<class Iterator >
void labust::tools::binaryToHex ( const Iterator &  start,
const Iterator &  end,
std::string *  data 
) [inline]

The function converts a binary range into a hex string representation. NOTE: this will work robustly for char nad uint8_t types. For other types the outcome might not be what you expect.

Parameters:
startThe iterator pointing to the start of the binary vector
endThe iterator pointing to the end of the binary vector
dataPointer to the string where to store the hex representation

Definition at line 99 of file StringUtilities.hpp.

template<class Iterator , class Stream >
void labust::tools::binaryToHex ( const Iterator &  start,
const Iterator &  end,
Stream &  data 
) [inline]

The function converts a binary range into a hex string representation. NOTE: this will work robustly for char nad uint8_t types. For other types the outcome might not be what you expect.

Parameters:
startThe iterator pointing to the start of the binary vector
endThe iterator pointing to the end of the binary vector
dataPointer to the output stream.

Definition at line 120 of file StringUtilities.hpp.

std::string labust::tools::chomp ( std::string &  main,
const char  token = ',' 
) [inline]

The function split the string into two parts separated by a delimiter.

Parameters:
mainThe string that will be split.
tokenSplit delimiter character.
Returns:
The string before the delimiter.

Definition at line 50 of file StringUtilities.hpp.

template<class VectorType , class Packable >
bool labust::tools::decodePackable ( const std::vector< VectorType > &  binary,
Packable *  data 
) [inline]

Decodes all messages that have a pack/unpack interface.

Definition at line 68 of file packer.h.

std::pair<double,double> labust::tools::deg2meter ( double  difflat,
double  difflon,
double  lat 
) [inline]

The function converts degrees to meters.

Parameters:
difflatNorth distance in degrees.
difflonEast distance in degrees.
latLatitude position in decimal degrees.
Returns:
Returns the latitude and longitude distance in relative meters.

Definition at line 81 of file GeoUtilities.hpp.

template<class Point , class Iterator >
void labust::tools::disableAxisToVector ( Point &  point,
const Iterator &  vec 
)

Definition at line 128 of file conversions.hpp.

Eigen::Vector3d labust::tools::ecef2geodetic ( const Eigen::Vector3d &  xyz) [inline]

Converts the geocentric ECEF coordinates into WGS84 geodetic coordinates.

Parameters:
xGeocentric position in meters.
yGeocentric position in meters.
zGeocentric position in meters.
Returns:
Geodetic coordinates in decimal degrees and altitude in meters.

Definition at line 149 of file GeoUtilities.hpp.

Eigen::Vector3d labust::tools::ecef2ned ( const Eigen::Vector3d &  xyz,
const Eigen::Vector3d &  geo 
) [inline]

Converts the geocentric ECEF coordinates into local NED coordinates.

Definition at line 230 of file GeoUtilities.hpp.

template<class Packable >
void labust::tools::encodePackable ( const Packable &  data,
std::vector< char > *  binary 
) [inline]

Encodes all messages that have a pack/unpack interface.

Definition at line 53 of file packer.h.

template<class T >
void labust::tools::eulerZYXFromQuaternion ( const T &  q,
double &  roll,
double &  pitch,
double &  yaw 
)

Definition at line 166 of file conversions.hpp.

template<class T , class V >
void labust::tools::eulerZYXFromQuaternion ( const T &  q,
V &  vect 
)

Definition at line 181 of file conversions.hpp.

void labust::tools::eulerZYXFromQuaternion ( const geometry_msgs::Quaternion &  q,
double &  roll,
double &  pitch,
double &  yaw 
) [inline]

Definition at line 196 of file conversions.hpp.

Eigen::Vector3d labust::tools::geodetic2ecef ( const Eigen::Vector3d &  geo) [inline]

Converts the WGS84 geodetic coordinates into geocentric ECEF coordinates

Parameters:
geoGeodetic latitude, longitude in decimal degrees and altitude in meters. Internally, the vector must be (longitude,latitude,altitude).
Returns:
ECEF coordinates in meters

Definition at line 129 of file GeoUtilities.hpp.

unsigned char labust::tools::getChecksum ( const unsigned char *const  data,
size_t  len 
) [inline]

The function returns the checksum of a byte array.

Parameters:
dataAddress of the range start.
lenLength of the range.
Returns:
XOR checksum of the given range.

Definition at line 83 of file StringUtilities.hpp.

template<class Derived >
std::pair<int,int> labust::tools::getMatrixParam ( const ros::NodeHandle nh,
const std::string &  name,
const Eigen::MatrixBase< Derived > &  matrix 
) [inline]

Reads a vector or matrix list and populates the supplied vector or matrix.

Todo:
Derive one function for variable and fixed size.

Definition at line 195 of file MatrixLoader.hpp.

template<class Derived >
std::pair<int,int> labust::tools::getMatrixParam_fixedsize ( const ros::NodeHandle nh,
const std::string &  name,
const Eigen::MatrixBase< Derived > &  matrix 
)

Reads a vector or matrix list and populates the supplied vector or matrix.

Definition at line 59 of file MatrixLoader.hpp.

template<class Derived >
std::pair<int,int> labust::tools::getMatrixParam_variablesize ( const ros::NodeHandle nh,
const std::string &  name,
const Eigen::MatrixBase< Derived > &  matrix 
)

Reads a vector or matrix list and populates the supplied vector or matrix.

Definition at line 118 of file MatrixLoader.hpp.

template<class Iterator >
void labust::tools::hexToBinary ( const std::string &  data,
const Iterator &  start,
const Iterator &  end 
) [inline]

The function converts a binary range into a hex string representation. NOTE: this will work robustly for char nad uint8_t types. For other types the outcome might not be what you expect.

Parameters:
startThe iterator pointing to the start of the binary vector
endThe iterator pointing to the end of the binary vector
dataPointer to the string where to store the hex representation

Definition at line 140 of file StringUtilities.hpp.

template<class IteratorIn , class OutVector >
void labust::tools::hexToBinary ( const IteratorIn &  instart,
const IteratorIn &  inend,
OutVector *  out 
) [inline]

The function converts a binary range into a hex string representation. NOTE: this will work robustly for char nad uint8_t types. For other types the outcome might not be what you expect.

Parameters:
startThe iterator pointing to the start of the binary vector
endThe iterator pointing to the end of the binary vector
dataPointer to the string where to store the hex representation

Definition at line 165 of file StringUtilities.hpp.

template<class Model >
void labust::tools::loadDynamicsParams ( const ros::NodeHandle nh,
Model &  model 
)

The function loads and configures the dynamics parameters from the supplied ROS node handle.

Definition at line 66 of file DynamicsLoader.hpp.

template<class Derived >
void labust::tools::matrixExtender ( const ros::NodeHandle nh,
const std::string &  name,
Eigen::MatrixBase< Derived > &  matrix 
) [inline]

The extender expands a diagonal vector representation of the matrix into a full rank diagonal matrix.

Definition at line 51 of file DynamicsLoader.hpp.

std::pair<double,double> labust::tools::meter2deg ( double  x,
double  y,
double  lat 
) [inline]

The function converts meters to relative degrees.

Parameters:
xNorth distance in meters.
yEast distance in meters.
latLatitude position in decimal degrees.
Returns:
Returns the relative angles of the distances.

Definition at line 94 of file GeoUtilities.hpp.

double labust::tools::mpdlat ( double  lat) [inline]

The function calculates meters per latitude degree. The conversion was taken from: http://en.wikipedia.org/wiki/Geographic_coordinate_system#Cartesian_coordinates

Definition at line 59 of file GeoUtilities.hpp.

double labust::tools::mpdlon ( double  lat) [inline]

The function calculates meters per longitude degree. The conversion was taken from: http://en.wikipedia.org/wiki/Geographic_coordinate_system#Cartesian_coordinates

Definition at line 68 of file GeoUtilities.hpp.

Eigen::Vector3d labust::tools::ned2ecef ( const Eigen::Vector3d &  ned,
const Eigen::Vector3d &  geo 
) [inline]

Converts the local NED coordinates into geocentric ECEF coordinates.

Definition at line 240 of file GeoUtilities.hpp.

Eigen::Matrix3d labust::tools::nedrot ( const Eigen::Vector3d &  geo) [inline]

Returns the rotation matrix between ECEF and NED frame.

Definition at line 174 of file GeoUtilities.hpp.

template<class Point , class Iterator >
void labust::tools::nedToVector ( const Point &  point,
Iterator &  vec,
int  offset = 0 
)

The function offers mapping from NED structure to a vector.

Definition at line 73 of file conversions.hpp.

Eigen::Matrix3d labust::tools::nwurot ( const Eigen::Vector3d &  geo) [inline]

Returns the rotation matrix between ECEF and NWU frame.

Definition at line 201 of file GeoUtilities.hpp.

template<class Point , class Iterator >
void labust::tools::pointToVector ( const Point &  point,
Iterator &  vec,
int  offset = 0 
)

The class offers mapping from a XYZ structure to a vector.

Definition at line 51 of file conversions.hpp.

template<class T >
void labust::tools::quaternionFromEulerZYX ( double  roll,
double  pitch,
double  yaw,
Eigen::Quaternion< T > &  q 
)

Definition at line 139 of file conversions.hpp.

template<class T >
void labust::tools::quaternionFromEulerZYX ( double  roll,
double  pitch,
double  yaw,
T &  q 
)

Definition at line 154 of file conversions.hpp.

template<class Point , class Iterator >
void labust::tools::rpyToVector ( const Point &  point,
Iterator &  vec,
int  offset = 0 
)

The function offers mapping from RPY structure to a vector.

Definition at line 95 of file conversions.hpp.

void labust::tools::sleep ( size_t  ms) [inline]

The function suspends the system for the specified amount of milliseconds.

Parameters:
msThe amount of milliseconds to sleep.

Definition at line 97 of file TimingTools.hpp.

std::string labust::tools::time_signature ( ) [inline]

The function generates a string format time signatures. Useful for creating time stamped filenames.

Returns:
String based time signature.

Definition at line 64 of file TimingTools.hpp.

template<class MyType >
std::string labust::tools::to_string ( MyType  value) [inline]

The function converts different types into string if a output operator is defined for the type.

Parameters:
valueValue which to convert into a string.
Template Parameters:
MyTypeType of the converted object.
Returns:
Returns the converted object in a string.

Definition at line 68 of file StringUtilities.hpp.

double labust::tools::unix_time ( ) [inline]

The function to calculate the UNIX time.

Returns:
Number of decimal seconds since 01.01.1970.

Definition at line 50 of file TimingTools.hpp.

std::string labust::tools::unix_time_string ( bool  microseconds = false) [inline]

The function returns the unix_time in a string format.

Parameters:
microsecondsTrue if we wish to display the microseconds.
Returns:
UNIX time in string format.

Definition at line 85 of file TimingTools.hpp.

template<class Point , class Iterator >
void labust::tools::vectorToDisableAxis ( const Iterator &  vec,
Point &  point 
)

The class offers mapping from auv_msgs disable_axis structure to a vector.

Definition at line 117 of file conversions.hpp.

template<class Point , class Iterator >
void labust::tools::vectorToNED ( const Iterator &  vec,
Point &  point,
int  offset = 0 
)

The class offers mapping to a RPY structure from a vector.

Definition at line 84 of file conversions.hpp.

template<class Point , class Iterator >
void labust::tools::vectorToPoint ( const Iterator &  vec,
Point &  point,
int  offset = 0 
)

The class offers mapping from a XYZ structure to a vector.

Definition at line 62 of file conversions.hpp.

template<class Point , class Iterator >
void labust::tools::vectorToRPY ( const Iterator &  vec,
Point &  point,
int  offset = 0 
)

The class offers mapping to a NED structure from a vector.

Definition at line 106 of file conversions.hpp.

template<class Derived , class XmlRpcVal >
Eigen::MatrixBase<Derived>::Scalar labust::tools::xmlRpcConvert ( XmlRpcVal &  data,
bool  intType 
) [inline]

Definition at line 49 of file MatrixLoader.hpp.


Variable Documentation

const double labust::tools::a = 6378137 [static]

Semi-major axis of the local geodetic datum ellipsoid.

Constants and full WGS84<->ECEF<->NED conversions.

Conversion references: 1. USER’s HANDBOOK ON DATUM TRANSFORMATIONS INVOLVING WGS 84 2. J. Zhu, "Conversion of Earth-centered Earth-fixed coordinates to geodetic coordinates," IEEE Transactions on Aerospace and Electronic Systems, vol. 30, pp. 957-961, 1994 3. http://www.navipedia.net/index.php/Transformations_between_ECEF_and_ENU_coordinates

Definition at line 112 of file GeoUtilities.hpp.

const double labust::tools::b = a*(1-f) [static]

Semi-minor axis of the local geodetic datum ellipsoid.

Definition at line 116 of file GeoUtilities.hpp.

const double labust::tools::deg2rad = M_PI/180 [static]

Constants for quick projection.

Definition at line 49 of file GeoUtilities.hpp.

const double labust::tools::ecsq = (a*a - b*b)/(b*b) [static]

Secondary eccentricity squared.

Definition at line 120 of file GeoUtilities.hpp.

const double labust::tools::esq = 2*f-f*f [static]

First eccentricity squared.

Definition at line 118 of file GeoUtilities.hpp.

const double labust::tools::f = 1/298.257223563 [static]

Flattening of the local geodetic datum ellipsoid.

Definition at line 114 of file GeoUtilities.hpp.

const double labust::tools::rad2deg = 180/M_PI [static]

Definition at line 50 of file GeoUtilities.hpp.

const double labust::tools::radius = 6378137 [static]

Definition at line 51 of file GeoUtilities.hpp.

const double labust::tools::ratio = 0.99664719 [static]

Definition at line 52 of file GeoUtilities.hpp.



snippets
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:22:33