Function nav2_util::getTransform(const std::string&, const rclcpp::Time&, const std::string&, const rclcpp::Time&, const std::string&, const tf2::Duration&, const std::shared_ptr<tf2_ros::Buffer>, tf2::Transform&)

Function Documentation

bool nav2_util::getTransform(const std::string &source_frame_id, const rclcpp::Time &source_time, const std::string &target_frame_id, const rclcpp::Time &target_time, const std::string &fixed_frame_id, const tf2::Duration &transform_tolerance, const std::shared_ptr<tf2_ros::Buffer> tf_buffer, tf2::Transform &tf2_transform)

Obtains a transform from source_frame_id at source_time -> to target_frame_id at target_time time.

Parameters:
  • source_frame_id – Source frame ID to convert from

  • source_time – Source timestamp to convert from

  • target_frame_id – Target frame ID to convert to

  • target_time – Current node time to interpolate to

  • fixed_frame_id – The frame in which to assume the transform is constant in time

  • transform_tolerance – Transform tolerance

  • tf_buffer – TF buffer to use for the transformation

  • tf_transform – Output source->target transform

Returns:

True if got correct transform, otherwise false