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

class construction error when using tf2_ros::Buffer

asked 2017-10-09 23:47:26 -0500

arkin gravatar image

updated 2017-10-10 04:11:32 -0500

Hi all, I am trying to use tf2_ros::Buffer in a simple code. When I put it in the main function, everything works fine. But when put in a class, building error occurs. The code is like this:

#include <ros/ros.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <geometry_msgs/TransformStamped.h>
#include <geometry_msgs/Twist.h>

class test_class

{
private:
    double start;
    double duration;
    ros::Time start_time;
    ros::Time end_time;
    std::string robot_name;

    tf2_ros::Buffer tf_buffer; // problem
    tf2_ros::TransformListener* tfListener;
    geometry_msgs::TransformStamped transformStamped;

public:
    std::string space_name;
    std::string node_name;

    test_class()
    {
        space_name = ros::this_node::getNamespace();
        node_name = ros::this_node::getName();
    }

    ~test_class()
    {}

    bool initialize(const ros::NodeHandle& n)
    {
        ROS_INFO("Class auto_mav_flight initialized done!");
        return true;
    }
    void timer_callback(const ros::TimerEvent& event)
    {
        ROS_INFO("Timer Callback triggered.");
        return;
    }
}; 

int main(int argc, char** argv)
{
    ros::init(argc, argv, "auto_mav_node");
    ros::NodeHandle node;
    ROS_WARN("The node is initilized and started.");
    test_class amf = test_class();
    amf.initialize(node);
    ros::Timer timer_1 = node.createTimer(ros::Duration(0.5), &test_class::timer_callback, &amf);
    ros::spin();
    return EXIT_SUCCESS;
}

and the building error information is:

/home/arkin/ros_code/sandbox/auto_mav_sandbox/src/auto_mav_flight/src/node_main.cpp: In function ‘int main(int, char**)’:
/home/arkin/ros_code/sandbox/auto_mav_sandbox/src/auto_mav_flight/src/node_main.cpp:73:44: error: no matching function for call to ‘test_class::test_class(test_class)’
  test_class amf = test_class();
                                            ^
/home/arkin/ros_code/sandbox/auto_mav_sandbox/src/auto_mav_flight/src/node_main.cpp:73:44: note: candidates are:
/home/arkin/ros_code/sandbox/auto_mav_sandbox/src/auto_mav_flight/src/node_main.cpp:26:2: note: test_class::test_class()
  test_class()
  ^
/home/arkin/ros_code/sandbox/auto_mav_sandbox/src/auto_mav_flight/src/node_main.cpp:26:2: note:   candidate expects 0 arguments, 1 provided
/home/arkin/ros_code/sandbox/auto_mav_sandbox/src/auto_mav_flight/src/node_main.cpp:9:7: note: test_class::test_class(test_class&)
 class test_class
       ^
/home/arkin/ros_code/sandbox/auto_mav_sandbox/src/auto_mav_flight/src/node_main.cpp:9:7: note:   no known conversion for argument 1 from ‘test_class’ to ‘test_class&’
make[2]: *** [auto_mav_flight/CMakeFiles/auto_mav_flight_node.dir/src/node_main.cpp.o] Error 1
make[1]: *** [auto_mav_flight/CMakeFiles/auto_mav_flight_node.dir/all] Error 2
make: *** [all] Error 2

I found that if I comment the code line:

 tf2_ros::Buffer tf_buffer;

the error disappear.

Why the tf2_ros::Buffer can cause problem of class construction even I just declare it as a member of class?

Any help will be appreciated.

Thanks in advance.

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2017-10-11 08:36:45 -0500

arkin gravatar image

updated 2017-10-13 01:23:23 -0500

For reference: https://stackoverflow.com/questions/4...

From tf2_ros::Buffer header, it inherits from BufferCore, which contains a boost::mutex(among other things - there could more than 1 non-copyable attribute) which is not copy-constructible. That makes tf2_ros::Buffer not copy-constructible. Since test_class do not define a copy-constructor and contains a non-copyable attribute, the compiler cannot generate a copy constructor and fails to compile when you try to call a copy constructor.

So, the class need a copy constructor to do the class initialization : test_class amf = test_class(); If I replace this code line with test_class amf; it works. Of course it will be necessary to remove the operation of the user-defined class constructor. An alternative way is to define a copy constructor (even an empty constructor) like: test_class(const test_class& right_side). This also solve the problem. It seems that realizing tf2_ros::Buffer not copy-constructibal is the key to solve this problem.

edit flag offensive delete link more

Comments

Could I please ask you to post the answer you got on SO here as an answer as well? We'd like to keep answers here self-contained, to avoid future readers having to click through N links to get to the actual solution.

Thanks.

gvdhoorn gravatar image gvdhoorn  ( 2017-10-11 09:56:19 -0500 )edit

Sure, Thank you. :-)

arkin gravatar image arkin  ( 2017-10-13 01:20:50 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2017-10-09 23:47:26 -0500

Seen: 2,798 times

Last updated: Oct 13 '17