Skip to content

Latest commit

 

History

History
163 lines (138 loc) · 5.5 KB

README.Chinese.md

File metadata and controls

163 lines (138 loc) · 5.5 KB

Badge LICENSE Slack

简介

KITTI 数据集建图

构建 & 编译

本地环境构建项目

依赖项

首先你应该已经安装了 ROS 环境,按照官方文档来进行安装,项目在 kinetic 和 melodic 版本中都经过了测试。

## 基础依赖项
sudo apt -y install cmake \
  libboost-dev \
  libeigen3-dev \
  libpng-dev \
  libgoogle-glog-dev \
  libatlas-base-dev \
  libsuitesparse-dev \
  imagemagick \
  libtbb-dev

## install pcl 
sudo apt -y install libpcl-dev

cd your_own_workspace 
## 比如 /home/user/3rd_parties
## 或者你可以直接 cd 到当前项目的 third_parties 目录下
## GeoGraphic
./path_of_StaticMapping/setup/install_geographiclib.sh
## GTSAM(4.0 or higher is needed)
./path_of_StaticMapping/setup/install_gtsam.sh
## libnabo
./path_of_StaticMapping/setup/install_libnabo.sh
## libpointmatcher
./path_of_StaticMapping/setup/install_libpointmatcher.sh

选配项

  • CUDA: 我尝试过使用 cuda 加速 kdtree,尝试来加速 ICP,但是测试下来发现也只达到 libnabo 的 1.5x ~ 2x 的速度,所以暂时没有继续跟进。
  • cuda_utils:

编译项目

mkdir build && cd build
cmake ..
make -j8

使用 Docker

在 ubuntu 18.04 下,用 docker 来构建是最好的方式,后面会针对加入 ubuntu 16.04 等其他系统的 docker。

获取 docker 镜像

中国大陆地区

在中国大陆,最快的方式就是直接从阿里云获取镜像:

docker pull registry.cn-hangzhou.aliyuncs.com/edward_slam/static_mapping:master_bionic_latest

或者也可以直接在本机构建:

docker build --rm -t slam/static_mapping:latest . 

其他地区

首先,移除掉 dockerfile 中针对中国大陆区域优化的部分:

COPY ./config/tsinghua_source.txt /etc/apt/sources.list
RUN sh -c '. /etc/lsb-release && echo "deb http://mirrors.tuna.tsinghua.edu.cn/ros/ubuntu/ `lsb_release -cs` main" > /etc/apt/sources.list.d/ros1-latest.list' 

接着在本机构建:

docker build --rm -t slam/static_mapping:latest . 

构建项目

## get code 
git clone https://github.com/EdwardLiuyc/StaticMapping.git
cd StaticMapping

## start the docker container
docker run -it --rm -v --net=host `pwd`:'/home/docker/src/StaticMapping' \
  registry.cn-hangzhou.aliyuncs.com/edward_slam/static_mapping:master_bionic_latest /bin/bash

## in the container 
mkdir -p build && cd build
cmake ..
make -j8

如何使用?

目前建议是在本机运行建图,后面会继续完善在 docker 中建图的流程

步骤一 开启建图进程

mkdir pcd
mkdir -p pkgs/test
./mapping.sh

在这之前您可以了解脚本中的具体内容:

## usally, you can leave this config file just like this, it will work fine
CONFIG_PATH=./config/static_mapping_default.xml
## the follow 2 items must be set!!!
## the topic name of your pointcloud msg (ros)
POINT_CLOUD_TOPIC=/fused_point_cloud
## the frame id of your pointcloud msg (ros)
POINT_CLOUD_FRAME_ID=base_link

## the following items are optional
## if you do not have a imu or gps or odom
## just remove the line started with
## imu: -imu -imu_frame_id
## odom: -odom -odom_frame_id
## gps: -gps -gps_frame_id
## and If you got one of these topics
## you MUST provide the tf connection between the one to pointcloud frame
IMU_TOPIC=/imu/data
IMU_FRAME_ID=novatel_imu

ODOM_TOPIC=/navsat/odom
ODOM_FRAME_ID=novatel_odom

GPS_TOPIC=/navsat/fix
GPS_FRAME_ID=novatel_imu

./build/static_mapping_node \
  -cfg ${CONFIG_PATH} \
  -pc ${POINT_CLOUD_TOPIC} \
  -pc_frame_id ${POINT_CLOUD_FRAME_ID} \
  -imu ${IMU_TOPIC} \
  -imu_frame_id ${IMU_FRAME_ID} \
  -odom ${ODOM_TOPIC} \
  -odom_frame_id ${ODOM_FRAME_ID} \
  -gps ${GPS_TOPIC} \
  -gps_frame_id ${GPS_FRAME_ID} 

exit 0 

步骤二

播放 rosbag 或者开启所需的传感器启动

步骤三

直接 'CTRL+C' 停止建图的进程,不过要注意的是进程不会马上结束,您只需要等所有运算结束,点云会生成在 pcd 文件夹中:

其中的一部分:

文档

使用 doxygen Doxyfile 生成文档,文档会生成在 doc 中.

引用

  1. M2DP: A Novel 3D Point Cloud Descriptor and Its Application in Loop,Li He, Xiaolong Wang and Hong Zhang,IEEE International Conference on Intelligent Robots and Systems (2016) 2016-November 231-237
  2. ISAM2: Incremental smoothing and mapping using the Bayes tree,Michael Kaess, Hordur Johannsson, Richard Roberts, Viorela Ila, John Leonard, and Frank Dellaert Abstract, International Journal of Robotics Research (2012) 31(2) 216-235
  3. Comparing ICP Variants on Real-World Data Sets, Autonomous Robots 2013
  4. Fast Segmentation of 3D Pointcloud for Ground Vehicles, M. Himmelsbach and Felix v. Hundelshausen and H.-J. Wuensche, IEEE Intelligent Vehicles Symposium, Proceedings, 2010