Class TfHandler

Class Documentation

class TfHandler

TfHandler class to handle the tf2_ros::Buffer and tf2_ros::TransformListener with ease inside a as2::Node class.

Public Functions

explicit TfHandler(as2::Node *_node)

Construct a new Tf Handler object.

Parameters:

_node – an as2::Node object

void setTfTimeoutThreshold(double tf_timeout_threshold)

Set the tf timeout threshold.

Parameters:

tf_timeout_threshold – double in seconds

void setTfTimeoutThreshold(const std::chrono::nanoseconds &tf_timeout_threshold)

Set the tf timeout threshold.

Parameters:

tf_timeout_threshold – std::chrono::nanoseconds

double getTfTimeoutThreshold() const

Get the tf timeout threshold.

Returns:

double

std::shared_ptr<tf2_ros::Buffer> getTfBuffer() const

Get the tf buffer object.

Returns:

std::shared_ptr<tf2_ros::Buffer>

template<typename T>
inline T convert(const T &input, const std::string &target_frame, const std::chrono::nanoseconds timeout)

convert a from one frame to another

Parameters:
  • input – variable to convert

  • target_frame – the target frame

  • timeout – the timeout for the transform

Throws:

tf2::TransformException – if the transform is not available

Returns:

variable in the target frame

template<typename T>
inline T convert(const T &input, const std::string &target_frame)

convert a from one frame to another

Parameters:
  • input – variable to convert

  • target_frame – the target frame

Throws:

tf2::TransformException – if the transform is not available

Returns:

variable in the target frame

inline geometry_msgs::msg::TwistStamped convert(const geometry_msgs::msg::TwistStamped &_twist, const std::string &target_frame, const std::chrono::nanoseconds timeout)
inline geometry_msgs::msg::TwistStamped convert(const geometry_msgs::msg::TwistStamped &twist, const std::string &target_frame)
inline nav_msgs::msg::Path convert(const nav_msgs::msg::Path &_path, const std::string &target_frame, const std::chrono::nanoseconds timeout)
inline nav_msgs::msg::Path convert(const nav_msgs::msg::Path &path, const std::string &target_frame)
geometry_msgs::msg::PoseStamped getPoseStamped(const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, const std::chrono::nanoseconds timeout)

obtain a PoseStamped from the TF_buffer

Parameters:
  • target_frame – the target frame

  • source_frame – the source frame

  • time – the time of the transform in TimePoint

  • timeout – the timeout for the transform

Throws:

tf2::TransformException – if the transform is not available

Returns:

geometry_msgs::msg::PoseStamped

geometry_msgs::msg::PoseStamped getPoseStamped(const std::string &target_frame, const std::string &source_frame, const rclcpp::Time &time, const std::chrono::nanoseconds timeout)

obtain a PoseStamped from the TF_buffer

Parameters:
  • target_frame – the target frame

  • source_frame – the source frame

  • time – the time of the transform in Ros Time

  • timeout – the timeout for the transform

Throws:

tf2::TransformException – if the transform is not available

Returns:

geometry_msgs::msg::PoseStamped

geometry_msgs::msg::PoseStamped getPoseStamped(const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time = tf2::TimePointZero)

obtain a TransformStamped from the TF_buffer

Parameters:
  • target_frame – the target frame

  • source_frame – the source frame

  • time – the time of the transform in TimePoint

Throws:

tf2::TransformException – if the transform is not available

Returns:

geometry_msgs::msg::TransformStamped

geometry_msgs::msg::PoseStamped getPoseStamped(const std::string &target_frame, const std::string &source_frame, const rclcpp::Time &time)

obtain a TransformStamped from the TF_buffer

Parameters:
  • target_frame – the target frame

  • source_frame – the source frame

  • time – the time of the transform in Ros Time

Throws:

tf2::TransformException – if the transform is not available

Returns:

geometry_msgs::msg::TransformStamped

geometry_msgs::msg::QuaternionStamped getQuaternionStamped(const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, const std::chrono::nanoseconds timeout)

obtain a TransformStamped from the TF_buffer

Parameters:
  • target_frame – the target frame

  • source_frame – the source frame

  • time – the time of the transform in TimePoint

  • timeout – the timeout for the transform

Throws:

tf2::TransformException – if the transform is not available

Returns:

geometry_msgs::msg::QuaternionStamped

geometry_msgs::msg::QuaternionStamped getQuaternionStamped(const std::string &target_frame, const std::string &source_frame, const rclcpp::Time &time, const std::chrono::nanoseconds timeout)

obtain a TransformStamped from the TF_buffer

Parameters:
  • target_frame – the target frame

  • source_frame – the source frame

  • time – the time of the transform in Ros Time

  • timeout – the timeout for the transform

Throws:

tf2::TransformException – if the transform is not available

Returns:

geometry_msgs::msg::QuaternionStamped

geometry_msgs::msg::QuaternionStamped getQuaternionStamped(const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time = tf2::TimePointZero)

obtain a TransformStamped from the TF_buffer

Parameters:
  • target_frame – the target frame

  • source_frame – the source frame

  • time – the time of the transform in TimePoint

Throws:

tf2::TransformException – if the transform is not available

Returns:

geometry_msgs::msg::QuaternionStamped

geometry_msgs::msg::QuaternionStamped getQuaternionStamped(const std::string &target_frame, const std::string &source_frame, const rclcpp::Time &time)

obtain a TransformStamped from the TF_buffer

Parameters:
  • target_frame – the target frame

  • source_frame – the source frame

  • time – the time of the transform in Ros Time

Throws:

tf2::TransformException – if the transform is not available

Returns:

geometry_msgs::msg::QuaternionStamped

geometry_msgs::msg::TransformStamped getTransform(const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time = tf2::TimePointZero)

obtain a TransformStamped from the TF_buffer

Parameters:
  • target_frame – the target frame

  • source_frame – the source frame

  • time – the time of the transform

Throws:

tf2::TransformException – if the transform is not available

Returns:

geometry_msgs::msg::QuaternionStamped

template<typename T>
inline bool tryConvert(T &input, const std::string &target_frame, const std::chrono::nanoseconds timeout)

convert input to desired frame, checking if frames are valid

Parameters:
  • input – a variable to get converted

  • target_frame – the target frame

  • timeout – the timeout for the transform

Throws:

tf2::TransformException – if the transform is not available

Returns:

bool true if the conversion was successful

template<typename T>
inline bool tryConvert(T &input, const std::string &target_frame)

convert to desired frame, checking if frames are valid

Parameters:
  • input – a variable to get converted

  • target_frame – the target frame

Throws:

tf2::TransformException – if the transform is not available

Returns:

bool true if the conversion was successful

std::pair<geometry_msgs::msg::PoseStamped, geometry_msgs::msg::TwistStamped> getState(const geometry_msgs::msg::TwistStamped &_twist, const std::string &_twist_target_frame, const std::string &_pose_target_frame, const std::string &_pose_source_frame, const std::chrono::nanoseconds timeout)

convert a geometry_msgs::msg::QuaternionStamped to desired frame, checking if frames are valid

Parameters:
  • _quaternion – a geometry_msgs::msg::QuaternionStamped to get converted

  • _target_frame – the target frame

  • _timeout – the timeout for the transform

Throws:

tf2::TransformException – if the transform is not available

Returns:

bool true if the conversion was successful

std::pair<geometry_msgs::msg::PoseStamped, geometry_msgs::msg::TwistStamped> getState(const geometry_msgs::msg::TwistStamped &_twist, const std::string &_twist_target_frame, const std::string &_pose_target_frame, const std::string &_pose_source_frame)

convert a geometry_msgs::msg::QuaternionStamped to desired frame, checking if frames are valid

Parameters:
  • _quaternion – a geometry_msgs::msg::QuaternionStamped to get converted

  • _target_frame – the target frame

Throws:

tf2::TransformException – if the transform is not available

Returns:

bool true if the conversion was successful