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

tf2_ros::Buffer.transform() causes "undefined reference" errors

asked 2016-07-11 13:38:12 -0500

tommises gravatar image

I am trying to use tf2_ros::Buffer.transform() and when trying to compile I am getting "undefined reference" errors from the linker. I don't link I'm missing any libraries, because tf2_ros::Buffer.lookupTransform() compiles just fine and I added all possible tf2 libraries. Am I doing something wrong or does it seem to be a bug?

Below is the code of my test node and error messages. And my entire test package is at https://github.com/tommises/ros-tf2-i...

For what it's worth, tf::TransformListener.transformPoint() works fine as well. Is there any risk in mixing tf and tf2?

  • ROS version: kinetic
  • OS: Ubuntu 16.04

#include <ros/ros.h>
#include <geometry_msgs/PointStamped.h>

#include <tf2_ros/transform_listener.h> 

tf2_ros::Buffer tfBuffer;

void ellipsevsCallback(const geometry_msgs::PointStamped::ConstPtr& point_raw){
    geometry_msgs::TransformStamped transformStamped;
    transformStamped = tfBuffer.lookupTransform("global", "local", ros::Time(0));

    geometry_msgs::PointStamped point_tf;
    /* This is the line which fails to compile. */
    tfBuffer.transform(*point_raw, point_tf, "local");
}

int main(int argc, char** argv){
    ros::init(argc, argv, "tf2_test_tf2_point");
    tf2_ros::TransformListener tfListener(tfBuffer);

    ros::NodeHandle node;
    ros::Subscriber topic_sub = node.subscribe("test/point", 1, &ellipsevsCallback);

    ros::spin();
    return 0;
};

linker errors

[100%] Linking CXX executable tf2_test_tf2_point
CMakeFiles/tf2_test_tf2_point.dir/src/tf2_test_tf2_point.cpp.o: In function `geometry_msgs::PointStamped_<std::allocator<void> >& tf2_ros::BufferInterface::transform<geometry_msgs::PointStamped_<std::allocator<void> > >(geometry_msgs::PointStamped_<std::allocator<void> > const&, geometry_msgs::PointStamped_<std::allocator<void> >&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, ros::Duration) const':
tf2_test_tf2_point.cpp:(.text._ZNK7tf2_ros15BufferInterface9transformIN13geometry_msgs13PointStamped_ISaIvEEEEERT_RKS6_S7_RKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEEN3ros8DurationE[_ZNK7tf2_ros15BufferInterface9transformIN13geometry_msgs13PointStamped_ISaIvEEEEERT_RKS6_S7_RKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEEN3ros8DurationE]+0x69): undefined reference to `ros::Time const& tf2::getTimestamp<geometry_msgs::PointStamped_<std::allocator<void> > >(geometry_msgs::PointStamped_<std::allocator<void> > const&)'
tf2_test_tf2_point.cpp:(.text._ZNK7tf2_ros15BufferInterface9transformIN13geometry_msgs13PointStamped_ISaIvEEEEERT_RKS6_S7_RKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEEN3ros8DurationE[_ZNK7tf2_ros15BufferInterface9transformIN13geometry_msgs13PointStamped_ISaIvEEEEERT_RKS6_S7_RKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEEN3ros8DurationE]+0x7b): undefined reference to `std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const& tf2::getFrameId<geometry_msgs::PointStamped_<std::allocator<void> > >(geometry_msgs::PointStamped_<std::allocator<void> > const&)'
tf2_test_tf2_point.cpp:(.text._ZNK7tf2_ros15BufferInterface9transformIN13geometry_msgs13PointStamped_ISaIvEEEEERT_RKS6_S7_RKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEEN3ros8DurationE[_ZNK7tf2_ros15BufferInterface9transformIN13geometry_msgs13PointStamped_ISaIvEEEEERT_RKS6_S7_RKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEEN3ros8DurationE]+0xc8): undefined reference to `void tf2::doTransform<geometry_msgs::PointStamped_<std::allocator<void> > >(geometry_msgs::PointStamped_<std::allocator<void> > const&, geometry_msgs::PointStamped_<std::allocator<void> >&, geometry_msgs::TransformStamped_<std::allocator<void> > const&)'
collect2: error: ld returned 1 exit status
tf2_test/CMakeFiles/tf2_test_tf2_point.dir/build.make:120: recipe for target 'tf2_test/tf2_test_tf2_point' failed
make[2]: *** [tf2_test/tf2_test_tf2_point] Error 1
CMakeFiles/Makefile2:1340: recipe for target 'tf2_test/CMakeFiles/tf2_test_tf2_point.dir/all' failed
make[1]: *** [tf2_test/CMakeFiles/tf2_test_tf2_point.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j4 -l4" failed

and my CMakeLists.txt

cmake_minimum_required(VERSION 2.8.3)
project(tf2_test)

find_package(catkin REQUIRED COMPONENTS
  geometry_msgs
  roscpp
  rospy
  tf2
  tf2_bullet
  tf2_eigen
  tf2_geometry_msgs
  tf2_kdl
  tf2_msgs
  tf2_py
  tf2_ros
  tf2_sensor_msgs
  tf2_tools
  tf
)

include_directories(
  ${catkin_INCLUDE_DIRS}
)

add_executable(tf2_test_tf2_point src/tf2_test_tf2_point.cpp)
add_executable(tf2_test_tf1_point src/tf2_test_tf1_point.cpp)

target_link_libraries(tf2_test_tf2_point
  ${catkin_LIBRARIES}
)
target_link_libraries(tf2_test_tf1_point
  ${catkin_LIBRARIES}
)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
14

answered 2016-08-25 04:20:54 -0500

Vincent R gravatar image

You should include "tf2_geometry_msgs/tf2_geometry_msgs.h"

You can look at this tutorial : http://wiki.ros.org/tf2/Tutorials/Usi...

edit flag offensive delete link more

Comments

4

This was helpful -- but for me the problem was that I did not have the packages in CMakeLists.txt. Thanks for pointing me in the right direction!

veggiebenz gravatar image veggiebenz  ( 2018-09-11 09:16:33 -0500 )edit

Hello veggiebenz, I encounter the same issue. Which packages did you needed to add in the CMakeLists.txt ?

Kapcirt gravatar image Kapcirt  ( 2018-12-24 02:58:16 -0500 )edit
2

I add tf2 and tf2_ros to the find_package to solve this problem

liyxhit gravatar image liyxhit  ( 2020-04-05 22:26:17 -0500 )edit

The solution is still valid until foxy. So, why is the tf2_geometry_msg essential here? The code doesn't use the lib directly. If there is indirectly use, the corresponding file should include the lib...

DC pig gravatar image DC pig  ( 2022-04-24 08:17:39 -0500 )edit

The transform method is uses templated methods on the type T. If you pass in the datatype geometry_msgs::PointStamped you also need to make sure to provide the templated converter methods to allow transform to operate on the datatype. The underlying "library" does not know about any datatypes except it's internal forms and is specifically designed not to know about any alternative datatypes. This design allows you to pass in any datatype and as long as you provide the templated conversion functions the library can operate on your custom datatype in your code without adding a dependency into the underlying library on your custom datatype.

tfoote gravatar image tfoote  ( 2022-04-25 14:49:06 -0500 )edit

3q so much!

DC pig gravatar image DC pig  ( 2022-04-25 22:24:37 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-07-11 13:38:12 -0500

Seen: 10,425 times

Last updated: Aug 25 '16