Robotics StackExchange | Archived questions

tf2_ros::Buffer.transrom() causes "undefiend reference" errors, but "tf2_geometry_msgs/tf2_geometry_msgs.h" is already included.

Hi, I am trying to use tf2 transform. However, similar error in this link is happened, but in my code, tf2geometrymsgs.h is already added. https://answers.ros.org/question/239260/tf2_rosbuffertransform-causes-undefined-reference-errors/

Could you give me some advice about this problem?


#include <ros/ros.h>

#include "ar_marker_pose_converter/ar_marker_pose_converter.h"

namespace ar_marker_pose_converter
{
    ar_marker_converter::ar_marker_converter(std::string &ar_marker_pose_topic, std::string &map_frame_param, const double convert_timer_duration)
    : nh_(), tfBuffer_(), tfListener_(tfBuffer_)
    {
        map_frame = map_frame_param;
        ar_marker_pose_publsiher_ = nh_.advertise<geometry_msgs::PoseStamped>("ar_marker_pose", 1);
        ar_marker_pose_subscriber_ = nh_.subscribe<geometry_msgs::PoseStamped>(ar_marker_pose_topic, 10, &ar_marker_converter::pose_callback, this);
        published_ar_pose.header.frame_id = map_frame_param;
    }

    void ar_marker_converter::pose_callback(const geometry_msgs::PoseStamped::ConstPtr &pose_topic_camera_coord)
    {
        std::string camera_frame = pose_topic_camera_coord->header.frame_id;
        geometry_msgs::Pose pose_on_camera_frame = pose_topic_camera_coord->pose;
        try
        {
            published_ar_pose.pose = tfBuffer_.transform(pose_on_camera_frame, map_frame);
        }
        catch (tf2::TransformException &ex)
        {
            ROS_WARN("%s", ex.what());
            return;
        }
        published_ar_pose.header.stamp = ros::Time::now();
        ar_marker_pose_publsiher_.publish(published_ar_pose);
    }

} // namespace ar_marker_pose_converter

int main(int argc, char *argv[])
{
    ros::init(argc, argv, "ar_marker_pose_converter");
    ros::NodeHandle pnh("~");
    std::string ar_marker_pose_topic = "ar_marker_pose";
    std::string map_frame = "map";
    double convert_timer_duration = 0.1; //[s]


    if (pnh.hasParam(("map_frame")))
    {
        pnh.getParam("map_frame", map_frame);
    }
    else
    {
        pnh.setParam("map_frame", map_frame);
    }

    ar_marker_pose_converter::ar_marker_converter(ar_marker_pose_topic, map_frame, convert_timer_duration);

    ros::spin();


    return 0;
}

Cmake error.

/usr/bin/ld: CMakeFiles/ar_marker_pose_converter.dir/src/ar_marker_pose_converter_node.cpp.o: in function `geometry_msgs::Pose_<std::allocator<void> >& tf2_ros::BufferInterface::transform<geometry_msgs::Pose_<std::allocator<void> > >(geometry_msgs::Pose_<std::allocator<void> > const&, geometry_msgs::Pose_<std::allocator<void> >&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, ros::Duration) const':
ar_marker_pose_converter_node.cpp:(.text._ZNK7tf2_ros15BufferInterface9transformIN13geometry_msgs5Pose_ISaIvEEEEERT_RKS6_S7_RKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEEN3ros8DurationE[_ZNK7tf2_ros15BufferInterface9transformIN13geometry_msgs5Pose_ISaIvEEEEERT_RKS6_S7_RKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEEN3ros8DurationE]+0x44): undefined reference to `std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const& tf2::getFrameId<geometry_msgs::Pose_<std::allocator<void> > >(geometry_msgs::Pose_<std::allocator<void> > const&)'
/usr/bin/ld: ar_marker_pose_converter_node.cpp:(.text._ZNK7tf2_ros15BufferInterface9transformIN13geometry_msgs5Pose_ISaIvEEEEERT_RKS6_S7_RKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEEN3ros8DurationE[_ZNK7tf2_ros15BufferInterface9transformIN13geometry_msgs5Pose_ISaIvEEEEERT_RKS6_S7_RKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEEN3ros8DurationE]+0x50): undefined reference to `ros::Time const& tf2::getTimestamp<geometry_msgs::Pose_<std::allocator<void> > >(geometry_msgs::Pose_<std::allocator<void> > const&)'
collect2: error: ld returned 1 exit status
make[2]: *** [CMakeFiles/ar_marker_pose_converter.dir/build.make:107: /home/catkin_ws/devel/.private/ar_marker_pose_converter/lib/ar_marker_pose_converter/ar_marker_pose_converter] Error 1
make[1]: *** [CMakeFiles/Makefile2:209: CMakeFiles/ar_marker_pose_converter.dir/all] Error 2
make: *** [Makefile:141: all] Error 2

cmake_minimum_required(VERSION 3.0.2)
project(ar_marker_pose_converter)

## Compile as C++11, supported in ROS Kinetic and newer
add_compile_options(-std=c++11)
find_package(catkin REQUIRED COMPONENTS
  geometry_msgs
  roscpp
  rospy
  std_msgs
  tf2
  tf2_msgs
  tf2_ros
  tf2_geometry_msgs
)



catkin_package(
  INCLUDE_DIRS include
  LIBRARIES ar_marker_pose_converter
  CATKIN_DEPENDS geometry_msgs roscpp rospy std_msgs  tf2 tf2_ros tf2_geometry_msgs
#  DEPENDS system_lib
)

include_directories(
 include
  ${catkin_INCLUDE_DIRS}
)


add_executable(ar_marker_pose_converter src/ar_marker_pose_converter_node.cpp)
add_dependencies(ar_marker_pose_converter ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(ar_marker_pose_converter
  ${catkin_LIBRARIES}
)

install(DIRECTORY launch/
  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
)

#ifndef AR_MARKER_POSE_CONVERTER_H
#define AR_MARKER_POSE_CONVERTER_H

#include "ros/ros.h"
#include "geometry_msgs/PoseStamped.h"
#include "tf2_ros/transform_listener.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"

namespace ar_marker_pose_converter

{
    class ar_marker_converter
    {
    public:
        ar_marker_converter(std::string &ar_marker_pose_topic, std::string &map_frame_param, const double convert_timer_duration);
        void pose_callback(const geometry_msgs::PoseStamped::ConstPtr &pose_topic_camera_coord);
        void timer_callback(const ros::TimerEvent &e);

    private:
        tf2_ros::Buffer tfBuffer_;
        tf2_ros::TransformListener tfListener_;
        ros::NodeHandle nh_;
        ros::Publisher ar_marker_pose_publsiher_;
        ros::Subscriber ar_marker_pose_subscriber_;
        std::string map_frame;
        geometry_msgs::Pose ar_marker_pose_on_map_frame;
        geometry_msgs::PoseStamped published_ar_pose;
    };

} // namespace ar_marker_pose_converter
#endif // AR_MARKER_POSE_CONVERTER_H

Asked by yataka231 on 2023-01-20 06:09:50 UTC

Comments

Sorry, I forgot to add header file.

Asked by yataka231 on 2023-01-22 22:20:37 UTC

About this problem, I finally solved by changed the code like this.


Before revision

published_ar_pose.pose = tfBuffer_.transform(pose_on_camera_frame, map_frame);

After revision

transform_stamped_ = tfBuffer_.lookupTransform(map_frame, camera_frame, ros::Time(0));
tf2::doTransform(pose_on_camera_frame, published_ar_pose.pose, transform_stamped_);

Asked by yataka231 on 2023-01-31 01:51:18 UTC

Answers

I think the actual error is:

undefined reference to ... tf2::getFrameId

If you grep the files in /opt/ros/noetic/include/tf2/, you will find this function in file convert.h. So the fix is to add an:

#include "tf2/convert.h"

line to the source code. My guess is that this code was originally written for an older ros release.

Asked by Mike Scheutzow on 2023-01-20 08:57:50 UTC

Comments

Thank you for your comment. I added the line to this source code, but the same build error was happened.

Asked by yataka231 on 2023-01-22 22:22:44 UTC