Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -216,6 +216,12 @@ roslaunch gslivm livo_botanic_garden.launch
roslaunch gslivm livo_botanic_garden_livox.launch
```

### 5). Run with Livox Mid-360

```bash
roslaunch gslivm livo_mid360.launch
```

## 5.Visualization
Please refer to [Gaussian-Splatting-Cuda](https://github.com/MrNeRF/gaussian-splatting-cuda) to build SIBR_viewer to visualize the 3D gaussian model. Certainly it can be built in the same conda environment. I have installed the dependencies (cos7) in *conda_pkgs.txt*.

Expand Down
39 changes: 39 additions & 0 deletions config/mid360.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
common:
lidar_topic: "/livox/lidar"
imu_topic: "/livox/imu"
image_topic: "/camera/color/image_raw"
image_type: RGB8 # 1 RGB8 2 COMPRESSED
gravity_acc: [ 0.0, 0.0, 9.81 ]

lidar_parameter:
lidar_type: 1 # 1 for Livox serials LiDAR
N_SCANS: 6
SCAN_RATE: 10 # unit: Hz
time_unit: 3 # 0-second, 1-ms, 2-us, 3-ns

imu_parameter:
acc_cov: 0.1
gyr_cov: 0.1
b_acc_cov: 0.0001
b_gyr_cov: 0.0001
time_diff_enable: false

camera_parameter:
image_width: 1280
image_height: 800
image_resize_ratio: 0.5
camera_intrinsic: [ 1000.0, 0.0, 640.0,
0.0, 1000.0, 400.0,
0.0, 0.0, 1.0 ]
camera_dist_coeffs: [ 0.0, 0.0, 0.0, 0.0, 0.0 ] #k1, k2, p1, p2, k3

extrinsic_parameter:
extrinsic_enable: false
extrinsic_t_imu_lidar: [ 0.0, 0.0, 0.0 ]
extrinsic_R_imu_lidar: [ 1, 0, 0,
0, 1, 0,
0, 0, 1 ]
extrinsic_t_imu_camera: [ 0.0, 0.0, 0.0 ]
extrinsic_R_imu_camera: [ 1, 0, 0,
0, 1, 0,
0, 0, 1 ]
10 changes: 10 additions & 0 deletions launch/livo_mid360.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
<launch>
<rosparam command="load" file="$(find gslivm)/config/mid360.yaml" />
<rosparam command="load" file="$(find gslivm)/config/basic_common.yaml" />

<param name="USE_LIVOX" type="bool" value="true"/>
<param name="debug_output" type="bool" value="0"/>
<param name="output_path" type="string" value="$(find gslivm)/output"/>

<node pkg="gslivm" type="livo_node" name="livo_node" output="screen" />
</launch>