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

inline explicit TfHandler(as2::Node *_node)

Construct a new Tf Handler object.

Parameters:

_node – an as2::Node object

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

Get the tf buffer object.

Returns:

std::shared_ptr<tf2_ros::Buffer>

geometry_msgs::msg::PointStamped convert(const geometry_msgs::msg::PointStamped &_point, const std::string &target_frame, const std::chrono::nanoseconds timeout = TF_TIMEOUT)

convert a geometry_msgs::msg::PointStamped from one frame to another

Parameters:
  • _point – a geometry_msgs::msg::PointStamped

  • _target_frame – the target frame

Throws:

tf2::TransformException – if the transform is not available

Returns:

geometry_msgs::msg::PointStamped in the target frame

geometry_msgs::msg::PoseStamped convert(const geometry_msgs::msg::PoseStamped &_pose, const std::string &target_frame, const std::chrono::nanoseconds timeout = TF_TIMEOUT)

convert a geometry_msgs::msg::PoseStamped from one frame to another

Parameters:
  • _pose – a geometry_msgs::msg::PoseStamped

  • _target_frame – the target frame

Throws:

tf2::TransformException – if the transform is not available

Returns:

geometry_msgs::msg::PoseStamped in the target frame

geometry_msgs::msg::TwistStamped convert(const geometry_msgs::msg::TwistStamped &_twist, const std::string &target_frame, const std::chrono::nanoseconds timeout = TF_TIMEOUT)

convert a geometry_msgs::msg::TwistStamped from one frame to another (only the linear part will be converted, the angular part will be maintained)

Parameters:
  • _twist – a geometry_msgs::msg::TwistStamped

  • _target_frame – the target frame

Throws:

tf2::TransformException – if the transform is not available

Returns:

geometry_msgs::msg::TwistStamped in the target frame

geometry_msgs::msg::Vector3Stamped convert(const geometry_msgs::msg::Vector3Stamped &_vector, const std::string &target_frame, const std::chrono::nanoseconds timeout = TF_TIMEOUT)

convert a geometry_msgs::msg::Vector3Stamped from one frame to another

Parameters:
  • _vector – a geometry_msgs::msg::Vector3Stamped

  • _target_frame – the target frame

Throws:

tf2::TransformException – if the transform is not available

Returns:

geometry_msgs::msg::Vector3Stamped in the target frame

nav_msgs::msg::Path convert(const nav_msgs::msg::Path &_path, const std::string &target_frame, const std::chrono::nanoseconds timeout = TF_TIMEOUT)

convert a nav_msgs::msg::Path from one frame to another

Parameters:
  • _path – a nav_msgs::msg::Path

  • _target_frame – the target frame

Throws:

tf2::TransformException – if the transform is not available

Returns:

nav_msgs::msg::Path in the target frame

geometry_msgs::msg::QuaternionStamped convert(const geometry_msgs::msg::QuaternionStamped &_quaternion, const std::string &target_frame, const std::chrono::nanoseconds timeout = TF_TIMEOUT)

convert a geometry_msgs::msg::QuaternionStamped from one frame to another

Parameters:
  • _quaternion – a geometry_msgs::msg::QuaternionStamped

  • _target_frame – the target frame

Throws:

tf2::TransformException – if the transform is not available

Returns:

geometry_msgs::msg::QuaternionStamped in the target frame

geometry_msgs::msg::PoseStamped getPoseStamped(const std::string &target_frame, const std::string &source_frame, const rclcpp::Time &time, const std::chrono::nanoseconds timeout = TF_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

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, const std::chrono::nanoseconds timeout = TF_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

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 = tf2::TimePointZero, const std::chrono::nanoseconds timeout = TF_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

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 = TF_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

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

bool tryConvert(geometry_msgs::msg::PointStamped &_point, const std::string &_target_frame, const std::chrono::nanoseconds timeout = TF_TIMEOUT)

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

Parameters:
  • point – a geometry_msgs::msg::PointStamped 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

bool tryConvert(geometry_msgs::msg::PoseStamped &_pose, const std::string &_target_frame, const std::chrono::nanoseconds timeout = TF_TIMEOUT)

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

Parameters:
  • point – a geometry_msgs::msg::PoseStamped 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

bool tryConvert(geometry_msgs::msg::TwistStamped &_twist, const std::string &_target_frame, const std::chrono::nanoseconds timeout = TF_TIMEOUT)

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

Parameters:
  • point – a geometry_msgs::msg::TwistStamped 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

bool tryConvert(geometry_msgs::msg::QuaternionStamped &_quaternion, const std::string &_target_frame, const std::chrono::nanoseconds timeout = TF_TIMEOUT)

Get the pose and twist of the UAV at the given twist timestamp, in the given frames.

Parameters:
  • _twist

  • _twist_target_frame

  • _pose_target_frame

  • _pose_source_frame

  • _timeout

Returns:

std::pair<geometry_msgs::msg::PoseStamped, geometry_msgs::msg::TwistStamped>

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 = TF_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

Throws:

tf2::TransformException – if the transform is not available

Returns:

bool true if the conversion was successful