mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
mrs_lib::Transformer Class Reference

A convenience wrapper class for ROS's native TF2 API to simplify transforming of various messages. More...

#include <transformer.h>

Public Member Functions

 Transformer ()
 A convenience constructor that doesn't initialize anything. More...
 
 Transformer (const std::string &node_name, const ros::Duration &cache_time=ros::Duration(tf2_ros::Buffer::DEFAULT_CACHE_TIME))
 The main constructor that actually initializes stuff. More...
 
 Transformer (const ros::NodeHandle &nh, const std::string &node_name=std::string(), const ros::Duration &cache_time=ros::Duration(tf2_ros::Buffer::DEFAULT_CACHE_TIME))
 The main constructor that actually initializes stuff. More...
 
Transformeroperator= (Transformer &&other)
 A convenience move assignment operator. More...
 
void setDefaultFrame (const std::string &frame_id)
 Sets the default frame ID to be used instead of any empty frame ID. More...
 
void setDefaultPrefix (const std::string &prefix)
 Sets the default frame ID prefix to be used if no prefix is present in the frame. More...
 
void setLatLon (const double lat, const double lon)
 Sets the curret lattitude and longitude for UTM zone calculation. More...
 
void setLookupTimeout (const ros::Duration timeout=ros::Duration(0))
 Set a timeout for transform lookup. More...
 
void retryLookupNewest (const bool retry=true)
 Enable/disable retry of a failed transform lookup with ros::Time(0). More...
 
void beQuiet (const bool quiet=true)
 Enable/disable some prints that may be too noisy. More...
 
std::string resolveFrame (const std::string &frame_id)
 Deduce the full frame ID from a shortened or empty string using current default prefix and default frame rules. More...
 
template<class T >
std::optional< T > transformSingle (const T &what, const std::string &to_frame)
 Transforms a single variable to a new frame and returns it or std::nullopt if transformation fails. More...
 
template<class T >
std::optional< boost::shared_ptr< T > > transformSingle (const boost::shared_ptr< T > &what, const std::string &to_frame)
 Transforms a single variable to a new frame. More...
 
template<class T >
std::optional< boost::shared_ptr< T > > transformSingle (const boost::shared_ptr< const T > &what, const std::string &to_frame)
 Transforms a single variable to a new frame. More...
 
template<class T >
std::optional< T > transformSingle (const std::string &from_frame, const T &what, const std::string &to_frame, const ros::Time &time_stamp=ros::Time(0))
 Transforms a single variable to a new frame and returns it or std::nullopt if transformation fails. More...
 
template<class T >
std::optional< boost::shared_ptr< T > > transformSingle (const std::string &from_frame, const boost::shared_ptr< T > &what, const std::string &to_frame, const ros::Time &time_stamp=ros::Time(0))
 Transforms a single variable to a new frame and returns it or std::nullopt if transformation fails. More...
 
template<class T >
std::optional< boost::shared_ptr< T > > transformSingle (const std::string &from_frame, const boost::shared_ptr< const T > &what, const std::string &to_frame, const ros::Time &time_stamp=ros::Time(0))
 Transforms a single variable to a new frame and returns it or std::nullopt if transformation fails. More...
 
template<class T >
std::optional< T > transform (const T &what, const geometry_msgs::TransformStamped &tf)
 Transform a variable to new frame using a particular transformation. More...
 
template<class T >
std::optional< boost::shared_ptr< T > > transform (const boost::shared_ptr< const T > &what, const geometry_msgs::TransformStamped &tf)
 Transform a variable to new frame using a particular transformation. More...
 
template<class T >
std::optional< boost::shared_ptr< T > > transform (const boost::shared_ptr< T > &what, const geometry_msgs::TransformStamped &tf)
 Transform a variable to new frame using a particular transformation. More...
 
std::optional< Eigen::Vector3d > transformAsVector (const Eigen::Vector3d &what, const geometry_msgs::TransformStamped &tf)
 Transform an Eigen::Vector3d (interpreting it as a vector). More...
 
std::optional< Eigen::Vector3d > transformAsVector (const std::string &from_frame, const Eigen::Vector3d &what, const std::string &to_frame, const ros::Time &time_stamp=ros::Time(0))
 Transform an Eigen::Vector3d (interpreting it as a vector). More...
 
std::optional< Eigen::Vector3d > transformAsPoint (const Eigen::Vector3d &what, const geometry_msgs::TransformStamped &tf)
 Transform an Eigen::Vector3d (interpreting it as a point). More...
 
std::optional< Eigen::Vector3d > transformAsPoint (const std::string &from_frame, const Eigen::Vector3d &what, const std::string &to_frame, const ros::Time &time_stamp=ros::Time(0))
 Transform an Eigen::Vector3d (interpreting it as a point). More...
 
std::optional< geometry_msgs::TransformStamped > getTransform (const std::string &from_frame, const std::string &to_frame, const ros::Time &time_stamp=ros::Time(0))
 Obtains a transform between two frames in a given time. More...
 
std::optional< geometry_msgs::TransformStamped > getTransform (const std::string &from_frame, const ros::Time &from_stamp, const std::string &to_frame, const ros::Time &to_stamp, const std::string &fixed_frame)
 Obtains a transform between two frames in a given time. More...
 

Static Public Member Functions

static constexpr const std::string & frame_from (const geometry_msgs::TransformStamped &msg)
 A convenience function that returns the frame from which the message transforms. More...
 
static constexpr std::string & frame_from (geometry_msgs::TransformStamped &msg)
 A convenience function that returns the frame from which the message transforms. More...
 
static constexpr const std::string & frame_to (const geometry_msgs::TransformStamped &msg)
 A convenience function that returns the frame to which the message transforms. More...
 
static constexpr std::string & frame_to (geometry_msgs::TransformStamped &msg)
 A convenience function that returns the frame to which the message transforms. More...
 
static geometry_msgs::TransformStamped inverse (const geometry_msgs::TransformStamped &msg)
 A convenience function implements returns the inverse of the transform message as a one-liner. More...
 

Detailed Description

A convenience wrapper class for ROS's native TF2 API to simplify transforming of various messages.

Implements optional automatic frame prefix deduction, seamless transformation lattitude/longitude coordinates and UTM coordinates, simple transformation of MRS messages etc.

Constructor & Destructor Documentation

◆ Transformer() [1/3]

mrs_lib::Transformer::Transformer ( )

A convenience constructor that doesn't initialize anything.

This constructor is just to enable usign the Transformer as a member variable of nodelets etc. To actually initialize the class, use the alternative constructor.

Note
This constructor doesn't initialize the TF2 transform listener and all calls to the transformation-related methods of an object constructed using this method will fail.

◆ Transformer() [2/3]

mrs_lib::Transformer::Transformer ( const std::string &  node_name,
const ros::Duration &  cache_time = ros::Duration(tf2_ros::Buffer::DEFAULT_CACHE_TIME) 
)

The main constructor that actually initializes stuff.

This constructor initializes the class and the TF2 transform listener.

Parameters
node_namethe name of the node running the transformer, is used in ROS prints. If you don't care, just set it to an empty string.
cache_timeduration of the transformation buffer's cache into the past that will be kept.

◆ Transformer() [3/3]

mrs_lib::Transformer::Transformer ( const ros::NodeHandle &  nh,
const std::string &  node_name = std::string(),
const ros::Duration &  cache_time = ros::Duration(tf2_ros::Buffer::DEFAULT_CACHE_TIME) 
)

The main constructor that actually initializes stuff.

This constructor initializes the class and the TF2 transform listener.

Parameters
nhthe node handle to be used for subscribing to the transformations.
node_namethe name of the node running the transformer, is used in ROS prints. If you don't care, just set it to an empty string.
cache_timeduration of the transformation buffer's cache into the past that will be kept.

Member Function Documentation

◆ beQuiet()

void mrs_lib::Transformer::beQuiet ( const bool  quiet = true)
inline

Enable/disable some prints that may be too noisy.

Parameters
quietenables or disables quiet mode.
Note
Disabled by default.

◆ frame_from() [1/2]

static constexpr const std::string& mrs_lib::Transformer::frame_from ( const geometry_msgs::TransformStamped &  msg)
inlinestaticconstexpr

A convenience function that returns the frame from which the message transforms.

Parameters
msgthe message representing the transformation.
Returns
the frame from which the transformation in \msg transforms.

◆ frame_from() [2/2]

static constexpr std::string& mrs_lib::Transformer::frame_from ( geometry_msgs::TransformStamped &  msg)
inlinestaticconstexpr

A convenience function that returns the frame from which the message transforms.

This overload returns a reference to the string in the message representing the frame id so that it can be modified.

Parameters
msgthe message representing the transformation.
Returns
a reference to the field in the message containing the string with the frame id from which the transformation in \msg transforms.

◆ frame_to() [1/2]

static constexpr const std::string& mrs_lib::Transformer::frame_to ( const geometry_msgs::TransformStamped &  msg)
inlinestaticconstexpr

A convenience function that returns the frame to which the message transforms.

Parameters
msgthe message representing the transformation.
Returns
the frame to which the transformation in \msg transforms.

◆ frame_to() [2/2]

static constexpr std::string& mrs_lib::Transformer::frame_to ( geometry_msgs::TransformStamped &  msg)
inlinestaticconstexpr

A convenience function that returns the frame to which the message transforms.

This overload returns a reference to the string in the message representing the frame id so that it can be modified.

Parameters
msgthe message representing the transformation.
Returns
a reference to the field in the message containing the string with the frame id to which the transformation in \msg transforms.

◆ getTransform() [1/2]

std::optional< geometry_msgs::TransformStamped > mrs_lib::Transformer::getTransform ( const std::string &  from_frame,
const ros::Time &  from_stamp,
const std::string &  to_frame,
const ros::Time &  to_stamp,
const std::string &  fixed_frame 
)

Obtains a transform between two frames in a given time.

This overload enables the user to select a different time of the source frame and the target frame.

Parameters
from_frameThe original frame of the transformation.
from_stampThe time at which the original frame should be evaluated. (0 will get the latest)
to_frameThe target frame of the transformation.
to_stampThe time to which the data should be transformed. (0 will get the latest)
fixed_frameThe frame that may be assumed constant in time (the "world" frame).
Returns
std::nullopt if failed, optional containing the requested transformation otherwise.
Note
An example of when this API may be useful is explained here: http://wiki.ros.org/tf2/Tutorials/Time%20travel%20with%20tf2%20%28C%2B%2B%29

◆ getTransform() [2/2]

std::optional< geometry_msgs::TransformStamped > mrs_lib::Transformer::getTransform ( const std::string &  from_frame,
const std::string &  to_frame,
const ros::Time &  time_stamp = ros::Time(0) 
)

Obtains a transform between two frames in a given time.

Parameters
from_frameThe original frame of the transformation.
to_frameThe target frame of the transformation.
time_stampThe time stamp of the transformation. (0 will get the latest)
Returns
std::nullopt if failed, optional containing the requested transformation otherwise.

◆ inverse()

static geometry_msgs::TransformStamped mrs_lib::Transformer::inverse ( const geometry_msgs::TransformStamped &  msg)
inlinestatic

A convenience function implements returns the inverse of the transform message as a one-liner.

Parameters
msgthe message representing the transformation.
Returns
a new message representing an inverse of the original transformation.

◆ operator=()

Transformer & mrs_lib::Transformer::operator= ( Transformer &&  other)

A convenience move assignment operator.

This operator moves all data from the object that is being assigned from, invalidating it.

Parameters
otherthe object to assign from. It will be invalid after this method returns.
Returns
a reference to the object being assigned to.

◆ resolveFrame()

std::string mrs_lib::Transformer::resolveFrame ( const std::string &  frame_id)
inline

Deduce the full frame ID from a shortened or empty string using current default prefix and default frame rules.

Example assuming default prefix is "uav1" and default frame is "uav1/gps_origin": "" -> "uav1/gps_origin" "local_origin" -> "uav1/local_origin"

Parameters
frame_idThe frame ID to be resolved.
Returns
The resolved frame ID.

◆ retryLookupNewest()

void mrs_lib::Transformer::retryLookupNewest ( const bool  retry = true)
inline

Enable/disable retry of a failed transform lookup with ros::Time(0).

If enabled, a failed transform lookup will be retried. The new try will ignore the requested timestamp and will attempt to fetch the latest transformation between the two frames.

Note
Disabled by default.
Parameters
retryenables or disables retry.

◆ setDefaultFrame()

void mrs_lib::Transformer::setDefaultFrame ( const std::string &  frame_id)
inline

Sets the default frame ID to be used instead of any empty frame ID.

If you call e.g. the transform() method with a message that has an empty header.frame_id field, this value will be used instead.

Parameters
frame_idthe default frame ID. Use an empty string to disable default frame ID deduction.
Note
Disabled by default.

◆ setDefaultPrefix()

void mrs_lib::Transformer::setDefaultPrefix ( const std::string &  prefix)
inline

Sets the default frame ID prefix to be used if no prefix is present in the frame.

If you call any method with a frame ID that doesn't begin with this string, it will be automatically prefixed including a forward slash between the prefix and raw frame ID. The forward slash should therefore not be included in the prefix.

Example frame ID resolution assuming default prefix is "uav1": "local_origin" -> "uav1/local_origin"

Parameters
prefixthe default frame ID prefix (without the forward slash at the end). Use an empty string to disable default frame ID prefixing.
Note
Disabled by default. The prefix will be applied as a namespace (with a forward slash between the prefix and raw frame ID).

◆ setLatLon()

void mrs_lib::Transformer::setLatLon ( const double  lat,
const double  lon 
)

Sets the curret lattitude and longitude for UTM zone calculation.

The Transformer uses this to deduce the current UTM zone used for transforming stuff to latlon_origin.

Parameters
latthe latitude in degrees.
lonthe longitude in degrees.
Note
Any transformation to latlon_origin will fail if this function is not called first!

◆ setLookupTimeout()

void mrs_lib::Transformer::setLookupTimeout ( const ros::Duration  timeout = ros::Duration(0))
inline

Set a timeout for transform lookup.

The transform lookup operation will block up to this duration if the transformation is not available immediately.

Note
Disabled by default.
Parameters
timeoutthe lookup timeout. Set to zero to disable blocking.

◆ transform() [1/3]

template<class T >
std::optional<boost::shared_ptr<T> > mrs_lib::Transformer::transform ( const boost::shared_ptr< const T > &  what,
const geometry_msgs::TransformStamped &  tf 
)
inline

Transform a variable to new frame using a particular transformation.

A convenience override for shared pointers to const.

Parameters
tfThe transformation to be used.
whatThe object to be transformed.
Returns
std::nullopt if failed, optional containing the transformed object otherwise.

◆ transform() [2/3]

template<class T >
std::optional<boost::shared_ptr<T> > mrs_lib::Transformer::transform ( const boost::shared_ptr< T > &  what,
const geometry_msgs::TransformStamped &  tf 
)
inline

Transform a variable to new frame using a particular transformation.

A convenience override for shared pointers.

Parameters
tfThe transformation to be used.
whatThe object to be transformed.
Returns
std::nullopt if failed, optional containing the transformed object otherwise.

◆ transform() [3/3]

template<class T >
std::optional< T > mrs_lib::Transformer::transform ( const T &  what,
const geometry_msgs::TransformStamped &  tf 
)

Transform a variable to new frame using a particular transformation.

Parameters
tfThe transformation to be used.
whatThe object to be transformed.
Returns
std::nullopt if failed, optional containing the transformed object otherwise.

◆ transformAsPoint() [1/2]

std::optional< Eigen::Vector3d > mrs_lib::Transformer::transformAsPoint ( const Eigen::Vector3d &  what,
const geometry_msgs::TransformStamped &  tf 
)

Transform an Eigen::Vector3d (interpreting it as a point).

Both the rotation and translation will be applied to the variable.

Parameters
tfThe transformation to be used.
whatThe object to be transformed.
Returns
std::nullopt if failed, optional containing the transformed object otherwise.

◆ transformAsPoint() [2/2]

std::optional< Eigen::Vector3d > mrs_lib::Transformer::transformAsPoint ( const std::string &  from_frame,
const Eigen::Vector3d &  what,
const std::string &  to_frame,
const ros::Time &  time_stamp = ros::Time(0) 
)

Transform an Eigen::Vector3d (interpreting it as a point).

Both the rotation and translation will be applied to the variable.

Parameters
from_frameThe current frame of what.
whatThe object to be transformed.
to_frameThe desired frame of what.
time_stampFrom which time to take the transformation (use ros::Time(0) for the latest time).
Returns
std::nullopt if failed, optional containing the transformed object otherwise.

◆ transformAsVector() [1/2]

std::optional< Eigen::Vector3d > mrs_lib::Transformer::transformAsVector ( const Eigen::Vector3d &  what,
const geometry_msgs::TransformStamped &  tf 
)

Transform an Eigen::Vector3d (interpreting it as a vector).

Only the rotation will be applied to the variable.

Parameters
tfThe transformation to be used.
whatThe vector to be transformed.
Returns
std::nullopt if failed, optional containing the transformed object otherwise.

◆ transformAsVector() [2/2]

std::optional< Eigen::Vector3d > mrs_lib::Transformer::transformAsVector ( const std::string &  from_frame,
const Eigen::Vector3d &  what,
const std::string &  to_frame,
const ros::Time &  time_stamp = ros::Time(0) 
)

Transform an Eigen::Vector3d (interpreting it as a vector).

Only the rotation will be applied to the variable.

Parameters
from_frameThe current frame of what.
whatThe vector to be transformed.
to_frameThe desired frame of what.
time_stampFrom which time to take the transformation (use ros::Time(0) for the latest time).
Returns
std::nullopt if failed, optional containing the transformed object otherwise.

◆ transformSingle() [1/6]

template<class T >
std::optional<boost::shared_ptr<T> > mrs_lib::Transformer::transformSingle ( const boost::shared_ptr< const T > &  what,
const std::string &  to_frame 
)
inline

Transforms a single variable to a new frame.

A convenience override for shared pointers to const.

Parameters
whatThe object to be transformed.
to_frameThe target fram ID.
Returns
std::nullopt if failed, optional containing the transformed object otherwise.

◆ transformSingle() [2/6]

template<class T >
std::optional<boost::shared_ptr<T> > mrs_lib::Transformer::transformSingle ( const boost::shared_ptr< T > &  what,
const std::string &  to_frame 
)
inline

Transforms a single variable to a new frame.

A convenience override for shared pointers.

Parameters
whatThe object to be transformed.
to_frameThe target fram ID.
Returns
std::nullopt if failed, optional containing the transformed object otherwise.

◆ transformSingle() [3/6]

template<class T >
std::optional<boost::shared_ptr<T> > mrs_lib::Transformer::transformSingle ( const std::string &  from_frame,
const boost::shared_ptr< const T > &  what,
const std::string &  to_frame,
const ros::Time &  time_stamp = ros::Time(0) 
)
inline

Transforms a single variable to a new frame and returns it or std::nullopt if transformation fails.

A convenience overload for shared pointers to const headerless variables.

Parameters
from_framethe original target frame ID.
whatthe object to be transformed.
to_framethe target frame ID.
time_stampthe time of the transformation.
Returns
std::nullopt if failed, optional containing the transformed object otherwise.

◆ transformSingle() [4/6]

template<class T >
std::optional<boost::shared_ptr<T> > mrs_lib::Transformer::transformSingle ( const std::string &  from_frame,
const boost::shared_ptr< T > &  what,
const std::string &  to_frame,
const ros::Time &  time_stamp = ros::Time(0) 
)
inline

Transforms a single variable to a new frame and returns it or std::nullopt if transformation fails.

A convenience overload for shared pointers to headerless variables.

Parameters
from_framethe original target frame ID.
whatthe object to be transformed.
to_framethe target frame ID.
time_stampthe time of the transformation.
Returns
std::nullopt if failed, optional containing the transformed object otherwise.

◆ transformSingle() [5/6]

template<class T >
std::optional< T > mrs_lib::Transformer::transformSingle ( const std::string &  from_frame,
const T &  what,
const std::string &  to_frame,
const ros::Time &  time_stamp = ros::Time(0) 
)

Transforms a single variable to a new frame and returns it or std::nullopt if transformation fails.

A convenience overload for headerless variables.

Parameters
from_framethe original target frame ID.
whatthe object to be transformed.
to_framethe target frame ID.
time_stampthe time of the transformation.
Returns
std::nullopt if failed, optional containing the transformed object otherwise.

◆ transformSingle() [6/6]

template<class T >
std::optional< T > mrs_lib::Transformer::transformSingle ( const T &  what,
const std::string &  to_frame 
)

Transforms a single variable to a new frame and returns it or std::nullopt if transformation fails.

Parameters
whatthe object to be transformed.
to_framethe target frame ID.
Returns
std::nullopt if failed, optional containing the transformed object otherwise.

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