Classes | |
| struct | wait_until_ms |
| struct | watchdog |
Functions | |
| std::string | chomp (std::string &main, const char token= ',') |
| std::pair< double, double > | deg2meter (double difflat, double difflon, double lat) |
| template<class Point , class Iterator > | |
| void | disableAxisToVector (Point &point, const Iterator &vec) |
| template<class T > | |
| void | eulerZYXFromQuaternion (const T &q, double &roll, double &pitch, double &yaw) |
| 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 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) |
| template<class Point , class Iterator > | |
| void | nedToVector (const Point &point, Iterator &vec, int offset=0) |
| 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 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 | deg2rad = M_PI/180 |
| static const double | rad2deg = 180/M_PI |
| static const double | radius = 6378137 |
| static const double | ratio = 0.99664719 |
| std::string labust::tools::chomp | ( | std::string & | main, |
| const char | token = ',' |
||
| ) | [inline] |
The function split the string into two parts separated by a delimiter.
| main | The string that will be split. |
| token | Split delimiter character. |
Definition at line 50 of file StringUtilities.hpp.
| std::pair<double,double> labust::tools::deg2meter | ( | double | difflat, |
| double | difflon, | ||
| double | lat | ||
| ) | [inline] |
The function converts degrees to meters.
| difflat | North distance in degrees. |
| difflon | East distance in degrees. |
| lat | Latitude position in decimal degrees. |
Definition at line 79 of file GeoUtilities.hpp.
| void labust::tools::disableAxisToVector | ( | Point & | point, |
| const Iterator & | vec | ||
| ) |
Definition at line 126 of file conversions.hpp.
| void labust::tools::eulerZYXFromQuaternion | ( | const T & | q, |
| double & | roll, | ||
| double & | pitch, | ||
| double & | yaw | ||
| ) |
Definition at line 150 of file conversions.hpp.
| unsigned char labust::tools::getChecksum | ( | const unsigned char *const | data, |
| size_t | len | ||
| ) | [inline] |
The function returns the checksum of a byte array.
| data | Address of the range start. |
| len | Length of the range. |
Definition at line 83 of file StringUtilities.hpp.
| 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.
Definition at line 195 of file MatrixLoader.hpp.
| 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.
| 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.
| 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.
| 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.
| x | North distance in meters. |
| y | East distance in meters. |
| lat | Latitude position in decimal degrees. |
Definition at line 92 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 57 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 66 of file GeoUtilities.hpp.
| 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 71 of file conversions.hpp.
| 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 49 of file conversions.hpp.
| void labust::tools::quaternionFromEulerZYX | ( | double | roll, |
| double | pitch, | ||
| double | yaw, | ||
| Eigen::Quaternion< T > & | q | ||
| ) |
Definition at line 137 of file conversions.hpp.
| 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 93 of file conversions.hpp.
| void labust::tools::sleep | ( | size_t | ms | ) | [inline] |
The function suspends the system for the specified amount of milliseconds.
| ms | The 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.
Definition at line 64 of file TimingTools.hpp.
| 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.
| value | Value which to convert into a string. |
| MyType | Type of the converted object. |
Definition at line 68 of file StringUtilities.hpp.
| double labust::tools::unix_time | ( | ) | [inline] |
The function to calculate the UNIX time.
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.
| microseconds | True if we wish to display the microseconds. |
Definition at line 85 of file TimingTools.hpp.
| 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 115 of file conversions.hpp.
| 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 82 of file conversions.hpp.
| 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 60 of file conversions.hpp.
| 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 104 of file conversions.hpp.
| Eigen::MatrixBase<Derived>::Scalar labust::tools::xmlRpcConvert | ( | XmlRpcVal & | data, |
| bool | intType | ||
| ) | [inline] |
Definition at line 49 of file MatrixLoader.hpp.
const double labust::tools::deg2rad = M_PI/180 [static] |
Definition at line 47 of file GeoUtilities.hpp.
const double labust::tools::rad2deg = 180/M_PI [static] |
Definition at line 48 of file GeoUtilities.hpp.
const double labust::tools::radius = 6378137 [static] |
Definition at line 49 of file GeoUtilities.hpp.
const double labust::tools::ratio = 0.99664719 [static] |
Definition at line 50 of file GeoUtilities.hpp.