0
$\begingroup$

Rosanswers logo

Hello, I try my best to make my Issue clear:

main()

ros::NodeHandle node;
ros::Publisher pub_vt = node.advertise<ratslam_ros::ViewTemplate>(topic_root + "/LocalView/Template", 0);
ros::Subscriber sub = node.subscribe<uhf_rfid_api::UhfRfid>("messageepc", 0, boost::bind(rfid_callback, _1, &pub_vt));

and,my clallback function is:

void rfid_callback( uhf_rfid_api::UhfRfid rfid, ros::Publisher *pub_vt)
{
   do something;
}

And my error messages is:

/usr/include/boost/bind/bind.hpp:313:34: error: could not convert ‘(& a)->boost::_bi::list1<A1>::operator[]<const boost::shared_ptr<const uhf_rfid_api::UhfRfid_<std::allocator<void> > >&>(boost::_bi::storage1<boost::arg<I> >::a1_<1>)’ from ‘const boost::shared_ptr<const uhf_rfid_api::UhfRfid_<std::allocator<void> > >’ to ‘uhf_rfid_api::UhfRfid_<std::allocator<void> >’
         unwrapper<F>::unwrap(f, 0)(a[base_type::a1_], a[base_type::a2_]);

and candidates are:

    In file included from /usr/include/boost/bind.hpp:22:0,
                 from /usr/include/boost/multi_index/sequenced_index.hpp:42,
                 from /usr/include/boost/property_tree/ptree.hpp:23,
                 from /home/feixiao/catkin_ws/src/ratslam-ratslam_ros/src/utils/utils.h:32,
                 from /home/feixiao/catkin_ws/src/ratslam-ratslam_ros/src/main_lv.cpp:35:
    /usr/include/boost/bind/bind.hpp: In instantiation of ‘void boost::_bi::list2<A1, A2>::operator()(boost::_bi::type<void>, F&, A&, int) [with F = void (*)(uhf_rfid_api::UhfRfid_<std::allocator<void> >, ros::Publisher*); A = boost::_bi::list1<const boost::shared_ptr<const uhf_rfid_api::UhfRfid_<std::allocator<void> > >&>; A1 = boost::arg<1>; A2 = boost::_bi::value<ros::Publisher*>]’:
    /usr/include/boost/bind/bind_template.hpp:47:59:   required from ‘boost::_bi::bind_t<R, F, L>::result_type boost::_bi::bind_t<R, F, L>::operator()(const A1&) [with A1 = boost::shared_ptr<const uhf_rfid_api::UhfRfid_<std::allocator<void> > >; R = void; F = void (*)(uhf_rfid_api::UhfRfid_<std::allocator<void> >, ros::Publisher*); L = boost::_bi::list2<boost::arg<1>, boost::_bi::value<ros::Publisher*> >; boost::_bi::bind_t<R, F, L>::result_type = void]’
    /usr/include/boost/function/function_template.hpp:153:11:   required from ‘static void boost::detail::function::void_function_obj_invoker1<FunctionObj, R, T0>::invoke(boost::detail::function::function_buffer&, T0) [with FunctionObj = boost::_bi::bind_t<void, void (*)(uhf_rfid_api::UhfRfid_<std::allocator<void> >, ros::Publisher*), boost::_bi::list2<boost::arg<1>, boost::_bi::value<ros::Publisher*> > >; R = void; T0 = const boost::shared_ptr<const uhf_rfid_api::UhfRfid_<std::allocator<void> > >&]’
    /usr/include/boost/function/function_template.hpp:934:38:   required from ‘void boost::function1<R, T1>::assign_to(Functor) [with Functor = boost::_bi::bind_t<void, void (*)(uhf_rfid_api::UhfRfid_<std::allocator<void> >, ros::Publisher*), boost::_bi::list2<boost::arg<1>, boost::_bi::value<ros::Publisher*> > >; R = void; T0 = const boost::shared_ptr<const uhf_rfid_api::UhfRfid_<std::allocator<void> > >&]’
    /usr/include/boost/function/function_template.hpp:722:7:   required from ‘boost::function1<R, T1>::function1(Functor, typename boost::enable_if_c<boost::type_traits::ice_not<boost::is_integral<InputIterator>::value>::value, int>::type) [with Functor = boost::_bi::bind_t<void, void (*)(uhf_rfid_api::UhfRfid_<std::allocator<void> >, ros::Publisher*), boost::_bi::list2<boost::arg<1>, boost::_bi::value<ros::Publisher*> > >; R = void; T0 = const boost::shared_ptr<const uhf_rfid_api::UhfRfid_<std::allocator<void> > >&; typename boost::enable_if_c<boost::type_traits::ice_not<boost::is_integral<InputIterator>::value>::value, int>::type = int]’
    /usr/include/boost/function/function_template.hpp:1069:16:   required from ‘boost::function<R(T0)>::function(Functor, typename boost::enable_if_c<boost::type_traits::ice_not<boost::is_integral<InputIterator>::value>::value, int>::type) [with Functor = boost::_bi::bind_t<void, void (*)(uhf_rfid_api::UhfRfid_<std::allocator<void> >, ros::Publisher*), boost::_bi::list2<boost::arg<1>, boost::_bi::value<ros::Publisher*> > >; R = void; T0 = const boost::shared_ptr<const uhf_rfid_api::UhfRfid_<std::allocator<void> > >&; typename boost::enable_if_c<boost::type_traits::ice_not<boost::is_integral<InputIterator>::value>::value, int>::type = int]’
    /home/feixiao/catkin_ws/src/ratslam-ratslam_ros/src/main_lv.cpp:142:119:   required from here
    /usr/include/boost/bind/bind.hpp:313:34: error: could not convert ‘(& a)->boost::_bi::list1<A1>::operator[]<const boost::shared_ptr<const uhf_rfid_api::UhfRfid_<std::allocator<void> > >&>(boost::_bi::storage1<boost::arg<I> >::a1_<1>)’ from ‘const boost::shared_ptr<const uhf_rfid_api::UhfRfid_<std::allocator<void> > >’ to ‘uhf_rfid_api::UhfRfid_<std::allocator<void> >’
         unwrapper<F>::unwrap(f, 0)(a[base_type::a1_], a[base_type::a2_]);

I have read some other people's problems like: this and this link text

but it don`t work. can you give me some suggestion?

thank you


Originally posted by feixiao on ROS Answers with karma: 15 on 2015-07-23

Post score: 0


Original comments

Comment by allenh1 on 2015-07-23:
Is that really your callback function? It would be nice to see it if not... And if that is your callback, then the compiler is trying to do function pointers and the function to which they are pointing isn't valid. Comment out the line and compile.

Comment by feixiao on 2015-07-28:
thank you,i use a global variable and it works,although i don`t know why my BOOST::BIND is wrong yet.

Comment by allenh1 on 2015-07-28:
Wait... Why do you need to do a bind here?

Comment by cyborg-x1 on 2015-07-29:
Because he want(s/ed) to supply the publisher by the function call and in the function pointer. So making a double parameter function to a single parameter function by bind ... but actually when the publisher is global you do not need the bind anymore. Just supply the function name, remove pub param

Comment by cyborg-x1 on 2015-07-29:
One of my simplest nodes using a class, with directly publishing in the callback: https://github.com/Hacks4ROS/h4r_joysound/blob/develop/src/joysound_node.cpp

Comment by allenh1 on 2015-07-29:
That's what I figured. I don't use boost all that much. Pretty neat stuff.

Comment by cyborg-x1 on 2015-07-30:
Not when you're getting this errors... When I read them I am always like: WTF? :D

Comment by allenh1 on 2015-07-30:
Hahaha, yup. That's a pretty good description of it... It's at the very least intimidating. XD

Comment by feixiao on 2015-08-02:
haha, it's she:^)and you are sooo funny. i use it because i read someones code and he use it. but global var is a better way

Comment by allenh1 on 2015-08-02:
Agreed! And our apologies! It's quite nice to have some women in this forum! Welcome aboard. :)

Comment by feixiao on 2015-08-02:
O(∩_∩)O thank you

$\endgroup$

2 Answers 2

0
$\begingroup$

Rosanswers logo

pay attention to

/home/feixiao/catkin_ws/src/ratslam-ratslam_ros/src/main_lv.cpp:142:119:   required from here
    /usr/include/boost/bind/bind.hpp:313:34: error: could not convert ‘(& a)->boost::_bi::list1<A1>::operator[]<const boost::shared_ptr<const uhf_rfid_api::UhfRfid_<std::allocator<void> > >&>(boost::_bi::storage1<boost::arg<I> >::a1_<1>)’ from ‘const boost::shared_ptr<const uhf_rfid_api::UhfRfid_<std::allocator<void> > >’ to ‘uhf_rfid_api::UhfRfid_<std::allocator<void> >’

change your callback function to

void rfid_callback( const uhf_rfid_api::UhfRfid::ConstPtr& rfid, ros::Publisher *pub_vt)
{
   do something;
}

when you declare your subscriber and publisher

ros::NodeHandle node;
ros::Publisher pub_vt = node.advertise<ratslam_ros::ViewTemplate>(topic_root + "/LocalView/Template", 0);
ros::Subscriber sub = node.subscribe<uhf_rfid_api::UhfRfid>("messageepc", 0, boost::bind(&rfid_callback, _1, &pub_vt));

Originally posted by tianb03 with karma: 710 on 2016-01-21

This answer was ACCEPTED on the original site

Post score: 3


Original comments

Comment by feixiao on 2016-01-21:
awesome! I should add a const before uhf_rfid_api, it works!!!thanks a lot

Comment by feixiao on 2016-01-25:
ok,I knew why that I have to declare a const before my message datatype,the definition of the publisher advertise is: Publisher advertise(const std::string& topic, uint32_t queue_size, bool latch = false) and the callback is: void Foo::callback(const std_msgs::Empty::ConstPtr& message)

Comment by feixiao on 2016-01-25:
the definition of ConstPtr is typedef boost::shared_ptr VoidConstPtr; so ConstPtr just a declare right?

Comment by Arthur_Ace on 2019-02-26:
Still relevant in 2019, thanks my man!

Comment by tianb03 on 2019-03-02:
LOL, my pleasure!

$\endgroup$
0
$\begingroup$

Rosanswers logo

I would either recommend you using a global publisher variable for simple nodes, or in a class doing the publisher with a member variable. In both of these ways you would not need that pointer to the publisher in the callback function header.


Originally posted by cyborg-x1 with karma: 1376 on 2015-07-23

This answer was NOT ACCEPTED on the original site

Post score: 1

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.