ros2 foxy订阅话题问题

代码片段

这部分代码在galactic版本编译是OK的,可在foxy下编译就出了问题

 TeleopPanel::TeleopPanel(QWidget* parent) : rviz_common::Panel(parent), playRate_(1.0)
 {
     signalPub_ = nh_->create_publisher<std_msgs::msg::Int16>("/pixel/lv/run_signal", 5);
     beginPub_ = nh_->create_publisher<std_msgs::msg::Float32>("/pixel/lv/begin_signal", 5);
     ratePub_ = nh_->create_publisher<std_msgs::msg::Float32>("/pixel/lv/rate_signal", 5);
 
     currTimeSub_ = nh_->create_subscription<std_msgs::msg::String>("/pixel/lv/current_time", 10, std::bind(&TeleopPanel::CurrTimeSub, this, std::placeholders::_1));
     selectPtSub_ = nh_->create_subscription<sensor_msgs::msg::PointCloud2>("/rviz_selected_points", 10, std::bind(&TeleopPanel::SelectPtSub, this, std::placeholders::_1));
 
     std::thread t(&TeleopPanel::StartSpin, this);
     t.detach();
 
     SetPanelLayout();
 }
 
 void TeleopPanel::CurrTimeSub(const std_msgs::msg::String& msg)
 {
     QString currTime = QString::fromStdString(msg.data);
     currentTimeEditor_->setText(currTime);
 }
 
 void TeleopPanel::SelectPtSub(const sensor_msgs::msg::PointCloud2& msg)
 {
     const auto ptsNum = msg.width;
     QString ptsNumQStr = QString::fromStdString(std::to_string(ptsNum));
     selectPtsEditor_->setText(ptsNumQStr);
 }

出错部分

两个create_subscription调用出错

 currTimeSub_ = nh_->create_subscription<std_msgs::msg::String>("/pixel/lv/current_time", 10, std::bind(&TeleopPanel::CurrTimeSub, this, std::placeholders::_1));
 selectPtSub_ = nh_->create_subscription<sensor_msgs::msg::PointCloud2>("/rviz_selected_points", 10, std::bind(&TeleopPanel::SelectPtSub, this, std::placeholders::_1));

create_subscription函数原型

 std::shared_ptr<SubscriptionT>
   create_subscription(
     const std::string & topic_name,
     const rclcpp::QoS & qos,
     CallbackT && callback,
     const SubscriptionOptionsWithAllocator<AllocatorT> & options =
     SubscriptionOptionsWithAllocator<AllocatorT>(),
     typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
       MessageMemoryStrategyT::create_default()
     )
   );

出错内容

下面是其中一部分报错内容

 // 报错一
 play_panel.cpp:26: error: no match for ‘operator= (operand types are ‘rclcpp::Subscription<sensor_msgs::msg::PointCloud2_<std::allocator<void> > >::SharedPtr’ {aka ‘std::shared_ptr<rclcpp::Subscription<sensor_msgs::msg::PointCloud2_<std::allocator<void> > > >} and ‘std::shared_ptr<rclcpp::Subscription<const sensor_msgs::msg::PointCloud2_<std::allocator<void> >&, std::allocator<void>, rclcpp::message_memory_strategy::MessageMemoryStrategy<const sensor_msgs::msg::PointCloud2_<std::allocator<void> >&, std::allocator<void> > > >)
    26 |     selectPtSub_ = nh_->create_subscription<sensor_msgs::msg::PointCloud2>("/rviz_selected_points", 10, std::bind(&TeleopPanel::SelectPtSub, this, std::placeholders::_1));
       |                                                                                                                                                                          ^
 // 报错二
 play_panel.cpp:26:25: error: no matching member function for call to 'create_subscription'
 node_impl.hpp:91:7: note: candidate template ignored: substitution failure [with MessageT = sensor_msgs::msg::PointCloud2_<std::allocator<void> >, CallbackT = std::_Bind<void (LidarViewRos2::RvizPlugin::TeleopPanel::*(LidarViewRos2::RvizPlugin::TeleopPanel *, std::_Placeholder<1>))(const sensor_msgs::msg::PointCloud2_<std::allocator<void> > &)>, AllocatorT = std::allocator<void>, CallbackMessageT = const sensor_msgs::msg::PointCloud2_<std::allocator<void> > &, SubscriptionT = rclcpp::Subscription<const sensor_msgs::msg::PointCloud2_<std::allocator<void> > &, std::allocator<void>, rclcpp::message_memory_strategy::MessageMemoryStrategy<const sensor_msgs::msg::PointCloud2_<std::allocator<void> > &, std::allocator<void> > >, MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<const sensor_msgs::msg::PointCloud2_<std::allocator<void> > &, std::allocator<void> >]
 
 // 报错三
 /opt/ros/foxy/include/rclcpp/subscription_factory.hpp:97: error: no matching function for call to ‘rclcpp::AnySubscriptionCallback<const sensor_msgs::msg::PointCloud2_<std::allocator<void> >&, std::allocator<void> >::set(std::_Bind<void (LidarViewRos2::RvizPlugin::TeleopPanel::*(LidarViewRos2::RvizPlugin::TeleopPanel*, std::_Placeholder<1>))(const sensor_msgs::msg::PointCloud2_<std::allocator<void> >&)>)
    97 |   any_subscription_callback.set(std::forward<CallbackT>(callback));
       |   ^~~~~~~~~~~~~~~~~~~~~~~~~
     
 // 报错四
 /usr/include/c++/9/ext/new_allocator.h:64: error: forming pointer to reference type ‘const sensor_msgs::msg::PointCloud2_<std::allocator<void> >&
 typedef const _Tp* const_pointer;

其实就是模板函数的原型不匹配导致的,CallbackT的模板参数需要传入指针类型才能正确解参数类型,传入引用类型是不对的

正确写法

只要把CurrTimeSubSelectPtSub两个函数的原型修改一下(入参改成指针)就OK了

 void TeleopPanel::CurrTimeSub(const std_msgs::msg::String::SharedPtr msg)
 {
     QString currTime = QString::fromStdString(msg->data);
     currentTimeEditor_->setText(currTime);
 }
 
 void TeleopPanel::SelectPtSub(const sensor_msgs::msg::PointCloud2::SharedPtr msg)
 {
     const auto ptsNum = msg->width;
     QString ptsNumQStr = QString::fromStdString(std::to_string(ptsNum));
     selectPtsEditor_->setText(ptsNumQStr);
 }

总结

foxygalactic及后续版本在create_subscription模板函数的实现有区别,移植的时候要注意兼容性,参考issue ros2 add arguments to callback - ROS Answers: Open Source Q&A Forum

阅读剩余
THE END