Class TransformManager

Class Documentation

class TransformManager

Wrapper around tf::TransformListener to support non-TF transforms

TransformManager wraps tf::TransformListener and provides a similar interface to get Transforms between TF frames, UTM, and WGS84.

TransformManager uses PluginLib to load all of the swri_transform_util::Transformer plugins it can find. To extend the functionality of TranformManager, create a new swri_transform_util::Transformer plugin that implements the desired transform.

Public Functions

explicit TransformManager(rclcpp::Node::SharedPtr node, std::shared_ptr<tf2_ros::Buffer> tf_buffer = nullptr)
void Initialize(std::shared_ptr<tf2_ros::Buffer> tf_buffer)

Initialize the TransformManager with a tf2_ros::Buffer

The TransformManager must be initialized before it can be used.

Parameters:

tf_buffer – A shared pointer to a tf2_ros::Buffer that the Transformer wraps.

bool GetTransform(const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, Transform &transform) const

Get the Transform between two frames at a specified time

This function gets the transform from source_frame to target_frame at the specified time and returns it as a swri_transform_util::Transform.

The frame IDs for target_frame and source_frame can be either a frame id in the current TF tree or one of the special frames /UTM or /WGS84.

This method waits for a 0.1 second timeout if the transform is not immediately available.

Parameters:
  • target_frame[in] The TF (or special) frame id of the target

  • source_frame[in] The TF (or special) frame id of the source

  • time[in] The requested time to request the transform. tf2::TimePoint(0) means the most recent time for which a valid transform is available.

  • transform[out] The transform requested. If the function returns false, transform is not mutated.

Returns:

True if the transform is supported and available at the requested time. False otherwise.

bool GetTransform(const std::string &target_frame, const std::string &source_frame, const rclcpp::Time &time, Transform &transform) const

Get the Transform between two frames at a specified time

This function gets the transform from source_frame to target_frame at the specified time and returns it as a swri_transform_util::Transform.

The frame IDs for target_frame and source_frame can be either a frame id in the current TF tree or one of the special frames /UTM or /WGS84.

This method waits for a 0.1 second timeout if the transform is not immediately available.

Parameters:
  • target_frame[in] The TF (or special) frame id of the target

  • source_frame[in] The TF (or special) frame id of the source

  • time[in] The requested time to request the transform. rclcpp::Time(0, 0, RCL_ROS_TIME) means the most recent time for which a valid transform is available.

  • transform[out] The transform requested. If the function returns false, transform is not mutated.

Returns:

True if the transform is supported and available at the requested time. False otherwise.

bool GetTransform(const std::string &target_frame, const std::string &source_frame, Transform &transform) const

Get the most recent Transform between two frames

This function gets the most recent transform from source_frame to target_frame and returns it as a swri_transform_util::Transform.

The frame IDs for target_frame and source_frame can be either a frame id in the current TF tree or one of the special frames /UTM or /WGS84.

This method waits for a 0.1 second timeout if the transform is not immediately available.

Parameters:
  • target_frame[in] The TF (or special) frame id of the target

  • source_frame[in] The TF (or special) frame id of the source

  • transform[out] The transform requested. If the function returns false, transform is not mutated

Returns:

True if the transform is supported and available. False otherwise.

bool SupportsTransform(const std::string &target_frame, const std::string &source_frame) const

Check whether the TransformManager supports transforms from source_frame to target_frame

Supporting a transform does not imply that the TransformManager supports the inverse.

Parameters:
  • target_frame[in] The TF (or special) frame id of the target

  • source_frame[in] The TF (or special) frame id of the source

Returns:

True if the transform is supported. False if the transform is unsupported.

bool GetTransform(const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, geometry_msgs::msg::TransformStamped &transform) const

Get the tf::Transform between two frames at a specified time

This function is a thin wrapper around the tf::TransformListener. Only TF frames are supported.

This method waits for a 0.1 second timeout if the transform is not immediately available.

Parameters:
  • target_frame[in] The TF frame id of the target

  • source_frame[in] The TF frame id of the source

  • time[in] The requested time to request the transform. tf2::TimePoint(0) means the most recent time for which a valid transform is available.

  • transform[out] The transform requested. If the function returns false, transform is not mutated.

Returns:

True if the transform is available at the requested time. False otherwise.

bool GetTransform(const std::string &target_frame, const std::string &source_frame, geometry_msgs::msg::TransformStamped &transform) const

Get the most recent tf::Transform between two frames

This function is a thin wrapper around the tf::TransformListener. Only TF frames are supported.

This method waits for a 0.1 second timeout if the transform is not immediately available.

Parameters:
  • target_frame[in] The TF frame id of the target

  • source_frame[in] The TF frame id of the source

  • transform[out] The transform requested. If the function returns false, transform is not mutated.

Returns:

True if the transform is available. False otherwise.

bool GetTransform(const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, const tf2::Duration &timeout, geometry_msgs::msg::TransformStamped &transform) const

Get the tf::Transform between two frames at a specified time

This function is a thin wrapper around the tf::TransformListener. Only TF frames are supported.

If the frames are not immediately available, this method will wait for the frames for the specified timeout period.

Parameters:
  • target_frame[in] The TF frame id of the target

  • source_frame[in] The TF frame id of the source

  • time[in] The requested time to request the transform. tf2::TimePoint(0) means the most recent time for which a valid transform is available.

  • timeout[in] How long to wait for the transform to be available before returning False.

  • transform[out] The transform requested. If the function returns false, transform is not mutated.

Returns:

True if the transform is available at the requested time. False otherwise.

bool GetTransform(const std::string &target_frame, const std::string &source_frame, const tf2::Duration &timeout, geometry_msgs::msg::TransformStamped &transform) const

Get the most recent tf::Transform between two frames

This function is a thin wrapper around the tf::TransformListener. Only TF frames are supported.

If the frames are not immediately available, this method will wait for the frames for the specified timeout period.

Parameters:
  • target_frame[in] The TF frame id of the target

  • source_frame[in] The TF frame id of the source

  • timeout[in] How long to wait for the transform to be available before returning False.

  • transform[out] The transform requested. If the function returns false, transform is not mutated.

Returns:

True if the transform is available. False otherwise.

const LocalXyWgs84UtilPtr &LocalXyUtil() const

LocalXyUtil exposes the private instance of LocalXyWgs84Util.

Returns: