ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

[ROS2]Are there any examples of tf2 broadcast or listener

asked 2019-11-25 08:16:21 -0500

Sol gravatar image

Hello comrades, I`m just trying to get odometry from t265 from realsense2_lib examples. After compiling and running this code below, I get that target frame does not exist.

Thanks in advance.

#include <math.h>
#include <iostream>
#include <chrono>
#include "std_msgs/msg/string.hpp"
#include "rclcpp/rclcpp.hpp"
#include <rclcpp/time_source.hpp>
#include "geometry_msgs/msg/pose_stamped.h"
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <tf2_ros/buffer_interface.h>
#include <tf2_ros/visibility_control.h>
#include <tf2/buffer_core.h>
#include <tf2/time.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <rclcpp/rclcpp.hpp>
#include <geometry_msgs/msg/transform_stamped.h>
/* We do not recommend this style anymore, because composition of multiple
 * nodes in the same executable is not possible. Please see one of the subclass
 * examples for the "new" recommended styles. This example is only included
 * for completeness because it is similar to "classic" standalone ROS nodes. */

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  auto node = rclcpp::Node::make_shared("tf_pub");
  auto publisher = node->create_publisher<geometry_msgs::msg::PoseStamped>("tf_pub", 10);

  //printf("TimePoint %d",tp);
//  std::shared_ptr<rclcpp::Clock> clock_ptr;
  rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
  rclcpp::TimeSource timesource;
  timesource.attachClock(clock);

//  tf2_ros::Buffer tfBuffer(clock_ptr);
  std::unique_ptr<tf2_ros::Buffer> buffer = nullptr;




  tf2::Transform transform_;
  transform_.setIdentity();
  buffer = std::make_unique<tf2_ros::Buffer>(clock);

  geometry_msgs::msg::PoseStamped message;
  rclcpp::WallRate loop_rate(500ms);

  while (rclcpp::ok()) {

    try {

        geometry_msgs::msg::TransformStamped transformStamped = buffer->lookupTransform("odom_frame", "camera_link", tf2::TimePointZero);
        message.pose.position.x = transformStamped.transform.translation.x;
        message.pose.position.y = transformStamped.transform.translation.y;
        RCLCPP_INFO(node->get_logger(), "Publishing: '%s'", message.pose);
        publisher->publish(message);
    }
    catch (tf2::TransformException & ex) {
          RCLCPP_ERROR(node->get_logger(), "StaticLayer: %s", ex.what());
    }


    rclcpp::spin_some(node);
    loop_rate.sleep();
  }
  rclcpp::shutdown();
  return 0;
}
edit retag flag offensive close merge delete

Comments

This probably doesn't help, but we did push a big set of changes to the documentation and how to's for Eloquent. Check them out here.

kscottz gravatar image kscottz  ( 2019-11-25 12:38:36 -0500 )edit

The code looks okay to me. Are you sure that the target frame ("odom_frame") does indeed exist? You can confirm by running ros2 run tf2_ros tf2_monitor odom_frame camera_link.

jacobperron gravatar image jacobperron  ( 2019-11-27 15:36:55 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
6

answered 2020-06-20 15:59:13 -0500

georgiy gravatar image

Hi! I had same trouble with lookup_transform. I'm found solution in tf_echo source code. You need add tf2_ros::TransformListener and init it with tf2_ros::Buffer:

std::unique_ptr<tf2_ros::Buffer> buffer = std::make_unique<tf2_ros::Buffer>(node->get_clock());
std::shared_ptr<tf2_ros::TransformListener> transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);

Now when I call lookupTransform() it works as expected. I hope this helps you.

edit flag offensive delete link more
3

answered 2019-11-27 15:55:17 -0500

jacobperron gravatar image

Unfortunately, we don't have any nice, succinct examples, but I think it would be good if we port the tf2 tutorials to ROS 2.

I know RViz makes use of tf2_ros::TransformListener as part of the TFWrapper class.

The AmclNode class also uses tf2_ros::TransformListener as well as tf2_ros::TransformBroadcaster. I'm sure there's other instances of them being used in the wild that others might be able to point you to.

edit flag offensive delete link more

Comments

From the description of tf2_ros I understand that this package is for ROS and roscpp, not ROS2. So why is it being used with ROS2? Isn't that some abomination?

Almost gravatar image Almost  ( 2020-07-15 06:52:28 -0500 )edit

I think "port" is a better word than "abomination", haha.

tf2_ros is a set of ROS bindings for the tf2 library. Since the ROS 1 implementation proved very useful to robot makers, there exists a ROS 2 port. Since the client libraries for ROS 1 and ROS 2 are significantly different (roscpp vs rclcpp), we can expect the respective tf2_ros bindings to look different. This is why we currently maintain a separate ROS 2 version of tf2_ros, as the implementation diverges from the original.

jacobperron gravatar image jacobperron  ( 2020-07-15 12:57:42 -0500 )edit

I understand why you would separate some interface to make the code maintenance easier. But I still don't see why it is not all in tf2:: namespace, or always tf2:: for ros2 and tf2_ros for ros. Now I even see ros2 code that uses both. I am sorry, I don't know the architecture and it just doesn't make sense to me.

Almost gravatar image Almost  ( 2020-07-15 16:00:35 -0500 )edit

The differences in namespaces are coming from different packages in the geometry2 repository. There is a package named tf2, which is ROS-agnostic. ROS-specific bindings/features are provided by a different package tf2_ros (which depends on tf2). The different namespaces, tf2:: and tf2_ros::, are named after the package where the API is coming from. To clarify, this is the same package/namespace structure used in both ROS 1 and ROS 2.

jacobperron gravatar image jacobperron  ( 2020-07-15 16:36:46 -0500 )edit

So, in theory, a single version of tf2 could be maintained and used by multiple versions of tf2_ros (but I think for historical reasons and convenience, we have separate versions of all geometry2 packages for ROS 1 and ROS 2).

jacobperron gravatar image jacobperron  ( 2020-07-15 16:39:33 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2019-11-25 08:16:21 -0500

Seen: 3,574 times

Last updated: Jun 20 '20