How to run A-LOAM 3D SLAM on reComputer
Introduction to A-LOAM
A-LOAM is an advanced implementation of the original LOAM (Lidar Odometry and Mapping) algorithm by J. Zhang and S. Singh. The key features of A-LOAM include:
- Real-time LiDAR odometry and mapping.
- Simplified code structure using Eigen and Ceres Solver.
- High performance and robustness in diverse environments.
A-LOAM can be used for various applications including autonomous driving, robotics, and 3D mapping.
This wiki provides detailed steps to set up and run the A-LOAM (Advanced LOAM) algorithm on reComputer Jetson Series using a RoboSense RS32 LiDAR sensor. A-LOAM is an advanced implementation of LOAM (Lidar Odometry and Mapping in Real-time) that utilizes Eigen and Ceres Solver for efficient and real-time mapping and localization.
Prerequisites
RoboSense RS32 Lidar.
note- Ensure your reComputer is running Jetpack 5.x. We have only tested on Ubuntu 20.04 and ROS Noetic. Follow the ROS1 installation for reComputer as outlined in this guide to complete the ROS environment setup.
- Ensure you follow the tutorial to launch the RoboSense RS32 LiDAR on reComputer in ROS, and successfully visualize the point cloud data.
Getting Started
Environment Setup
- Step 1: Install gflags, google-glog, suitesparse, cxsparse3, cxsparse.
sudo apt-get install libgflags-dev libgoogle-glog-dev
sudo apt-get install libsuitesparse-dev libcxsparse3 libcxsparse-dev - Step 2: Install PCL (Point Cloud Library).
sudo apt install libpcl-dev
- Step 3: Install Ceres.
wget ceres-solver.org/ceres-solver-1.14.0.tar.gz
tar xvf ceres-solver-1.14.0.tar.gz
cd ceres-solver-1.14.0
mkdir build
cd build
cmake ..
make -j4
sudo make install - Step 4: Clone the A-LOAM code into the src directory of your workspace (~/catkin_ws/src).
cd ~/catkin_ws/src
git clone https://github.com/HKUST-Aerial-Robotics/A-LOAM.git
Modify Configuration Files and Source Code
Step 1: Since the A-LOAM algorithm requires the point cloud type to be XYZIRT, and the RS32 LiDAR default output is XYZI, you need to modify the CMakeLists.txt file at line 8 in the ~/catkin_ws/src/rslidar_sdk/ directory, changing XYZI to XYZIRT.
Step 2: The default point cloud topic that A-LOAM subscribes to is /velodyne_points, while the RS32 LiDAR default output topic is /rslidar_points. Therefore, modify the topic name at line 26 in the ~/catkin_ws/src/rslidar_sdk/config/config.yaml file to /velodyne_points.
Step 3: If you are using C++14, modify line 5 in the CMakeLists.txt file located in the ~/catkin_ws/src/A-LOAM/ directory, changing C++11 to C++14.
Step 4: If you are using OpenCV 4.x, you need to update the OpenCV header file references at line 44 in the scanRegistration.cpp file located in the ~/catkin_ws/src/A-LOAM/src directory (this step can be skipped if you are using OpenCV 3.x).
Replace code
#include <opencv/cv.h>
with
#include <opencv2/opencv.hpp>
Step 5: In lines 91 and 93 of ~/catkin_ws/src/A-LOAM/src/kittiHelper.cpp, change CV_LOAD_IMAGE_GRAYSCALE to cv::IMREAD_GRAYSCALE
Step 6: If you are using tf2, modify all .cpp files (kittiHelper.cpp, laserMapping.cpp, laserOdometry.cpp, scanRegistration.cpp) in the ~/catkin_ws/src/A-LOAM/src/ directory by changing frame_id=/camera_init to frame_id=camera_init, removing only the '/' symbol.
Compile the Package
- Step 1: Go back to the workspace and recompile the feature pack and reload the environment.
cd ~/catkin_ws
catkin_make
source ~/catkin_ws/devel/setup.bash
Starting 3D SLAM
- Step 1: Running lidar code
roslaunch rslidar_sdk start.launch
- Step 2: Running A loam code
roslaunch aloam_velodyne aloam_velodyne_HDL_32.launch
Tech Support & Product Discussion
Thank you for choosing our products! We are here to provide you with different support to ensure that your experience with our products is as smooth as possible. We offer several communication channels to cater to different preferences and needs.