mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
|
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 > | |
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... | |
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 |
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
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.
object | The object to be constructed. |
args | These arguments are passed to the object constructor. |
std::string mrs_lib::containerToString | ( | const Container & | cont, |
const char * | delimiter = ", " |
||
) |
Convenience function for converting containers to strings (e.g. for printing).
cont | the container that will be converted to std::string . |
delimiter | will be used to separate the elements in the output. |
begin
to end
(excluding), converted to string and separated by delimiter
. std::string mrs_lib::containerToString | ( | const Container & | cont, |
const std::string & | delimiter = ", " |
||
) |
Convenience function for converting containers to strings (e.g. for printing).
cont | the container that will be converted to std::string . |
delimiter | will be used to separate the elements in the output. |
begin
to end
(excluding), converted to string and separated by delimiter
. 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).
begin | first element of the container that will be converted to std::string . |
end | one-after-the-last element of the container that will be converted to std::string . |
delimiter | will be used to separate the elements in the output. |
begin
to end
(excluding), converted to string and separated by delimiter
. 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).
begin | first element of the container that will be converted to std::string . |
end | one-after-the-last element of the container that will be converted to std::string . |
delimiter | will be used to separate the elements in the output. |
begin
to end
(excluding), converted to string and separated by delimiter
. 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).
in | The input vector to be converted to the ret_t type. |
ret_t | Type of the return vector. You need to specify this when calling the function. |
in_t | Type of the input vector. This parameter is deduced by the compiler and doesn't need to be specified in usual cases. |
std::tuple<Args...> mrs_lib::get_mutexed | ( | std::mutex & | mut, |
Args &... | args | ||
) |
thread-safe getter for values of variables (args)
Args | types of the variables |
mut | mutex which protects the variables |
args | variables to obtain the values from |
T mrs_lib::get_mutexed | ( | std::mutex & | mut, |
T & | arg | ||
) |
thread-safe getter a value from a variable
T | type of the variable |
mut | mutex which protects the variable |
arg | variable to obtain the value from |
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)
GetArgs | types of the variables to get |
SetArgs | types of the variables to set |
mut | mutex which protects the variables |
get | tuple of variable references to obtain the values from |
to_set | tuple of variable references to set the new values from from_set |
from_set | tuple of the new values to be set to to_set |
get
double mrs_lib::getHeading | ( | const geometry_msgs::Pose & | data | ) |
get heading from geometry_msgs::Pose
data | pose |
double mrs_lib::getHeading | ( | const geometry_msgs::PoseConstPtr & | data | ) |
get heading from geometry_msgs::PoseConstPtr
data | pose (ConstPtr) |
double mrs_lib::getHeading | ( | const geometry_msgs::PoseWithCovariance & | data | ) |
get heading from geometry_msgs::PoseWithCovariance
data | pose with covariance |
double mrs_lib::getHeading | ( | const geometry_msgs::PoseWithCovarianceConstPtr & | data | ) |
get heading from geometry_msgs::PoseWithCovarianceConstPtr
data | pose with covariance (ConstPtr) |
double mrs_lib::getHeading | ( | const mrs_msgs::Reference & | data | ) |
get heading from mrs_msgs::Reference
data | reference |
double mrs_lib::getHeading | ( | const mrs_msgs::ReferenceConstPtr & | data | ) |
get heading from mrs_msgs::ReferenceConstPtr
data | reference (ContrPtr) |
double mrs_lib::getHeading | ( | const mrs_msgs::ReferenceStamped & | data | ) |
get heading from mrs_msgs::ReferenceStamped
data | referencestamped |
double mrs_lib::getHeading | ( | const mrs_msgs::ReferenceStampedConstPtr & | data | ) |
get heading from mrs_msgs::ReferenceStampedConstPtr
data | referencestamped (ContrPtr) |
double mrs_lib::getHeading | ( | const mrs_msgs::TrackerCommand & | data | ) |
get heading from mrs_msgs::TrackerCommand
data | position command |
double mrs_lib::getHeading | ( | const mrs_msgs::TrackerCommandConstPtr & | data | ) |
get heading from mrs_msgs::TrackerCommandConstPtr
data | position command (ConstPtr) |
double mrs_lib::getHeading | ( | const nav_msgs::Odometry & | data | ) |
get heading from nav_msgs::Odometry
data | odometry |
double mrs_lib::getHeading | ( | const nav_msgs::OdometryConstPtr & | data | ) |
get heading from nav_msgs::OdometryConstPtr
data | odometry (ConstPtr) |
geometry_msgs::Pose mrs_lib::getPose | ( | const nav_msgs::Odometry & | data | ) |
returns the Pose part of the nav_msgs::Odometry message
data | odometry |
geometry_msgs::Pose mrs_lib::getPose | ( | const nav_msgs::OdometryConstPtr & | data | ) |
returns the Pose part of the nav_msgs::OdometryConstPtr message
data | odometry (ConstPtr) |
std::tuple<double, double, double> mrs_lib::getPosition | ( | const geometry_msgs::Pose & | data | ) |
get position from geometry_msgs::Pose
data | pose |
std::tuple<double, double, double> mrs_lib::getPosition | ( | const geometry_msgs::PoseConstPtr & | data | ) |
get position from geometry_msgs::PoseConstPtr
data | pose (ConstPtr) |
std::tuple<double, double, double> mrs_lib::getPosition | ( | const geometry_msgs::PoseWithCovariance & | data | ) |
get position from geometry_msgs::PoseWithCovariance
data | pose with covariance |
std::tuple<double, double, double> mrs_lib::getPosition | ( | const geometry_msgs::PoseWithCovarianceConstPtr & | data | ) |
get position from geometry_msgs::PoseWithCovarianceConstPtr
data | pose with covariance (ConstPtr) |
std::tuple<double, double, double> mrs_lib::getPosition | ( | const geometry_msgs::TwistConstPtr & | data | ) |
get position from geometry_msgs::TwistConstPtr
data | twist (ConstPtr) |
std::tuple<double, double, double> mrs_lib::getPosition | ( | const geometry_msgs::TwistWithCovarianceConstPtr & | data | ) |
get position from geometry_msgs::TwistWithCovarianceConstPtr
data | twistwithcovariance (ConstPtr) |
std::tuple<double, double, double> mrs_lib::getPosition | ( | const mrs_msgs::Reference & | data | ) |
get position from mrs_msgs::Reference
data | reference |
std::tuple<double, double, double> mrs_lib::getPosition | ( | const mrs_msgs::ReferenceConstPtr & | data | ) |
get position from mrs_msgs::ReferenceConstPtr
data | reference (ContrPtr) |
std::tuple<double, double, double> mrs_lib::getPosition | ( | const mrs_msgs::ReferenceStamped & | data | ) |
get position from mrs_msgs::ReferenceStamped
data | reference stamped |
std::tuple<double, double, double> mrs_lib::getPosition | ( | const mrs_msgs::ReferenceStampedConstPtr & | data | ) |
get position from mrs_msgs::ReferenceStampedConstPtr
data | reference stamped (ContrPtr) |
std::tuple<double, double, double> mrs_lib::getPosition | ( | const mrs_msgs::TrackerCommand & | data | ) |
get position data from mrs_msgs::TrackerCommand
data | position command |
std::tuple<double, double, double> mrs_lib::getPosition | ( | const mrs_msgs::TrackerCommandConstPtr & | data | ) |
get position data from mrs_msgs::TrackerCommandConstPtr
data | position command (ConstPtr) |
std::tuple<double, double, double> mrs_lib::getPosition | ( | const nav_msgs::Odometry & | data | ) |
get position from nav_msgs::Odometry
data | odometry |
std::tuple<double, double, double> mrs_lib::getPosition | ( | const nav_msgs::OdometryConstPtr & | data | ) |
get position from nav_msgs::OdometryConstPtr
data | odometry (ConstPtr) |
std::tuple<double, double, double> mrs_lib::getVelocity | ( | const geometry_msgs::Twist & | data | ) |
get velocity from geometry_msgs::Twist
data | twist |
std::tuple<double, double, double> mrs_lib::getVelocity | ( | const geometry_msgs::TwistWithCovariance & | data | ) |
get velocity from geometry_msgs::TwistWithCovariance
data | twistwithcovariance |
std::tuple<double, double, double> mrs_lib::getVelocity | ( | const mrs_msgs::TrackerCommand & | data | ) |
get velocity data from mrs_msgs::TrackerCommand
data | position command |
std::tuple<double, double, double> mrs_lib::getVelocity | ( | const mrs_msgs::TrackerCommandConstPtr & | data | ) |
get velocity data from mrs_msgs::TrackerCommandConstPtr
data | position command (ConstPtr) |
std::tuple<double, double, double> mrs_lib::getVelocity | ( | const nav_msgs::Odometry & | data | ) |
get position from nav_msgs::Odometry
data | odometry |
std::tuple<double, double, double> mrs_lib::getVelocity | ( | const nav_msgs::OdometryConstPtr & | data | ) |
get velocity from nav_msgs::OdometryConstPtr
data | odometry (ConstPtr) |
std::tuple<double, double, double> mrs_lib::getXYZ | ( | const geometry_msgs::Point & | data | ) |
get XYZ from geometry_msgs::Point
data | point |
std::tuple<double, double, double> mrs_lib::getXYZ | ( | const geometry_msgs::PointConstPtr & | data | ) |
get XYZ from geometry_msgs::PointConstPtr
data | point (ConstPtr) |
std::tuple<double, double, double> mrs_lib::getXYZ | ( | const geometry_msgs::Vector3 & | data | ) |
get XYZ from geometry_msgs::Vector3
data | vector3 |
std::tuple<double, double, double> mrs_lib::getXYZ | ( | const geometry_msgs::Vector3ConstPtr & | data | ) |
get XYZ from geometry_msgs::Vector3ConstPtr
data | vector3 (ConstPtr) |
double mrs_lib::getYaw | ( | const geometry_msgs::Pose & | data | ) |
get yaw from geometry_msgs::Pose
data | pose |
double mrs_lib::getYaw | ( | const geometry_msgs::PoseConstPtr & | data | ) |
get yaw from geometry_msgs::PoseConstPtr
data | pose (ConstPtr) |
double mrs_lib::getYaw | ( | const geometry_msgs::PoseWithCovariance & | data | ) |
get yaw from geometry_msgs::PoseWithCovariance
data | pose with covariance |
double mrs_lib::getYaw | ( | const geometry_msgs::PoseWithCovarianceConstPtr & | data | ) |
get yaw from geometry_msgs::PoseWithCovarianceConstPtr
data | pose with covariance (ConstPtr) |
double mrs_lib::getYaw | ( | const nav_msgs::Odometry & | data | ) |
get yaw from nav_msgs::Odometry
data | odometry |
double mrs_lib::getYaw | ( | const nav_msgs::OdometryConstPtr & | data | ) |
get yaw from nav_msgs::OdometryConstPtr
data | odometry (ConstPtr) |
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.
name | Name of the parameter in the rosparam server. |
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.
name | Name of the parameter in the rosparam server. |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
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).
quantile | the 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). |
quantile
. T::iterator mrs_lib::remove_const | ( | const typename T::const_iterator & | it, |
T & | cont | ||
) |
Convenience class for removing const-ness from a container iterator.
it | the iterator from which const-ness should be removed. |
cont | the corresponding container of the iterator. |
it
. 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
Args | types of the variables |
mut | mutex to be locked |
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
Args | types of the variables |
mut | mutex to be locked |
from | std::tuple of the values |
to | std::tuple of reference to the variablaes |
auto mrs_lib::set_mutexed | ( | std::mutex & | mut, |
const T | what, | ||
T & | where | ||
) |
thread-safe setter for a variable
T | type of the variable |
mut | mutex to be locked |
what | value to set |
where | reference to be set |
void mrs_lib::set_mutexed_impl | ( | const T | what, |
T & | where | ||
) |
base case of the variadic template for set_mutexed()
T | variable type |
what | value to set |
where | reference to be set |
void mrs_lib::set_mutexed_impl | ( | const T | what, |
T & | where, | ||
Args... | args | ||
) |
general case of the variadic template for set_mutexed()
T | type of the next variable to set |
Args | types of the rest of the variables |
what | value to set |
where | reference to be set |
args | the remaining arguments |