LIO-SAM install (ROS1 noetic)

https://github.com/TixiaoShan/LIO-SAM.git


Reference

https://github.com/TixiaoShan/LIO-SAM/issues/206


1) Install GTSAM following readme
 

2) Configure the utility.h to use #include <opencv2/opencv.hpp> instead of #include <opencv/cv.h>
 

Move #include <opencv2/opencv.hpp> after the pcl headers

 

3) Configure CMakeLists.txt to use set(CMAKE_CXX_FLAGS "-std=c++14") instead of set(CMAKE_CXX_FLAGS "-std=c++11")
 

4) Launch

 

5)  Save PCD

 

0. install to need the ros package
sudo apt-get install -y ros-noetic-navigation
sudo apt-get install -y ros-noetic-robot-localization
sudo apt-get install -y ros-noetic-robot-state-publisher

 

1. Install GTSAM following readme

https://gtsam.org/get_started/

Add PPA for the latest GTSAM 4.x stable release

sip2@sip2-2021:~$ sudo add-apt-repository ppa:borglab/gtsam-release-4.0
sip2@sip2-2021:~$ sudo apt update
sip2@sip2-2021:~$ sudo apt install libgtsam-dev libgtsam-unstable-dev

 

2. Configure the utility.h to use #include <opencv2/opencv.hpp> instead of #include <opencv/cv.h>

 

sip2@sip2-2021:~$ mkdir -p ~/catkin_lio_sam/src
sip2@sip2-2021:~$ cd ~/catkin_lio_sam/src
sip2@sip2-2021:~/catkin_lio_sam/src$ git clone https://github.com/TixiaoShan/LIO-SAM.git
Cloning into 'LIO-SAM'...
remote: Enumerating objects: 792, done.
remote: Counting objects: 100% (29/29), done.
remote: Compressing objects: 100% (22/22), done.
remote: Total 792 (delta 11), reused 14 (delta 6), pack-reused 763
Receiving objects: 100% (792/792), 127.84 MiB | 12.49 MiB/s, done.
Resolving deltas: 100% (442/442), done. 

 

before utility.h

#pragma once
#ifndef _UTILITY_LIDAR_ODOMETRY_H_
#define _UTILITY_LIDAR_ODOMETRY_H_
#define PCL_NO_PRECOMPILE

#include <ros/ros.h>

#include <std_msgs/Header.h>
#include <std_msgs/Float64MultiArray.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/NavSatFix.h>
#include <nav_msgs/Odometry.h>
#include <nav_msgs/Path.h>
#include <visualization_msgs/Marker.h>
#include <visualization_msgs/MarkerArray.h>

#include <opencv/cv.h> // delete

#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/search/impl/search.hpp>
#include <pcl/range_image/range_image.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/common/common.h>
#include <pcl/common/transforms.h>
#include <pcl/registration/icp.h>
#include <pcl/io/pcd_io.h>
#include <pcl/filters/filter.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/filters/crop_box.h>
#include <pcl_conversions/pcl_conversions.h>

 

 after utility.h

#pragma once
#ifndef _UTILITY_LIDAR_ODOMETRY_H_
#define _UTILITY_LIDAR_ODOMETRY_H_
#define PCL_NO_PRECOMPILE

#include <ros/ros.h>

#include <std_msgs/Header.h>
#include <std_msgs/Float64MultiArray.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/NavSatFix.h>
#include <nav_msgs/Odometry.h>
#include <nav_msgs/Path.h>
#include <visualization_msgs/Marker.h>
#include <visualization_msgs/MarkerArray.h>

#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/search/impl/search.hpp>
#include <pcl/range_image/range_image.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/common/common.h>
#include <pcl/common/transforms.h>
#include <pcl/registration/icp.h>
#include <pcl/io/pcd_io.h>
#include <pcl/filters/filter.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/filters/crop_box.h>
#include <pcl_conversions/pcl_conversions.h>

#include <opencv2/opencv.hpp>    //insert


3. Configure CMakeLists.txt to use set(CMAKE_CXX_FLAGS "-std=c++14") instead of set(CMAKE_CXX_FLAGS "-std=c++11")

before

cmake_minimum_required(VERSION 2.8.3)
project(lio_sam)

set(CMAKE_BUILD_TYPE "Release")
set(CMAKE_CXX_FLAGS "-std=c++11")
set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -g -pthread")

 

after

cmake_minimum_required(VERSION 2.8.3)
project(lio_sam)

set(CMAKE_BUILD_TYPE "Release")
set(CMAKE_CXX_FLAGS "-std=c++14")
set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -g -pthread")


sip2@sip2-2021:~/catkin_lio_sam$ catkin_make -j1

[100%] Generating EusLisp manifest code for lio_sam
[100%] Built target lio_sam_generate_messages_eus
Scanning dependencies of target lio_sam_generate_messages
[100%] Built target lio_sam_generate_messages


4. Launch

sip2@sip2-2021:~/catkin_lio_sam$ source devel/setup.bash
sip2@sip2-2021:~/catkin_lio_sam$ roslaunch lio_sam run.launch
[ INFO] [1663207863.351423722]: ----> Feature Extraction Started.
[ INFO] [1663207863.360245612]: ----> Image Projection Started.
[ INFO] [1663207863.371944484]: ----> Map Optimization Started.
[ INFO] [1663207863.375593675]: ----> IMU Preintegration Started.

sip2@sip2-2021:~/Downloads$ rosbag play park_dataset.bag -r 3
[ INFO] [1663207943.222557262]: Opening park_dataset.bag

Waiting 0.2 seconds after advertising topics... done.

Hit space to toggle paused, or 's' to step.
 [RUNNING]  Bag Time: 1593996836.773328   Duration: 560.557628 / 560.563894               7.32  




5. Save PCD 

rosservice call [service] [resolution] [destination]

sip2@sip2-2021:~/catkin_lio_sam$ source devel/setup.bash
sip2@sip2-2021:~/catkin_lio_sam$ rosservice call /lio_sam/save_map 0.2 "/Downloads/LOAM/"
success: True

Saving map to pcd files ...
Save destination: /home/sip2/Downloads/LOAM/
rm: cannot remove '/home/sip2/Downloads/LOAM/': No such file or directory
Processing feature cloud 658 of 659 ...

Save resolution: 0.2
****************************************************
Saving map to pcd files completed




コメント