Octomap安装
sudo apt-get install ros-melodic-octomap-ros
sudo apt-get install ros-melodic-octomap-msgs
sudo apt-get install ros-melodic-octomap-server
sudo apt-get install ros-melodic-octomap-rviz-plugins
# map_server安装
sudo apt-get install ros-melodic-map-server
启动rviz
roscore
rosrun rviz rviz
点击add,可以看到多了Octomap_rviz_plugins模组:
OccupancyGrid是显示三维概率地图,也就是octomap地图。OccupancyMap是显示二维占据栅格地图
从PCD创建PointCloud2点云话题并发布出去:
参考资料:
测试的test数据采用以下第一条博客的pcd测试数据
Octomap 在ROS环境下实时显示_octomap在ros环境下实时显示-飞天熊猫-CSDN博客
学习笔记:使用Octomap将点云地图pcd转换为三维栅格地图,并在rviz中可视化_octomap功能包-CSDN博客
创建点云发布话题的工作空间:
mkdir -p ~/publish_pointcloudtest/src #使用系统命令创建工作空间目录
cd ~/publish_pointcloudtest/src
catkin_init_workspace # ROS的工作空间初始化命令
在工作空间下放入以下两个文件:
octomap_mapping
octomap_server
资源下载:
https://github.com/OctoMap/octomap_mapping
src下创建cpp文件pointcloud_publisher.cpp
#include <iostream>
#include <string>
#include <stdlib.h>
#include <stdio.h>
#include <sstream>
#include <vector>
#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>
#include <octomap_msgs/OctomapWithPose.h>
#include <octomap_msgs/Octomap.h>
#include <geometry_msgs/Pose.h>
#include <octomap/octomap.h>
#include <octomap_msgs/Octomap.h>
#include <octomap_msgs/conversions.h>
#include <geometry_msgs/TransformStamped.h>
#define TESTCLOUDPOINTS 1 // 设置为 1 以测试点云发布,设置为 0 不测试
#define TESTOCTOTREE 0 // 设置为 1 以测试OctoMap发布,设置为 0 不测试
int main (int argc, char **argv)
{
std::string topic, path, frame_id;
int hz = 5; // 发布频率,单位 Hz
ros::init(argc, argv, "publish_pointcloud"); // 初始化ROS节点
ros::NodeHandle nh; // 创建节点句柄
// 从参数服务器获取参数
nh.param<std::string>("path", path, "/home/nvidia/publish_pointcloudtest/data/test.pcd");
nh.param<std::string>("frame_id", frame_id, "map");
nh.param<std::string>("topic", topic, "pointcloud_topic");
nh.param<int>("hz", hz, 5);
// 加载点云数据到pcl::PointCloud对象中
pcl::PointCloud<pcl::PointXYZ> pcl_cloud;
pcl::io::loadPCDFile(path, pcl_cloud); // 从文件加载点云数据
#if TESTCLOUDPOINTS // 如果 TESTCLOUDPOINTS 定义为 1,则执行这部分代码
ros::Publisher pcl_pub = nh.advertise<sensor_msgs::PointCloud2>(topic, 10); // 创建Publisher对象,将点云数据发布到指定话题
// 转换PCL点云到ROS下的 PointCloud2 类型
sensor_msgs::PointCloud2 output;
pcl::toROSMsg(pcl_cloud, output);
output.header.stamp = ros::Time::now(); // 设置时间戳
output.header.frame_id = frame_id; // 设置坐标系框架
// 打印参数信息
std::cout << "path = " << path << std::endl;
std::cout << "frame_id = " << frame_id << std::endl;
std::cout << "topic = " << topic << std::endl;
std::cout << "hz = " << hz << std::endl;
ros::Rate loop_rate(hz); // 设置发布频率
while (ros::ok())
{
pcl_pub.publish(output); // 发布 PointCloud2 数据
ros::spinOnce(); // 处理所有回调函数
loop_rate.sleep(); // 按照指定频率睡眠
}
#endif
#if TESTOCTOTREE // 如果 TESTOCTOTREE 定义为 1,则执行这部分代码
ros::Publisher octomap_pub = nh.advertise<octomap_msgs::Octomap>(topic, 1); // 创建Publisher对象,将OctoMap数据发布到指定话题
// 创建 octomap 对象,并设置其分辨率
octomap::OcTree tree(0.1); // 你可以根据需要调整分辨率
// 将点云数据插入到 octomap 中
for (const auto& point : pcl_cloud.points) {
tree.updateNode(point.x, point.y, point.z, true);
}
// 发布OctoMap消息
octomap_msgs::Octomap octomap_msg;
octomap_msgs::fullMapToMsg(tree, octomap_msg); // 转换为 OctoMap 消息
// 设置 OctoMap 消息的头信息
octomap_msg.header.stamp = ros::Time::now();
octomap_msg.header.frame_id = frame_id;
// 打印参数信息
std::cout << "path = " << path << std::endl;
std::cout << "frame_id = " << frame_id << std::endl;
std::cout << "topic = " << topic << std::endl;
std::cout << "hz = " << hz << std::endl;
ros::Rate loop_rate(hz); // 设置发布频率
while (ros::ok())
{
octomap_pub.publish(octomap_msg); // 发布 OctoMap 数据
ros::spinOnce(); // 处理所有回调函数
loop_rate.sleep(); // 按照指定频率睡眠
}
#endif
return 0; // 主函数返回值
}
代码中需要进行修改为自己的点云,后续相应都需要修改为自己的路径(自行修改):
nh.param<std::string>("path", path, "/home/nvidia/publish_pointcloudtest/data/test.pcd");
CMakeLists.txt
cmake_minimum_required(VERSION 3.0.2)
project(publish_pointcloud)
## 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
set(octomap_ros_DIR "/opt/ros/melodic/share/octomap_ros/cmake")
find_package(catkin REQUIRED COMPONENTS
roscpp
std_msgs
sensor_msgs
octomap_msgs
geometry_msgs
octomap_ros
)
find_package(PCL REQUIRED)
find_package(octomap REQUIRED)
## 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
# std_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 my_pkg
# CATKIN_DEPENDS roscpp std_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}
${PCL_INCLUDE_DIRS}
${OCTOMAP_INCLUDE_DIRS}
)
## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/my_pkg.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(publish_pointcloud src/pointcloud_publisher.cpp)
## 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(publish_pointcloud
${catkin_LIBRARIES}
${PCL_LIBRARIES}
${OCTOMAP_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_my_pkg.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)
package.xml
<?xml version="1.0"?>
<package format="2">
<name>publish_pointcloud</name>
<version>0.0.0</version>
<description>The publish_pointcloud package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="nvidia@todo.todo">nvidia</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/point_publish</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>std_msgs</build_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>std_msgs</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>
编译通过
记得在devel那边进行source
source devel/setup.bash
roscore
rosrun publish_pointcloud publish_pointcloud
查看下是否有话题,且可以打印出来
rostopic list
rostopic echo /pointcloud_topic
然后打开终端打开rviz
rviz
将PointCloud2 添加进来,话题选择之前的点云话题
编写octomap_mapping.launch文件,launch文件在:
将frameid修改即可
<launch>
<node pkg="octomap_server" type="octomap_server_node" name="octomap_server">
<param name="resolution" value="0.05" />
<!-- fixed map frame (set to 'map' if SLAM or localization running!) -->
<param name="frame_id" type="string" value="map" />
<!-- maximum range to integrate (speedup!) -->
<param name="sensor_model/max_range" value="5.0" />
<!-- data source to integrate (PointCloud2) -->
<remap from="cloud_in" to="/pointcloud_topic" />
</node>
</launch>
然后就可以运行launch文件了:
roslaunch octomap_server octomap_mapping.launch
总结上面所有的过程 :
1、改完代码后编译
nvidia@Xavier-NX:~/publish_pointcloudtest$ catkin_make
2、编译完后roscore
nvidia@Xavier-NX:~$ roscore
3、运行点云发布代码
nvidia@Xavier-NX:~/publish_pointcloudtest$ rosrun publish_pointcloud publish_pointcloud
4、运行rviz使其显示白色的点云
nvidia@Xavier-NX:~$ rviz
5、运行octomap
nvidia@Xavier-NX:~/publish_pointcloudtest$ roslaunch octomap_server octomap_mapping.launch
上面的点云也是可以测试出来的,如第一张的图,最后用的自己4D毫米波雷达生成的点云也进行了测试,不过有些点云没能显示,后续还需要改进,估计跟坐标系的范围也有关系:
后续考虑实时动态,以及将其转换为二维栅格地图作为无人机的导航地图。