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

Issues calling registerCallback()

asked 2021-05-04 16:57:09 -0500

anonymous user

Anonymous

updated 2021-05-04 16:58:05 -0500

Hello,

I want to synchronise two topics by using Time_synchronizer. The first one is Is a sensor_msgs and the second one is a custom message containing an int32. I followed the tutorial and read some post on various pages, but it does not build properly.

class Controller
{
    public:
        ros::NodeHandle node;
        ros::ServiceClient service_client;
        std::vector<NumberAndPicture> storage;
        message_filters::Subscriber<sensor_msgs::Image> img_subscriber; 
        message_filters::Subscriber<imagineer::Number> int_subscriber;
        message_filters::TimeSynchronizer<sensor_msgs::Image, imagineer::Number> sync;

        Controller() : sync(img_subscriber, int_subscriber, 10)
        {
            service_client = node.serviceClient<imagineer::ImageAck>("ImageAck");
            img_subscriber.subscribe(node, "processor/image", 1);
            int_subscriber.subscribe(node, "camera/integer", 1); 
            sync.registerCallback(boost::bind(&Controller::callback, this, _1, _2));
        }

        void callback(const sensor_msgs::ImageConstPtr& image, const imagineer::Number& digit)
        {
            try
            {
                imagineer::ImageAck ack_service;
                add_to_list(digit, image);
                ROS_INFO("Int and image are saved");
                send_image(image, ack_service);
            }
            catch (cv_bridge::Exception& e)
            {
                ROS_ERROR("Error: %s", e.what());
            }
        }
};

The error message I get when I execute catkin_make:

[ 95%] Building CXX object imagineer/CMakeFiles/controller.dir/src/controller.cpp.o
In file included from /usr/include/boost/bind.hpp:22,
                 from /opt/ros/noetic/include/ros/publisher.h:35,
                 from /opt/ros/noetic/include/ros/node_handle.h:32,
                 from /opt/ros/noetic/include/ros/ros.h:45,
                 from /home/marta/catkin_ws/src/imagineer/src/controller.cpp:1:
/usr/include/boost/bind/bind.hpp: In instantiation of ‘void boost::_bi::list3<A1, A2, A3>::operator()(boost::_bi::type<void>, F&, A&, int) [with F = boost::_mfi::mf2<void, Controller, const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, const imagineer::Number_<std::allocator<void> >&>; A = boost::_bi::rrlist9<const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, const boost::shared_ptr<const imagineer::Number_<std::allocator<void> > >&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&>; A1 = boost::_bi::value<Controller*>; A2 = boost::arg<1>; A3 = boost::arg<2>]’:
/usr/include/boost/bind/bind.hpp:1402:50:   required from ‘boost::_bi::bind_t<R, F, L>::result_type boost::_bi::bind_t<R, F, L>::operator()(A1&&, A2&&, A3&&, A4&&, A5&&, A6&&, A7&&, A8&&, A9&&) [with A1 = const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&; A2 = const boost::shared_ptr<const imagineer::Number_<std::allocator<void> > >&; A3 = const boost::shared_ptr<const message_filters::NullType>&; A4 = const boost::shared_ptr<const message_filters::NullType>&; A5 = const boost::shared_ptr<const message_filters::NullType>&; A6 = const boost::shared_ptr<const message_filters::NullType>&; A7 = const boost::shared_ptr<const message_filters::NullType>&; A8 = const boost::shared_ptr<const message_filters::NullType>&; A9 = const boost::shared_ptr<const message_filters::NullType>&; R = void; F = boost::_mfi::mf2<void, Controller, const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, const imagineer::Number_<std::allocator<void> >&>; L = boost::_bi::list3<boost::_bi::value<Controller*>, boost::arg<1>, boost::arg<2> >; boost::_bi::bind_t<R, F, L>::result_type = void]’
/usr/include/boost/bind/bind.hpp:833:35:   required from ‘void boost::_bi::list9<A1, A2, A3, A4, A5, A6, A7, A8, A9>::operator()(boost::_bi::type<void>, F&, A&, int) [with F = boost::_bi::bind_t<void, boost::_mfi::mf2<void, Controller, const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, const imagineer::Number_<std::allocator<void> >&>, boost::_bi::list3<boost::_bi::value<Controller*>, boost ...
(more)
edit retag flag offensive close merge delete

Comments

This is the main error:

no known conversion for argument 1 from ‘Controller*’ to ‘Controller&’

The arguments you pass to boost::bind(..) are apparently incorrect.

I haven't checked the rest of your code, but does it start to compile when you pass *this* instead ofthis`?

Note also: time synchronisation can only happen when all messages carry std_msgs/Headers. Does your custom message have such a field? If not, you'll end up with another long compiler error.

gvdhoorn gravatar image gvdhoorn  ( 2021-05-05 00:21:51 -0500 )edit

Yes, thanks for mentioning it I already added the std_msgs/Header line to my custom message. If I pass *this I end up with another huge compiler error. I am not exactly sure what error: use of deleted function ‘Controller::Controller(const Controller&)’ means.

anonymous74063 gravatar image anonymous74063  ( 2021-05-05 02:35:56 -0500 )edit

1 Answer

Sort by » oldest newest most voted
0

answered 2021-05-06 08:51:28 -0500

anonymous user

Anonymous

I solved it. The solution is to add a shared_ptr to TimeSynchronizer without boost::bind()

class Controller
{
    public:    
        /* Contructor
        */ 
        Controller() 
        {
            img_subscriber.subscribe(node, "processor/image", 1);
            int_subscriber.subscribe(node, "camera/integer", 1); 
            cv::namedWindow("view");
            sync.reset(new message_filters::TimeSynchronizer<sensor_msgs::Image, imagineer::Number>(img_subscriber, int_subscriber, 10));
            service_client = node.serviceClient<imagineer::ImageAck>("ImageAck");
            sync->registerCallback(&Controller::callback, this);   
        }

        void callback(const sensor_msgs::ImageConstPtr& image, const imagineer::Number& digit)
        {

            try
            {
                cv::imshow("view", cv_bridge::toCvCopy(image)->image);
                cv::waitKey(30);
                imagineer::ImageAck ack_service;
                add_to_list(digit, image);
                ROS_INFO("Int and image are saved");
               // send_image(image, ack_service);
               // ROS_INFO("Image sent");
            }
            catch (cv_bridge::Exception& e)
            {
                ROS_ERROR("Error: %s", e.what());
            }
        }

        private:
            ros::NodeHandle node;
            ros::ServiceClient service_client;
            std::vector<NumberAndPicture> storage;
            message_filters::Subscriber<sensor_msgs::Image> img_subscriber; 
            message_filters::Subscriber<imagineer::Number> int_subscriber;
            boost::shared_ptr<message_filters::TimeSynchronizer<sensor_msgs::Image, imagineer::Number>> sync;
};
edit flag offensive delete link more

Comments

Thanks, run into similar issue and solved by looking a your code. You can also use std::shared_ptr or std::unique_ptr instead of boost ptr.

shafeeq gravatar image shafeeq  ( 2022-12-06 17:24:37 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-05-04 16:57:09 -0500

Seen: 628 times

Last updated: May 06 '21