在使用ros寫訂閱者時,代碼如下:
#include "ros/ros.h" #include "std_msgs/String.h" #include <boost/thread.hpp> #include <sensor_msgs/PointCloud2.h> #include <nav_msgs/Odometry.h> #include <typeinfo> class multiThreadListener { public: void chatterCallback1(const nav_msgs::Odometry::ConstPtr &input_msg, std::string topicName); void chatterCallback2(const sensor_msgs::PointCloud2ConstPtr& input_msg, std::string topicName); multiThreadListener(); private: ros::NodeHandle n; std::string name1; std::string name2; ros::Subscriber sub1; ros::Subscriber sub2; }; multiThreadListener::multiThreadListener() { name1 = "/navsat/odom"; name2 = "/radar_cloud"; sub1 = n.subscribe("/navsat/odom", 10, boost::bind(&multiThreadListener::chatterCallback1, this, _1, name1)); sub2 = n.subscribe("/radar_cloud", 10, boost::bind(&multiThreadListener::chatterCallback2, this,_1, name2)); } void multiThreadListener::chatterCallback1(const nav_msgs::Odometry::ConstPtr &input_msg, std::string topicName) { ROS_INFO("I heard: [%s]", topicName); ros::Rate loop_rate(0.5);//block chatterCallback1() loop_rate.sleep(); } void multiThreadListener::chatterCallback2(const sensor_msgs::PointCloud2ConstPtr& input_msg, std::string topicName) { ROS_INFO("I heard: [%s]", topicName); ros::Rate loop_rate(0.5);//block chatterCallback2() loop_rate.sleep(); } int main(int argc, char **argv) { ros::init(argc, argv, "multi_sub"); multiThreadListener listener_obj; ros::MultiThreadedSpinner s(2); ros::spin(s); return 0; }
編譯總是報如下錯,
error: no matching function for call to ‘ros::NodeHandle::subscribe(const char [13], int, boost::_bi::bind_t<void, boost::_mfi::mf2<void, multiThreadListener,
const boost::shared_ptr<const nav_msgs::Odometry_<std::allocator<void> > >&, std::__cxx11::basic_string<char> >, boost::_bi::list3<boost::_bi::value<multiThreadListener*>,
boost::arg<1>, boost::_bi::value<std::__cxx11::basic_string<char> > > >)’ sub1 = n.subscribe("/navsat/odom", 10, boost::bind(&multiThreadListener::chatterCallback1, this, _1, name1));
原因是subscribe()函數在使用函數對象時,如boost::bind()函數返回的對象,必須要明確指定消息類型作為模板參數,因為編譯器無法推斷它。
上面就是沒有指明導致的錯誤。
在查看NodeHandle.h源碼查看subscribe()函數的定義如下
template<class M, class T> Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M), T* obj, const TransportHints& transport_hints = TransportHints()) { ... } template<class M, class T> Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr<M const>&), T* obj, const TransportHints& transport_hints = TransportHints()) { ... } template<class M, class T> Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M), const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints()) { ... } template<class M, class T> Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr<M const>&), const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints()) { ... } template<class M> Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(*fp)(M), const TransportHints& transport_hints = TransportHints()) { ... } template<class M> Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(*fp)(const boost::shared_ptr<M const>&), const TransportHints& transport_hints = TransportHints()) { ... } template<class M> Subscriber subscribe(const std::string& topic, uint32_t queue_size, const boost::function<void (const boost::shared_ptr<M const>&)>& callback, const VoidConstPtr& tracked_object = VoidConstPtr(), const TransportHints& transport_hints = TransportHints()) { ... } template<class M, class C> Subscriber subscribe(const std::string& topic, uint32_t queue_size, const boost::function<void (C)>& callback, const VoidConstPtr& tracked_object = VoidConstPtr(), const TransportHints& transport_hints = TransportHints()) { ... }
很顯然,subscribe是模板函數,在傳入boost::function類型時,需要傳入模板參數,上面的代碼
sub2 = n.subscribe("/radar_cloud", 10, boost::bind(&multiThreadListener::chatterCallback2, this,_1, name2));
傳入了三個參數,第三個參數中的chatterCallback2()的第一個參數時sensor_msgs::PointCloud2ConstPtr,其定義是
typedef boost::shared_ptr< ::sensor_msgs::PointCloud2 const> sensor_msgs::PointCloud2ConstPtr
顯然,上面代碼使用的subscribe()函數是下面這個版本
template<class M> Subscriber subscribe(const std::string& topic, uint32_t queue_size, const boost::function<void (const boost::shared_ptr<M const>&)>& callback, const VoidConstPtr& tracked_object = VoidConstPtr(), const TransportHints& transport_hints = TransportHints()) { ... }
故,正確的代碼應該如下
#include "ros/ros.h" #include "std_msgs/String.h" #include <boost/thread.hpp> #include <sensor_msgs/PointCloud2.h> #include <nav_msgs/Odometry.h> #include <typeinfo> class multiThreadListener { public: void chatterCallback1(const nav_msgs::Odometry::ConstPtr &input_msg, std::string topicName); void chatterCallback2(const sensor_msgs::PointCloud2ConstPtr& input_msg, std::string topicName); multiThreadListener(); private: ros::NodeHandle n; std::string name1; std::string name2; ros::Subscriber sub1; ros::Subscriber sub2; }; multiThreadListener::multiThreadListener() { name1 = "/navsat/odom"; name2 = "/radar_cloud"; sub1 = n.subscribe<nav_msgs::Odometry>("/navsat/odom", 10, boost::bind(&multiThreadListener::chatterCallback1, this, _1, name1)); sub2 = n.subscribe<sensor_msgs::PointCloud2>("/radar_cloud", 10, boost::bind(&multiThreadListener::chatterCallback2, this,_1, name2)); } void multiThreadListener::chatterCallback1(const nav_msgs::Odometry::ConstPtr &input_msg, std::string topicName) { ROS_INFO("I heard: [%s]", topicName); ros::Rate loop_rate(0.5);//block chatterCallback1() loop_rate.sleep(); } void multiThreadListener::chatterCallback2(const sensor_msgs::PointCloud2ConstPtr& input_msg, std::string topicName) { ROS_INFO("I heard: [%s]", topicName); ros::Rate loop_rate(0.5);//block chatterCallback2() loop_rate.sleep(); } int main(int argc, char **argv) { ros::init(argc, argv, "multi_sub"); multiThreadListener listener_obj; ros::MultiThreadedSpinner s(2); ros::spin(s); return 0; }
編譯通過。