鱼香ROS社区
    • 版块
    • 最新
    • 未解决
    • 已解决
    • 群组
    • 注册
    • 登录
    紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
    提问前必看的发帖注意事项: 社区问答规则(小鱼个人)更新 | 高质量帖子发布指南

    ros2订阅pointcloud2话题出错

    已定时 已固定 已锁定 已移动 已解决
    综合问题
    ros2 pclviewer
    2
    12
    1.8k
    正在加载更多帖子
    • 从旧到新
    • 从新到旧
    • 最多赞同
    回复
    • 在新帖中回复
    登录后回复
    此主题已被删除。只有拥有主题管理权限的用户可以查看。
    • 9720322329
      -
      最后由 小鱼 编辑

      #include "rclcpp/rclcpp.hpp"
      #include "sensor_msgs/msg/point_cloud2.hpp"
      #include "std_msgs/msg/string.hpp"
      #include "std_msgs/msg/u_int32.hpp"
      #include <iostream>
      #include <pcl/point_cloud.h>
      #include <pcl/point_types.h>
      #include <pcl/common/common.h>
      #include <pcl/io/pcd_io.h>
      #include <pcl_conversions/pcl_conversions.h>
      using std::placeholders::_1;
      
      class SingleDogNode : public rclcpp::Node
      {
      
      public:
      SingleDogNode()
      : Node("name")
      {
      sub_novel = this->create_subscription<sensor_msgs::msg::PointCloud2>("sexy_girl", 10, std::bind(&SingleDogNode::topic_callback, this, _1));
      }
      
      private:
      // 声明一个订阅者(成员变量),用于订阅小说
      rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr sub_novel;
      
      // 收到话题数据的回调函数
      void topic_callback(const sensor_msgs::msg::PointCloud2::SharedPtr msg)
      {
      pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudPtr(new pcl::PointCloud<pcl::PointXYZRGB>);
      pcl::fromROSMsg(*msg,*cloudPtr);
      std::cout << "滤波前点云有: " << cloudPtr->points.size () << " 个点。" << std::endl;
      };
      
      };
      
      int main(int argc, char **argv)
      {
      rclcpp::init(argc, argv);
      rclcpp::spin(std::make_shared<SingleDogNode>());
      rclcpp::shutdown();
      return 0;
      }
      
      小鱼小 1 条回复 最后回复 回复 引用 0
      • 9720322329
        - @小鱼
        最后由 编辑

        @小鱼 好的鱼哥,下次我发帖注意哈哈,明天我试试这行代码

        1 条回复 最后回复 回复 引用 0
        • 小鱼小
          小鱼 技术大佬 @972032232
          最后由 小鱼 编辑

          @972032232 一看就是发帖前必看没有看,我帮你修改好了格式~

          提前安装依赖

          sudo apt install ros-foxy-pcl*
          

          文件1:src/subscription_pcl.cpp

          #include "rclcpp/rclcpp.hpp"
          #include "sensor_msgs/msg/point_cloud2.hpp"
          #include <iostream>
          #include <pcl/point_cloud.h>
          #include <pcl/point_types.h>
          #include <pcl/common/common.h>
          #include <pcl/io/pcd_io.h>
          #include <pcl_conversions/pcl_conversions.h>
          
          class PclSub : public rclcpp::Node
          {
          
          public:
              PclSub(std::string name)
                  : Node(name)
              {
                  using std::placeholders::_1;
                  sub_novel = this->create_subscription<sensor_msgs::msg::PointCloud2>("sexy_girl", 10, std::bind(&PclSub::topic_callback, this, std::placeholders::_1));
              }
          
          private:
              rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr sub_novel;
          
              void topic_callback(const sensor_msgs::msg::PointCloud2::SharedPtr msg)
              {
                  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud =
                      boost::make_shared<pcl::PointCloud<pcl::PointXYZRGB>>();
                  pcl::fromROSMsg(*msg, *cloud);
                  RCLCPP_INFO(this->get_logger(), "points_size(%d,%d)",msg->height,msg->width);
              };
          };
          
          int main(int argc, char **argv)
          {
              rclcpp::init(argc, argv);
              auto node = std::make_shared<PclSub>("pclsub");
              rclcpp::spin(node);
              rclcpp::shutdown();
              return 0;
          }
          

          文件2:CMakeLists.txt

          cmake_minimum_required(VERSION 3.5)
          project(ros2pcl_test)
          
          # Default to C99
          if(NOT CMAKE_C_STANDARD)
            set(CMAKE_C_STANDARD 99)
          endif()
          
          # Default to C++14
          if(NOT CMAKE_CXX_STANDARD)
            set(CMAKE_CXX_STANDARD 14)
          endif()
          
          if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
            add_compile_options(-Wall -Wextra -Wpedantic)
          endif()
          
          # find dependencies
          find_package(ament_cmake REQUIRED)
          find_package(sensor_msgs REQUIRED)
          find_package(rclcpp REQUIRED)
          find_package(PCL REQUIRED)
          
          if(BUILD_TESTING)
            find_package(ament_lint_auto REQUIRED)
            # the following line skips the linter which checks for copyrights
            # uncomment the line when a copyright and license is not present in all source files
            #set(ament_cmake_copyright_FOUND TRUE)
            # the following line skips cpplint (only works in a git repo)
            # uncomment the line when this package is not in a git repo
            #set(ament_cmake_cpplint_FOUND TRUE)
            ament_lint_auto_find_test_dependencies()
          endif()
          
          add_executable(ros2pcl_test_sub 
            src/subscription_pcl.cpp
          )
          ament_target_dependencies(ros2pcl_test_sub 
            rclcpp 
            sensor_msgs
            PCL
          )
          
          ament_package()
          

          新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

          9720322329 1 条回复 最后回复 回复 引用 0
          • 9720322329
            - @小鱼
            最后由 编辑

            @小鱼 好的鱼哥,下次我发帖注意哈哈,明天我试试这行代码

            1 条回复 最后回复 回复 引用 0
            • 9720322329
              -
              最后由 972032232 编辑

              #include "rclcpp/rclcpp.hpp"
              #include "sensor_msgs/msg/point_cloud2.hpp"
              #include <iostream>
              #include <pcl/point_cloud.h>
              #include <pcl/point_types.h>
              #include <pcl/common/common.h>
              #include <pcl/io/pcd_io.h>
              #include <pcl_conversions/pcl_conversions.h>
              using std::placeholders::_1;
              
              class PclSub : public rclcpp::Node
              {
              
              public:
                  PclSub()
                      : Node("name")
                  {
                      sub_novel = this->create_subscription<sensor_msgs::msg::PointCloud2>("sexy_girl", 10, std::bind(&PclSub::topic_callback, this, _1));
                  }
              
              private:
                  rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr sub_novel;
              
                  void topic_callback(const sensor_msgs::msg::PointCloud2::SharedPtr msg)
                  {
                      pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud =
                          boost::make_shared<pcl::PointCloud<pcl::PointXYZRGB>>();
                      pcl::fromROSMsg(*msg, *cloud);
                      
                  };
              };
              
              int main(int argc, char **argv)
              {
                  rclcpp::init(argc, argv);
                  rclcpp::spin(std::make_shared<PclSub>("pclsub"));
                  rclcpp::shutdown();
                  return 0;
              }
              

              这是cpp文件。

              cmake_minimum_required(VERSION 3.5)
              project(ros_ws)
              
              # Default to C99
              if(NOT CMAKE_C_STANDARD)
                set(CMAKE_C_STANDARD 99)
              endif()
              
              # Default to C++14
              if(NOT CMAKE_CXX_STANDARD)
                set(CMAKE_CXX_STANDARD 14)
              endif()
              
              if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
                add_compile_options(-Wall -Wextra -Wpedantic)
              endif()
              
              # find dependencies
              find_package(ament_cmake REQUIRED)
              find_package(rclcpp REQUIRED)
              find_package(sensor_msgs REQUIRED)
              find_package(pcl_conversions REQUIRED)
              find_package(pcl_ros REQUIRED)
              
              
              if(BUILD_TESTING)
                find_package(ament_lint_auto REQUIRED)
                # the following line skips the linter which checks for copyrights
                # uncomment the line when a copyright and license is not present in all source files
                #set(ament_cmake_copyright_FOUND TRUE)
                # the following line skips cpplint (only works in a git repo)
                # uncomment the line when this package is not in a git repo
                #set(ament_cmake_cpplint_FOUND TRUE)
                ament_lint_auto_find_test_dependencies()
              endif()
              add_executable(ros2pcl_test_sub 
                src/subscription_pcl.cpp
              )
              ament_target_dependencies(ros2pcl_test_sub 
                rclcpp 
                sensor_msgs
                pcl_ros
                pcl_conversions
              )
              
              
              ament_package()
              

              这是cmake文件

              Starting >>> ros_ws  
              --- stderr: ros_ws                             
              /home/a/ros2_ws/src/ros_ws/src/subscription_pcl.cpp: In constructor ‘PclSub::PclSub()’:
              /home/a/ros2_ws/src/ros_ws/src/subscription_pcl.cpp:18:136: error: reference to ‘_1’ is ambiguous
                 18 | 2>("sexy_girl", 10, std::bind(&PclSub::topic_callback, this, _1));
                    |                                                              ^~
              
              In file included from /usr/include/boost/bind/bind.hpp:2356,
                               from /usr/include/boost/bind.hpp:22,
                               from /usr/include/boost/signals2/slot.hpp:15,
                               from /usr/include/boost/signals2/connection.hpp:24,
                               from /usr/include/boost/signals2/signal.hpp:22,
                               from /usr/include/boost/signals2.hpp:19,
                               from /usr/include/pcl-1.10/pcl/io/boost.h:64,
                               from /usr/include/pcl-1.10/pcl/io/file_io.h:42,
                               from /usr/include/pcl-1.10/pcl/io/pcd_io.h:44,
                               from /home/a/ros2_ws/src/ros_ws/src/subscription_pcl.cpp:7:
              /usr/include/boost/bind/placeholders.hpp:46:38: note: candidates are: ‘constexpr const boost::arg<1> boost::placeholders::_1’
                 46 | BOOST_STATIC_CONSTEXPR boost::arg<1> _1;
                    |                                      ^~
              In file included from /opt/ros/foxy/include/rclcpp/context.hpp:19,
                               from /opt/ros/foxy/include/rclcpp/contexts/default_context.hpp:18,
                               from /opt/ros/foxy/include/rclcpp/executor.hpp:32,
                               from /opt/ros/foxy/include/rclcpp/executors/multi_threaded_executor.hpp:26,
                               from /opt/ros/foxy/include/rclcpp/executors.hpp:21,
                               from /opt/ros/foxy/include/rclcpp/rclcpp.hpp:146,
                               from /home/a/ros2_ws/src/ros_ws/src/subscription_pcl.cpp:1:
              /usr/include/c++/9/functional:211:34: note:                 ‘const std::_Placeholder<1> std::placeholders::_1’
                211 |     extern const _Placeholder<1> _1;
                    |                                  ^~
              /home/a/ros2_ws/src/ros_ws/src/subscription_pcl.cpp: In member function ‘void PclSub::topic_callback(sensor_msgs::msg::PointCloud2_<std::allocator<void> >::SharedPtr)’:
              /home/a/ros2_ws/src/ros_ws/src/subscription_pcl.cpp:24:72: warning: unused parameter ‘msg’ [-Wunused-parameter]
                 24 |     void topic_callback(const sensor_msgs::msg::PointCloud2::SharedPtr msg)
                    |                         ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~^~~
              In file included from /usr/include/x86_64-linux-gnu/c++/9/bits/c++allocator.h:33,
                               from /usr/include/c++/9/bits/allocator.h:46,
                               from /usr/include/c++/9/memory:63,
                               from /opt/ros/foxy/include/rclcpp/rclcpp.hpp:144,
                               from /home/a/ros2_ws/src/ros_ws/src/subscription_pcl.cpp:1:
              /usr/include/c++/9/ext/new_allocator.h: In instantiation of ‘void __gnu_cxx::new_allocator<_Tp>::construct(_Up*, _Args&& ...) [with _Up = PclSub; _Args = {const char (&)[7]}; _Tp = PclSub]’:
              /usr/include/c++/9/bits/alloc_traits.h:483:4:   required from ‘static void std::allocator_traits<std::allocator<_Tp1> >::construct(std::allocator_traits<std::allocator<_Tp1> >::allocator_type&, _Up*, _Args&& ...) [with _Up = PclSub; _Args = {const char (&)[7]}; _Tp = PclSub; std::allocator_traits<std::allocator<_Tp1> >::allocator_type = std::allocator<PclSub>]’
              /usr/include/c++/9/bits/shared_ptr_base.h:548:39:   required from ‘std::_Sp_counted_ptr_inplace<_Tp, _Alloc, _Lp>::_Sp_counted_ptr_inplace(_Alloc, _Args&& ...) [with _Args = {const char (&)[7]}; _Tp = PclSub; _Alloc = std::allocator<PclSub>; __gnu_cxx::_Lock_policy _Lp = __gnu_cxx::_S_atomic]’
              /usr/include/c++/9/bits/shared_ptr_base.h:679:16:   required from ‘std::__shared_count<_Lp>::__shared_count(_Tp*&, std::_Sp_alloc_shared_tag<_Alloc>, _Args&& ...) [with _Tp = PclSub; _Alloc = std::allocator<PclSub>; _Args = {const char (&)[7]}; __gnu_cxx::_Lock_policy _Lp = __gnu_cxx::_S_atomic]’
              /usr/include/c++/9/bits/shared_ptr_base.h:1344:71:   required from ‘std::__shared_ptr<_Tp, _Lp>::__shared_ptr(std::_Sp_alloc_shared_tag<_Tp>, _Args&& ...) [with _Alloc = std::allocator<PclSub>; _Args = {const char (&)[7]}; _Tp = PclSub; __gnu_cxx::_Lock_policy _Lp = __gnu_cxx::_S_atomic]’
              /usr/include/c++/9/bits/shared_ptr.h:359:59:   required from ‘std::shared_ptr<_Tp>::shared_ptr(std::_Sp_alloc_shared_tag<_Tp>, _Args&& ...) [with _Alloc = std::allocator<PclSub>; _Args = {const char (&)[7]}; _Tp = PclSub]’
              /usr/include/c++/9/bits/shared_ptr.h:701:14:   required from ‘std::shared_ptr<_Tp> std::allocate_shared(const _Alloc&, _Args&& ...) [with _Tp = PclSub; _Alloc = std::allocator<PclSub>; _Args = {const char (&)[7]}]’
              /usr/include/c++/9/bits/shared_ptr.h:717:39:   required from ‘std::shared_ptr<_Tp> std::make_shared(_Args&& ...) [with _Tp = PclSub; _Args = {const char (&)[7]}]’
              /home/a/ros2_ws/src/ros_ws/src/subscription_pcl.cpp:33:51:   required from here
              /usr/include/c++/9/ext/new_allocator.h:146:4: error: no matching function for call to ‘PclSub::PclSub(const char [7])’
                146 |  { ::new((void *)__p) _Up(std::forward<_Args>(__args)...); }
                    |    ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
              /home/a/ros2_ws/src/ros_ws/src/subscription_pcl.cpp:15:5: note: candidate: ‘PclSub::PclSub()’
                 15 |     PclSub()
                    |     ^~~~~~
              /home/a/ros2_ws/src/ros_ws/src/subscription_pcl.cpp:15:5: note:   candidate expects 0 arguments, 1 provided
              make[2]: *** [CMakeFiles/ros2pcl_test_sub.dir/build.make:63:CMakeFiles/ros2pcl_test_sub.dir/src/subscription_pcl.cpp.o] 错误 1
              make[1]: *** [CMakeFiles/Makefile2:78:CMakeFiles/ros2pcl_test_sub.dir/all] 错误 2
              make: *** [Makefile:141:all] 错误 2
              ---
              Failed   <<< ros_ws [4.91s, exited with code 2]
              
              Summary: 0 packages finished [5.06s]
                1 package failed: ros_ws
                1 package had stderr output: ros_ws
              
              

              我不太明白问题出现在了哪里,也总是解决不了,我尝试把 46 | BOOST_STATIC_CONSTEXPR boost::arg<1> _1;文件这条注释掉,他仍然不可运行

              小鱼小 1 条回复 最后回复 回复 引用 0
              • 9720322329 972032232 将这个主题标记为已解决,在
              • 小鱼小
                小鱼 技术大佬 @972032232
                最后由 编辑

                @972032232 你用的PCL哪个版本的

                新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

                9720322329 2 条回复 最后回复 回复 引用 0
                • 9720322329
                  - @小鱼
                  最后由 编辑

                  @小鱼 用的ros2环境中的pcl,应该是1.10

                  1 条回复 最后回复 回复 引用 0
                  • 9720322329
                    - @小鱼
                    最后由 编辑

                    @小鱼 就是foxy自带的pcl 1.10,pcl_ros和conversions是我用apt下载的,命令是 sudo apt install ros-foxy-pcl*

                    小鱼小 1 条回复 最后回复 回复 引用 0
                    • 小鱼小
                      小鱼 技术大佬 @972032232
                      最后由 编辑

                      @972032232 更新了下代码,你再试试

                      @小鱼 在 ros2订阅pointcloud2话题出错 中说:

                      @972032232 一看就是发帖前必看没有看,我帮你修改好了格式~

                      提前安装依赖

                      sudo apt install ros-foxy-pcl*
                      

                      文件1:src/subscription_pcl.cpp

                      #include "rclcpp/rclcpp.hpp"
                      #include "sensor_msgs/msg/point_cloud2.hpp"
                      #include <iostream>
                      #include <pcl/point_cloud.h>
                      #include <pcl/point_types.h>
                      #include <pcl/common/common.h>
                      #include <pcl/io/pcd_io.h>
                      #include <pcl_conversions/pcl_conversions.h>
                      
                      class PclSub : public rclcpp::Node
                      {
                      
                      public:
                          PclSub(std::string name)
                              : Node(name)
                          {
                              using std::placeholders::_1;
                              sub_novel = this->create_subscription<sensor_msgs::msg::PointCloud2>("sexy_girl", 10, std::bind(&PclSub::topic_callback, this, std::placeholders::_1));
                          }
                      
                      private:
                          rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr sub_novel;
                      
                          void topic_callback(const sensor_msgs::msg::PointCloud2::SharedPtr msg)
                          {
                              pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud =
                                  boost::make_shared<pcl::PointCloud<pcl::PointXYZRGB>>();
                              pcl::fromROSMsg(*msg, *cloud);
                              RCLCPP_INFO(this->get_logger(), "points_size(%d,%d)",msg->height,msg->width);
                          };
                      };
                      
                      int main(int argc, char **argv)
                      {
                          rclcpp::init(argc, argv);
                          auto node = std::make_shared<PclSub>("pclsub");
                          rclcpp::spin(node);
                          rclcpp::shutdown();
                          return 0;
                      }
                      

                      文件2:CMakeLists.txt

                      cmake_minimum_required(VERSION 3.5)
                      project(ros2pcl_test)
                      
                      # Default to C99
                      if(NOT CMAKE_C_STANDARD)
                        set(CMAKE_C_STANDARD 99)
                      endif()
                      
                      # Default to C++14
                      if(NOT CMAKE_CXX_STANDARD)
                        set(CMAKE_CXX_STANDARD 14)
                      endif()
                      
                      if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
                        add_compile_options(-Wall -Wextra -Wpedantic)
                      endif()
                      
                      # find dependencies
                      find_package(ament_cmake REQUIRED)
                      find_package(sensor_msgs REQUIRED)
                      find_package(rclcpp REQUIRED)
                      find_package(PCL REQUIRED)
                      
                      if(BUILD_TESTING)
                        find_package(ament_lint_auto REQUIRED)
                        # the following line skips the linter which checks for copyrights
                        # uncomment the line when a copyright and license is not present in all source files
                        #set(ament_cmake_copyright_FOUND TRUE)
                        # the following line skips cpplint (only works in a git repo)
                        # uncomment the line when this package is not in a git repo
                        #set(ament_cmake_cpplint_FOUND TRUE)
                        ament_lint_auto_find_test_dependencies()
                      endif()
                      
                      add_executable(ros2pcl_test_sub 
                        src/subscription_pcl.cpp
                      )
                      ament_target_dependencies(ros2pcl_test_sub 
                        rclcpp 
                        sensor_msgs
                        PCL
                      )
                      
                      ament_package()
                      

                      新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

                      9720322329 1 条回复 最后回复 回复 引用 0
                      • 9720322329
                        - @小鱼
                        最后由 编辑

                        @小鱼 我好像又遇到新问题了,在我打算将接受的点云保存为实时点云时,添加了

                        pcl::io::savePCDFileASCII ("asd.pcd", *cloud);
                        

                        结果在编译时候报错

                        /usr/bin/ld: CMakeFiles/ros2pcl_test_sub.dir/src/subscription_pcl.cpp.o: in function `pcl::PCDWriter::write(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, pcl::PCLPointCloud2 const&, Eigen::Matrix<float, 4, 1, 0, 4, 1> const&, Eigen::Quaternion<float, 0> const&, bool)':
                        subscription_pcl.cpp:(.text._ZN3pcl9PCDWriter5writeERKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_14PCLPointCloud2ERKN5Eigen6MatrixIfLi4ELi1ELi0ELi4ELi1EEERKNSC_10QuaternionIfLi0EEEb[_ZN3pcl9PCDWriter5writeERKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_14PCLPointCloud2ERKN5Eigen6MatrixIfLi4ELi1ELi0ELi4ELi1EEERKNSC_10QuaternionIfLi0EEEb]+0x47): undefined reference to `pcl::PCDWriter::writeBinary(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, pcl::PCLPointCloud2 const&, Eigen::Matrix<float, 4, 1, 0, 4, 1> const&, Eigen::Quaternion<float, 0> const&)'
                        /usr/bin/ld: subscription_pcl.cpp:(.text._ZN3pcl9PCDWriter5writeERKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_14PCLPointCloud2ERKN5Eigen6MatrixIfLi4ELi1ELi0ELi4ELi1EEERKNSC_10QuaternionIfLi0EEEb[_ZN3pcl9PCDWriter5writeERKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_14PCLPointCloud2ERKN5Eigen6MatrixIfLi4ELi1ELi0ELi4ELi1EEERKNSC_10QuaternionIfLi0EEEb]+0x6e): undefined reference to `pcl::PCDWriter::writeASCII(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, pcl::PCLPointCloud2 const&, Eigen::Matrix<float, 4, 1, 0, 4, 1> const&, Eigen::Quaternion<float, 0> const&, int)'
                        /usr/bin/ld: CMakeFiles/ros2pcl_test_sub.dir/src/subscription_pcl.cpp.o: in function `int pcl::PCDWriter::writeBinary<pcl::PointXYZRGB>(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, pcl::PointCloud<pcl::PointXYZRGB> const&)':
                        subscription_pcl.cpp:(.text._ZN3pcl9PCDWriter11writeBinaryINS_11PointXYZRGBEEEiRKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_10PointCloudIT_EE[_ZN3pcl9PCDWriter11writeBinaryINS_11PointXYZRGBEEEiRKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_10PointCloudIT_EE]+0x27b): undefined reference to `pcl::PCDWriter::setLockingPermissions(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, boost::interprocess::file_lock&)'
                        /usr/bin/ld: subscription_pcl.cpp:(.text._ZN3pcl9PCDWriter11writeBinaryINS_11PointXYZRGBEEEiRKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_10PointCloudIT_EE[_ZN3pcl9PCDWriter11writeBinaryINS_11PointXYZRGBEEEiRKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_10PointCloudIT_EE]+0x487): undefined reference to `pcl::PCDWriter::resetLockingPermissions(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, boost::interprocess::file_lock&)'
                        /usr/bin/ld: subscription_pcl.cpp:(.text._ZN3pcl9PCDWriter11writeBinaryINS_11PointXYZRGBEEEiRKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_10PointCloudIT_EE[_ZN3pcl9PCDWriter11writeBinaryINS_11PointXYZRGBEEEiRKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_10PointCloudIT_EE]+0x5c4): undefined reference to `pcl::PCDWriter::resetLockingPermissions(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, boost::interprocess::file_lock&)'
                        /usr/bin/ld: subscription_pcl.cpp:(.text._ZN3pcl9PCDWriter11writeBinaryINS_11PointXYZRGBEEEiRKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_10PointCloudIT_EE[_ZN3pcl9PCDWriter11writeBinaryINS_11PointXYZRGBEEEiRKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_10PointCloudIT_EE]+0x8bc): undefined reference to `pcl::PCDWriter::resetLockingPermissions(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, boost::interprocess::file_lock&)'
                        /usr/bin/ld: subscription_pcl.cpp:(.text._ZN3pcl9PCDWriter11writeBinaryINS_11PointXYZRGBEEEiRKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_10PointCloudIT_EE[_ZN3pcl9PCDWriter11writeBinaryINS_11PointXYZRGBEEEiRKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_10PointCloudIT_EE]+0x978): undefined reference to `pcl::PCDWriter::resetLockingPermissions(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, boost::interprocess::file_lock&)'
                        /usr/bin/ld: CMakeFiles/ros2pcl_test_sub.dir/src/subscription_pcl.cpp.o: in function `int pcl::PCDWriter::writeASCII<pcl::PointXYZRGB>(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, pcl::PointCloud<pcl::PointXYZRGB> const&, int)':
                        subscription_pcl.cpp:(.text._ZN3pcl9PCDWriter10writeASCIIINS_11PointXYZRGBEEEiRKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_10PointCloudIT_EEi[_ZN3pcl9PCDWriter10writeASCIIINS_11PointXYZRGBEEEiRKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_10PointCloudIT_EEi]+0x2e0): undefined reference to `pcl::PCDWriter::setLockingPermissions(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, boost::interprocess::file_lock&)'
                        /usr/bin/ld: subscription_pcl.cpp:(.text._ZN3pcl9PCDWriter10writeASCIIINS_11PointXYZRGBEEEiRKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_10PointCloudIT_EEi[_ZN3pcl9PCDWriter10writeASCIIINS_11PointXYZRGBEEEiRKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKNS_10PointCloudIT_EEi]+0xbff): undefined reference to `pcl::PCDWriter::resetLockingPermissions(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, boost::interprocess::file_lock&)'
                        collect2: error: ld returned 1 exit status
                        make[2]: *** [CMakeFiles/ros2pcl_test_sub.dir/build.make:156:ros2pcl_test_sub] 错误 1
                        make[1]: *** [CMakeFiles/Makefile2:78:CMakeFiles/ros2pcl_test_sub.dir/all] 错误 2
                        make: *** [Makefile:141:all] 错误 2
                        ---
                        Failed   <<< ros2pcl_test [8.44s, exited with code 2]
                        
                        
                        

                        这个是因为什么愿意呢

                        小鱼小 1 条回复 最后回复 回复 引用 0
                        • 小鱼小
                          小鱼 技术大佬 @972032232
                          最后由 编辑

                          @972032232 在 ros2订阅pointcloud2话题出错 中说:

                          undefined reference to `pcl::PCDWriter::setLockingPermissions

                          要么库没link上,要么版本有问题

                          新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

                          9720322329 1 条回复 最后回复 回复 引用 0
                          • 9720322329
                            - @小鱼
                            最后由 编辑

                            @小鱼 如何添加库呢

                            小鱼小 1 条回复 最后回复 回复 引用 0
                            • 小鱼小
                              小鱼 技术大佬 @972032232
                              最后由 编辑

                              @972032232 修改下Cmake即可

                              cmake_minimum_required(VERSION 3.5)
                              project(ros2pcl_test)
                              
                              # Default to C99
                              if(NOT CMAKE_C_STANDARD)
                                set(CMAKE_C_STANDARD 99)
                              endif()
                              
                              # Default to C++14
                              if(NOT CMAKE_CXX_STANDARD)
                                set(CMAKE_CXX_STANDARD 14)
                              endif()
                              
                              if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
                                add_compile_options(-Wall -Wextra -Wpedantic)
                              endif()
                              
                              # find dependencies
                              find_package(ament_cmake REQUIRED)
                              find_package(sensor_msgs REQUIRED)
                              find_package(rclcpp REQUIRED)
                              find_package(PCL REQUIRED COMPONENTS common io)
                              
                              if(BUILD_TESTING)
                                find_package(ament_lint_auto REQUIRED)
                                # the following line skips the linter which checks for copyrights
                                # uncomment the line when a copyright and license is not present in all source files
                                #set(ament_cmake_copyright_FOUND TRUE)
                                # the following line skips cpplint (only works in a git repo)
                                # uncomment the line when this package is not in a git repo
                                #set(ament_cmake_cpplint_FOUND TRUE)
                                ament_lint_auto_find_test_dependencies()
                              endif()
                              
                              link_directories(${PCL_LIBRARY_DIRS})
                              add_definitions(${PCL_DEFINITIONS})
                              
                              add_executable(ros2pcl_test_sub 
                                src/subscription_pcl.cpp
                              )
                              ament_target_dependencies(ros2pcl_test_sub 
                                rclcpp 
                                sensor_msgs
                              )
                              
                              target_link_libraries(ros2pcl_test_sub ${PCL_LIBRARIES})
                              
                              ament_package()
                              

                              新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

                              1 条回复 最后回复 回复 引用 0
                              • 第一个帖子
                                最后一个帖子
                              皖ICP备16016415号-7
                              Powered by NodeBB | 鱼香ROS