本文将实现在ROS下将pcd点云文件转为深度前视图。
一 准备工作
系统:ubuntu 18.04 ROS版本:ros-melodic IDE:VScode 语言:C++
二 程序实现
直接上代码!
1.创建工作空间
创建工作空间存,src下存放执行文件。
mkdir -p ~/deep_image/src
cd ~/deep_image
catkin_make
code .
主要的VS配置主要参考赵虚左老师的教程,具体配置点此处链接: http://www.autolabor.com.cn/book/ROSTutorials/chapter1/14-ros-ji-cheng-kai-fa-huan-jing-da-jian/142-an-zhuang-vscode.html.
2.功能包及头文件
创建功能包: 包名:deep_image 依赖:
image_transport pcl_conversions pcl_ros roscpp rospy sensor_msgs std_msgs
创建头文件: 文件名:image_pro.h
#pragma once
#include <iostream>
#include <pcl/visualization/pcl_plotter.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <pcl/range_image/range_image.h>
#include <pcl/visualization/range_image_visualizer.h>
#include <vector>
#include <ros/ros.h>
#include <opencv2/core/core.hpp>
#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/Image.h>
#include <opencv2/opencv.hpp>
#include <pcl_conversions/pcl_conversions.h>
#include <std_msgs/Header.h>
#include <pcl/conversions.h>
#include <limits>
#include <cstring>
#include <cmath>
#include <pcl/range_image/range_image_spherical.h>
#include <sensor_msgs/image_encodings.h>
#include <dynamic_reconfigure/server.h>
#include <geometry_msgs/Pose.h>
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
#include <opencv2/highgui/highgui.hpp>
#include <pcl/filters/impl/passthrough.hpp>
#include <pcl/common/common_headers.h>
#include <pcl/console/parse.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/PointCloud.h>
class pcl_image_pro
{
private:
ros::Subscriber sub_point_cloud_;
ros::Publisher pub_Img_;
void point_cb(const sensor_msgs::PointCloud2ConstPtr& in_cloud);
void setViewerPose(pcl::visualization::PCLVisualizer& viewer,
const Eigen::Affine3f& viewer_pose);
public:
pcl_image_pro(ros::NodeHandle &nh);
~pcl_image_pro();
void Spin();
};
3.节点文件
文件名:image_pro_node
#include "image_pro.h"
int main(int argc, char* argv[])
{
setlocale(LC_ALL,"");
ros::init(argc, argv, "deep_image");
ros::NodeHandle nh;
pcl_image_pro core(nh);
return 0;
}
4.具体实现文件
文件名:image_pro
#include "image_pro.h"
typedef pcl::PointXYZ PointType;
pcl_image_pro::pcl_image_pro(ros::NodeHandle &nh)
{
sub_point_cloud_ = nh.subscribe("/velodyne_points", 10, &pcl_image_pro::point_cb, this);
pub_Img_ = nh.advertise<sensor_msgs::PointCloud2>("/pub_image", 10);
ros::spin();
}
pcl_image_pro::~pcl_image_pro() {}
void pcl_image_pro::Spin()
{
}
void pcl_image_pro::setViewerPose(pcl::visualization::PCLVisualizer& viewer, const Eigen::Affine3f& viewer_pose)
{
Eigen::Vector3f pos_vector = viewer_pose * Eigen::Vector3f(0, 0, 0);
Eigen::Vector3f look_at_vector = viewer_pose.rotation()*Eigen::Vector3f(0, 0, 1) + pos_vector;
Eigen::Vector3f up_vector = viewer_pose.rotation() * Eigen::Vector3f(0, -1, 0);
viewer.setCameraPosition(
pos_vector[0], pos_vector[1], pos_vector[2],
look_at_vector[0], look_at_vector[1], look_at_vector[2],
up_vector[0], up_vector[1], up_vector[2]);
}
void pcl_image_pro::point_cb(const sensor_msgs::PointCloud2ConstPtr& in_cloud)
{
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in_per(new pcl::PointCloud<pcl::PointXYZ>);
pcl::fromROSMsg(*in_cloud, *cloud_in_per);
pcl::PointCloud<PointType>& point_cloud = *cloud_in_per;
float angular_resolution_x = 0.5f,
angular_resolution_y = angular_resolution_x;
pcl::RangeImage::CoordinateFrame coordinate_frame =pcl::RangeImage::CAMERA_FRAME;
bool live_update = false;
angular_resolution_x = pcl::deg2rad(angular_resolution_x);
angular_resolution_y = pcl::deg2rad(angular_resolution_y);
Eigen::Affine3f scene_sensor_pose(Eigen::Affine3f::Identity());
scene_sensor_pose = Eigen::Affine3f(Eigen::Translation3f(point_cloud.sensor_origin_[0],
point_cloud.sensor_origin_[1],
point_cloud.sensor_origin_[2])) *
Eigen::Affine3f(point_cloud.sensor_orientation_);
float noise_level = 0.0;
float min_range = 0.0f;
int border_size = 1;
pcl::RangeImage::Ptr range_image_ptr(new pcl::RangeImage);
pcl::RangeImage & range_image = *range_image_ptr;
range_image.createFromPointCloud(point_cloud, angular_resolution_x, angular_resolution_y,
pcl::deg2rad(360.0f), pcl::deg2rad(180.f), scene_sensor_pose, coordinate_frame,
noise_level, min_range, border_size);
pcl::visualization::PCLVisualizer viewer("3D Viewer");
viewer.setBackgroundColor(1, 1, 1);
pcl::visualization::PointCloudColorHandlerCustom < pcl::PointWithRange>range_image_color_handler(range_image_ptr, 0, 0, 0);
viewer.addPointCloud(range_image_ptr, range_image_color_handler, "range image");
viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "range image");
viewer.initCameraParameters();
setViewerPose(viewer, range_image.getTransformationToWorldSystem());
pcl::visualization::RangeImageVisualizer range_image_wiget("Range Image");
range_image_wiget.showRangeImage(range_image);
while (!viewer.wasStopped())
{
range_image_wiget.spinOnce();
viewer.spinOnce();
pcl_sleep(0.01);
if (live_update)
{
scene_sensor_pose = viewer.getViewerPose();
range_image.createFromPointCloud(point_cloud,angular_resolution_x,angular_resolution_y,
pcl::deg2rad(360.0f),pcl::deg2rad(180.0f), scene_sensor_pose, pcl::RangeImage::LASER_FRAME, noise_level, min_range, border_size);
range_image_wiget.showRangeImage(range_image);
}
}
}
5.发布pcd点云
文件名:clouds_to_image_point_pub
#include <iostream>
#include <ros/ros.h>
#include <sstream>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/PointCloud.h>
#include <pcl/conversions.h>
#include <pcl_ros/transforms.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/console/print.h>
#include <pcl/io/pcd_io.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/visualization/cloud_viewer.h>
#include <cmath>
#include <pcl/filters/statistical_outlier_removal.h>
#include <vector>
#include <pcl/filters/voxel_grid.h>
#include <pcl/kdtree/kdtree_flann.h>
int main(int argc, char *argv[])
{
ros::init(argc, argv, "pointclouds_grid_pub");
ros::NodeHandle nh;
ros::Publisher pub = nh.advertise<sensor_msgs::PointCloud2>("/velodyne_points",1);
pcl::PointCloud<pcl::PointXYZRGB> cloud;
sensor_msgs::PointCloud2 output;
pcl::io::loadPCDFile ("/media/tzy/linux/jjj/cloud_cluster_6.pcd", cloud);
pcl::toROSMsg(cloud, output);
output.header.frame_id = "/velodyne";
ros::Rate loop_rate(1);
while (ros::ok())
{
pub.publish(output);
ros::spinOnce();
loop_rate.sleep();
}
return 0;
}
6.配置CMakeLists.txt
cmake_minimum_required(VERSION 3.0.2)
project(deep_image)
find_package(catkin REQUIRED COMPONENTS
image_transport
pcl_conversions
pcl_ros
roscpp
rospy
sensor_msgs
std_msgs
)
find_package(PCL 1.8 REQUIRED)
find_package(OpenCV REQUIRED)
catkin_package(
INCLUDE_DIRS include
CATKIN_DEPENDS image_transport pcl_conversions pcl_ros roscpp rospy sensor_msgs std_msgs
DEPENDS PCL
)
include_directories(
include
${catkin_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
)
link_directories(${PCL_LIBRARY_DIRS})
add_executable(${PROJECT_NAME}_node src/image_pro_node.cpp src/image_pro.cpp)
add_executable(clouds_to_image_point_pub src/clouds_to_image_point_pub.cpp)
target_link_libraries(${PROJECT_NAME}_node
${catkin_LIBRARIES}
${PCL_LIBRARIES}
${OpenCV_LIBS}
)
target_link_libraries(clouds_to_image_point_pub
${catkin_LIBRARIES}
${PCL_LIBRARIES}
${OpenCV_LIBS}
)
7.launch文件
文件名:deep_image
<?xml version="1.0"?>
<launch>
<node pkg="deep_image" type="deep_image_node" name="deep_image_node" />
<node pkg="deep_image" type="clouds_to_image_point_pub" name="clouds_to_image_point_pub" />
</launch>
8.运行及结果
到此为止完成代码编写,,VS编译通过后,在工作空间下打开终端输入
source ./devel/setup.bash
roslaunch deep_image deep_image.launch
range_image图片
9.参考
感谢CSDN各位大牛,参考了你们的博客才有了今天这篇文章,也是本人的第一篇博客,在此附上各位的链接。
http://www.autolabor.com.cn/book/ROSTutorials/chapter1/14-ros-ji-cheng-kai-fa-huan-jing-da-jian/142-an-zhuang-vscode.html.
https://pcl.readthedocs.io/projects/tutorials/en/latest/range_image_visualization.html#range-image-visualization.
https://blog.csdn.net/luolaihua2018/article/details/117383916?utm_medium=distribute.pc_relevant.none-task-blog-2%7Edefault%7ECTRLIST%7Edefault-2.no_search_link&depth_1-utm_source=distribute.pc_relevant.none-task-blog-2%7Edefault%7ECTRLIST%7Edefault-2.no_search_link.
https://blog.csdn.net/RuoQiQingCheDi/article/details/83987405.
https://adamshan.blog.csdn.net/article/details/82901295?utm_medium=distribute.pc_relevant.none-task-blog-2%7Edefault%7ECTRLIST%7Edefault-2.no_search_link&depth_1-utm_source=distribute.pc_relevant.none-task-blog-2%7Edefault%7ECTRLIST%7Edefault-2.no_search_link.
https://blog.csdn.net/suyunzzz/article/details/105930636.
|