Skip to content
This repository is currently being migrated. It's locked while the migration is in progress.

Commit

Permalink
feat:first release
Browse files Browse the repository at this point in the history
  • Loading branch information
Livox-SDK committed Jun 19, 2020
0 parents commit cc14cb1
Show file tree
Hide file tree
Showing 20 changed files with 3,177 additions and 0 deletions.
54 changes: 54 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
cmake_minimum_required(VERSION 2.8.3)
project(livox_mapping)

SET(CMAKE_BUILD_TYPE "Debug")

#set(CMAKE_CXX_COMPILER "/usr/bin/clang++")

#set(CMAKE_C_COMPILER "/usr/bin/clang")
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fexceptions")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -pthread -std=c++0x -std=c++14 -fexceptions -Wno-unused-local-typedefs")

find_package(OpenMP QUIET)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}")
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}")

find_package(catkin REQUIRED COMPONENTS
geometry_msgs
nav_msgs
sensor_msgs
roscpp
rospy
std_msgs
pcl_ros
tf
livox_ros_driver
)

find_package(Eigen3 REQUIRED)
find_package(PCL REQUIRED)
find_package(OpenCV REQUIRED)

include_directories(
${catkin_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIR}
${PCL_INCLUDE_DIRS})

catkin_package(
CATKIN_DEPENDS geometry_msgs nav_msgs roscpp rospy std_msgs
DEPENDS EIGEN3 PCL OpenCV
INCLUDE_DIRS
)

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

add_executable(loam_scanRegistration src/scanRegistration.cpp)
target_link_libraries(loam_scanRegistration ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBS})

add_executable(loam_scanRegistration_horizon src/scanRegistration_horizon.cpp)
target_link_libraries(loam_scanRegistration_horizon ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBS})

add_executable(loam_laserMapping src/laserMapping.cpp)
target_link_libraries(loam_laserMapping ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBS})

97 changes: 97 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,97 @@
## Livox_mapping
Livox_mapping is a mapping package for Livox LiDARs.
The package currently contains the basic functions of low-speed mapping.

<div align="center">
<img src="doc/results/mid40_hall.gif" width = 45% >
<img src="doc/results/horizon_parking.gif" width = 45% >
</div>

Some key issues:
1. Support multiple livox lidar;
2. Different feature extraction;
3. Remove odometry for small FOV situation;

In the development of our package, we reference to LOAM, LOAM_NOTED.
## 1. Prerequisites
### 1.1 **Ubuntu** and **ROS**
Ubuntu 64-bit 16.04 or 18.04.
ROS Kinetic or Melodic. [ROS Installation](http://wiki.ros.org/ROS/Installation)

### 1.2. **PCL && Eigen && openCV**
Follow [PCL Installation](http://www.pointclouds.org/downloads/linux.html).
Follow [Eigen Installation](http://eigen.tuxfamily.org/index.php?title=Main_Page).
Follow [openCV Installation](https://opencv.org/releases/).

### 1.3. **livox_ros_driver**
Follow [livox_ros_driver Installation](https://github.com/Livox-SDK/livox_ros_driver).


## 2. Build
Clone the repository and catkin_make:

```
cd ~/catkin_ws/src
git clone https://github.com/Livox-SDK/livox_mapping.git
cd ..
catkin_make
source ~/catkin_ws/devel/setup.bash
```

*Remarks:*
- If you want to save the pcd file please add map_file_path in launch file.
## 3. Directly run
### 3.1 Livox Mid-40
Connect to your PC to Livox LiDAR (mid40) by following [Livox-ros-driver installation](https://github.com/Livox-SDK/livox_ros_driver), then
```
....
roslaunch livox_mapping mapping_mid.launch
roslaunch livox_ros_driver livox_lidar.launch
```
### 3.2 Livox Horizon
Connect to your PC to Livox LiDAR (Horizon) by following [Livox-ros-driver installation](https://github.com/Livox-SDK/livox_ros_driver), then
```
....
roslaunch livox_mapping mapping_horizon.launch
roslaunch livox_ros_driver livox_lidar.launch
```
## 4. Rosbag Example
### 4.1 Livox Mid-40 rosbag

<div align="center"><img src="doc/results/mid40_hall_01.png" width=90% /></div>

<div align="center"><img src="doc/results/mid40_outdoor.png" width=90% /></div>

Download [mid40_hall_example](https://terra-1-g.djicdn.com/65c028cd298f4669a7f0e40e50ba1131/Showcase/mid40_hall_example.bag) or [mid40_outdoor](https://terra-1-g.djicdn.com/65c028cd298f4669a7f0e40e50ba1131/Showcase/mid40_outdoor.bag)
and then
```
roslaunch livox_mapping mapping_mid.launch
rosbag play YOUR_DOWNLOADED.bag
```
### 4.2 Livox Mid-100 rosbag

<div align="center"><img src="doc/results/mid100_01.png" width=90% /></div>

<div align="center"><img src="doc/results/mid100_02.png" width=90% /></div>

Download [mid100_example](https://terra-1-g.djicdn.com/65c028cd298f4669a7f0e40e50ba1131/Showcase/mid100_example.bag) and then
```
roslaunch livox_mapping mapping_mid.launch
rosbag play YOUR_DOWNLOADED.bag
```
### 4.3 Livox Horizon rosbag

<div align="center"><img src="doc/results/horizon_outdoor_01.png" width=90% /></div>

<div align="center"><img src="doc/results/horizon_parking_01.png" width=90% /></div>

Download [horizon_parking](https://terra-1-g.djicdn.com/65c028cd298f4669a7f0e40e50ba1131/Showcase/horizon_parking.bag) or [horizon_outdoor](https://terra-1-g.djicdn.com/65c028cd298f4669a7f0e40e50ba1131/Showcase/horizon_outdoor.bag)
and then
```
roslaunch livox_mapping mapping_horizon.launch
rosbag play YOUR_DOWNLOADED.bag
```
## 5.Acknowledgments
Thanks for LOAM(J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time), [LOAM_NOTED](https://github.com/cuitaixiang/LOAM_NOTED).
Binary file added doc/results/horizon_outdoor_01.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/results/horizon_parking.gif
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/results/horizon_parking_01.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/results/mid100_01.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/results/mid100_02.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/results/mid40_hall.gif
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/results/mid40_hall_01.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/results/mid40_outdoor.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
22 changes: 22 additions & 0 deletions launch/mapping_horizon.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
<launch>

<arg name="rviz" default="true" />

<node pkg="livox_mapping" type="loam_scanRegistration_horizon" name="scanRegistration_horizon" output="screen">
</node>

<node pkg="livox_mapping" type="loam_laserMapping" name="laserMapping" output="screen">
<param name="map_file_path" type="string" value=" " />
<param name="filter_parameter_corner" type="double" value="0.2" />
<param name="filter_parameter_surf" type="double" value="0.4" />
</node>

<node pkg="livox_mapping" type="livox_repub" name="livox_repub" output="screen" >
<remap from="/livox/lidar" to="/livox/lidar" />
</node>

<group if="$(arg rviz)">
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find livox_mapping)/rviz_cfg/loam_livox.rviz" />
</group>

</launch>
18 changes: 18 additions & 0 deletions launch/mapping_mid.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<launch>

<arg name="rviz" default="true" />

<node pkg="livox_mapping" type="loam_scanRegistration" name="scanRegistration" output="screen">
</node>

<node pkg="livox_mapping" type="loam_laserMapping" name="laserMapping" output="screen">
<param name="map_file_path" type="string" value=" " />
<param name="filter_parameter_corner" type="double" value="0.1" />
<param name="filter_parameter_surf" type="double" value="0.2" />
</node>

<group if="$(arg rviz)">
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find livox_mapping)/rviz_cfg/loam_livox.rviz" />
</group>

</launch>
18 changes: 18 additions & 0 deletions launch/mapping_outdoor.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<launch>

<arg name="rviz" default="true" />

<node pkg="livox_mapping" type="loam_scanRegistration" name="scanRegistration" output="screen">
</node>

<node pkg="livox_mapping" type="loam_laserMapping" name="laserMapping" output="screen">
<param name="map_file_path" type="string" value=" " />
<param name="filter_parameter_corner" type="double" value="0.2" />
<param name="filter_parameter_surf" type="double" value="0.4" />
</node>

<group if="$(arg rviz)">
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find livox_mapping)/rviz_cfg/loam_livox.rviz" />
</group>

</launch>
45 changes: 45 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
<?xml version="1.0"?>
<package>
<name>livox_mapping</name>
<version>0.0.0</version>

<description>
This is a modified version of LOAM which is original algorithm
is described in the following paper:
J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time.
Robotics: Science and Systems Conference (RSS). Berkeley, CA, July 2014.
</description>

<maintainer email="dev@livoxtech.com">claydergc</maintainer>

<license>BSD</license>

<author email="zhangji@cmu.edu">Ji Zhang</author>

<buildtool_depend>catkin</buildtool_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>nav_msgs</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>tf</build_depend>
<build_depend>pcl_ros</build_depend>
<build_depend>livox_ros_driver</build_depend>

<run_depend>geometry_msgs</run_depend>
<run_depend>nav_msgs</run_depend>
<run_depend>sensor_msgs</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>rospy</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>tf</run_depend>
<run_depend>pcl_ros</run_depend>
<run_depend>livox_ros_driver</run_depend>

<test_depend>rostest</test_depend>
<test_depend>rosbag</test_depend>

<export>
</export>
</package>
Empty file added rviz_cfg/.gitignore
Empty file.
Loading

0 comments on commit cc14cb1

Please sign in to comment.