当前位置:   article > 正文

点云cloudpoint生成octomap的OcTree的两种方法以及rviz可视化_octomaprealtimeshow

octomaprealtimeshow

第一种:在自己的项目中将点云通过ros的topic发布,用octomap_server订阅点云消息,在octomap_server中生成ocTree

再用rviz进行可视化。

创建工作空间,记得source

  1. mkdir temp_ocotmap_test/src
  2. cd temp_ocotmap_test
  3. catkin_make
  4. source devel/setup.bash

将这两个功能包下载放进自己的ros项目

再创建一个用于发布点云的功能包

  1. cd src
  2. catkin_create_pkg my_pkg std_msgs roscpp

形成这样的目录结构

 这里使用:Octomap 在ROS环境下实时显示_ros octomap-CSDN博客

的点云数据进行说明。

进入自己的功能包,创建一个data文件,将那位博主的点云文件test.pcd放进data文件夹

  1. cd my_pkg
  2. mkdir data

接下来写自己节点的cpp文件和自己功能包的CMakeLists.txt

  1. cd my_pkg/src
  2. vim my_pkg.cpp

my_pkg.cpp写入如下内容

  1. #include<iostream>
  2. #include<string>
  3. #include <stdlib.h>
  4. #include <stdio.h>
  5. #include <sstream>
  6. #include <vector>
  7. #include<ros/ros.h>
  8. #include<pcl/point_cloud.h>
  9. #include<pcl_conversions/pcl_conversions.h>
  10. #include<sensor_msgs/PointCloud2.h>
  11. #include<pcl/io/pcd_io.h>
  12. #include <octomap_msgs/OctomapWithPose.h>
  13. #include <octomap_msgs/Octomap.h>
  14. #include <geometry_msgs/Pose.h>
  15. #include <octomap/octomap.h>
  16. #include <octomap_msgs/Octomap.h>
  17. #include <octomap_msgs/conversions.h>
  18. #include <geometry_msgs/TransformStamped.h>
  19. #define TESTCLOUDPOINTS 1
  20. #define TESTOCTOTREE 0
  21. int main (int argc, char **argv)
  22. {
  23. std::string topic,path,frame_id;
  24. int hz=5;
  25. ros::init (argc, argv, "publish_pointcloud");
  26. ros::NodeHandle nh;
  27. nh.param<std::string>("path", path, "/home/username/Downloads/temp_for_run_octomap_server/src/publish_pointcloud/data/test.pcd");
  28. nh.param<std::string>("frame_id", frame_id, "your_frame_id");
  29. nh.param<std::string>("topic", topic, "your_pointcloud_topic");
  30. nh.param<int>("hz", hz, 5);
  31. // load cloudpoint
  32. pcl::PointCloud<pcl::PointXYZ> pcl_cloud;
  33. pcl::io::loadPCDFile (path, pcl_cloud);
  34. #if TESTCLOUDPOINTS
  35. ros::Publisher pcl_pub = nh.advertise<sensor_msgs::PointCloud2> (topic, 10);
  36. // 转换成ROS下的数据类型 通过topic发布
  37. sensor_msgs::PointCloud2 output;
  38. pcl::toROSMsg(pcl_cloud, output);
  39. output.header.stamp=ros::Time::now();
  40. output.header.frame_id =frame_id;
  41. std::cout<<"path = "<<path<<std::endl;
  42. std::cout<<"frame_id = "<<frame_id<<std::endl;
  43. std::cout<<"topic = "<<topic<<std::endl;
  44. std::cout<<"hz = "<<hz<<std::endl;
  45. ros::Rate loop_rate(hz);
  46. while (ros::ok())
  47. {
  48. pcl_pub.publish(output);
  49. ros::spinOnce();
  50. loop_rate.sleep();
  51. }
  52. #endif
  53. #if TESTOCTOTREE
  54. ros::Publisher octomap_pub = nh.advertise<octomap_msgs::Octomap>(topic, 1);
  55. octomap::OcTree tree(0.1); // You can adjust the resolution as needed
  56. for (const auto& point : pcl_cloud.points) {
  57. tree.updateNode(point.x, point.y, point.z, true);
  58. }
  59. // Publish the octree as an OctoMap message
  60. octomap_msgs::Octomap octomap_msg;
  61. octomap_msgs::fullMapToMsg(tree, octomap_msg);
  62. // Assuming you have a publisher for the octomap
  63. octomap_msg.header.stamp=ros::Time::now();
  64. octomap_msg.header.frame_id =frame_id;
  65. std::cout<<"path = "<<path<<std::endl;
  66. std::cout<<"frame_id = "<<frame_id<<std::endl;
  67. std::cout<<"topic = "<<topic<<std::endl;
  68. std::cout<<"hz = "<<hz<<std::endl;
  69. ros::Rate loop_rate(hz);
  70. while (ros::ok())
  71. {
  72. octomap_pub.publish(octomap_msg);
  73. ros::spinOnce();
  74. loop_rate.sleep();
  75. }
  76. #endif
  77. return 0;
  78. }

CMakeLists.txt这样写

  1. cmake_minimum_required(VERSION 3.0.2)
  2. project(my_pkg)
  3. ## Compile as C++11, supported in ROS Kinetic and newer
  4. # add_compile_options(-std=c++11)
  5. ## Find catkin macros and libraries
  6. ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
  7. ## is used, also find other catkin packages
  8. find_package(catkin REQUIRED COMPONENTS
  9. roscpp
  10. std_msgs
  11. sensor_msgs
  12. octomap_msgs
  13. geometry_msgs
  14. )
  15. find_package(PCL REQUIRED)
  16. find_package(octomap REQUIRED)
  17. ## System dependencies are found with CMake's conventions
  18. # find_package(Boost REQUIRED COMPONENTS system)
  19. ## Uncomment this if the package has a setup.py. This macro ensures
  20. ## modules and global scripts declared therein get installed
  21. ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
  22. # catkin_python_setup()
  23. ################################################
  24. ## Declare ROS messages, services and actions ##
  25. ################################################
  26. ## To declare and build messages, services or actions from within this
  27. ## package, follow these steps:
  28. ## * Let MSG_DEP_SET be the set of packages whose message types you use in
  29. ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
  30. ## * In the file package.xml:
  31. ## * add a build_depend tag for "message_generation"
  32. ## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
  33. ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
  34. ## but can be declared for certainty nonetheless:
  35. ## * add a exec_depend tag for "message_runtime"
  36. ## * In this file (CMakeLists.txt):
  37. ## * add "message_generation" and every package in MSG_DEP_SET to
  38. ## find_package(catkin REQUIRED COMPONENTS ...)
  39. ## * add "message_runtime" and every package in MSG_DEP_SET to
  40. ## catkin_package(CATKIN_DEPENDS ...)
  41. ## * uncomment the add_*_files sections below as needed
  42. ## and list every .msg/.srv/.action file to be processed
  43. ## * uncomment the generate_messages entry below
  44. ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
  45. ## Generate messages in the 'msg' folder
  46. # add_message_files(
  47. # FILES
  48. # Message1.msg
  49. # Message2.msg
  50. # )
  51. ## Generate services in the 'srv' folder
  52. # add_service_files(
  53. # FILES
  54. # Service1.srv
  55. # Service2.srv
  56. # )
  57. ## Generate actions in the 'action' folder
  58. # add_action_files(
  59. # FILES
  60. # Action1.action
  61. # Action2.action
  62. # )
  63. ## Generate added messages and services with any dependencies listed here
  64. # generate_messages(
  65. # DEPENDENCIES
  66. # std_msgs
  67. # )
  68. ################################################
  69. ## Declare ROS dynamic reconfigure parameters ##
  70. ################################################
  71. ## To declare and build dynamic reconfigure parameters within this
  72. ## package, follow these steps:
  73. ## * In the file package.xml:
  74. ## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
  75. ## * In this file (CMakeLists.txt):
  76. ## * add "dynamic_reconfigure" to
  77. ## find_package(catkin REQUIRED COMPONENTS ...)
  78. ## * uncomment the "generate_dynamic_reconfigure_options" section below
  79. ## and list every .cfg file to be processed
  80. ## Generate dynamic reconfigure parameters in the 'cfg' folder
  81. # generate_dynamic_reconfigure_options(
  82. # cfg/DynReconf1.cfg
  83. # cfg/DynReconf2.cfg
  84. # )
  85. ###################################
  86. ## catkin specific configuration ##
  87. ###################################
  88. ## The catkin_package macro generates cmake config files for your package
  89. ## Declare things to be passed to dependent projects
  90. ## INCLUDE_DIRS: uncomment this if your package contains header files
  91. ## LIBRARIES: libraries you create in this project that dependent projects also need
  92. ## CATKIN_DEPENDS: catkin_packages dependent projects also need
  93. ## DEPENDS: system dependencies of this project that dependent projects also need
  94. catkin_package(
  95. # INCLUDE_DIRS include
  96. # LIBRARIES my_pkg
  97. # CATKIN_DEPENDS roscpp std_msgs
  98. # DEPENDS system_lib
  99. )
  100. ###########
  101. ## Build ##
  102. ###########
  103. ## Specify additional locations of header files
  104. ## Your package locations should be listed before other locations
  105. include_directories(
  106. # include
  107. ${catkin_INCLUDE_DIRS}
  108. ${PCL_INCLUDE_DIRS}
  109. ${OCTOMAP_INCLUDE_DIRS}
  110. )
  111. ## Declare a C++ library
  112. # add_library(${PROJECT_NAME}
  113. # src/${PROJECT_NAME}/my_pkg.cpp
  114. # )
  115. ## Add cmake target dependencies of the library
  116. ## as an example, code may need to be generated before libraries
  117. ## either from message generation or dynamic reconfigure
  118. # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
  119. ## Declare a C++ executable
  120. ## With catkin_make all packages are built within a single CMake context
  121. ## The recommended prefix ensures that target names across packages don't collide
  122. add_executable(publish_pointcloud src/my_pkg.cpp)
  123. ## Rename C++ executable without prefix
  124. ## The above recommended prefix causes long target names, the following renames the
  125. ## target back to the shorter version for ease of user use
  126. ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
  127. # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
  128. ## Add cmake target dependencies of the executable
  129. ## same as for the library above
  130. # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
  131. ## Specify libraries to link a library or executable target against
  132. target_link_libraries(publish_pointcloud
  133. ${catkin_LIBRARIES}
  134. ${PCL_LIBRARIES}
  135. ${OCTOMAP_LIBRARIES}
  136. )
  137. #############
  138. ## Install ##
  139. #############
  140. # all install targets should use catkin DESTINATION variables
  141. # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
  142. ## Mark executable scripts (Python etc.) for installation
  143. ## in contrast to setup.py, you can choose the destination
  144. # catkin_install_python(PROGRAMS
  145. # scripts/my_python_script
  146. # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
  147. # )
  148. ## Mark executables for installation
  149. ## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
  150. # install(TARGETS ${PROJECT_NAME}_node
  151. # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
  152. # )
  153. ## Mark libraries for installation
  154. ## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
  155. # install(TARGETS ${PROJECT_NAME}
  156. # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
  157. # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
  158. # RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
  159. # )
  160. ## Mark cpp header files for installation
  161. # install(DIRECTORY include/${PROJECT_NAME}/
  162. # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
  163. # FILES_MATCHING PATTERN "*.h"
  164. # PATTERN ".svn" EXCLUDE
  165. # )
  166. ## Mark other files for installation (e.g. launch and bag files, etc.)
  167. # install(FILES
  168. # # myfile1
  169. # # myfile2
  170. # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
  171. # )
  172. #############
  173. ## Testing ##
  174. #############
  175. ## Add gtest based cpp test target and link libraries
  176. # catkin_add_gtest(${PROJECT_NAME}-test test/test_my_pkg.cpp)
  177. # if(TARGET ${PROJECT_NAME}-test)
  178. # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
  179. # endif()
  180. ## Add folders to be run by python nosetests
  181. # catkin_add_nosetests(test)

my_pkg.cpp中,先使用 宏TESTCLOUDPOINTS,发布点云数据

  1. #define TESTCLOUDPOINTS 1
  2. #define TESTOCTOTREE 0

定义好frame_idtopic

  1. nh.param<std::string>("path", path, "/home/.../test.pcd");
  2. nh.param<std::string>("frame_id", frame_id, "your_frame_id");
  3. nh.param<std::string>("topic", topic, "your_pointcloud_topic");
  4. nh.param<int>("hz", hz, 5);

回到工作空间,编译

  1. cd temp_ocotmap_test
  2. caikin_make

在工作空间中运行节点

rosrun my_pkg publish_pointcloud

打开一个terminal,进入工作空间,新打开terminal要source一下

source devel/setup.bash

接下来要运行octomap_server,通过octomap_server中的launch文件运行,launch文件在octomap_server/launch,运行之前,要修改其中的frame_id 和topic为你自己定义的frame_id和topic

  1. <launch>
  2. <node pkg="octomap_server" type="octomap_server_node" name="octomap_server">
  3. <!-- resolution in meters per pixel -->
  4. <param name="resolution" value="0.05" />
  5. <!-- name of the fixed frame, needs to be "/map" for SLAM -->
  6. <param name="frame_id" type="string" value="your_frame_id" />
  7. <!-- max range / depth resolution of the kinect in meter -->
  8. <param name="sensor_model/max_range" value="100.0" />
  9. <param name="latch" value="true" />
  10. <!-- max/min height for occupancy map, should be in meters -->
  11. <param name="pointcloud_max_z" value="1000" />
  12. <param name="pointcloud_min_z" value="0" />
  13. <!-- topic from where pointcloud2 messages are subscribed -->
  14. <remap from="/cloud_in" to="your_pointcloud_topic" />
  15. </node>
  16. </launch>

在工作空间中运行octomap_server

roslaunch octomap_server octomap_mapping.launch

这时会出现

 不用担心,其实octree已经生成,不知道为什么会显示这个,因为这个问题困扰了好久

再打开一个terminal,运行rviz,记得提前要安装rviz的octomap 插件

rosrun rviz rviz

修改Fixed Frame,Add一个OccupancyGrid,订阅/ocotmap_full这个topic,就可以看到生成的octree了

 第二种:不使用octomap_server,在自己项目中引用octomap包,生成octree,直接发布octree的topic,rviz订阅topic进行可视化

将上面my_pkg.cpp中的宏改为

  1. #define TESTCLOUDPOINTS 0
  2. #define TESTOCTOTREE 1

这样就运行了直接生成octree并发布的那段代码,回到工作空间,编译,运行节点

  1. cd temp_ocotmap_test
  2. catkin_make
  3. rosrun my_pkg publish_pointcloud

在rviz中修改topic和frame_id,便可以看到octree

以上!

声明:本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有侵权的内容,请联系我们。转载请注明出处:【wpsshop博客】
推荐阅读
相关标签
  

闽ICP备14008679号