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

Synchronization with 8 incoming channels, registerCallback boost::bind -> compilation error

asked 2012-10-02 02:55:22 -0500

andreas gravatar image

updated 2012-10-25 23:57:38 -0500

Hi all,

UPDATE: I found a workaround which I posted at the end of this question

I try to use ApproximateTime Synchronization with 8 channels, but I get a compilation error. Strangely it works with 4.

Here's some of the code: (The error is at sync_->registerCallback(boost::bind(&S2::filter_image, this, _1, _2, _3, _4, _5, _6, _7, _8, "ok")); )

class S2 {
    ros::NodeHandle nh_;

    image_transport::ImageTransport image_transporter_;
    boost::unordered_map<std::string, boost::shared_ptr<image_transport::SubscriberFilter> > response_; //images from C1

    //Synchronizer
    typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image,
        sensor_msgs::Image, sensor_msgs::Image,
        sensor_msgs::Image, sensor_msgs::Image,
        sensor_msgs::Image, sensor_msgs::Image> syncPolicy;


    typedef message_filters::Synchronizer<syncPolicy> mySynchronizer;
    boost::shared_ptr<mySynchronizer>  sync_;

public:

    S2(ros::NodeHandle nh): image_transporter_(nh) {
        nh_ = nh;
        read_parameters();
    }

    void read_parameters(){


    //Subscribe to C1 images

            sync_.reset( new mySynchronizer ( syncPolicy(10),
                *C1_response_[subscribe_strings.at(0)].get(),
                *C1_response_[subscribe_strings.at(1)].get(),
                    *C1_response_[subscribe_strings.at(2)].get(),
                    *C1_response_[subscribe_strings.at(3)].get(),
                    *C1_response_[subscribe_strings.at(4)].get(),
                    *C1_response_[subscribe_strings.at(5)].get(),
                    *C1_response_[subscribe_strings.at(6)].get(),
                    *C1_response_[subscribe_strings.at(7)].get()));             
            sync_->registerCallback(boost::bind(&S2::filter_image, this,  _1, _2, _3, _4, _5, _6, _7, _8, "ok"));




    }


    void filter_image(const sensor_msgs::ImageConstPtr& original_image1, const sensor_msgs::ImageConstPtr& original_image2,
            const sensor_msgs::ImageConstPtr& original_image3, const sensor_msgs::ImageConstPtr& original_image4,std::string name){

    }

};

int main(int argc, char **argv){

  ros::init(argc, argv, "S2_node");
  ros::NodeHandle nh;

    S2 s2(nh);
ros::spin();
    return 0;
}

The error I get is:

S2_new_node.cpp: In member function ‘void S2::read_parameters()’:
S2_new_node.cpp:88:102: error: no matching function for call to ‘bind(void (S2::*)(const ImageConstPtr&, const ImageConstPtr&, const ImageConstPtr&, const ImageConstPtr&, std::string), S2* const, boost::arg<1>&, boost::arg<2>&, boost::arg<3>&, boost::arg<4>&, boost::arg<5>&, boost::arg<6>&, boost::arg<7>&, boost::arg<8>&, const char [3])’
/work/ros/hmax/src/S2_new_node.cpp:88:102: note: candidates are:
/usr/include/boost/bind/bind.hpp:1298:5: note: template<class R, class F> boost::_bi::bind_t<R, F, boost::_bi::list0> boost::bind(F)
/usr/include/boost/bind/bind.hpp:1306:5: note: template<class R, class F, class A1> boost::_bi::bind_t<R, F, typename boost::_bi::list_av_1<A1>::type> boost::bind(F, A1)
/usr/include/boost/bind/bind.hpp:1314:5: note: template<class R, class F, class A1, class A2> boost::_bi::bind_t<R, F, typename boost::_bi::list_av_2<A1, A2>::type> boost::bind(F, A1, A2)
/usr/include/boost/bind/bind.hpp:1322:5: note: template<class R, class F, class A1, class A2, class A3> boost::_bi::bind_t<R, F, typename boost::_bi::list_av_3<A1, A2, A3>::type> boost::bind(F, A1, A2, A3)
/usr/include/boost/bind/bind.hpp:1330:5: note: template<class R, class F, class A1, class A2, class A3, class A4> boost::_bi::bind_t<R, F, typename boost::_bi::list_av_4<A1, A2, A3, A4>::type> boost::bind(F, A1, A2, A3, A4)
/usr/include/boost/bind/bind.hpp:1338:5: note: template<class R, class F, class A1, class ...
(more)
edit retag flag offensive close merge delete

Comments

Please provide the complete error message. You left out the interesting part. See the support page.

Lorenz gravatar image Lorenz  ( 2012-10-02 03:18:43 -0500 )edit

complete error message added :) I hope it helps.

andreas gravatar image andreas  ( 2012-10-02 03:34:13 -0500 )edit

It would be great if you could reformat it as code, not as citation. The line breaks make it hard to read.

Lorenz gravatar image Lorenz  ( 2012-10-02 03:37:46 -0500 )edit

Ups sorry, just changed it.

andreas gravatar image andreas  ( 2012-10-02 03:43:53 -0500 )edit

As I just added, might it be possible, that the problem is occurring due to boost 1.46 and not 1.48?

andreas gravatar image andreas  ( 2012-10-02 03:55:42 -0500 )edit

1 Answer

Sort by » oldest newest most voted
2

answered 2012-10-02 04:15:56 -0500

Lorenz gravatar image

Can you try if it works with 6 and 7 chanels? I suspect that boost::bind is just not implemented for so many parameters. Maybe you will have to implement your callback as a functor object manually, e.g. create the following nestet struct in your class S2 and use it as callback:

struct FilterFunctor {
  S2 *self_;
  const std::string &name_;

  FilterFunctor(S2 *self, const std::string &name) 
    : self_(self), name_(name) {}

  void operator()(const sensor_msgs::ImageConstPtr& original_image1, const sensor_msgs::ImageConstPtr& original_image2,
            const sensor_msgs::ImageConstPtr& original_image3, const sensor_msgs::ImageConstPtr& original_image4) {
    ...
  }
};
edit flag offensive delete link more

Comments

It works with 6 and works with 7. I will try it with the functor object, or just split the callback up to twice four channels. Thanks!

andreas gravatar image andreas  ( 2012-10-02 04:27:12 -0500 )edit

Or maybe is it possible to somehow use registerCallback without bind?

andreas gravatar image andreas  ( 2012-10-02 04:31:10 -0500 )edit

Yes. The functor above basically shows you how to implement it without bind.

Lorenz gravatar image Lorenz  ( 2012-10-02 04:50:21 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2012-10-02 02:55:22 -0500

Seen: 2,142 times

Last updated: Oct 25 '12