ROS学习笔记——PCL激光雷达点云处理

4.27更新

一、创建节点发布点云数据并可视化

1、在ros工作空间的src目录下新建包(包含依赖项)

catkin_create_pkg chapter10_tutorials pcl_conversions pcl_ros pcl_msgs sensor_msgs

3、在软件包中新建src目录

rospack profile
roscd chapter10_tutorials
mkdir src

4、在src目录下新建pcl_create.cpp,该程序创建了100个随机座标的点云并以1Hz的频率,topic为“pcl_output"发布。frame设为odom。

#include <ros/ros.h>
#include <pcl/point_cloud.h>
#include <pcl_conversions/pcl_conversions.h>
#include <sensor_msgs/PointCloud2.h>

main (int argc, char **argv)
{
    ros::init (argc, argv, "pcl_create");

    ros::NodeHandle nh;
    ros::Publisher pcl_pub = nh.advertise<sensor_msgs::PointCloud2> ("pcl_output", 1);
    pcl::PointCloud<pcl::PointXYZ> cloud;
    sensor_msgs::PointCloud2 output;

    // Fill in the cloud data
    cloud.width  = 100;
    cloud.height = 1;
    cloud.points.resize(cloud.width * cloud.height);

    for (size_t i = 0; i < cloud.points.size (); ++i)
    {
        cloud.points[i].x = 1024 * rand () / (RAND_MAX + 1.0f);
        cloud.points[i].y = 1024 * rand () / (RAND_MAX + 1.0f);
        cloud.points[i].z = 1024 * rand () / (RAND_MAX + 1.0f);
    }

    //Convert the cloud to ROS message
    pcl::toROSMsg(cloud, output);
    output.header.frame_id = "odom";

    ros::Rate loop_rate(1);
    while (ros::ok())
    {
        pcl_pub.publish(output);
        ros::spinOnce();
        loop_rate.sleep();
    }

    return 0;
}

5、修改cmakelist.txt内容

cmake_minimum_required(VERSION 2.8.3)
project(chapter10_tutorials)
find_package(catkin REQUIRED COMPONENTS
  pcl_conversions
  pcl_ros
  roscpp
  sensor_msgs
  rospy
)

find_package(PCL REQUIRED)
catkin_package()

include_directories(
  ${catkin_INCLUDE_DIRS}
  ${PCL_INCLUDE_DIRS}
)

link_directories(${PCL_LIBRARY_DIRS})


add_executable(pcl_create src/pcl_create.cpp)
target_link_libraries(pcl_create ${catkin_LIBRARIES} ${PCL_LIBRARIES})

6、进入工作空间编译包

cd ~/catkin_ws
catkin_make --pkg chapter10_tutorials

7、若编译成功,新窗口打开ros,新窗口运行pcl_create节点

roscore
rosrun chapter10_tutorials pcl_create

8、新窗口打开rviz,add topic"pcl_output",Global options 设置Frame为odom

rviz

 

 二、加载pcd文件、保存点云为pcd文件

1、加载pcd文件并发布为pcl_output点云:在src下新建pcl_read.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>

main(int argc, char **argv)
{
    ros::init (argc, argv, "pcl_read");

    ros::NodeHandle nh;
    ros::Publisher pcl_pub = nh.advertise<sensor_msgs::PointCloud2> ("pcl_output", 1);

    sensor_msgs::PointCloud2 output;
    pcl::PointCloud<pcl::PointXYZ> cloud;

    pcl::io::loadPCDFile ("test_pcd.pcd", cloud);

    pcl::toROSMsg(cloud, output);
    output.header.frame_id = "odom";

    ros::Rate loop_rate(1);
    while (ros::ok())
    {
        pcl_pub.publish(output);
        ros::spinOnce();
        loop_rate.sleep();
    }

    return 0;
}

2、保存topic发布的点云为pcd文件,在src下新建pcl_write.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>

void cloudCB(const sensor_msgs::PointCloud2 &input)
{
    pcl::PointCloud<pcl::PointXYZ> cloud;
    pcl::fromROSMsg(input, cloud);
    pcl::io::savePCDFileASCII ("write_pcd_test.pcd", cloud);
}

main (int argc, char **argv)
{
    ros::init (argc, argv, "pcl_write");
    ros::NodeHandle nh;
    ros::Subscriber bat_sub = nh.subscribe("pcl_output", 10, cloudCB);
    ros::spin();

    return 0;
}

 3、添加内容到cmakelist.txt

add_executable(pcl_read src/pcl_read.cpp)
add_executable(pcl_write src/pcl_write.cpp)

target_link_libraries(pcl_read ${catkin_LIBRARIES} ${PCL_LIBRARIES})
target_link_libraries(pcl_write ${catkin_LIBRARIES} ${PCL_LIBRARIES})

 4、在catkin_ws空间下编译包(同上)

5、打开不同的窗口,在pcd文件夹下分别运行节点(因为pcl_read要读取pcd文件)

roscore
roscd chapter10_tutorials/data && rosrun chapter10_tutorials pcl_read
roscd chapter10_tutorials/data && rosrun chapter10_tutorials pcl_write

6、可视化同上

三、cloud_viewer可视化pcd文件的点云

新建cpp文件,所有步骤同上。

#include <iostream>
#include <ros/ros.h>
#include <pcl/visualization/cloud_viewer.h>
#include <sensor_msgs/PointCloud2.h>
#include <pcl_conversions/pcl_conversions.h>

class cloudHandler
{
public:
    cloudHandler()
    : viewer("Cloud Viewer")
    {
     pcl::PointCloud<pcl::PointXYZ> cloud;
     pcl::io::loadPCDFile ("0.pcd", cloud);
     viewer.showCloud(cloud.makeShared());
     viewer_timer = nh.createTimer(ros::Duration(0.1), &cloudHandler::timerCB, this);
    }

    void timerCB(const ros::TimerEvent&)
    {
        if (viewer.wasStopped())
        {
            ros::shutdown();
        }
    }

protected:
    ros::NodeHandle nh;
    pcl::visualization::CloudViewer viewer;
    ros::Timer viewer_timer;
};

main (int argc, char **argv)
{
    ros::init (argc, argv, "pcl_filter");
    cloudHandler handler;
    ros::spin();
    return 0;
}

 编译并在pcd数据文件夹下运行节点,可得下图。可以按住ctrl键滑轮放大缩小。

 

三、点云预处理——滤波和缩减采样

滤波删除离群值pcl_filter.cpp,处理流程同上

#include <iostream>
#include <ros/ros.h>
#include <pcl/visualization/cloud_viewer.h>
#include <sensor_msgs/PointCloud2.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/filters/statistical_outlier_removal.h>

class cloudHandler
{
public:
    cloudHandler()
    : viewer("Cloud Viewer")
    {
     pcl::PointCloud<pcl::PointXYZ> cloud;
     pcl::PointCloud<pcl::PointXYZ> cloud_filtered;
     pcl::io::loadPCDFile ("0.pcd", cloud);

     pcl::StatisticalOutlierRemoval<pcl::PointXYZ> statFilter;
        statFilter.setInputCloud(cloud.makeShared());
        statFilter.setMeanK(10);
        statFilter.setStddevMulThresh(0.4);
        statFilter.filter(cloud_filtered);
     viewer.showCloud(cloud_filtered.makeShared());
     viewer_timer = nh.createTimer(ros::Duration(0.1), &cloudHandler::timerCB, this);
    }

    void timerCB(const ros::TimerEvent&)
    {
        if (viewer.wasStopped())
        {
            ros::shutdown();
        }
    }

protected:
    ros::NodeHandle nh;
    
    pcl::visualization::CloudViewer viewer;
    ros::Timer viewer_timer;
};

main (int argc, char **argv)
{
    ros::init (argc, argv, "pcl_filter");
    cloudHandler handler;
    ros::spin();
    return 0;
}

滤波结果:

 

 滤波以后缩减采样,只有public变化了:

public:
    cloudHandler()
    : viewer("Cloud Viewer")
    {
     pcl::PointCloud<pcl::PointXYZ> cloud;
pcl::PointCloud<pcl::PointXYZ> cloud_filtered;
 pcl::PointCloud<pcl::PointXYZ> cloud_downsampled;

     pcl::io::loadPCDFile ("0.pcd", cloud);

      pcl::StatisticalOutlierRemoval<pcl::PointXYZ> statFilter;
        statFilter.setInputCloud(cloud.makeShared());
        statFilter.setMeanK(10);
        statFilter.setStddevMulThresh(0.2);
        statFilter.filter(cloud_filtered);

 	pcl::VoxelGrid<pcl::PointXYZ> voxelSampler;
        voxelSampler.setInputCloud(cloud_filtered.makeShared());
        voxelSampler.setLeafSize(0.01f, 0.01f, 0.01f);
        voxelSampler.filter(cloud_downsampled);

     viewer.showCloud(cloud_downsampled.makeShared());

     viewer_timer = nh.createTimer(ros::Duration(0.1), &cloudHandler::timerCB, this);
    }

缩减采样结果:


4.24更新:播放bag并可视化激光雷达点云

1、查看无人艇的视频和雷达数据20200116.bag信息:

rosbag info 20200116.bag

发现时长约3分钟,topic有fix(卫星导航数据)、heading(姿态四元数)、points_raw(激光雷达点云)、rosout(节点图)、camera_info(摄像机信息)、image_raw(摄像机图片)、time_reference(时间)、vel(速度?角速度?)

2、回放bag文件:

rosbag play 20200116.bag

 

3、打开rviz:

rosrun rviz rviz

4、点击add--->add topic--->Pointcloud2(或 image)

5、Global Options :Fixed Frame 改成pandar

(刚开始没有改fixed frame,add topic以后总是显示错误,后来在src下的雷达的包里看到readme文件里面写着:4. Change fixed frame to `pandar`。所以在vriz里修改了,图像和点云都可以显示了。

 

4.23更新:让turtlebot3建图并导航

turtlebot3教程 :https://www.ncnynl.com/archives/201702/1396.html

一、远程连接步骤

1、连上同一个无线局域网

2、pc端: ifconfig查看ip,修改bashrc文件的ip

ifconfig
gedit ~/.bashrc
source ~/.bsahrc

3、pc端:  连接机器人

SSH登录到远程计算机:$ ssh username@ip_address

ssh [email protected] 

启动机器人:


export TURTLEBOT3_MODEL=burger
cd ~/catkin_ws
source devel/setup.bash
roslaunch turtlebot3_bringup turtlebot3_robot.launch

修改ip(i 编辑  esc退出编辑 shift:wq 保存退出)

vi ~/.bashrc  

source ~/.bashrc

4、pc端运行以下命令才能进行节点其他操作:

cd ~/catkin_ws
source devel/setup.bash

 

二、运行以下启动命令时报错

ModuleNotFoundError: No module named 'rospkg'

roslaunch turtlebot3_bringup turtlebot3_robot.launch

解决方法:

1、命令行输入Python,检查Python版本是否为2.7,如果不是2.7则需要修改系统Python版本

2、确认2.7版本,命令行输入 pip install rospkg 即可

 

4.20更新

turtlebot3 安装软件git clone 报错(因为家里网不行):fatal:early EOF    fatal:index-pack failed

解决方法:

1、增加缓存(亲测无效)

2、直接复制github网址,下载包到catkin_ws文件夹下,再重新执行命令即可

看过的教程:

https://www.bilibili.com/video/BV1mJ411R7Ni?p=17

https://blog.csdn.net/zhangrelay/article/details/51737074

 

VREP:

官方手册https://www.coppeliarobotics.com/helpFiles/index.html

入门教程https://www.jianshu.com/p/eb3f38c0c5fa

基础https://blog.csdn.net/danieldingshengli/category_7238158.html

泡泡机器人https://max.book118.com/html/2019/0430/6102210112002025.shtm

發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章