![]()  | 
  
    mrs_lib
    
   Various reusable classes, functions and utilities for use in MRS projects 
   | 
 
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.   | |
| Transformer (const rclcpp::Node::SharedPtr &node) | |
| The main constructor that actually initializes stuff.   | |
| Transformer (const rclcpp::Node::SharedPtr &node, const rclcpp::Clock::SharedPtr &clock, const rclcpp::Duration &cache_time=rclcpp::Duration(tf2::BUFFER_CORE_DEFAULT_CACHE_TIME), const rclcpp::QoS &qos=rclcpp::ServicesQoS()) | |
| The main constructor that actually initializes stuff.   | |
| Transformer & | operator= (Transformer &&other) | 
| A convenience move assignment operator.   | |
| void | setDefaultFrame (const std::string &frame_id) | 
| Sets the default frame ID to be used instead of any empty frame ID.   | |
| void | setDefaultPrefix (const std::string &prefix) | 
| Sets the default frame ID prefix to be used if no prefix is present in the frame.   | |
| void | setLatLon (const double lat, const double lon) | 
| Sets the curret lattitude and longitude for UTM zone calculation.   | |
| void | setLookupTimeout (const rclcpp::Duration timeout=rclcpp::Duration(0, 0)) | 
| Set a timeout for transform lookup.   | |
| void | retryLookupNewest (const bool retry=true) | 
Enable/disable retry of a failed transform lookup with rclcpp::Time(0).   | |
| void | beQuiet (const bool quiet=true) | 
| Enable/disable some prints that may be too noisy.   | |
| 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.   | |
| 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.   | |
| template<class T > | |
| std::optional< std::shared_ptr< T > > | transformSingle (const std::shared_ptr< T > &what, const std::string &to_frame) | 
| Transforms a single variable to a new frame.   | |
| template<class T > | |
| std::optional< std::shared_ptr< T > > | transformSingle (const std::shared_ptr< const T > &what, const std::string &to_frame) | 
| Transforms a single variable to a new frame.   | |
| template<class T > | |
| std::optional< T > | transformSingle (const std::string &from_frame, const T &what, const std::string &to_frame, const rclcpp::Time &time_stamp=rclcpp::Time(0)) | 
Transforms a single variable to a new frame and returns it or std::nullopt if transformation fails.   | |
| template<class T > | |
| std::optional< std::shared_ptr< T > > | transformSingle (const std::string &from_frame, const std::shared_ptr< T > &what, const std::string &to_frame, const rclcpp::Time &time_stamp=rclcpp::Time(0)) | 
Transforms a single variable to a new frame and returns it or std::nullopt if transformation fails.   | |
| template<class T > | |
| std::optional< std::shared_ptr< T > > | transformSingle (const std::string &from_frame, const std::shared_ptr< const T > &what, const std::string &to_frame, const rclcpp::Time &time_stamp=rclcpp::Time(0)) | 
Transforms a single variable to a new frame and returns it or std::nullopt if transformation fails.   | |
| template<class T > | |
| std::optional< T > | transform (const T &what, const geometry_msgs::msg::TransformStamped &tf) | 
| Transform a variable to new frame using a particular transformation.   | |
| template<class T > | |
| std::optional< std::shared_ptr< T > > | transform (const std::shared_ptr< const T > &what, const geometry_msgs::msg::TransformStamped &tf) | 
| Transform a variable to new frame using a particular transformation.   | |
| template<class T > | |
| std::optional< std::shared_ptr< T > > | transform (const std::shared_ptr< T > &what, const geometry_msgs::msg::TransformStamped &tf) | 
| Transform a variable to new frame using a particular transformation.   | |
| std::optional< Eigen::Vector3d > | transformAsVector (const Eigen::Vector3d &what, const geometry_msgs::msg::TransformStamped &tf) | 
| Transform an Eigen::Vector3d (interpreting it as a vector).   | |
| std::optional< Eigen::Vector3d > | transformAsVector (const std::string &from_frame, const Eigen::Vector3d &what, const std::string &to_frame, const rclcpp::Time &time_stamp=rclcpp::Time(0)) | 
| Transform an Eigen::Vector3d (interpreting it as a vector).   | |
| std::optional< Eigen::Vector3d > | transformAsPoint (const Eigen::Vector3d &what, const geometry_msgs::msg::TransformStamped &tf) | 
| Transform an Eigen::Vector3d (interpreting it as a point).   | |
| std::optional< Eigen::Vector3d > | transformAsPoint (const std::string &from_frame, const Eigen::Vector3d &what, const std::string &to_frame, const rclcpp::Time &time_stamp=rclcpp::Time(0)) | 
| Transform an Eigen::Vector3d (interpreting it as a point).   | |
| std::optional< geometry_msgs::msg::TransformStamped > | getTransform (const std::string &from_frame, const std::string &to_frame, const rclcpp::Time &time_stamp=rclcpp::Time(0)) | 
| Obtains a transform between two frames in a given time.   | |
| std::optional< geometry_msgs::msg::TransformStamped > | getTransform (const std::string &from_frame, const rclcpp::Time &from_stamp, const std::string &to_frame, const rclcpp::Time &to_stamp, const std::string &fixed_frame) | 
| Obtains a transform between two frames in a given time.   | |
Static Public Member Functions | |
| static constexpr const std::string & | frame_from (const geometry_msgs::msg::TransformStamped &msg) | 
| A convenience function that returns the frame from which the message transforms.   | |
| static constexpr std::string & | frame_from (geometry_msgs::msg::TransformStamped &msg) | 
| A convenience function that returns the frame from which the message transforms.   | |
| static constexpr const std::string & | frame_to (const geometry_msgs::msg::TransformStamped &msg) | 
| A convenience function that returns the frame to which the message transforms.   | |
| static constexpr std::string & | frame_to (geometry_msgs::msg::TransformStamped &msg) | 
| A convenience function that returns the frame to which the message transforms.   | |
| static geometry_msgs::msg::TransformStamped | inverse (const geometry_msgs::msg::TransformStamped &msg) | 
| A convenience function implements returns the inverse of the transform message as a one-liner.   | |
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.
| 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.
| mrs_lib::Transformer::Transformer | ( | const rclcpp::Node::SharedPtr & | node | ) | 
The main constructor that actually initializes stuff.
This constructor initializes the class and the TF2 transform listener.
| node | the node handle to be used for subscribing to the transformations. | 
| mrs_lib::Transformer::Transformer | ( | const rclcpp::Node::SharedPtr & | node, | 
| const rclcpp::Clock::SharedPtr & | clock, | ||
| const rclcpp::Duration & | cache_time = rclcpp::Duration(tf2::BUFFER_CORE_DEFAULT_CACHE_TIME),  | 
        ||
| const rclcpp::QoS & | qos = rclcpp::ServicesQoS()  | 
        ||
| ) | 
The main constructor that actually initializes stuff.
This constructor initializes the class and the TF2 transform listener.
| node | the node handle to be used for subscribing to the transformations. | 
| cache_time | duration of the transformation buffer's cache into the past that will be kept. | 
The main constructor that actually initializes stuff.
This constructor initializes the class and the TF2 transform listener.
| node | the node handle to be used for subscribing to the transformations. | 
| cache_time | duration of the transformation buffer's cache into the past that will be kept. | 
      
  | 
  inline | 
Enable/disable some prints that may be too noisy.
| quiet | enables or disables quiet mode. | 
      
  | 
  inlinestaticconstexpr | 
A convenience function that returns the frame from which the message transforms.
| msg | the message representing the transformation. | 
      
  | 
  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.
| msg | the message representing the transformation. | 
      
  | 
  inlinestaticconstexpr | 
A convenience function that returns the frame to which the message transforms.
| msg | the message representing the transformation. | 
      
  | 
  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.
| msg | the message representing the transformation. | 
| std::optional< geometry_msgs::msg::TransformStamped > mrs_lib::Transformer::getTransform | ( | const std::string & | from_frame, | 
| const rclcpp::Time & | from_stamp, | ||
| const std::string & | to_frame, | ||
| const rclcpp::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.
| from_frame | The original frame of the transformation. | 
| from_stamp | The time at which the original frame should be evaluated. (0 will get the latest) | 
| to_frame | The target frame of the transformation. | 
| to_stamp | The time to which the data should be transformed. (0 will get the latest) | 
| fixed_frame | The frame that may be assumed constant in time (the "world" frame). | 
std::nullopt if failed, optional containing the requested transformation otherwise.| std::optional< geometry_msgs::msg::TransformStamped > mrs_lib::Transformer::getTransform | ( | const std::string & | from_frame, | 
| const std::string & | to_frame, | ||
| const rclcpp::Time & | time_stamp = rclcpp::Time(0)  | 
        ||
| ) | 
Obtains a transform between two frames in a given time.
| from_frame | The original frame of the transformation. | 
| to_frame | The target frame of the transformation. | 
| time_stamp | The time stamp of the transformation. (0 will get the latest) | 
std::nullopt if failed, optional containing the requested transformation otherwise. 
      
  | 
  inlinestatic | 
A convenience function implements returns the inverse of the transform message as a one-liner.
| msg | the message representing the transformation. | 
| 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.
| other | the object to assign from. It will be invalid after this method returns. | 
      
  | 
  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"
| frame_id | The frame ID to be resolved. | 
      
  | 
  inline | 
Enable/disable retry of a failed transform lookup with rclcpp::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.
| retry | enables or disables retry. | 
      
  | 
  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.
| frame_id | the default frame ID. Use an empty string to disable default frame ID deduction. | 
      
  | 
  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"
| prefix | the default frame ID prefix (without the forward slash at the end). Use an empty string to disable default frame ID prefixing. | 
| 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.
| lat | the latitude in degrees. | 
| lon | the longitude in degrees. | 
      
  | 
  inline | 
Set a timeout for transform lookup.
The transform lookup operation will block up to this duration if the transformation is not available immediately.
| timeout | the lookup timeout. Set to zero to disable blocking. | 
      
  | 
  inline | 
Transform a variable to new frame using a particular transformation.
A convenience override for shared pointers to const.
| tf | The transformation to be used. | 
| what | The object to be transformed. | 
std::nullopt if failed, optional containing the transformed object otherwise. 
      
  | 
  inline | 
Transform a variable to new frame using a particular transformation.
A convenience override for shared pointers.
| tf | The transformation to be used. | 
| what | The object to be transformed. | 
std::nullopt if failed, optional containing the transformed object otherwise. | std::optional< T > mrs_lib::Transformer::transform | ( | const T & | what, | 
| const geometry_msgs::msg::TransformStamped & | tf | ||
| ) | 
Transform a variable to new frame using a particular transformation.
| tf | The transformation to be used. | 
| what | The object to be transformed. | 
std::nullopt if failed, optional containing the transformed object otherwise. | std::optional< Eigen::Vector3d > mrs_lib::Transformer::transformAsPoint | ( | const Eigen::Vector3d & | what, | 
| const geometry_msgs::msg::TransformStamped & | tf | ||
| ) | 
Transform an Eigen::Vector3d (interpreting it as a point).
Both the rotation and translation will be applied to the variable.
| tf | The transformation to be used. | 
| what | The object to be transformed. | 
std::nullopt if failed, optional containing the transformed object otherwise. | std::optional< Eigen::Vector3d > mrs_lib::Transformer::transformAsPoint | ( | const std::string & | from_frame, | 
| const Eigen::Vector3d & | what, | ||
| const std::string & | to_frame, | ||
| const rclcpp::Time & | time_stamp = rclcpp::Time(0)  | 
        ||
| ) | 
Transform an Eigen::Vector3d (interpreting it as a point).
Both the rotation and translation will be applied to the variable.
| from_frame | The current frame of what.  | 
| what | The object to be transformed. | 
| to_frame | The desired frame of what.  | 
| time_stamp | From which time to take the transformation (use rclcpp::Time(0) for the latest time). | 
std::nullopt if failed, optional containing the transformed object otherwise. | std::optional< Eigen::Vector3d > mrs_lib::Transformer::transformAsVector | ( | const Eigen::Vector3d & | what, | 
| const geometry_msgs::msg::TransformStamped & | tf | ||
| ) | 
Transform an Eigen::Vector3d (interpreting it as a vector).
Only the rotation will be applied to the variable.
| tf | The transformation to be used. | 
| what | The vector to be transformed. | 
std::nullopt if failed, optional containing the transformed object otherwise. | std::optional< Eigen::Vector3d > mrs_lib::Transformer::transformAsVector | ( | const std::string & | from_frame, | 
| const Eigen::Vector3d & | what, | ||
| const std::string & | to_frame, | ||
| const rclcpp::Time & | time_stamp = rclcpp::Time(0)  | 
        ||
| ) | 
Transform an Eigen::Vector3d (interpreting it as a vector).
Only the rotation will be applied to the variable.
| from_frame | The current frame of what.  | 
| what | The vector to be transformed. | 
| to_frame | The desired frame of what.  | 
| time_stamp | From which time to take the transformation (use rclcpp::Time(0) for the latest time). | 
std::nullopt if failed, optional containing the transformed object otherwise. 
      
  | 
  inline | 
Transforms a single variable to a new frame.
A convenience override for shared pointers to const.
| what | The object to be transformed. | 
| to_frame | The target fram ID. | 
std::nullopt if failed, optional containing the transformed object otherwise. 
      
  | 
  inline | 
Transforms a single variable to a new frame.
A convenience override for shared pointers.
| what | The object to be transformed. | 
| to_frame | The target fram ID. | 
std::nullopt if failed, optional containing the transformed object otherwise. 
      
  | 
  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.
| from_frame | the original target frame ID. | 
| what | the object to be transformed. | 
| to_frame | the target frame ID. | 
| time_stamp | the time of the transformation. | 
std::nullopt if failed, optional containing the transformed object otherwise. 
      
  | 
  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.
| from_frame | the original target frame ID. | 
| what | the object to be transformed. | 
| to_frame | the target frame ID. | 
| time_stamp | the time of the transformation. | 
std::nullopt if failed, optional containing the transformed object otherwise. | std::optional< T > mrs_lib::Transformer::transformSingle | ( | const std::string & | from_frame, | 
| const T & | what, | ||
| const std::string & | to_frame, | ||
| const rclcpp::Time & | time_stamp = rclcpp::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.
| from_frame | the original target frame ID. | 
| what | the object to be transformed. | 
| to_frame | the target frame ID. | 
| time_stamp | the time of the transformation. | 
std::nullopt if failed, optional containing the transformed object otherwise. | 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. 
| what | the object to be transformed. | 
| to_frame | the target frame ID. | 
std::nullopt if failed, optional containing the transformed object otherwise.