- Name: VIRUS-NeRF - Vision, InfraRed and UltraSonic based Neural Radiance Fields
- Authors: Nicolaj Schmid ([email protected]), Cornelius von Einem, Cesar Cadena, Roland Siegwart, Lorenz Hruby and Florian Tschopp
- Keywords: local mapping, NeRF, implicit neural representation, Instant-NGP, occupancy grid, low-cost sensors, infrared sensor, ultrasonic sensor, camera
Autonomous mobile robots are an increasingly integral part of modern factory and warehouse operations. Obstacle detection, avoidance and path planning are critical safety-relevant tasks, which are often solved using expensive LiDAR sensors and depth cameras. We propose to use cost-effective low-resolution ranging sensors, such as ultrasonic and infrared time-of-flight sensors by developing VIRUS-NeRF - Vision, InfraRed, and UltraSonic based Neural Radiance Fields.
Building upon Instant-NGP, VIRUS-NeRF incorporates depth measurements from ultrasonic and infrared sensors and utilizes them to update the occupancy grid used for ray marching. Experimental evaluation in 2D demonstrates that VIRUS-NeRF achieves comparable mapping performance to LiDAR point clouds regarding coverage. Notably, in small environments, its accuracy aligns with that of LiDAR measurements, while in larger ones, it is bounded by the utilized ultrasonic sensors. An in-depth ablation study reveals that adding ultrasonic and infrared sensors is highly effective when dealing with sparse data and low view variation. Further, the proposed occupancy grid of VIRUS-NeRF improves the mapping capabilities and increases the training speed by 46% compared to Instant-NGP. Overall, VIRUS-NeRF presents a promising approach for cost-effective local mapping in mobile robotics, with potential applications in safety and navigation tasks.
- Navigate to the desired directory
- Clone this repository
- Make sure that the requirements indicated in requirements.txt are met
- Contains one second of the ETHZ-office dataset (see sample_dataset).
- Install ROS1
- Create a catkin workspace in USS_experiments/catkin_ws
- Install the following packages inside USS_experiments/catkin_ws/src to create a new dataset: BALM, KISS-ICP, Rosserial, RS-to-Velodyne and Timed Roslaunch
- Install the following packages inside USS_experiments/catkin_ws/src to calibrate the sensors: Camera-LiDAR Calibration and Kilibr
Choose the desired hyper-parameters as described below. Then execute one of the following scripts:
- Single run: run.py
- PSO optimization: run_optimization.py
- Ablation study: run_ablation.py
- Relaunch optimization continuously to circumvent memory leak of Taichi Instant-NGP implementation: watch_optimization.py
- Relaunch ablation continuously to circumvent memory leak of Taichi Instant-NGP implementation: watch_ablation.py
- Connect Arduino and USS
- Flash Arduino with the desired script
- Execute USS_experiments/read_data.py
- Connect Arduino and sensor stacks (USS, IRS and camera)
- Flash Arduino with ETHZ_experimens/Arduino/sensor_stack/sensor_stack.ino
- Navigate to: ETHZ_experimens/catkin_ws/src/sensors/
- Launch logging file to collect the data in Rosbags: roslaunch sensors Launch/stack_log.launch
- Crop Rosbag to have correct start and ending time: rosbag filter
- Create LiDAR poses file and Rosbag with filtered LiDAR pointcloud by launching: roslaunch sensors Launch/lidarFilter_poseEstimation.launch
- Read out filtered LiDAR pointcloud as pcd files: rosrun pcl_ros bag_to_pcd lidar_filtered.bag /rslidar_filtered ./lidars/filtered
- Create dataset for BALM: run src/data_tools/main_balm.py
- Optimize poses with BALM: roslaunch balm2 ethz_dataset.launch
- Create ground truth maps: run src/pcl_tools/pcl_merge.py
- Synchronize data: run src/data_tools/main_syncData.py
- Create final dataset: run src/data_tools/main_rosbag2dataset.py
- Create pose lookup tables run src/data_tools/main_createPoseLookupTables.py
- Visualize dataset: roslaunch sensors Launch/simulation.launch
The hyper-parameters can be set in the json files of the directory args:
Cathegory | Name | Meaning | Type | Options |
---|---|---|---|---|
dataset | name | dataset name | ETHZ or RH2 (Robot@Home2) | |
dataset | spli_ratio | train, validation and test split ratios | dict of floats | must sum up to 1 |
dataset | keep_N_observations | number of samples to load | int | |
dataset | keep_sensor | sensor name to use; only available with RH2 dataset | str | "all" means all sensors; "RGBD", "USS" or "ToF" |
dataset | sensors | sensors to load | list of str | "RGBD", "USS" or "ToF" |
model | ckpt_path | checkpoint path to load | bool or str | false means to start training from skratch |
model | scale | scale of normalized scene | float | |
model | encoder_type | encoder type | str | "hash" or "triplane" |
model | hash_levels | number of hash levels | int | |
model | hash_max_res | resolution of finest hash level | int | |
model | grid_type | type of occupancy grid | str | "occ" (VIRUS-NeRF) or "ngp" (Instant-NGP) |
model | save | save model after training | bool | |
training | batch_size | training batch size | int | |
training | sampling_strategy | sampling strategy for images and pixels | dict | images: "all" or "same"; pixels: "entire_img", "random", "valid_uss" or "valid_tof" |
training | sensors | sensors used for training | list of str | "RGBD", "USS" or "ToF" |
training | max_steps | maximum amount of training steps | int | |
training | max_time | maximum amount of training time | float | |
training | lr | learning rate | float | |
training | rgbd_loss_w | loss weight of RGBD sensor | float | |
training | tof_loss_w | loss weight of IRS (ToF) sensor | float | |
training | uss_loss_w | loss weight of USS sensor | float | |
training | color_loss_w | loss weight of camera | float | |
training | debug_mode | test intermediate results | bool | |
training | real_time_simulation | simulate measurements been done in real-time experiment | bool | |
evaluation | batch_size | evaluation batch size | int | |
evaluation | res_map | side length resolution of evaluation maps | int | |
evaluation | eval_every_n_steps | intermediate evaluation every given steps | int | |
evaluation | num_color_pts | number of colour images to evaluate after training | int | |
evaluation | num_depth_pts | number of depth scans to evaluate after training | int | |
evaluation | num_plot_pts | number of intermediate depth scans to evaluate during training | int | |
evaluation | height_tolerance | distance to consider above and bellow measurements for evaluation | float | |
evaluation | density_map_thr | density threshold for occupancy grid plots | float | |
evaluation | inlier_threshold | inlier/outlier theshold distance in meters for NND plots | float | |
evaluation | zones | definition of zone ranges | dict of lists | |
evaluation | sensors | sensors to evaluate | list of str | "GT", "USS", "ToF", "LiDAR" or "NeRF" |
evaluation | plot_results | wheather to generate plots | bool | |
ngp_grid | update_interval | update grid every given steps | int | |
ngp_grid | warmup_steps | sample all cells for the given first steps | int | |
occ_grid | batch_size | batch size of occupancy grid update | int | |
occ_grid | update_interval | update grid every given steps | int | |
occ_grid | decay_warmup_steps | reduce cell values exponentially for given number of steps | int | |
occ_grid | batch_ratio_ray_update | ratio of Depth-Update; the rest will be NeRF-Update | float | between 0 and 1 |
occ_grid | false_detection_prob_every_m | false detection probability of sensor model (Depth-Update) every meter | float | |
occ_grid | std_every_m | standard deviation of sensor model (Depth-Update) every meter | float | |
occ_grid | nerf_pos_noise_every_m | position noise added during NeRF-Update | float | |
occ_grid | nerf_threshold_max | maximum density threshold for NeRF-Update | float | |
occ_grid | nerf_threshold_slope | density convertion slope for NeRF-Update | float | |
ethz | dataset_dir | path to dataset directory | str | |
ethz | room | name of envrionment | str | "office", "office2", "commonroom", "commonroom2", "corridor" |
ethz | cam_ids | camera identity numbers to load | list of str | "CAM1" or "CAM3" |
ethz | use_optimized_poses | use optimized poses | bool | |
RH2 | dataset_dir | path to dataset directory | str | |
RH2 | session | session name | str | |
RH2 | home | home name | str | |
RH2 | room | room name | str | |
RH2 | subsession | subsession name | str | |
RH2 | home_session | home session id | str | |
RGBD | angle_of_view | angle of view of depth camera in degrees | list of float | |
USS | angle_of_view | ellipsoid angle of view of USS in degrees | list of float | |
USS | angle_of_view | angle of view of IRS (ToF) in degrees | list of float | |
USS | matrix | number of beams | list of ints | |
USS | sensor_calibration_error | angular calibration error added to IRS (ToF) measurements in degrees | float | |
USS | sensor_random_error | add random error to IRS (ToF) depth measurement in meters | float | |
LiDAR | angle_min_max | field of view of LiDAR for given rooms | dict of lists |
The Taichi Instant-NGP implementation is used for this project. All Taichi code is contained inside the modules directory (except of modules/grid.py and modules/occupancy_grid.py which are written by us).
VIRUS-NeRF is based on Instant-NGP: Müller, T., Evans, A., Schied, C., and Keller, A. (2022). Instant neural graphics primitives with a multiresolution hash encoding. ACM Transactions on Graphics (ToG).