4.3.6.7 读取PCD文件并在rviz中展示
4.3.6.7 读取PCD文件并在rviz中展示
参考教程:
读取PCD文件的点云并在 RVIZ显示_rviz显示pcd点云-CSDN博客
读取pcd文件并在rviz中进行显示_rviz看不到pcd-CSDN博客
Hinson-A/pcd2pgm_package: 点云pcd文件转二维栅格地图 (github.com)
ROS-PCL读取pcd点云数据并在rviz中进行显示_ros-pcl读取pcd点云数据并在rviz中显示-CSDN博客
1. 查看系统环境
要运行本仿真程序,需要保证当前环境为ubuntu20.04+ros-noetic-desktop-full
查看ubuntu
版本:
rosnoetic@rosnoetic-VirtualBox:~$ lsb_release -a
No LSB modules are available.
Distributor ID: Ubuntu
Description: Ubuntu 20.04.6 LTS
Release: 20.04
Codename: focal
可知,当前ubuntu
版本满足20.04
查看ros
版本:
rosnoetic@rosnoetic-VirtualBox:~$ rosversion -d
noetic
可知,当前ros
版本满足noetic
2. 读取PCD文件
2.1 编写读取PCD文件
2.1.1 创建功能包,导入依赖
-
2.1.1.1 新建文件夹
ctrl+alt+T
打开终端,执行如下指令创建文件夹:rosnoetic@rosnoetic-VirtualBox:~$ mkdir -p pcdreadshow_ws/src rosnoetic@rosnoetic-VirtualBox:~$ cd pcdreadshow_ws/src/ rosnoetic@rosnoetic-VirtualBox:~/pcdreadshow_ws/src$ catkin_init_workspace
-
catkin_init_workspace
接着创建工作空间:
rosnoetic@rosnoetic-VirtualBox:~/pcdreadshow_ws/src$ catkin_create_pkg read_pcd pcl_conversions pcl_ros roscpp sensor_msgs
-
-
2.1.1.2 创建功能包
在当前功能包
read_pcd
下,再新建几个目录:点击
read_pcd
,右键,选择“新建文件夹
”新建文件夹名称如下
launch
:存储launch
启动文件使用
launch
文件,可以一次性启动多个ROS
节点。
2.1.2 编写读取文件
-
2.1.2.1 编写程序
然后在功能包下的
src
文件夹中创建源文件:点击
read_pcd /src
文件夹,右键,选择“新建文件
”新建文件名为:
read_pcd.cpp
在
read_pcd.cpp
中添加如下内容-
read_pcd.cpp
#include<ros/ros.h> #include<pcl/point_cloud.h> #include<pcl_conversions/pcl_conversions.h> #include<sensor_msgs/PointCloud2.h> #include<pcl/io/pcd_io.h> int main(int argc,char argv){ ros::init(argc,argv,"pcd_pub"); ros::NodeHandle nh; ros::Publisher pcl_pub=nh.advertise<sensor_msgs::PointCloud2> ("pcl_output",1); pcl::PointCloud<pcl::PointXYZ> cloud; sensor_msgs::PointCloud2 output; std::string file_path; nh.param<std::string>("file_path", file_path, "/pcd/data_1/0000000001.pcd"); pcl::io::loadPCDFile(file_path,cloud);//通过launch文件修改路径即可 pcl::toROSMsg(cloud,output); output.header.frame_id="map"; ros::Rate loop_rate(1); while (ros::ok()) { pcl_pub.publish(output); ros::spinOnce(); loop_rate.sleep(); } return 0; }
-
-
2.1.2.2 编辑配置文件
向
read_pcd
功能包下的CMakeLists.txt
文件中修改为如下内容:cmake_minimum_required(VERSION 3.0.2) project(read_pcd) ## Compile as C++11, supported in ROS Kinetic and newer # add_compile_options(-std=c++11) ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## is used, also find other catkin packages find_package(catkin REQUIRED COMPONENTS pcl_conversions pcl_ros roscpp sensor_msgs ) ## System dependencies are found with CMake's conventions # find_package(Boost REQUIRED COMPONENTS system) ## Uncomment this if the package has a setup.py. This macro ensures ## modules and global scripts declared therein get installed ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html # catkin_python_setup() ################################################ ## Declare ROS messages, services and actions ## ################################################ ## To declare and build messages, services or actions from within this ## package, follow these steps: ## * Let MSG_DEP_SET be the set of packages whose message types you use in ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). ## * In the file package.xml: ## * add a build_depend tag for "message_generation" ## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in ## but can be declared for certainty nonetheless: ## * add a exec_depend tag for "message_runtime" ## * In this file (CMakeLists.txt): ## * add "message_generation" and every package in MSG_DEP_SET to ## find_package(catkin REQUIRED COMPONENTS ...) ## * add "message_runtime" and every package in MSG_DEP_SET to ## catkin_package(CATKIN_DEPENDS ...) ## * uncomment the add_*_files sections below as needed ## and list every .msg/.srv/.action file to be processed ## * uncomment the generate_messages entry below ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) ## Generate messages in the 'msg' folder # add_message_files( # FILES # Message1.msg # Message2.msg # ) ## Generate services in the 'srv' folder # add_service_files( # FILES # Service1.srv # Service2.srv # ) ## Generate actions in the 'action' folder # add_action_files( # FILES # Action1.action # Action2.action # ) ## Generate added messages and services with any dependencies listed here # generate_messages( # DEPENDENCIES # sensor_msgs # ) ################################################ ## Declare ROS dynamic reconfigure parameters ## ################################################ ## To declare and build dynamic reconfigure parameters within this ## package, follow these steps: ## * In the file package.xml: ## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" ## * In this file (CMakeLists.txt): ## * add "dynamic_reconfigure" to ## find_package(catkin REQUIRED COMPONENTS ...) ## * uncomment the "generate_dynamic_reconfigure_options" section below ## and list every .cfg file to be processed ## Generate dynamic reconfigure parameters in the 'cfg' folder # generate_dynamic_reconfigure_options( # cfg/DynReconf1.cfg # cfg/DynReconf2.cfg # ) ################################### ## catkin specific configuration ## ################################### ## The catkin_package macro generates cmake config files for your package ## Declare things to be passed to dependent projects ## INCLUDE_DIRS: uncomment this if your package contains header files ## LIBRARIES: libraries you create in this project that dependent projects also need ## CATKIN_DEPENDS: catkin_packages dependent projects also need ## DEPENDS: system dependencies of this project that dependent projects also need catkin_package( # INCLUDE_DIRS include # LIBRARIES read_pcd # CATKIN_DEPENDS pcl_conversions pcl_ros roscpp sensor_msgs # DEPENDS system_lib ) ########### ## Build ## ########### ## Specify additional locations of header files ## Your package locations should be listed before other locations include_directories( # include ${catkin_INCLUDE_DIRS} ) ## Declare a C++ library # add_library(${PROJECT_NAME} # src/${PROJECT_NAME}/read_pcd.cpp # ) ## Add cmake target dependencies of the library ## as an example, code may need to be generated before libraries ## either from message generation or dynamic reconfigure # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) ## Declare a C++ executable ## With catkin_make all packages are built within a single CMake context ## The recommended prefix ensures that target names across packages don't collide # add_executable(${PROJECT_NAME}_node src/read_pcd_node.cpp) add_executable(read_pcd src/read_pcd.cpp) target_link_libraries(read_pcd ${catkin_LIBRARIES}) ## Rename C++ executable without prefix ## The above recommended prefix causes long target names, the following renames the ## target back to the shorter version for ease of user use ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") ## Add cmake target dependencies of the executable ## same as for the library above # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) ## Specify libraries to link a library or executable target against # target_link_libraries(${PROJECT_NAME}_node # ${catkin_LIBRARIES} # ) ############# ## Install ## ############# # all install targets should use catkin DESTINATION variables # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html ## Mark executable scripts (Python etc.) for installation ## in contrast to setup.py, you can choose the destination # catkin_install_python(PROGRAMS # scripts/my_python_script # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} # ) ## Mark executables for installation ## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html # install(TARGETS ${PROJECT_NAME}_node # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} # ) ## Mark libraries for installation ## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html # install(TARGETS ${PROJECT_NAME} # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} # RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} # ) ## Mark cpp header files for installation # install(DIRECTORY include/${PROJECT_NAME}/ # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} # FILES_MATCHING PATTERN "*.h" # PATTERN ".svn" EXCLUDE # ) ## Mark other files for installation (e.g. launch and bag files, etc.) # install(FILES # # myfile1 # # myfile2 # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} # ) ############# ## Testing ## ############# ## Add gtest based cpp test target and link libraries # catkin_add_gtest(${PROJECT_NAME}-test test/test_read_pcd.cpp) # if(TARGET ${PROJECT_NAME}-test) # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) # endif() ## Add folders to be run by python nosetests # catkin_add_nosetests(test)
2.1.3 编写launch文件
点击read_pcd/launch
文件夹,右键,选择”新建文件
“
新建文件名为:read_pcd.launch
在read_pcd.launch
中添加如下代码:
-
read_pcd.launch
<launch> <param name="file_path" value="/home/rosnoetic/pcdreadshow_ws/scans.pcd"/> <node type="read_pcd" name="read_pcd" pkg="read_pcd" /> </launch>
2.1.4 编译
ctrl+alt+T
打开终端,执行如下指令catkin_make
编译:
rosnoetic@rosnoetic-VirtualBox:~$ cd pcdreadshow_ws
rosnoetic@rosnoetic-VirtualBox:~/pcdreadshow_ws$ catkin_make
-
catkin_make
2.2 启动演示
2.2.1 启动程序
将pcd
文件放在pcdreadshow_ws
文件夹下:
ctrl+alt+T
打开终端,执行如下指令启动仿真
rosnoetic@rosnoetic-VirtualBox:~$ cd pcdreadshow_ws
rosnoetic@rosnoetic-VirtualBox:~/pcdreadshow_ws$ source ./devel/setup.bash
rosnoetic@rosnoetic-VirtualBox:~/pcdreadshow_ws$ roslaunch read_pcd read_pcd.launch
ctrl+alt+T
打开终端,执行如下指令,启动rviz
rosnoetic@rosnoetic-VirtualBox:~$ rviz
设置Global Options
的Fixed Frame
为map
点击rviz
软件的左下角的Add
按钮,选择By display type
,选择PointCloud2
,点击OK
将PointCloud2
的Topic
设置为/pcl_output
将PointCloud2
的Size
设置为0.02
,即可看到放大版的点云图像了
2.2.2 保存rviz配置文件
点击RVIZ软件左上角的File选项,选择Save Config As
输入rviz配置文件的文件名称read_pcd_rviz,并保存到pcdreadshow_ws/src/read_pcd/launch
文件夹下,点击Save即可完成保存。
-
read_pcd_rviz.rviz
Panels: - Class: rviz/Displays Help Height: 78 Name: Displays Property Tree Widget: Expanded: - /Global Options1 - /PointCloud21 Splitter Ratio: 0.5 Tree Height: 416 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties Expanded: - /2D Pose Estimate1 - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.5886790156364441 - Class: rviz/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - Class: rviz/Time Name: Time SyncMode: 0 SyncSource: PointCloud2 Preferences: PromptSaveOnExit: true Toolbars: toolButtonStyle: 2 Visualization Manager: Class: "" Displays: - Alpha: 0.5 Cell Size: 1 Class: rviz/Grid Color: 160; 160; 164 Enabled: true Line Style: Line Width: 0.029999999329447746 Value: Lines Name: Grid Normal Cell Count: 0 Offset: X: 0 Y: 0 Z: 0 Plane: XY Plane Cell Count: 10 Reference Frame: <Fixed Frame> Value: true - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 10 Min Value: -10 Value: true Axis: Z Channel Name: intensity Class: rviz/PointCloud2 Color: 255; 255; 255 Color Transformer: Intensity Decay Time: 0 Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 Min Color: 0; 0; 0 Name: PointCloud2 Position Transformer: XYZ Queue Size: 10 Selectable: true Size (Pixels): 3 Size (m): 0.019999999552965164 Style: Flat Squares Topic: /pcl_output Unreliable: false Use Fixed Frame: true Use rainbow: true Value: true Enabled: true Global Options: Background Color: 48; 48; 48 Default Light: true Fixed Frame: map Frame Rate: 30 Name: root Tools: - Class: rviz/Interact Hide Inactive Objects: true - Class: rviz/MoveCamera - Class: rviz/Select - Class: rviz/FocusCamera - Class: rviz/Measure - Class: rviz/SetInitialPose Theta std deviation: 0.2617993950843811 Topic: /initialpose X std deviation: 0.5 Y std deviation: 0.5 - Class: rviz/SetGoal Topic: /move_base_simple/goal - Class: rviz/PublishPoint Single click: true Topic: /clicked_point Value: true Views: Current: Class: rviz/Orbit Distance: 13.600000381469727 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Field of View: 0.7853981852531433 Focal Point: X: -1.47225821018219 Y: 0.2789226174354553 Z: 0.37235042452812195 Focal Shape Fixed Size: true Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 Pitch: 0.9603979587554932 Target Frame: <Fixed Frame> Yaw: 1.0203980207443237 Saved: ~ Window Geometry: Displays: collapsed: false Height: 713 Hide Left Dock: false Hide Right Dock: true QMainWindow State: 000000ff00000000fd0000000400000000000001560000022bfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000022b000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000022bfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d0000022b000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005260000003efc0100000002fb0000000800540069006d0065010000000000000526000003bc00fffffffb0000000800540069006d00650100000000000004500000000000000000000003ca0000022b00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: collapsed: false Tool Properties: collapsed: false Views: collapsed: true Width: 1318 X: 72 Y: 27
2.2.3 修改launch文件,添加rviz执行程序
在read_pcd.launch
中添加如下代码:
-
read_pcd.launch
<launch> <param name="file_path" value="/home/rosnoetic/pcdreadshow_ws/scans.pcd"/> <node type="read_pcd" name="read_pcd" pkg="read_pcd" /> <node name="rviz" pkg="rviz" type="rviz" args="-d $(find read_pcd)/launch/read_pcd_rviz.rviz" required="true" /> </launch>
【推荐】编程新体验,更懂你的AI,立即体验豆包MarsCode编程助手
【推荐】凌霞软件回馈社区,博客园 & 1Panel & Halo 联合会员上线
【推荐】抖音旗下AI助手豆包,你的智能百科全书,全免费不限次数
【推荐】博客园社区专享云产品让利特惠,阿里云新客6.5折上折
【推荐】轻量又高性能的 SSH 工具 IShell:AI 加持,快人一步
· CSnakes vs Python.NET:高效嵌入与灵活互通的跨语言方案对比
· DeepSeek “源神”启动!「GitHub 热点速览」
· 我与微信审核的“相爱相杀”看个人小程序副业
· 上周热点回顾(2.17-2.23)
· 如何使用 Uni-app 实现视频聊天(源码,支持安卓、iOS)