mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
mrs_lib Namespace Reference

All mrs_lib functions, classes, variables and definitions are contained in this namespace. More...

Classes

class  AtomicScopeFlag
 Convenience class for automatically setting and unsetting an atomic boolean based on the object's scope. Useful e.g. for indicating whether a thread is running or not. More...
 
class  AttitudeConverter
 The main convertor class. Instantiate with any type in constructor and get the value in any other type by assigning the instance to your variable, as: tf::Quaternion tf1_quaternion = AttitudeConverter(roll, pitch, yaw); All the default Euler angles are in the extrinsic RPY notation. More...
 
class  BatchVisualizer
 library for drawing large amounts of geometric objects in RVIZ at the same time More...
 
class  DKF
 Implementation of the Degenerate measurement Linear Kalman filter. More...
 
class  DynamicPublisher
 A helper class for easy publishing of ROS messages for debugging purposes. More...
 
class  DynamicReconfigureMgr
 
struct  eigenvector_exception
 This exception may be thrown when solving the generalized eigenvalue problem with the M and N matrices. More...
 
class  EulerAttitude
 A small class for storing the Euler angles. More...
 
class  IirFilter
 
struct  ImagePubliserData
 
class  ImagePublisher
 
struct  Intersection
 
class  JLKF
 
class  KalmanFilter
 This abstract class defines common interfaces and types for a generic Kalman filter. More...
 
class  KalmanFilterAloamGarm
 This abstract class defines common interfaces and types for a generic Kalman filter. More...
 
class  LKF
 Implementation of the Linear Kalman filter [3]. More...
 
class  LKF_MRS_odom
 
class  MedianFilter
 Implementation of a median filter with a fixed-length buffer. More...
 
class  MRSTimer
 Common wrapper representing the functionality of the ros::Timer. More...
 
class  NCLKF
 This class implements the norm-constrained linear Kalman filter [5]. More...
 
class  NCLKF_partial
 This class implements the partially norm-constrained linear Kalman filter [5]. More...
 
class  NCUKF
 
class  NotchFilter
 
class  ParamLoader
 Convenience class for loading parameters from rosparam server. More...
 
class  ParamProvider
 Helper class for ParamLoader. More...
 
class  Polygon
 
class  Profiler
 
class  PublisherHandler
 user wrapper of the publisher handler implementation More...
 
class  PublisherHandler_impl
 implementation of the publisher handler More...
 
class  Repredictor
 Implementation of the Repredictor for fusing measurements with variable delays. More...
 
class  RepredictorAloamgarm
 Implementation of the RepredictorAloamgarm for fusing measurements with variable delays. More...
 
class  RHEIV
 Implementation of the Reduced Heteroscedastic Errors In Variables surface fitting algorithm [2]. More...
 
class  ROSTimer
 ros::Timer wrapper. The interface is the same as with ros::Timer, except for the initialization method. More...
 
class  Routine
 
class  SafetyZone
 
class  ScopeTimer
 Simple timer which will time a duration of a scope and checkpoints inside the scope in ros time and std::chrono time. More...
 
class  ScopeTimerLogger
 Simple file logger of scope timer and its checkpoints. More...
 
class  ServiceClientHandler
 user wrapper of the service client handler implementation More...
 
class  ServiceClientHandler_impl
 implementation of the service client handler More...
 
class  SubscribeHandler
 The main class for ROS topic subscription, message timeout handling etc. More...
 
struct  SubscribeHandlerOptions
 A helper class to simplify setup of SubscribeHandler construction. This class is passed to the SubscribeHandler constructor and specifies its common options. More...
 
class  ThreadTimer
 Custom thread-based Timers with the same interface as mrs_lib::ROSTimer. More...
 
class  TimeoutManager
 TODO. More...
 
class  TransformBroadcaster
 Wrapper for the tf2_ros::TransformBroadcaster. With each sendTransform() command, the message is checked against the last message with the same frame IDs. If the transform was already published in this ros::Time step, then the transform is skipped. Prevents endless stream of warnings from spamming the console output. More...
 
class  Transformer
 A convenience wrapper class for ROS's native TF2 API to simplify transforming of various messages. More...
 
class  UKF
 Implementation of the Unscented Kalman filter [4]. More...
 
class  varstepLKF
 
class  Vector3Converter
 Converter of Vector3 representations. Instantiate it with any type of vector3 in constructor and convert it by assigning it to any other type of vector3 variable. More...
 
class  VisualObject
 

Typedefs

template<typename SubscribeHandler >
using message_type = typename SubscribeHandler::message_type
 Helper alias for convenient extraction of handled message type from a SubscribeHandlerPtr.
 
using dkf_t = DKF< n_states, n_inputs >
 
using lkf_t = LKF< n_states, n_inputs, n_measurements >
 
using rep_t = Repredictor< lkf_t >
 
using rheiv_t = RHEIV< n_states, n_params >
 
using theta_t = rheiv_t::theta_t
 
using xs_t = rheiv_t::xs_t
 
using zs_t = rheiv_t::zs_t
 
using P_t = rheiv_t::P_t
 
using Ps_t = rheiv_t::Ps_t
 
using f_z_t = rheiv_t::f_z_t
 
using dzdx_t = rheiv_t::dzdx_t
 
using ukf_t = UKF< n_states, n_inputs, n_measurements >
 
using dumbrep_t = Repredictor< lkf_t, true >
 

Enumerations

enum  RPY_convention_t { RPY_INTRINSIC = 1, RPY_EXTRINSIC = 2 }
 
enum  MarkerType { POINT = 0, LINE = 1, TRIANGLE = 2 }
 

Functions

double probit (const double quantile)
 Inverse cumulative distribution function of the standard normal probability distribution. More...
 
std::tuple< double, double, double > getXYZ (const geometry_msgs::Point &data)
 get XYZ from geometry_msgs::Point More...
 
std::tuple< double, double, double > getXYZ (const geometry_msgs::PointConstPtr &data)
 get XYZ from geometry_msgs::PointConstPtr More...
 
std::tuple< double, double, double > getXYZ (const geometry_msgs::Vector3 &data)
 get XYZ from geometry_msgs::Vector3 More...
 
std::tuple< double, double, double > getXYZ (const geometry_msgs::Vector3ConstPtr &data)
 get XYZ from geometry_msgs::Vector3ConstPtr More...
 
std::tuple< double, double, double > getPosition (const geometry_msgs::Pose &data)
 get position from geometry_msgs::Pose More...
 
std::tuple< double, double, double > getPosition (const geometry_msgs::PoseConstPtr &data)
 get position from geometry_msgs::PoseConstPtr More...
 
double getHeading (const geometry_msgs::Pose &data)
 get heading from geometry_msgs::Pose More...
 
double getHeading (const geometry_msgs::PoseConstPtr &data)
 get heading from geometry_msgs::PoseConstPtr More...
 
double getYaw (const geometry_msgs::Pose &data)
 get yaw from geometry_msgs::Pose More...
 
double getYaw (const geometry_msgs::PoseConstPtr &data)
 get yaw from geometry_msgs::PoseConstPtr More...
 
std::tuple< double, double, double > getPosition (const geometry_msgs::PoseWithCovariance &data)
 get position from geometry_msgs::PoseWithCovariance More...
 
std::tuple< double, double, double > getPosition (const geometry_msgs::PoseWithCovarianceConstPtr &data)
 get position from geometry_msgs::PoseWithCovarianceConstPtr More...
 
double getHeading (const geometry_msgs::PoseWithCovariance &data)
 get heading from geometry_msgs::PoseWithCovariance More...
 
double getHeading (const geometry_msgs::PoseWithCovarianceConstPtr &data)
 get heading from geometry_msgs::PoseWithCovarianceConstPtr More...
 
double getYaw (const geometry_msgs::PoseWithCovariance &data)
 get yaw from geometry_msgs::PoseWithCovariance More...
 
double getYaw (const geometry_msgs::PoseWithCovarianceConstPtr &data)
 get yaw from geometry_msgs::PoseWithCovarianceConstPtr More...
 
std::tuple< double, double, double > getVelocity (const geometry_msgs::Twist &data)
 get velocity from geometry_msgs::Twist More...
 
std::tuple< double, double, double > getPosition (const geometry_msgs::TwistConstPtr &data)
 get position from geometry_msgs::TwistConstPtr More...
 
std::tuple< double, double, double > getVelocity (const geometry_msgs::TwistWithCovariance &data)
 get velocity from geometry_msgs::TwistWithCovariance More...
 
std::tuple< double, double, double > getPosition (const geometry_msgs::TwistWithCovarianceConstPtr &data)
 get position from geometry_msgs::TwistWithCovarianceConstPtr More...
 
std::tuple< double, double, double > getPosition (const nav_msgs::Odometry &data)
 get position from nav_msgs::Odometry More...
 
std::tuple< double, double, double > getPosition (const nav_msgs::OdometryConstPtr &data)
 get position from nav_msgs::OdometryConstPtr More...
 
std::tuple< double, double, double > getVelocity (const nav_msgs::Odometry &data)
 get position from nav_msgs::Odometry More...
 
std::tuple< double, double, double > getVelocity (const nav_msgs::OdometryConstPtr &data)
 get velocity from nav_msgs::OdometryConstPtr More...
 
double getHeading (const nav_msgs::Odometry &data)
 get heading from nav_msgs::Odometry More...
 
double getHeading (const nav_msgs::OdometryConstPtr &data)
 get heading from nav_msgs::OdometryConstPtr More...
 
double getYaw (const nav_msgs::Odometry &data)
 get yaw from nav_msgs::Odometry More...
 
double getYaw (const nav_msgs::OdometryConstPtr &data)
 get yaw from nav_msgs::OdometryConstPtr More...
 
geometry_msgs::Pose getPose (const nav_msgs::Odometry &data)
 returns the Pose part of the nav_msgs::Odometry message More...
 
geometry_msgs::Pose getPose (const nav_msgs::OdometryConstPtr &data)
 returns the Pose part of the nav_msgs::OdometryConstPtr message More...
 
std::tuple< double, double, double > getPosition (const mrs_msgs::TrackerCommand &data)
 get position data from mrs_msgs::TrackerCommand More...
 
std::tuple< double, double, double > getPosition (const mrs_msgs::TrackerCommandConstPtr &data)
 get position data from mrs_msgs::TrackerCommandConstPtr More...
 
std::tuple< double, double, double > getVelocity (const mrs_msgs::TrackerCommand &data)
 get velocity data from mrs_msgs::TrackerCommand More...
 
std::tuple< double, double, double > getVelocity (const mrs_msgs::TrackerCommandConstPtr &data)
 get velocity data from mrs_msgs::TrackerCommandConstPtr More...
 
double getHeading (const mrs_msgs::TrackerCommand &data)
 get heading from mrs_msgs::TrackerCommand More...
 
double getHeading (const mrs_msgs::TrackerCommandConstPtr &data)
 get heading from mrs_msgs::TrackerCommandConstPtr More...
 
std::tuple< double, double, double > getPosition (const mrs_msgs::Reference &data)
 get position from mrs_msgs::Reference More...
 
std::tuple< double, double, double > getPosition (const mrs_msgs::ReferenceConstPtr &data)
 get position from mrs_msgs::ReferenceConstPtr More...
 
double getHeading (const mrs_msgs::Reference &data)
 get heading from mrs_msgs::Reference More...
 
double getHeading (const mrs_msgs::ReferenceConstPtr &data)
 get heading from mrs_msgs::ReferenceConstPtr More...
 
std::tuple< double, double, double > getPosition (const mrs_msgs::ReferenceStamped &data)
 get position from mrs_msgs::ReferenceStamped More...
 
std::tuple< double, double, double > getPosition (const mrs_msgs::ReferenceStampedConstPtr &data)
 get position from mrs_msgs::ReferenceStampedConstPtr More...
 
double getHeading (const mrs_msgs::ReferenceStamped &data)
 get heading from mrs_msgs::ReferenceStamped More...
 
double getHeading (const mrs_msgs::ReferenceStampedConstPtr &data)
 get heading from mrs_msgs::ReferenceStampedConstPtr More...
 
template<class... GetArgs, class... SetArgs>
std::tuple< GetArgs... > get_set_mutexed (std::mutex &mut, std::tuple< GetArgs &... > get, std::tuple< SetArgs... > from_set, std::tuple< SetArgs &... > to_set)
 thread-safe getter and setter for values of variables (args) More...
 
template<class... Args>
std::tuple< Args... > get_mutexed (std::mutex &mut, Args &... args)
 thread-safe getter for values of variables (args) More...
 
template<class T >
get_mutexed (std::mutex &mut, T &arg)
 thread-safe getter a value from a variable More...
 
template<class T >
void set_mutexed_impl (const T what, T &where)
 base case of the variadic template for set_mutexed() More...
 
template<class T , class... Args>
void set_mutexed_impl (const T what, T &where, Args... args)
 general case of the variadic template for set_mutexed() More...
 
template<class T >
auto set_mutexed (std::mutex &mut, const T what, T &where)
 thread-safe setter for a variable More...
 
template<class... Args>
auto set_mutexed (std::mutex &mut, Args &... args)
 thread-safe setter for multiple variables More...
 
template<class... Args>
auto set_mutexed (std::mutex &mut, const std::tuple< Args... > from, std::tuple< Args &... > to)
 thread-safe setter for multiple variables More...
 
template<>
ros::Duration ParamLoader::loadParam2< ros::Duration > (const std::string &name, const ros::Duration &default_value)
 An overload for loading ros::Duration. More...
 
template<>
ros::Duration ParamLoader::loadParam2< ros::Duration > (const std::string &name)
 An overload for loading ros::Duration. More...
 
Intersection sectionIntersect (Eigen::RowVector2d start1, Eigen::RowVector2d end1, Eigen::RowVector2d start2, Eigen::RowVector2d end2)
 
template<typename Class , class ... Types>
void construct_object (Class &object, Types ... args)
 Helper function for object construstion e.g. in case of member objects. This function is useful to avoid specifying object template parameters twice - once in definition of the variable and second time during object construction. This function can deduce the template parameters from the type of the already defined object, because it returns the newly constructed object as a reference argument and not as a return type. More...
 
bool breakable_sleep (const ros::Duration &dur, const std::atomic< bool > &continue_sleep)
 
template<typename Iterator >
std::string containerToString (const Iterator begin, const Iterator end, const std::string &delimiter=", ")
 Convenience function for converting container ranges to strings (e.g. for printing). More...
 
template<typename Iterator >
std::string containerToString (const Iterator begin, const Iterator end, const char *delimiter)
 Convenience function for converting container ranges to strings (e.g. for printing). More...
 
template<typename Container >
std::string containerToString (const Container &cont, const std::string &delimiter=", ")
 Convenience function for converting containers to strings (e.g. for printing). More...
 
template<typename Container >
std::string containerToString (const Container &cont, const char *delimiter=", ")
 Convenience function for converting containers to strings (e.g. for printing). More...
 
template<typename T >
T::iterator remove_const (const typename T::const_iterator &it, T &cont)
 Convenience class for removing const-ness from a container iterator. More...
 
template<typename T >
int signum (T val)
 
template<typename ret_t , typename in_t >
ret_t convert (const in_t &in)
 Converts between different vector representations. More...
 
geometry_msgs::Point eigenToMsg (const Eigen::Vector3d &v)
 
std_msgs::ColorRGBA generateColor (const double r, const double g, const double b, const double a)
 
Eigen::Vector3d msgToEigen (const geometry_msgs::Point &p)
 
std::vector< Eigen::Vector3d > buildEllipse (const mrs_lib::geometry::Ellipse &ellipse, const int num_points)
 
template bool ParamProvider::getParam< std::string > (const std::string &name, std::string &out_value) const
 

Variables

const double RADIANS_PER_DEGREE = M_PI / 180.0
 
const double DEGREES_PER_RADIAN = 180.0 / M_PI
 
const double WGS84_A = 6378137.0
 
const double WGS84_B = 6356752.31424518
 
const double WGS84_F = 0.0033528107
 
const double WGS84_E = 0.0818191908
 
const double WGS84_EP = 0.0820944379
 
const double UTM_K0 = 0.9996
 
const double UTM_FE = 500000.0
 
const double UTM_FN_N = 0.0
 
const double UTM_FN_S = 10000000.0
 
const double UTM_E2 = (WGS84_E * WGS84_E)
 
const double UTM_E4 = (UTM_E2 * UTM_E2)
 
const double UTM_E6 = (UTM_E4 * UTM_E2)
 
const double UTM_EP2 = (UTM_E2 / (1 - UTM_E2))
 
const int n_states = 6
 
const int n_inputs = 0
 
const int n_measurements = 2
 
const int n_states_norm_constrained = 2
 
const int n_params = 4
 

Detailed Description

All mrs_lib functions, classes, variables and definitions are contained in this namespace.

Function Documentation

◆ construct_object()

template<typename Class , class ... Types>
void mrs_lib::construct_object ( Class &  object,
Types ...  args 
)

Helper function for object construstion e.g. in case of member objects. This function is useful to avoid specifying object template parameters twice - once in definition of the variable and second time during object construction. This function can deduce the template parameters from the type of the already defined object, because it returns the newly constructed object as a reference argument and not as a return type.

Parameters
objectThe object to be constructed.
argsThese arguments are passed to the object constructor.
Examples
subscribe_handler/example.cpp.

◆ containerToString() [1/4]

template<typename Container >
std::string mrs_lib::containerToString ( const Container &  cont,
const char *  delimiter = ", " 
)

Convenience function for converting containers to strings (e.g. for printing).

Parameters
contthe container that will be converted to std::string.
delimiterwill be used to separate the elements in the output.
Returns
elements of the container from begin to end (excluding), converted to string and separated by delimiter.

◆ containerToString() [2/4]

template<typename Container >
std::string mrs_lib::containerToString ( const Container &  cont,
const std::string &  delimiter = ", " 
)

Convenience function for converting containers to strings (e.g. for printing).

Parameters
contthe container that will be converted to std::string.
delimiterwill be used to separate the elements in the output.
Returns
elements of the container from begin to end (excluding), converted to string and separated by delimiter.

◆ containerToString() [3/4]

template<typename Iterator >
std::string mrs_lib::containerToString ( const Iterator  begin,
const Iterator  end,
const char *  delimiter 
)

Convenience function for converting container ranges to strings (e.g. for printing).

Parameters
beginfirst element of the container that will be converted to std::string.
endone-after-the-last element of the container that will be converted to std::string.
delimiterwill be used to separate the elements in the output.
Returns
elements of the container from begin to end (excluding), converted to string and separated by delimiter.

◆ containerToString() [4/4]

template<typename Iterator >
std::string mrs_lib::containerToString ( const Iterator  begin,
const Iterator  end,
const std::string &  delimiter = ", " 
)

Convenience function for converting container ranges to strings (e.g. for printing).

Parameters
beginfirst element of the container that will be converted to std::string.
endone-after-the-last element of the container that will be converted to std::string.
delimiterwill be used to separate the elements in the output.
Returns
elements of the container from begin to end (excluding), converted to string and separated by delimiter.

◆ convert()

template<typename ret_t , typename in_t >
ret_t mrs_lib::convert ( const in_t &  in)

Converts between different vector representations.

Usage (for full example, see the file vector_converter/example.cpp):

auto out = mrs_lib::convert<to_type>(in);

Supported types by default are: Eigen::Vector3d, cv::Vec3d, geometry_msgs::Vector3. If you want to use this with a new type, it should work automagically if it provides a reasonable API. If it doesn't work by default, you just need to implement the respective convertTo() and convertFrom() functions for that type (see the file impl/vector_converter.hpp and the example file vector_converter/example.cpp).

Parameters
inThe input vector to be converted to the ret_t type.
Template Parameters
ret_tType of the return vector. You need to specify this when calling the function.
in_tType of the input vector. This parameter is deduced by the compiler and doesn't need to be specified in usual cases.

◆ get_mutexed() [1/2]

template<class... Args>
std::tuple<Args...> mrs_lib::get_mutexed ( std::mutex &  mut,
Args &...  args 
)

thread-safe getter for values of variables (args)

Template Parameters
Argstypes of the variables
Parameters
mutmutex which protects the variables
argsvariables to obtain the values from
Returns
std::tuple of the values
Examples
repredictor/example.cpp.

◆ get_mutexed() [2/2]

template<class T >
T mrs_lib::get_mutexed ( std::mutex &  mut,
T &  arg 
)

thread-safe getter a value from a variable

Template Parameters
Ttype of the variable
Parameters
mutmutex which protects the variable
argvariable to obtain the value from
Returns
value of the variable

◆ get_set_mutexed()

template<class... GetArgs, class... SetArgs>
std::tuple<GetArgs...> mrs_lib::get_set_mutexed ( std::mutex &  mut,
std::tuple< GetArgs &... >  get,
std::tuple< SetArgs... >  from_set,
std::tuple< SetArgs &... >  to_set 
)

thread-safe getter and setter for values of variables (args)

Template Parameters
GetArgstypes of the variables to get
SetArgstypes of the variables to set
Parameters
mutmutex which protects the variables
gettuple of variable references to obtain the values from
to_settuple of variable references to set the new values from from_set
from_settuple of the new values to be set to to_set
Returns
tuple of the values from get

◆ getHeading() [1/12]

double mrs_lib::getHeading ( const geometry_msgs::Pose &  data)

get heading from geometry_msgs::Pose

Parameters
datapose
Returns
heading

◆ getHeading() [2/12]

double mrs_lib::getHeading ( const geometry_msgs::PoseConstPtr &  data)

get heading from geometry_msgs::PoseConstPtr

Parameters
datapose (ConstPtr)
Returns
heading

◆ getHeading() [3/12]

double mrs_lib::getHeading ( const geometry_msgs::PoseWithCovariance &  data)

get heading from geometry_msgs::PoseWithCovariance

Parameters
datapose with covariance
Returns
heading

◆ getHeading() [4/12]

double mrs_lib::getHeading ( const geometry_msgs::PoseWithCovarianceConstPtr &  data)

get heading from geometry_msgs::PoseWithCovarianceConstPtr

Parameters
datapose with covariance (ConstPtr)
Returns
heading

◆ getHeading() [5/12]

double mrs_lib::getHeading ( const mrs_msgs::Reference &  data)

get heading from mrs_msgs::Reference

Parameters
datareference
Returns
heading

◆ getHeading() [6/12]

double mrs_lib::getHeading ( const mrs_msgs::ReferenceConstPtr &  data)

get heading from mrs_msgs::ReferenceConstPtr

Parameters
datareference (ContrPtr)
Returns
heading

◆ getHeading() [7/12]

double mrs_lib::getHeading ( const mrs_msgs::ReferenceStamped &  data)

get heading from mrs_msgs::ReferenceStamped

Parameters
datareferencestamped
Returns
heading

◆ getHeading() [8/12]

double mrs_lib::getHeading ( const mrs_msgs::ReferenceStampedConstPtr &  data)

get heading from mrs_msgs::ReferenceStampedConstPtr

Parameters
datareferencestamped (ContrPtr)
Returns
heading

◆ getHeading() [9/12]

double mrs_lib::getHeading ( const mrs_msgs::TrackerCommand &  data)

get heading from mrs_msgs::TrackerCommand

Parameters
dataposition command
Returns
heading

◆ getHeading() [10/12]

double mrs_lib::getHeading ( const mrs_msgs::TrackerCommandConstPtr &  data)

get heading from mrs_msgs::TrackerCommandConstPtr

Parameters
dataposition command (ConstPtr)
Returns
heading

◆ getHeading() [11/12]

double mrs_lib::getHeading ( const nav_msgs::Odometry &  data)

get heading from nav_msgs::Odometry

Parameters
dataodometry
Returns
heading

◆ getHeading() [12/12]

double mrs_lib::getHeading ( const nav_msgs::OdometryConstPtr &  data)

get heading from nav_msgs::OdometryConstPtr

Parameters
dataodometry (ConstPtr)
Returns
heading

◆ getPose() [1/2]

geometry_msgs::Pose mrs_lib::getPose ( const nav_msgs::Odometry &  data)

returns the Pose part of the nav_msgs::Odometry message

Parameters
dataodometry
Returns
pose

◆ getPose() [2/2]

geometry_msgs::Pose mrs_lib::getPose ( const nav_msgs::OdometryConstPtr &  data)

returns the Pose part of the nav_msgs::OdometryConstPtr message

Parameters
dataodometry (ConstPtr)
Returns
pose

◆ getPosition() [1/14]

std::tuple<double, double, double> mrs_lib::getPosition ( const geometry_msgs::Pose &  data)

get position from geometry_msgs::Pose

Parameters
datapose
Returns
x, y, z

◆ getPosition() [2/14]

std::tuple<double, double, double> mrs_lib::getPosition ( const geometry_msgs::PoseConstPtr &  data)

get position from geometry_msgs::PoseConstPtr

Parameters
datapose (ConstPtr)
Returns
x, y, z

◆ getPosition() [3/14]

std::tuple<double, double, double> mrs_lib::getPosition ( const geometry_msgs::PoseWithCovariance &  data)

get position from geometry_msgs::PoseWithCovariance

Parameters
datapose with covariance
Returns
x, y, z

◆ getPosition() [4/14]

std::tuple<double, double, double> mrs_lib::getPosition ( const geometry_msgs::PoseWithCovarianceConstPtr &  data)

get position from geometry_msgs::PoseWithCovarianceConstPtr

Parameters
datapose with covariance (ConstPtr)
Returns
x, y, z

◆ getPosition() [5/14]

std::tuple<double, double, double> mrs_lib::getPosition ( const geometry_msgs::TwistConstPtr &  data)

get position from geometry_msgs::TwistConstPtr

Parameters
datatwist (ConstPtr)
Returns
x, y, z

◆ getPosition() [6/14]

std::tuple<double, double, double> mrs_lib::getPosition ( const geometry_msgs::TwistWithCovarianceConstPtr &  data)

get position from geometry_msgs::TwistWithCovarianceConstPtr

Parameters
datatwistwithcovariance (ConstPtr)
Returns
x, y, z

◆ getPosition() [7/14]

std::tuple<double, double, double> mrs_lib::getPosition ( const mrs_msgs::Reference &  data)

get position from mrs_msgs::Reference

Parameters
datareference
Returns
x, y, z

◆ getPosition() [8/14]

std::tuple<double, double, double> mrs_lib::getPosition ( const mrs_msgs::ReferenceConstPtr &  data)

get position from mrs_msgs::ReferenceConstPtr

Parameters
datareference (ContrPtr)
Returns
x, y, z

◆ getPosition() [9/14]

std::tuple<double, double, double> mrs_lib::getPosition ( const mrs_msgs::ReferenceStamped &  data)

get position from mrs_msgs::ReferenceStamped

Parameters
datareference stamped
Returns
x, y, z

◆ getPosition() [10/14]

std::tuple<double, double, double> mrs_lib::getPosition ( const mrs_msgs::ReferenceStampedConstPtr &  data)

get position from mrs_msgs::ReferenceStampedConstPtr

Parameters
datareference stamped (ContrPtr)
Returns
x, y, z

◆ getPosition() [11/14]

std::tuple<double, double, double> mrs_lib::getPosition ( const mrs_msgs::TrackerCommand &  data)

get position data from mrs_msgs::TrackerCommand

Parameters
dataposition command
Returns
x, y, z

◆ getPosition() [12/14]

std::tuple<double, double, double> mrs_lib::getPosition ( const mrs_msgs::TrackerCommandConstPtr &  data)

get position data from mrs_msgs::TrackerCommandConstPtr

Parameters
dataposition command (ConstPtr)
Returns
x, y, z

◆ getPosition() [13/14]

std::tuple<double, double, double> mrs_lib::getPosition ( const nav_msgs::Odometry &  data)

get position from nav_msgs::Odometry

Parameters
dataodometry
Returns
x, y, z

◆ getPosition() [14/14]

std::tuple<double, double, double> mrs_lib::getPosition ( const nav_msgs::OdometryConstPtr &  data)

get position from nav_msgs::OdometryConstPtr

Parameters
dataodometry (ConstPtr)
Returns
x, y, z

◆ getVelocity() [1/6]

std::tuple<double, double, double> mrs_lib::getVelocity ( const geometry_msgs::Twist &  data)

get velocity from geometry_msgs::Twist

Parameters
datatwist
Returns
x, y, z

◆ getVelocity() [2/6]

std::tuple<double, double, double> mrs_lib::getVelocity ( const geometry_msgs::TwistWithCovariance &  data)

get velocity from geometry_msgs::TwistWithCovariance

Parameters
datatwistwithcovariance
Returns
x, y, z

◆ getVelocity() [3/6]

std::tuple<double, double, double> mrs_lib::getVelocity ( const mrs_msgs::TrackerCommand &  data)

get velocity data from mrs_msgs::TrackerCommand

Parameters
dataposition command
Returns
x, y, z

◆ getVelocity() [4/6]

std::tuple<double, double, double> mrs_lib::getVelocity ( const mrs_msgs::TrackerCommandConstPtr &  data)

get velocity data from mrs_msgs::TrackerCommandConstPtr

Parameters
dataposition command (ConstPtr)
Returns
x, y, z

◆ getVelocity() [5/6]

std::tuple<double, double, double> mrs_lib::getVelocity ( const nav_msgs::Odometry &  data)

get position from nav_msgs::Odometry

Parameters
dataodometry
Returns
x, y, z

◆ getVelocity() [6/6]

std::tuple<double, double, double> mrs_lib::getVelocity ( const nav_msgs::OdometryConstPtr &  data)

get velocity from nav_msgs::OdometryConstPtr

Parameters
dataodometry (ConstPtr)
Returns
x, y, z

◆ getXYZ() [1/4]

std::tuple<double, double, double> mrs_lib::getXYZ ( const geometry_msgs::Point &  data)

get XYZ from geometry_msgs::Point

Parameters
datapoint
Returns
x, y, z

◆ getXYZ() [2/4]

std::tuple<double, double, double> mrs_lib::getXYZ ( const geometry_msgs::PointConstPtr &  data)

get XYZ from geometry_msgs::PointConstPtr

Parameters
datapoint (ConstPtr)
Returns
x, y, z

◆ getXYZ() [3/4]

std::tuple<double, double, double> mrs_lib::getXYZ ( const geometry_msgs::Vector3 &  data)

get XYZ from geometry_msgs::Vector3

Parameters
datavector3
Returns
x, y, z

◆ getXYZ() [4/4]

std::tuple<double, double, double> mrs_lib::getXYZ ( const geometry_msgs::Vector3ConstPtr &  data)

get XYZ from geometry_msgs::Vector3ConstPtr

Parameters
datavector3 (ConstPtr)
Returns
x, y, z

◆ getYaw() [1/6]

double mrs_lib::getYaw ( const geometry_msgs::Pose &  data)

get yaw from geometry_msgs::Pose

Parameters
datapose
Returns
yaw

◆ getYaw() [2/6]

double mrs_lib::getYaw ( const geometry_msgs::PoseConstPtr &  data)

get yaw from geometry_msgs::PoseConstPtr

Parameters
datapose (ConstPtr)
Returns
yaw

◆ getYaw() [3/6]

double mrs_lib::getYaw ( const geometry_msgs::PoseWithCovariance &  data)

get yaw from geometry_msgs::PoseWithCovariance

Parameters
datapose with covariance
Returns
yaw

◆ getYaw() [4/6]

double mrs_lib::getYaw ( const geometry_msgs::PoseWithCovarianceConstPtr &  data)

get yaw from geometry_msgs::PoseWithCovarianceConstPtr

Parameters
datapose with covariance (ConstPtr)
Returns
yaw

◆ getYaw() [5/6]

double mrs_lib::getYaw ( const nav_msgs::Odometry &  data)

get yaw from nav_msgs::Odometry

Parameters
dataodometry
Returns
yaw

◆ getYaw() [6/6]

double mrs_lib::getYaw ( const nav_msgs::OdometryConstPtr &  data)

get yaw from nav_msgs::OdometryConstPtr

Parameters
dataodometry (ConstPtr)
Returns
yaw

◆ ParamLoader::loadParam2< ros::Duration >() [1/2]

template<>
ros::Duration mrs_lib::ParamLoader::loadParam2< ros::Duration > ( const std::string &  name)

An overload for loading ros::Duration.

The duration will be loaded as a double, representing a number of seconds, and then converted to ros::Duration.

Parameters
nameName of the parameter in the rosparam server.
Returns
The loaded parameter value.

◆ ParamLoader::loadParam2< ros::Duration >() [2/2]

template<>
ros::Duration mrs_lib::ParamLoader::loadParam2< ros::Duration > ( const std::string &  name,
const ros::Duration &  default_value 
)

An overload for loading ros::Duration.

The duration will be loaded as a double, representing a number of seconds, and then converted to ros::Duration.

Parameters
nameName of the parameter in the rosparam server.
default_valueThis value will be used if the parameter name is not found in the rosparam server.
Returns
The loaded parameter value.

◆ probit()

double mrs_lib::probit ( const double  quantile)

Inverse cumulative distribution function of the standard normal probability distribution.

Implements the quantile function of a standard normal probability distribution (aka the probit function, see https://en.wikipedia.org/wiki/Probit). The implementation uses the Beasley-Springer-Moro approximation (see page 68 of Glasserman, Paul, "Monte Carlo Methods in Financial Engineering. Stochastic Modelling and Applied Probability", 2003, doi:10.1007/978-0-387-21617-1, available at https://sci-hub.se/10.1007/978-0-387-21617-1).

Parameters
quantilethe probability that a realization of a random variable with a standard normal dostribution is equal or less than the returned value (see https://en.wikipedia.org/wiki/Quantile).
Returns
such a value that the probability that a realization of a random variable with a standard normal dostribution is equal or less is quantile.

◆ remove_const()

template<typename T >
T::iterator mrs_lib::remove_const ( const typename T::const_iterator &  it,
T &  cont 
)

Convenience class for removing const-ness from a container iterator.

Parameters
itthe iterator from which const-ness should be removed.
contthe corresponding container of the iterator.
Returns
a non-const iterator, pointing to the same element as it.

◆ set_mutexed() [1/3]

template<class... Args>
auto mrs_lib::set_mutexed ( std::mutex &  mut,
Args &...  args 
)

thread-safe setter for multiple variables

example: set_mutexed(my_mutex_, a, a_, b, b_, c, c_); where a, b, c are the values to be set a_, b_, c_ are the variables to be updated

Template Parameters
Argstypes of the variables
Parameters
mutmutex to be locked
args
Returns
alternating list of values that were just set

◆ set_mutexed() [2/3]

template<class... Args>
auto mrs_lib::set_mutexed ( std::mutex &  mut,
const std::tuple< Args... >  from,
std::tuple< Args &... >  to 
)

thread-safe setter for multiple variables

example: set_mutexed(mu_mutex, std::tuple(a, b, c), std::forward_as_tuple(a_, b_, c_)); where a, b, c are the values to be set a_, b_, c_ are the updated variables

Template Parameters
Argstypes of the variables
Parameters
mutmutex to be locked
fromstd::tuple of the values
tostd::tuple of reference to the variablaes
Returns

◆ set_mutexed() [3/3]

template<class T >
auto mrs_lib::set_mutexed ( std::mutex &  mut,
const T  what,
T &  where 
)

thread-safe setter for a variable

Template Parameters
Ttype of the variable
Parameters
mutmutex to be locked
whatvalue to set
wherereference to be set
Returns
Examples
repredictor/example.cpp.

◆ set_mutexed_impl() [1/2]

template<class T >
void mrs_lib::set_mutexed_impl ( const T  what,
T &  where 
)

base case of the variadic template for set_mutexed()

Template Parameters
Tvariable type
Parameters
whatvalue to set
wherereference to be set

◆ set_mutexed_impl() [2/2]

template<class T , class... Args>
void mrs_lib::set_mutexed_impl ( const T  what,
T &  where,
Args...  args 
)

general case of the variadic template for set_mutexed()

Template Parameters
Ttype of the next variable to set
Argstypes of the rest of the variables
Parameters
whatvalue to set
wherereference to be set
argsthe remaining arguments