Robotics StackExchange | Archived questions

compiling error for messge_filter

I'm using Ubuntu 16.04 with ROS kinect . Trying to write a message_filter to synchronize depth and color image from Kinect2.

but a alway have three errors while compiling,says like

error:ISO C++ forbids taking the address of an unqualified or parenthesized non-static member function to form a pointer to member function. 
error: ‘void (spaceteam_ros_tool::Perception::*)(boost::shared_ptr > >&, boost::shared_ptr > >&)’ is not a class, struct, or union type typedef typename F::result_type type;

I think it has something to do with bind and callbackfuntion but don't have a clue about how to solve it.

Thank you for your help in Advance!

I defined a Class in this file

#pragma once
#include <dynamic_reconfigure/server.h>
#include <ros/forwards.h>
#include "spaceteam_ros_tool/PerceptionInterface.h"
#include <sensor_msgs/Image.h>

namespace spaceteam_ros_tool {

class Perception {

    using Interface = PerceptionInterface;
    using ReconfigureConfig = PerceptionConfig;
    using ReconfigureServer = dynamic_reconfigure::Server<ReconfigureConfig>;

    using Ima = sensor_msgs::Image;


public:
    Perception(ros::NodeHandle, ros::NodeHandle);

private:
    void callbackSubscriber(Ima::ConstPtr& Imagedepth, Ima::ConstPtr& Imagecolor); 
    void reconfigureRequest(const ReconfigureConfig&, uint32_t);
    Interface interface_;
    ReconfigureServer reconfigureServer_;
};
} 

hier are the functions above

namespace spaceteam_ros_tool {

Perception::Perception(ros::NodeHandle nhPublic, ros::NodeHandle nhPrivate)
    : interface_{nhPrivate}, reconfigureServer_{nhPrivate} {
    interface_.fromParamServer();
    reconfigureServer_.setCallback(boost::bind(&Perception::reconfigureRequest, this, _1, _2));
    typedef message_filters::sync_policies::ApproximateTime<Ima, Ima> MySyncPolicy;
    message_filters::Synchronizer<MySyncPolicy> sync(MySyncPolicy(10),*interface_.Kinect_depth_sub, *interface_.Kinect_color_sub);

    sync.registerCallback(boost::bind(&callbackSubscriber, _1, _2));
    rosinterface_handler::showNodeInfo();
}

void Perception::callbackSubscriber(Ima::ConstPtr& Imagedepth,Ima::ConstPtr& Imagecolor) { //
// processing
    interface_.Kinect_depth_pub.publish(Imagedepth);
}


void Perception::reconfigureRequest(const ReconfigureConfig& config, uint32_t level) {
    interface_.fromConfig(config);
}


} // namespace spaceteam_ros_tool

and i have the errors as following:

spaceteam_ros_tool:make /home/kal4-2/catkin_ws/logs/spaceteam_ros_tool/build.make.079.log                                             
/home/kal4-2/catkin_ws/src/spaceteam_ros_tool/src/perception/perception.cpp: In constructor ‘spaceteam_ros_tool::Perception::Perception(ros::NodeHandle, ros::NodeHandle)’:
/home/kal4-2/catkin_ws/src/spaceteam_ros_tool/src/perception/perception.cpp:41:40: **error: ISO C++ forbids taking the address of an unqualified or parenthesized non-static member function to form a pointer to member function.  Say ‘&spaceteam_ros_tool::Perception::callbackSubscriber’ [-fpermissive]
     sync.registerCallback(boost::bind(&callbackSubscriber, _1, _2));**
                                        ^
    In file included from /usr/include/boost/bind.hpp:22:0,
                 from /opt/ros/kinetic/include/ros/publisher.h:35,
                 from /opt/ros/kinetic/include/ros/node_handle.h:32,
                 from /opt/ros/kinetic/include/dynamic_reconfigure/server.h:50,
                 from /home/kal4-2/catkin_ws/src/spaceteam_ros_tool/src/perception/perception.hpp:3,
                 from /home/kal4-2/catkin_ws/src/spaceteam_ros_tool/src/perception/perception.cpp:1:
/usr/include/boost/bind/bind.hpp: In instantiation of ‘struct boost::_bi::result_traits<boost::_bi::unspecified, void (spaceteam_ros_tool::Perception::*)(boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&)>’:
/usr/include/boost/bind/bind.hpp:883:48:   required from ‘class boost::_bi::bind_t<boost::_bi::unspecified, void (spaceteam_ros_tool::Perception::*)(boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&), boost::_bi::list2<boost::arg<1>, boost::arg<2> > >’
/home/kal4-2/catkin_ws/src/spaceteam_ros_tool/src/perception/perception.cpp:41:66:   required from here
/usr/include/boost/bind/bind.hpp:69:37: **error: ‘void (spaceteam_ros_tool::Perception::*)(boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&)’ is not a class, struct, or union type
     typedef typename F::result_type type;**
                                     ^
In file included from /usr/include/boost/function/detail/maybe_include.hpp:58:0,
                 from /usr/include/boost/function/detail/function_iterate.hpp:14,
                 from /usr/include/boost/preprocessor/iteration/detail/iter/forward1.hpp:92,
                 from /usr/include/boost/function.hpp:64,
                 from /opt/ros/kinetic/include/dynamic_reconfigure/server.h:48,
                 from /home/kal4-2/catkin_ws/src/spaceteam_ros_tool/src/perception/perception.hpp:3,
                 from /home/kal4-2/catkin_ws/src/spaceteam_ros_tool/src/perception/perception.cpp:1:
/usr/include/boost/function/function_template.hpp: In instantiation of ‘static void boost::detail::function::void_function_obj_invoker9<FunctionObj, R, T0, T1, T2, T3, T4, T5, T6, T7, T8>::invoke(boost::detail::function::function_buffer&, T0, T1, T2, T3, T4, T5, T6, T7, T8) [with FunctionObj = boost::_bi::bind_t<boost::_bi::unspecified, boost::_bi::bind_t<boost::_bi::unspecified, void (spaceteam_ros_tool::Perception::*)(boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&), boost::_bi::list2<boost::arg<1>, boost::arg<2> > >, boost::_bi::list9<boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>, boost::arg<7>, boost::arg<8>, boost::arg<9> > >; R = void; T0 = const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&; T1 = const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&; T2 = const boost::shared_ptr<const message_filters::NullType>&; T3 = const boost::shared_ptr<const message_filters::NullType>&; T4 = const boost::shared_ptr<const message_filters::NullType>&; T5 = const boost::shared_ptr<const message_filters::NullType>&; T6 = const boost::shared_ptr<const message_filters::NullType>&; T7 = const boost::shared_ptr<const message_filters::NullType>&; T8 = const boost::shared_ptr<const message_filters::NullType>&]’:
/usr/include/boost/function/function_template.hpp:940:38:   required from ‘void boost::function9<R, T1, T2, T3, T4, T5, T6, T7, T8, T9>::assign_to(Functor) [with Functor = boost::_bi::bind_t<boost::_bi::unspecified, boost::_bi::bind_t<boost::_bi::unspecified, void (spaceteam_ros_tool::Perception::*)(boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&), boost::_bi::list2<boost::arg<1>, boost::arg<2> > >, boost::_bi::list9<boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>, boost::arg<7>, boost::arg<8>, boost::arg<9> > >; R = void; T0 = const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&; T1 = const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&; T2 = const boost::shared_ptr<const message_filters::NullType>&; T3 = const boost::shared_ptr<const message_filters::NullType>&; T4 = const boost::shared_ptr<const message_filters::NullType>&; T5 = const boost::shared_ptr<const message_filters::NullType>&; T6 = const boost::shared_ptr<const message_filters::NullType>&; T7 = const boost::shared_ptr<const message_filters::NullType>&; T8 = const boost::shared_ptr<const message_filters::NullType>&]’
/usr/include/boost/function/function_template.hpp:728:7:   required from ‘boost::function9<R, T1, T2, T3, T4, T5, T6, T7, T8, T9>::function9(Functor, typename boost::enable_if_c<(boost::type_traits::ice_not<(boost::is_integral<Functor>::value)>::value), int>::type) [with Functor = boost::_bi::bind_t<boost::_bi::unspecified, boost::_bi::bind_t<boost::_bi::unspecified, void (spaceteam_ros_tool::Perception::*)(boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&), boost::_bi::list2<boost::arg<1>, boost::arg<2> > >, boost::_bi::list9<boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>, boost::arg<7>, boost::arg<8>, boost::arg<9> > >; R = void; T0 = const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&; T1 = const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&; T2 = const boost::shared_ptr<const message_filters::NullType>&; T3 = const boost::shared_ptr<const message_filters::NullType>&; T4 = const boost::shared_ptr<const message_filters::NullType>&; T5 = const boost::shared_ptr<const message_filters::NullType>&; T6 = const boost::shared_ptr<const message_filters::NullType>&; T7 = const boost::shared_ptr<const message_filters::NullType>&; T8 = const boost::shared_ptr<const message_filters::NullType>&; typename boost::enable_if_c<(boost::type_traits::ice_not<(boost::is_integral<Functor>::value)>::value), int>::type = int]’
/usr/include/boost/function/function_template.hpp:1077:16:   required from ‘boost::function<R(T0, T1, T2, T3, T4, T5, T6, T7, T8)>::function(Functor, typename boost::enable_if_c<(boost::type_traits::ice_not<(boost::is_integral<Functor>::value)>::value), int>::type) [with Functor = boost::_bi::bind_t<boost::_bi::unspecified, boost::_bi::bind_t<boost::_bi::unspecified, void (spaceteam_ros_tool::Perception::*)(boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&), boost::_bi::list2<boost::arg<1>, boost::arg<2> > >, boost::_bi::list9<boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>, boost::arg<7>, boost::arg<8>, boost::arg<9> > >; R = void; T0 = const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&; T1 = const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&; T2 = const boost::shared_ptr<const message_filters::NullType>&; T3 = const boost::shared_ptr<const message_filters::NullType>&; T4 = const boost::shared_ptr<const message_filters::NullType>&; T5 = const boost::shared_ptr<const message_filters::NullType>&; T6 = const boost::shared_ptr<const message_filters::NullType>&; T7 = const boost::shared_ptr<const message_filters::NullType>&; T8 = const boost::shared_ptr<const message_filters::NullType>&; typename boost::enable_if_c<(boost::type_traits::ice_not<(boost::is_integral<Functor>::value)>::value), int>::type = int]’
/opt/ros/kinetic/include/message_filters/signal9.h:281:40:   required from ‘message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(C&) [with C = const boost::_bi::bind_t<boost::_bi::unspecified, void (spaceteam_ros_tool::Perception::*)(boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&), boost::_bi::list2<boost::arg<1>, boost::arg<2> > >; M0 = sensor_msgs::Image_<std::allocator<void> >; M1 = sensor_msgs::Image_<std::allocator<void> >; M2 = message_filters::NullType; M3 = message_filters::NullType; M4 = message_filters::NullType; M5 = message_filters::NullType; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
/opt/ros/kinetic/include/message_filters/synchronizer.h:310:40:   required from ‘message_filters::Connection message_filters::Synchronizer<Policy>::registerCallback(const C&) [with C = boost::_bi::bind_t<boost::_bi::unspecified, void (spaceteam_ros_tool::Perception::*)(boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&), boost::_bi::list2<boost::arg<1>, boost::arg<2> > >; Policy = message_filters::sync_policies::ApproximateTime<sensor_msgs::Image_<std::allocator<void> >, sensor_msgs::Image_<std::allocator<void> > >]’
/home/kal4-2/catkin_ws/src/spaceteam_ros_tool/src/perception/perception.cpp:41:67:   required from here
/usr/include/boost/function/function_template.hpp:159:11: **error:** no match for call to ‘(boost::_bi::bind_t<boost::_bi::unspecified, boost::_bi::bind_t<boost::_bi::unspecified, void (spaceteam_ros_tool::Perception::*)(boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&), boost::_bi::list2<boost::arg<1>, boost::arg<2> > >, boost::_bi::list9<boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>, boost::arg<7>, boost::arg<8>, boost::arg<9> > >) (const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, const boost::shared_ptr<const sensor_msgs::Image_<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>&)’
           BOOST_FUNCTION_RETURN((*f)(BOOST_FUNCTION_ARGS));
           ^
make[2]: *** [CMakeFiles/spaceteam_ros_tool-perception-nodelet.dir/src/perception/perception.cpp.o] Error 1
make[2]: *** Waiting for unfinished jobs....
make[1]: *** [CMakeFiles/spaceteam_ros_tool-perception-nodelet.dir/all] Error 2
make: *** [all] Error 2

Asked by jlyw1017 on 2018-05-18 09:10:28 UTC

Comments

Answers

I solved this problem by

change this line

sync.registerCallback(boost::bind(&callbackSubscriber, _1, _2));

into

sync.registerCallback(boost::bind(& Perception::callbackSubscriber, this,_1, _2));

Asked by jlyw1017 on 2018-06-18 03:41:07 UTC

Comments