update readme; update launch; remove redundant files

This commit is contained in:
HViktorTsoi
2021-08-08 23:09:40 +08:00
parent 8fbffa2802
commit aa31e7c405
45 changed files with 666 additions and 3569 deletions

2
.gitignore vendored
View File

@@ -6,3 +6,5 @@ Log/*.pdf
.vscode/c_cpp_properties.json
.vscode/settings.json
PCD/*.pcd
.idea
cmake-build-debug

View File

@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 2.8.3)
project(fast_lio)
project(fast_lio_localization)
SET(CMAKE_BUILD_TYPE "Debug")

198
README.md
View File

@@ -1,83 +1,52 @@
## Related Works
# FAST-LIO-LOCALIZATION
1. [ikd-Tree](https://github.com/hku-mars/ikd-Tree): A state-of-art dynamic KD-Tree for 3D kNN search.
2. [IKFOM](https://github.com/hku-mars/IKFoM): A Toolbox for fast and high-precision on-manifold Kalman filter.
3. [UAV Avoiding Dynamic Obstacles](https://github.com/hku-mars/dyn_small_obs_avoidance): One of the implementation of FAST-LIO in robot's planning.
4. [R2LIVE](https://github.com/hku-mars/r2live): A high-precision LiDAR-inertial-Vision fusion work using FAST-LIO as LiDAR-inertial front-end.
5. [UGV Demo](https://www.youtube.com/watch?v=wikgrQbE6Cs): Model Predictive Control for Trajectory Tracking on Differentiable Manifolds.
6. [FAST-LIO-SLAM](https://github.com/gisbi-kim/FAST_LIO_SLAM): The integration of FAST-LIO with [Scan-Context](https://github.com/irapkaist/scancontext) **loop closure** module.
A simple localization framework that can re-localize in built maps based on [FAST-LIO](https://github.com/hku-mars/FAST_LIO).
## FAST-LIO
**FAST-LIO** (Fast LiDAR-Inertial Odometry) is a computationally efficient and robust LiDAR-inertial odometry package. It fuses LiDAR feature points with IMU data using a tightly-coupled iterated extended Kalman filter to allow robust navigation in fast-motion, noisy or cluttered environments where degeneration occurs. Our package address many key issues:
1. Fast iterated Kalman filter for odometry optimization;
2. Automaticaly initialized at most steady environments;
3. Parallel KD-Tree Search to decrease the computation;
## Features
- Realtime 3D global localization in a pre-built point cloud map.
By fusing low-frequency global localization (about 0.5~0.2Hz), and high-frequency odometry from FAST-LIO, the entire system is computationally efficient.
<div align="center"><img src="doc/demo.GIF" width=100% /></div>
- Eliminate the accumulative error of odometry.
<div align="center"><img src="doc/demo_accu.GIF" width=100% /></div>
- The initial localization can be provided either by rough manual estimation from RVIZ, or pose from another sensor/algorithm.
## FAST-LIO 2.0 (2021-07-05 Update)
<!-- ![image](doc/real_experiment2.gif) -->
<!-- [![Watch the video](doc/real_exp_2.png)](https://youtu.be/2OvjGnxszf8) -->
<div align="left">
<img src="doc/real_experiment2.gif" width=49.6% />
<img src="doc/ulhkwh_fastlio.gif" width = 49.6% >
</div>
**Related video:** [FAST-LIO2](https://youtu.be/2OvjGnxszf8), [FAST-LIO1](https://youtu.be/iYCY6T79oNU), [FAST-LIO2 + Scan-context Loop Closure](https://www.youtube.com/watch?v=nu8j4yaBMnw)
**Pipeline:**
<div align="center">
<img src="doc/overview_fastlio2.svg" width=99% />
<img src="doc/demo_init.GIF" width=49.6% />
<img src="doc/demo_init_2.GIF" width = 49.6% >
</div>
**New Features:**
1. Incremental mapping using [ikd-Tree](https://github.com/hku-mars/ikd-Tree), achieve faster speed and over 100Hz LiDAR rate.
2. Direct odometry (scan to map) on Raw LiDAR points (feature extraction can be disabled), achieving better accuracy.
3. Since no requirements for feature extraction, FAST-LIO2 can support may types of LiDAR including spinning (Velodyne, Ouster) and solid-state (Livox Avia, Horizon, MID-70) LiDARs, and can be easily extended to support more LiDARs.
4. Support external IMU.
5. Support ARM-based platforms including Khadas VIM3, Nivida TX2, Raspberry Pi 4B(8G RAM).
**Related papers**:
## Prerequisites
### 1.1 Dependencies for FAST-LIO
[FAST-LIO2: Fast Direct LiDAR-inertial Odometry](doc/Fast_LIO_2.pdf)
Technically, if you have built and run FAST-LIO before, you may skip this section.
[FAST-LIO: A Fast, Robust LiDAR-inertial Odometry Package by Tightly-Coupled Iterated Kalman Filter](https://arxiv.org/abs/2010.08196)
This part of dependency is consistent with FAST-LIO, please refer to the documentation https://github.com/hku-mars/FAST_LIO#1-prerequisites
**Contributors**
### 1.2 Dependencies for localization module
[Wei Xu 徐威](https://github.com/XW-HKU)[Yixi Cai 蔡逸熙](https://github.com/Ecstasy-EC)[Dongjiao He 贺东娇](https://github.com/Joanna-HE)[Fangcheng Zhu 朱方程](https://github.com/zfc-zfc)[Jiarong Lin 林家荣](https://github.com/ziv-lin)[Zheng Liu 刘政](https://github.com/Zale-Liu), [Borong Yuan](https://github.com/borongyuan)
- python 2.7
<!-- <div align="center">
<img src="doc/results/HKU_HW.png" width = 49% >
<img src="doc/results/HKU_MB_001.png" width = 49% >
</div> -->
- [ros_numpy](https://github.com/eric-wieser/ros_numpy)
## 1. Prerequisites
### 1.1 **Ubuntu** and **ROS**
**Ubuntu >= 16.04**
For **Ubuntu 18.04 or higher**, the **default** PCL and Eigen is enough for FAST-LIO to work normally.
ROS >= Melodic. [ROS Installation](http://wiki.ros.org/ROS/Installation)
### 1.2. **PCL && Eigen**
PCL >= 1.8, Follow [PCL Installation](http://www.pointclouds.org/downloads/linux.html).
Eigen >= 3.3.4, Follow [Eigen Installation](http://eigen.tuxfamily.org/index.php?title=Main_Page).
### 1.3. **livox_ros_driver**
Follow [livox_ros_driver Installation](https://github.com/Livox-SDK/livox_ros_driver).
*Remarks:*
- Since the FAST-LIO must support Livox serials LiDAR firstly, so the **livox_ros_driver** must be installed and **sourced** before run any FAST-LIO luanch file.
- How to source? The easiest way is add the line ``` source $Licox_ros_driver_dir$/devel/setup.bash ``` to the end of file ``` ~/.bashrc ```, where ``` $Licox_ros_driver_dir$ ``` is the directory of the livox ros driver workspace (should be the ``` ws_livox ``` directory if you completely followed the livox official document).
- [python-pcl](https://github.com/strawlab/python-pcl)
Notice that, if using **Ubuntu 18.04** with native **PCL 1.8**, there may be issue after installing **python-pcl** through pip,
please refer to https://github.com/barrygxwan/Python-PCL-Ubuntu18.04, download the **.whl** file and then install.
## 2. Build
Clone the repository and catkin_make:
```
cd ~/$A_ROS_DIR$/src
git clone https://github.com/hku-mars/FAST_LIO.git
cd FAST_LIO
git clone https://github.com/hviktortsoi/FAST_LIO_LOCALIZATION.git
cd FAST_LIO_LOCALIZATION
git submodule update --init
cd ../..
catkin_make
@@ -85,107 +54,62 @@ Clone the repository and catkin_make:
```
- Remember to source the livox_ros_driver before build (follow 1.3 **livox_ros_driver**)
- If you want to use a custom build of PCL, add the following line to ~/.bashrc
```export PCL_ROOT={CUSTOM_PCL_PATH}```
## 3. Directly run
```export PCL_ROOT={CUSTOM_PCL_PATH}```
Please make sure the IMU and LiDAR are **Synchronized**, that's important.
### 3.1 For Avia
Connect to your PC to Livox Avia LiDAR by following [Livox-ros-driver installation](https://github.com/Livox-SDK/livox_ros_driver), then
```
cd ~/$FAST_LIO_ROS_DIR$
source devel/setup.bash
roslaunch fast_lio mapping_avia.launch
roslaunch livox_ros_driver livox_lidar_msg.launch
```
- For livox serials, FAST-LIO only support the data collected by the ``` livox_lidar_msg.launch ``` since only its ``` livox_ros_driver/CustomMsg ``` data structure produces the timestamp of each LiDAR point which is very important for the motion undistortion. ``` livox_lidar.launch ``` can not produce it right now.
- If you want to change the frame rate, please modify the **publish_freq** parameter in the [livox_lidar_msg.launch](https://github.com/Livox-SDK/livox_ros_driver/blob/master/livox_ros_driver/launch/livox_lidar_msg.launch) of [Livox-ros-driver](https://github.com/Livox-SDK/livox_ros_driver) before make the livox_ros_driver pakage.
### 3.2 For Livox serials with external IMU
## 3. Run Localization
### Sample Dataset
mapping_avia.launch theratically supports mid-70, mid-40 or other livox serial LiDAR, but need to setup some parameters befor run:
Demo rosbag in a large underground garage:
[Baidu Pan (Code: ne8d)](https://pan.baidu.com/s/1ceBiIAUqHa1vY3QjWpxwNA);
Edit ``` config/avia.yaml ``` to set the below parameters:
Corresponding map: [Baidu Pan (Code: kw6f)](https://pan.baidu.com/s/1Yw4vY3kEK8x2g-AsBi6VCw)
1. LiDAR point cloud topic name: ``` lid_topic ```
2. IMU topic name: ``` imu_topic ```
3. Translational extrinsic: ``` extrinsic_T ```
4. Rotational extrinsic: ``` extrinsic_R ``` (only support rotation matrix)
- The extrinsic parameters in FAST-LIO is defined as the LiDAR's pose (position and rotation matrix) in IMU body frame (i.e. the IMU is the base frame). They can be found in the official manual.
- FAST-LIO produces a very simple software time sync for livox LiDAR, set parameter ```time_sync_en``` to ture to turn on. But turn on **ONLY IF external time synchronization is really not possible**, since the software time sync cannot make sure accuracy.
The map can be built using LIO-SAM or FAST-LIO-SLAM.
### 3.3 For Velodyne or Ouster (Velodyne as an example)
### Run
Step A: Setup before run
1. First, please make sure you're using **Python 2.7** environment;
Edit ``` config/velodyne.yaml ``` to set the below parameters:
1. LiDAR point cloud topic name: ``` lid_topic ```
2. IMU topic name: ``` imu_topic ``` (both internal and external, 6-aixes or 9-axies are fine)
3. Line number (we tested 16, 32 and 64 line, but not tested 128 or above): ``` scan_line ```
4. Translational extrinsic: ``` extrinsic_T ```
5. Rotational extrinsic: ``` extrinsic_R ``` (only support rotation matrix)
- The extrinsic parameters in FAST-LIO is defined as the LiDAR's pose (position and rotation matrix) in IMU body frame (i.e. the IMU is the base frame).
2. Run localization, here we take Livox AVIA as an example:
Step B: Run below
```
cd ~/$FAST_LIO_ROS_DIR$
source devel/setup.bash
roslaunch fast_lio mapping_velodyne.launch
```shell
roslaunch fast_lio_localization localization_avia.launch map:=/path/to/your/map.pcd
```
Step C: Run LiDAR's ros driver or play rosbag.
Please modify `/path/to/your/map.pcd` to your own map point cloud file path.
*Remarks:*
- We will produce some velodyne datasets which is already transfered to Rosbags, please wait for a while.
Wait for 3~5 seconds until the map cloud shows up in RVIZ;
### 3.4 PCD file save
Set ``` pcd_save_enable ``` in launchfile to ``` 1 ```. All the scans (in global frame) will be accumulated and saved to the file ``` FAST_LIO/PCD/scans.pcd ``` after the FAST-LIO is terminated. ```pcl_viewer scans.pcd``` can visualize the point clouds.
*Tips for pcl_viewer:*
- change what to visualize/color by pressing keyboard 1,2,3,4,5 when pcl_viewer is running.
```
1 is all random
2 is X values
3 is Y values
4 is Z values
5 is intensity
3. If you are testing with the sample rosbag data:
```shell
rosbag play localization_test_scene_1.bag
```
## 4. Rosbag Example
### 4.1 Indoor rosbag (Livox Avia LiDAR)
<div align="center"><img src="doc/results/HKU_LG_Indoor.png" width=100% /></div>
Download [avia_indoor_quick_shake_example1](https://drive.google.com/file/d/1SWmrwlUD5FlyA-bTr1rakIYx1GxS4xNl/view?usp=sharing) or [avia_indoor_quick_shake_example2](https://drive.google.com/file/d/1wD485CIbzZlNs4z8e20Dv2Q1q-7Gv_AT/view?usp=sharing) and then
```
roslaunch fast_lio mapping_avia.launch
rosbag play YOUR_DOWNLOADED.bag
Or if you are running realtime
```shell
roslaunch livox_ros_driver livox_lidar_msg.launch
```
### 4.2 Outdoor rosbag (Livox Avia LiDAR)
<div align="center"><img src="doc/results/HKU_MB_002.png" width=100% /></div>
<!-- <div align="center"><img src="doc/results/mid40_outdoor.png" width=90% /></div> -->
Download [avia_hku_main building_mapping](https://drive.google.com/file/d/1GSb9eLQuwqmgI3VWSB5ApEUhOCFG_Sv5/view?usp=sharing) and then
```
roslaunch fast_lio mapping_avia.launch
rosbag play YOUR_DOWNLOADED.bag
4. Provide initial pose
```shell
rosrun fast_lio_localization publish_initial_pose.py 14.5 -7.5 0 -0.25 0 0
```
The numerical value **14.5 -7.5 0 -0.25 0 0** denotes 6D pose **x y z yaw pitch roll** in map frame,
which is a rough initial guess for **localization_test_scene_1.bag**.
## 5.Implementation on UAV
In order to validate the robustness and computational efficiency of FAST-LIO in actual mobile robots, we build a small-scale quadrotor which can carry a Livox Avia LiDAR with 70 degree FoV and a DJI Manifold 2-C onboard computer with a 1.8 GHz Intel i7-8550U CPU and 8 G RAM, as shown in below.
The initial guess can also be provided by the '2D Pose Estimate' Tool in RVIZ.
The main structure of this UAV is 3d printed (Aluminum or PLA), the .stl file will be open-sourced in the future.
Note that, during the initialization stage, it's better to keep the robot still. Or if you play bags, fistly play the bag for about 0.5s, and then pause the bag until the initialization succeed.
<div align="center">
<img src="doc/uav01.jpg" width=40.5% >
<img src="doc/uav_system.png" width=57% >
</div>
## 6.Acknowledgments
## Related Works
1. [FAST-LIO](https://github.com/hku-mars/FAST_LIO): A computationally efficient and robust LiDAR-inertial odometry (LIO) package
2. [FAST-LIO-SLAM](https://github.com/gisbi-kim/FAST_LIO_SLAM): The integration of FAST-LIO with [Scan-Context](https://github.com/irapkaist/scancontext) **loop closure** module.
3. [LIO-SAM_based_relocalization](https://github.com/Gaochao-hit/LIO-SAM_based_relocalization): A simple system that can relocalize a robot on a built map based on LIO-SAM.
Thanks for LOAM(J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time), [Livox_Mapping](https://github.com/Livox-SDK/livox_mapping), [LINS](https://github.com/ChaoqinRobotics/LINS---LiDAR-inertial-SLAM) and [Loam_Livox](https://github.com/hku-mars/loam_livox).
## Acknowledgments
Thanks for the authors of [FAST-LIO](https://github.com/hku-mars/FAST_LIO) and [LIO-SAM_based_relocalization](https://github.com/Gaochao-hit/LIO-SAM_based_relocalization).

Binary file not shown.

Before

Width:  |  Height:  |  Size: 323 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 244 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 13 MiB

After

Width:  |  Height:  |  Size: 13 MiB

BIN
doc/demo_accu.GIF Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 6.7 MiB

BIN
doc/demo_init.GIF Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.0 MiB

BIN
doc/demo_init_2.GIF Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.2 MiB

File diff suppressed because one or more lines are too long

Before

Width:  |  Height:  |  Size: 401 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 2.0 MiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 50 MiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 2.2 MiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 1.6 MiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 1.9 MiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 4.9 MiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 3.1 MiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 962 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 580 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 1.2 MiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 1.8 MiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 1.4 MiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 774 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 698 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 1.3 MiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 549 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 1.2 MiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 434 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 2.0 MiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 333 KiB

Binary file not shown.

Binary file not shown.

Before

Width:  |  Height:  |  Size: 421 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 34 MiB

View File

@@ -0,0 +1,35 @@
<launch>
<!-- Launch file for Livox AVIA LiDAR -->
<arg name="rviz" default="true" />
<rosparam command="load" file="$(find fast_lio_localization)/config/avia.yaml" />
<param name="feature_extract_enable" type="bool" value="0"/>
<param name="point_filter_num" type="int" value="1"/>
<param name="max_iteration" type="int" value="3" />
<param name="filter_size_surf" type="double" value="0.5" />
<param name="filter_size_map" type="double" value="0.5" />
<param name="cube_side_length" type="double" value="1000" />
<param name="runtime_pos_log_enable" type="bool" value="0" />
<param name="pcd_save_enable" type="bool" value="0" />
<node pkg="fast_lio_localization" type="fastlio_mapping" name="laserMapping" output="screen" />
<arg name="map" default="" />
<!-- loalization-->
<node pkg="fast_lio_localization" type="global_localization.py" name="global_localization" output="screen" />
<!-- transform fusion-->
<node pkg="fast_lio_localization" type="transform_fusion.py" name="transform_fusion" output="screen" />
<!-- glbal map-->
<node pkg="pcl_ros" type="pcd_to_pointcloud" name="map_publishe" output="screen"
args="$(arg map) 5 _frame_id:=/map cloud_pcd:=/map" />
<group if="$(arg rviz)">
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find fast_lio_localization)/rviz_cfg/localization.rviz" />
</group>
</launch>

View File

@@ -0,0 +1,34 @@
<launch>
<!-- Launch file for Livox Horizon LiDAR -->
<arg name="rviz" default="true" />
<rosparam command="load" file="$(find fast_lio_localization)/config/horizon.yaml" />
<param name="feature_extract_enable" type="bool" value="0"/>
<param name="point_filter_num" type="int" value="3"/>
<param name="dense_publish_enable" type="bool" value="1" />
<param name="filter_size_surf" type="double" value="0.5" />
<param name="filter_size_map" type="double" value="0.5" />
<param name="cube_side_length" type="double" value="1000" />
<param name="runtime_pos_log_enable" type="bool" value="0" />
<param name="pcd_save_enable" type="bool" value="0" />
<node pkg="fast_lio_localization" type="fastlio_mapping" name="laserMapping" output="screen" />
<arg name="map" default="" />
<!-- loalization-->
<node pkg="fast_lio_localization" type="global_localization.py" name="global_localization" output="screen" />
<!-- transform fusion-->
<node pkg="fast_lio_localization" type="transform_fusion.py" name="transform_fusion" output="screen" />
<!-- glbal map-->
<node pkg="pcl_ros" type="pcd_to_pointcloud" name="map_publishe" output="screen"
args="$(arg map) 5 _frame_id:=/map cloud_pcd:=/map" />
<group if="$(arg rviz)">
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find fast_lio_localization)/rviz_cfg/localization.rviz" />
</group>
</launch>

View File

@@ -0,0 +1,34 @@
<launch>
<!-- Launch file for ouster OS2-64 LiDAR -->
<arg name="rviz" default="true" />
<rosparam command="load" file="$(find fast_lio_localization)/config/ouster64.yaml" />
<param name="feature_extract_enable" type="bool" value="0"/>
<param name="point_filter_num" type="int" value="4"/>
<param name="max_iteration" type="int" value="3" />
<param name="filter_size_surf" type="double" value="0.5" />
<param name="filter_size_map" type="double" value="0.5" />
<param name="cube_side_length" type="double" value="1000" />
<param name="runtime_pos_log_enable" type="bool" value="0" />
<param name="pcd_save_enable" type="bool" value="0" />
<node pkg="fast_lio_localization" type="fastlio_mapping" name="laserMapping" output="screen" />
<arg name="map" default="" />
<!-- loalization-->
<node pkg="fast_lio_localization" type="global_localization.py" name="global_localization" output="screen" />
<!-- transform fusion-->
<node pkg="fast_lio_localization" type="transform_fusion.py" name="transform_fusion" output="screen" />
<!-- glbal map-->
<node pkg="pcl_ros" type="pcd_to_pointcloud" name="map_publishe" output="screen"
args="$(arg map) 5 _frame_id:=/map cloud_pcd:=/map" />
<group if="$(arg rviz)">
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find fast_lio_localization)/rviz_cfg/localization.rviz" />
</group>
</launch>

View File

@@ -0,0 +1,34 @@
<launch>
<!-- Launch file for velodyne16 VLP-16 LiDAR -->
<arg name="rviz" default="true" />
<rosparam command="load" file="$(find fast_lio_localization)/config/velodyne.yaml" />
<param name="feature_extract_enable" type="bool" value="0"/>
<param name="point_filter_num" type="int" value="4"/>
<param name="max_iteration" type="int" value="3" />
<param name="filter_size_surf" type="double" value="0.5" />
<param name="filter_size_map" type="double" value="0.5" />
<param name="cube_side_length" type="double" value="1000" />
<param name="runtime_pos_log_enable" type="bool" value="0" />
<param name="pcd_save_enable" type="bool" value="0" />
<node pkg="fast_lio_localization" type="fastlio_mapping" name="laserMapping" output="screen" />
<arg name="map" default="" />
<!-- loalization-->
<node pkg="fast_lio_localization" type="global_localization.py" name="global_localization" output="screen" />
<!-- transform fusion-->
<node pkg="fast_lio_localization" type="transform_fusion.py" name="transform_fusion" output="screen" />
<!-- glbal map-->
<node pkg="pcl_ros" type="pcd_to_pointcloud" name="map_publishe" output="screen"
args="$(arg map) 5 _frame_id:=/map cloud_pcd:=/map" />
<group if="$(arg rviz)">
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find fast_lio_localization)/rviz_cfg/localization.rviz" />
</group>
</launch>

View File

@@ -1,22 +0,0 @@
<launch>
<!-- Launch file for Livox AVIA LiDAR -->
<arg name="rviz" default="true" />
<rosparam command="load" file="$(find fast_lio)/config/avia.yaml" />
<param name="feature_extract_enable" type="bool" value="0"/>
<param name="point_filter_num" type="int" value="1"/>
<param name="max_iteration" type="int" value="3" />
<param name="filter_size_surf" type="double" value="0.5" />
<param name="filter_size_map" type="double" value="0.5" />
<param name="cube_side_length" type="double" value="1000" />
<param name="runtime_pos_log_enable" type="bool" value="0" />
<param name="pcd_save_enable" type="bool" value="0" />
<node pkg="fast_lio" type="fastlio_mapping" name="laserMapping" output="screen" />
<group if="$(arg rviz)">
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find fast_lio)/rviz_cfg/loam_livox.rviz" />
</group>
</launch>

View File

@@ -1,22 +0,0 @@
<launch>
<!-- Launch file for Livox Horizon LiDAR -->
<arg name="rviz" default="true" />
<rosparam command="load" file="$(find fast_lio)/config/horizon.yaml" />
<param name="feature_extract_enable" type="bool" value="0"/>
<param name="point_filter_num" type="int" value="3"/>
<param name="dense_publish_enable" type="bool" value="1" />
<param name="filter_size_surf" type="double" value="0.5" />
<param name="filter_size_map" type="double" value="0.5" />
<param name="cube_side_length" type="double" value="1000" />
<param name="runtime_pos_log_enable" type="bool" value="0" />
<param name="pcd_save_enable" type="bool" value="0" />
<node pkg="fast_lio" type="fastlio_mapping" name="laserMapping" output="screen" />
<group if="$(arg rviz)">
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find fast_lio)/rviz_cfg/loam_livox.rviz" />
</group>
</launch>

View File

@@ -1,22 +0,0 @@
<launch>
<!-- Launch file for ouster OS2-64 LiDAR -->
<arg name="rviz" default="true" />
<rosparam command="load" file="$(find fast_lio)/config/ouster64.yaml" />
<param name="feature_extract_enable" type="bool" value="0"/>
<param name="point_filter_num" type="int" value="4"/>
<param name="max_iteration" type="int" value="3" />
<param name="filter_size_surf" type="double" value="0.5" />
<param name="filter_size_map" type="double" value="0.5" />
<param name="cube_side_length" type="double" value="1000" />
<param name="runtime_pos_log_enable" type="bool" value="0" />
<param name="pcd_save_enable" type="bool" value="0" />
<node pkg="fast_lio" type="fastlio_mapping" name="laserMapping" output="screen" />
<group if="$(arg rviz)">
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find fast_lio)/rviz_cfg/loam_livox.rviz" />
</group>
</launch>

View File

@@ -1,22 +0,0 @@
<launch>
<!-- Launch file for velodyne16 VLP-16 LiDAR -->
<arg name="rviz" default="true" />
<rosparam command="load" file="$(find fast_lio)/config/velodyne.yaml" />
<param name="feature_extract_enable" type="bool" value="0"/>
<param name="point_filter_num" type="int" value="4"/>
<param name="max_iteration" type="int" value="3" />
<param name="filter_size_surf" type="double" value="0.5" />
<param name="filter_size_map" type="double" value="0.5" />
<param name="cube_side_length" type="double" value="1000" />
<param name="runtime_pos_log_enable" type="bool" value="0" />
<param name="pcd_save_enable" type="bool" value="0" />
<node pkg="fast_lio" type="fastlio_mapping" name="laserMapping" output="screen" />
<group if="$(arg rviz)">
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find fast_lio)/rviz_cfg/loam_livox.rviz" />
</group>
</launch>

View File

@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<package>
<name>fast_lio</name>
<name>fast_lio_localization</name>
<version>0.0.0</version>
<description>

View File

@@ -16,7 +16,7 @@ Panels:
- /Odometry1/Odometry1/Covariance1/Orientation1
- /MarkerArray1/Namespaces1
Splitter Ratio: 0.6432291865348816
Tree Height: 1146
Tree Height: 1139
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
@@ -85,14 +85,14 @@ Visualization Manager:
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 234
Max Intensity: 255
Min Color: 0; 0; 0
Min Intensity: 0
Name: surround
Position Transformer: XYZ
Queue Size: 1
Selectable: false
Size (Pixels): 3
Size (Pixels): 1
Size (m): 0.05000000074505806
Style: Points
Topic: /cloud_registered
@@ -100,8 +100,8 @@ Visualization Manager:
Use Fixed Frame: true
Use rainbow: true
Value: true
- Alpha: 0.15000000596046448
Autocompute Intensity Bounds: true
- Alpha: 0.6000000238418579
Autocompute Intensity Bounds: false
Autocompute Value Bounds:
Max Value: 15
Min Value: -5
@@ -110,12 +110,12 @@ Visualization Manager:
Channel Name: intensity
Class: rviz/PointCloud2
Color: 255; 255; 255
Color Transformer: AxisColor
Color Transformer: Intensity
Decay Time: 1000
Enabled: true
Invert Rainbow: true
Enabled: false
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 0
Max Intensity: 70
Min Color: 0; 0; 0
Min Intensity: 0
Name: currPoints
@@ -129,7 +129,7 @@ Visualization Manager:
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
Value: false
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
@@ -325,26 +325,26 @@ Visualization Manager:
Value: true
Views:
Current:
Class: rviz/ThirdPersonFollower
Distance: 89.18838500976562
Class: rviz/Orbit
Distance: 19.453998565673828
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: -4.903029441833496
Y: -19.24248504638672
Z: -2.85572896245867e-5
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: false
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.29979732632637024
Target Frame: global
Value: ThirdPersonFollower (rviz)
Yaw: 4.977229118347168
Pitch: 1.0753980875015259
Target Frame: body
Value: Orbit (rviz)
Yaw: 2.4953973293304443
Saved: ~
Window Geometry:
Displays:
@@ -352,7 +352,7 @@ Window Geometry:
Height: 1385
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd0000000400000000000001c8000004b7fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000004b7000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650000000297000001dc0000000000000000fb0000000a0049006d0061006700650000000394000001600000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c700000000000000000000000100000152000004b7fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000004b7000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000009bd00000052fc0100000002fb0000000800540069006d00650100000000000009bd000002eb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000697000004b700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
QMainWindow State: 000000ff00000000fd0000000400000000000001c8000004b3fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003f000004b3000000cc00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650000000297000001dc0000000000000000fb0000000a0049006d0061006700650000000394000001600000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c700000000000000000000000100000152000004b3fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003f000004b3000000a900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000009c100000052fc0100000002fb0000000800540069006d00650100000000000009c10000031300fffffffb0000000800540069006d006501000000000000045000000000000000000000069b000004b300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
@@ -361,6 +361,6 @@ Window Geometry:
collapsed: false
Views:
collapsed: false
Width: 2493
X: 67
Width: 2497
X: 63
Y: 27

437
rviz_cfg/localization.rviz Normal file
View File

@@ -0,0 +1,437 @@
Panels:
- Class: rviz/Displays
Help Height: 0
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /mapping1/surround1
- /mapping1/currPoints1
- /mapping1/currPoints1/Autocompute Value Bounds1
- /Odometry1/Odometry1
- /Odometry1/Odometry1/Shape1
- /Odometry1/Odometry1/Covariance1
- /Odometry1/Odometry1/Covariance1/Position1
- /Odometry1/Odometry1/Covariance1/Orientation1
- /Localization1
- /Localization1/map1
- /Localization1/localization1
- /Localization1/localization1/Shape1
- /MarkerArray1/Namespaces1
Splitter Ratio: 0.6382352709770203
Tree Height: 779
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: map
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 1
Cell Size: 1000
Class: rviz/Grid
Color: 160; 160; 164
Enabled: false
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 40
Reference Frame: <Fixed Frame>
Value: false
- Class: rviz/Axes
Enabled: false
Length: 0.699999988079071
Name: Axes
Radius: 0.05999999865889549
Reference Frame: <Fixed Frame>
Value: false
- Class: rviz/Group
Displays:
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud2
Color: 238; 238; 236
Color Transformer: Intensity
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 255
Min Color: 0; 0; 0
Min Intensity: 0
Name: surround
Position Transformer: XYZ
Queue Size: 1
Selectable: false
Size (Pixels): 1
Size (m): 0.05000000074505806
Style: Points
Topic: /cloud_registered
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
- Alpha: 0.6000000238418579
Autocompute Intensity Bounds: false
Autocompute Value Bounds:
Max Value: 15
Min Value: -5
Value: false
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud2
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 1000
Enabled: false
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 70
Min Color: 0; 0; 0
Min Intensity: 0
Name: currPoints
Position Transformer: XYZ
Queue Size: 100000
Selectable: true
Size (Pixels): 1
Size (m): 0.009999999776482582
Style: Points
Topic: /cloud_registered
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: false
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud2
Color: 255; 0; 0
Color Transformer: FlatColor
Decay Time: 0
Enabled: false
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 151
Min Color: 0; 0; 0
Min Intensity: 0
Name: PointCloud2
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.10000000149011612
Style: Flat Squares
Topic: /Laser_map
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: false
Enabled: false
Name: mapping
- Class: rviz/Group
Displays:
- Angle Tolerance: 0.009999999776482582
Class: rviz/Odometry
Covariance:
Orientation:
Alpha: 0.5
Color: 255; 255; 127
Color Style: Unique
Frame: Local
Offset: 1
Scale: 1
Value: true
Position:
Alpha: 0.30000001192092896
Color: 204; 51; 204
Scale: 1
Value: true
Value: true
Enabled: true
Keep: 1
Name: Odometry
Position Tolerance: 0.0010000000474974513
Shape:
Alpha: 1
Axes Length: 1
Axes Radius: 0.20000000298023224
Color: 255; 85; 0
Head Length: 0
Head Radius: 0
Shaft Length: 0.05000000074505806
Shaft Radius: 0.05000000074505806
Value: Axes
Topic: /Odometry
Unreliable: false
Value: true
Enabled: false
Name: Odometry
- Class: rviz/Group
Displays:
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud2
Color: 252; 233; 79
Color Transformer: FlatColor
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 255
Min Color: 0; 0; 0
Min Intensity: 0
Name: cur_scan_in_map
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.009999999776482582
Style: Points
Topic: /cur_scan_in_map
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
- Alpha: 0.5
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud2
Color: 138; 226; 52
Color Transformer: FlatColor
Decay Time: 0
Enabled: false
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 0
Min Color: 0; 0; 0
Min Intensity: 0
Name: submap_in_FOV
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.009999999776482582
Style: Points
Topic: /submap
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: false
- Alpha: 0.4000000059604645
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/PointCloud2
Color: 255; 25; 0
Color Transformer: FlatColor
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 255
Min Color: 0; 0; 0
Min Intensity: 0
Name: map
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 1
Size (m): 0.009999999776482582
Style: Points
Topic: /map
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
- Angle Tolerance: 0.10000000149011612
Class: rviz/Odometry
Covariance:
Orientation:
Alpha: 0.5
Color: 255; 255; 127
Color Style: Unique
Frame: Local
Offset: 1
Scale: 1
Value: true
Position:
Alpha: 0.30000001192092896
Color: 204; 51; 204
Scale: 1
Value: true
Value: true
Enabled: true
Keep: 500
Name: localization
Position Tolerance: 0.10000000149011612
Shape:
Alpha: 1
Axes Length: 1
Axes Radius: 0.10000000149011612
Color: 138; 226; 52
Head Length: 0.30000001192092896
Head Radius: 0.10000000149011612
Shaft Length: 1
Shaft Radius: 1
Value: Arrow
Topic: /localization
Unreliable: false
Value: true
Enabled: true
Name: Localization
- Class: rviz/Axes
Enabled: true
Length: 0.699999988079071
Name: Axes
Radius: 0.10000000149011612
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 0
Buffer Length: 2
Class: rviz/Path
Color: 25; 255; 255
Enabled: true
Head Diameter: 0
Head Length: 0
Length: 0.30000001192092896
Line Style: Billboards
Line Width: 0.20000000298023224
Name: Path
Offset:
X: 0
Y: 0
Z: 0
Pose Color: 25; 255; 255
Pose Style: None
Radius: 0.029999999329447746
Shaft Diameter: 0.4000000059604645
Shaft Length: 0.4000000059604645
Topic: /path
Unreliable: false
Value: true
- Class: rviz/MarkerArray
Enabled: false
Marker Topic: /MarkerArray
Name: MarkerArray
Namespaces:
{}
Queue Size: 100
Value: false
Enabled: true
Global Options:
Background Color: 0; 0; 0
Default Light: true
Fixed Frame: map
Frame Rate: 20
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 49.95238494873047
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 52.61579895019531
Y: -22.996828079223633
Z: 0.13604862987995148
Focal Shape Fixed Size: false
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 1.0397968292236328
Target Frame: map
Value: Orbit (rviz)
Yaw: 1.380398154258728
Saved: ~
Window Geometry:
Displays:
collapsed: true
Height: 1385
Hide Left Dock: true
Hide Right Dock: true
QMainWindow State: 000000ff00000000fd0000000400000000000001560000034bfc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003f0000034b000000cc00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650000000297000001dc0000000000000000fb0000000a0049006d0061006700650000000394000001600000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c7000000000000000000000001000001520000034bfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003f0000034b000000a900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000009c100000052fc0100000002fb0000000800540069006d00650100000000000009c10000031300fffffffb0000000800540069006d00650100000000000004500000000000000000000009c1000004b300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: true
Width: 2497
X: 63
Y: 27

View File

@@ -556,7 +556,8 @@ void publish_odometry(const ros::Publisher & pubOdomAftMapped)
{
odomAftMapped.header.frame_id = "camera_init";
odomAftMapped.child_frame_id = "body";
odomAftMapped.header.stamp = ros::Time().fromSec(lidar_end_time);// ros::Time().fromSec(lidar_end_time);
// odomAftMapped.header.stamp = ros::Time().fromSec(lidar_end_time);// ros::Time().fromSec(lidar_end_time);
odomAftMapped.header.stamp = ros::Time::now();// ros::Time().fromSec(lidar_end_time);
set_posestamp(odomAftMapped.pose);
pubOdomAftMapped.publish(odomAftMapped);
auto P = kf.get_P();
@@ -582,7 +583,9 @@ void publish_odometry(const ros::Publisher & pubOdomAftMapped)
q.setY(odomAftMapped.pose.pose.orientation.y);
q.setZ(odomAftMapped.pose.pose.orientation.z);
transform.setRotation( q );
br.sendTransform( tf::StampedTransform( transform, odomAftMapped.header.stamp, "camera_init", "body" ) );
// TODO 这里使用当前时间发布tf 否则当livox时间不正确时无法正常tf
// br.sendTransform( tf::StampedTransform( transform, odomAftMapped.header.stamp, "camera_init", "body" ) );
br.sendTransform( tf::StampedTransform( transform, ros::Time::now(), "camera_init", "body" ) );
}
void publish_path(const ros::Publisher pubPath)