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

[ROS2] tf2 broadcaster

asked 2020-08-28 06:40:13 -0500

Loekes gravatar image

Hello,

I'm currently working on a differential drive robot with ROS2 and encountering some errors with a rclcpp transform broadcaster. I hope i can get some answers as to what I am doing wrong. I'm using ROS2 dashing on ubuntu 18.04.

code:

#include <memory>
#include "rclcpp/rclcpp.hpp"
#include <tf2_ros/transform_broadcaster.h>
#include "nav_msgs/msg/odometry.hpp"
#include <geometry_msgs/msg/transform_stamped.h>
#include <tf2/LinearMath/Quaternion.h>

std::shared_ptr<rclcpp::Node> node = nullptr;

void topic_callback(const nav_msgs::msg::Odometry::SharedPtr msg){
       static tf2_ros::TransformBroadcaster br;
       geometry_msgs::msg::TransformStamped transformStamped; 
       transformStamped.header.stamp = rclcpp::Time();
       transformStamped.header.frame_id = "odom";
       transformStamped.child_frame_id = "base_link";
       transformStamped.transform.translation.x = msg->pose.pose.position.x;
       transformStamped.transform.translation.y = msg->pose.pose.position.y;
       transformStamped.transform.translation.z = 0.0;
       transformStamped.transform.rotation.x = 0.0;
       transformStamped.transform.rotation.y = 0.0;
       transformStamped.transform.rotation.z = msg->pose.pose.orientation.z;
       transformStamped.transform.rotation.w = msg->pose.pose.orientation.w;
           broadcaster.sendTransform(transformStamped);
        }

    int main(int argc, char * argv[])
    {
      rclcpp::init(argc, argv);

      auto node = std::make_shared<rclcpp::Node>("tf_broadcaster");
      auto subscriber = node->create_subscription<nav_msgs::msg::Odometry>("odom",10, &topic_callback); 
      rclcpp::spin(node);
      rclcpp::shutdown();
      return 0;
    }

error message:

/home/frederik/ros2botpc/src/tfbroadcast/src/tfbroadcast.cpp: In function ‘void topic_callback(nav_msgs::msg::Odometry_<std::allocator<void> >::SharedPtr)’:
/home/frederik/ros2botpc/src/tfbroadcast/src/tfbroadcast.cpp:12:45: error: no matching function for call to ‘tf2_ros::TransformBroadcaster::TransformBroadcaster()’
        static tf2_ros::TransformBroadcaster br;
                                             ^~
In file included from /home/frederik/ros2botpc/src/tfbroadcast/src/tfbroadcast.cpp:4:0:
/opt/ros/eloquent/include/tf2_ros/transform_broadcaster.h:53:3: note: candidate: template<class NodeT, class AllocatorT> tf2_ros::TransformBroadcaster::TransformBroadcaster(NodeT&&, const rclcpp::QoS&, const rclcpp::PublisherOptionsWithAllocator<AllocatorT>&)
   TransformBroadcaster(
   ^~~~~~~~~~~~~~~~~~~~
/opt/ros/eloquent/include/tf2_ros/transform_broadcaster.h:53:3: note:   template argument deduction/substitution failed:
/home/frederik/ros2botpc/src/tfbroadcast/src/tfbroadcast.cpp:12:45: note:   candidate expects 3 arguments, 0 provided
        static tf2_ros::TransformBroadcaster br;
                                             ^~
In file included from /home/frederik/ros2botpc/src/tfbroadcast/src/tfbroadcast.cpp:4:0:
/opt/ros/eloquent/include/tf2_ros/transform_broadcaster.h:49:7: note: candidate: tf2_ros::TransformBroadcaster::TransformBroadcaster(const tf2_ros::TransformBroadcaster&)
 class TransformBroadcaster{
       ^~~~~~~~~~~~~~~~~~~~
/opt/ros/eloquent/include/tf2_ros/transform_broadcaster.h:49:7: note:   candidate expects 1 argument, 0 provided
/opt/ros/eloquent/include/tf2_ros/transform_broadcaster.h:49:7: note: candidate: tf2_ros::TransformBroadcaster::TransformBroadcaster(tf2_ros::TransformBroadcaster&&)
/opt/ros/eloquent/include/tf2_ros/transform_broadcaster.h:49:7: note:   candidate expects 1 argument, 0 provided
/home/frederik/ros2botpc/src/tfbroadcast/src/tfbroadcast.cpp:24:8: error: ‘broadcaster’ was not declared in this scope
        broadcaster.sendTransform(transformStamped);
edit retag flag offensive close merge delete

Comments

Was this resolved?

surfertas gravatar image surfertas  ( 2020-09-06 07:25:22 -0500 )edit

3 Answers

Sort by » oldest newest most voted
3

answered 2020-08-29 06:32:44 -0500

updated 2020-09-06 08:10:06 -0500

  1. Assuming that you have split declarations into a header file and definitions in the source file.
  2. You can declare the broadcaster in the header file.

    private:
       std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
    
  3. Then initialize somewhere in the constructor of the source file.

    tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(this);
    
  4. Finally, you can send a stamped transform message as so:

    tf_broadcaster_->sendTransform(transform_stamped);
    

A good place to check for implementations/best-practices is by reviewing the tests implemented by the maintainers of the respective package in particular when working with ROS 2 as documentation is trying to keep up. In this case review the geometry2 package, specifically test_transform_broadcaster.cpp. Finally, change the branch that you are viewing to the ROS 2 distro that you are using. (e.g. dashing in this case)

edit flag offensive delete link more

Comments

1

Yes this is resolved! Thanks a lot for your answer, it helped me greatly! :)

Loekes gravatar image Loekes  ( 2020-09-06 07:44:53 -0500 )edit
1

No problem. Please mark the answers as correct in that case.

surfertas gravatar image surfertas  ( 2020-09-07 05:38:57 -0500 )edit
1

@Loekes could you put the corrected code snippet of tf2? I am stuck in the implementation of tf2 in ROS2 Dashing

Sourabh Misal gravatar image Sourabh Misal  ( 2020-12-10 10:01:07 -0500 )edit
1

answered 2020-12-10 14:20:01 -0500

Loekes gravatar image

My final code snippet, hope it helps!

  #include <memory>
        #include <chrono>
        #include "rclcpp/rclcpp.hpp"
        #include <tf2_ros/transform_broadcaster.h>
        #include "nav_msgs/msg/odometry.hpp"
        #include "sensor_msgs/msg/laser_scan.hpp"
        #include <geometry_msgs/msg/transform_stamped.h>
        #include <tf2/LinearMath/Quaternion.h>
        #include <tf2_ros/static_transform_broadcaster.h>
        #include "tf2_ros/buffer.h"
        #include <string.h>
        using std::placeholders::_1;
        using namespace std;

    class TFbroadcast : public rclcpp::Node
    {
      public:
        TFbroadcast()
        : Node("tf_broadcaster")
        {
          subscription_ = this->create_subscription<nav_msgs::msg::Odometry>(
          "odom", 20, std::bind(&TFbroadcast::topic_callback, this, _1));
          subscription2_ = this->create_subscription<sensor_msgs::msg::LaserScan>("rawscan", rclcpp::SensorDataQoS(), std::bind(&TFbroadcast::scanCallback, this, _1));
          publisher_ = this->create_publisher<sensor_msgs::msg::LaserScan>("scan", rclcpp::SensorDataQoS());

          tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(this);
        }
      private:
        rclcpp::Time now;
        void topic_callback(const nav_msgs::msg::Odometry::SharedPtr msg)
        {
           geometry_msgs::msg::TransformStamped transformStamped;
           now = rclcpp::Node::now();
           transformStamped.header.stamp = now;
           transformStamped.header.frame_id = "odom";
           transformStamped.child_frame_id = "base_link";
           transformStamped.transform.translation.x = msg->pose.pose.position.x;
           transformStamped.transform.translation.y = msg->pose.pose.position.y;
           transformStamped.transform.translation.z = 0.0;
           transformStamped.transform.rotation.x = 0.0;
           transformStamped.transform.rotation.y = 0.0;
           transformStamped.transform.rotation.z = msg->pose.pose.orientation.z;
           transformStamped.transform.rotation.w = msg->pose.pose.orientation.w; 
           tf_broadcaster_->sendTransform(transformStamped);
        }
        void scanCallback(const sensor_msgs::msg::LaserScan::SharedPtr msg)
        {
           sensor_msgs::msg::LaserScan laser;
           laser.header.frame_id = "laser_frame";
           laser.header.stamp = now;
           laser.angle_min = msg->angle_min;
           laser.angle_max = msg->angle_max;
           laser.angle_increment = msg->angle_increment;
           laser.scan_time = msg->scan_time;
           laser.time_increment = msg->time_increment;
           laser.range_min = msg->range_min;
           laser.range_max = msg->range_max;
           laser.ranges = msg->ranges;
           publisher_->publish(laser);
           laser.intensities = msg->intensities ;
        }
           rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr subscription_;
           rclcpp::Subscription<sensor_msgs::msg::LaserScan>::SharedPtr subscription2_;
           rclcpp::Publisher<sensor_msgs::msg::LaserScan>::SharedPtr publisher_;
           std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
    };
    int main(int argc, char * argv[])
    {
      rclcpp::init(argc, argv);
      rclcpp::spin(std::make_shared<TFbroadcast>());
      rclcpp::shutdown();
      return 0;
    }
edit flag offensive delete link more

Comments

Thanks a lot, I understood your code and got it working

Sourabh Misal gravatar image Sourabh Misal  ( 2020-12-11 02:03:36 -0500 )edit
-1

answered 2021-02-02 23:37:22 -0500

Hi, please help me out with this as well would really appreciate it!!!!

CLoned the following git repo: git clone https://github.com/ros/geometry2.git on kinetic for ubuntu 16.04

Getting the following error in the Geometry2/tf2 file:

/home/bhushan/catkin_ws/src/geometry2/tf2_ros/include/tf2_ros/static_transform_broadcaster.h:58:75: warning: extended initializer lists only available with -std=c++11 or -std=gnu++11

/home/bhushan/catkin_ws/src/geometry2/tf2_ros/include/tf2_ros/static_transform_broadcaster.h:58:75: error: no matching function for call to ‘std::vector<geometry_msgs::transformstamped_<std::allocator<void> > >::vector(<brace-enclosed initializer="" list="">)’

In file included from /usr/include/c++/5/vector:64:0, from /usr/include/boost/format.hpp:17, from /usr/include/boost/math/policies/error_handling.hpp:31, from /usr/include/boost/math/special_functions/round.hpp:14, from /opt/ros/kinetic/include/ros/time.h:58, from /opt/ros/kinetic/include/ros/ros.h:38, from /home/bhushan/catkin_ws/src/geometry2/tf2_ros/src/static_transform_broadcaster.cpp:34:

/usr/include/c++/5/bits/stl_vector.h:407:9: note: candidate: template<class _inputiterator=""> std::vector<_Tp, _Alloc>::vector(_InputIterator, _InputIterator, const allocator_type&) vector(_InputIterator __first, _InputIterator __last,

further errors:

/home/bhushan/catkin_ws/src/geometry2/tf2_ros/src/static_transform_broadcaster.cpp:52:10: error: ‘predicate’ does not name a type auto predicate = &input { ^

/home/bhushan/catkin_ws/src/geometry2/tf2_ros/src/static_transform_broadcaster.cpp:55:10: error: ‘existing’ does not name a type auto existing = std::find_if(net_message_.transforms.begin(), net_message_.transforms.end(), predicate); ^

/home/bhushan/catkin_ws/src/geometry2/tf2_ros/src/static_transform_broadcaster.cpp:57:9: error: ‘existing’ was not declared in this scope if (existing != net_message_.transforms.end())

edit flag offensive delete link more

Comments

@bhushan Please ask your own question. This is not an answer to the above question. Make sure to include enough of a description in your question for someone to reproduce your problem. You don't state what else is in your workspace, what commands you've run and what you've done to install dependencies or how you got your code (we need specifics including the branch to be able to help you.)

tfoote gravatar image tfoote  ( 2021-02-03 11:22:35 -0500 )edit

Question Tools

Stats

Asked: 2020-08-28 06:40:13 -0500

Seen: 2,909 times

Last updated: Dec 10 '20