mirror of
https://github.com/karma-riuk/hdr_esim.git
synced 2025-06-20 11:18:12 +02:00
initial commit
This commit is contained in:
23
event_camera_simulator/esim_ros/CMakeLists.txt
Normal file
23
event_camera_simulator/esim_ros/CMakeLists.txt
Normal file
@ -0,0 +1,23 @@
|
||||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(esim_ros)
|
||||
|
||||
find_package(catkin_simple REQUIRED)
|
||||
find_package(OpenCV REQUIRED)
|
||||
catkin_simple()
|
||||
|
||||
set(HEADERS
|
||||
)
|
||||
|
||||
set(SOURCES
|
||||
src/esim_node.cpp
|
||||
)
|
||||
|
||||
cs_add_library(${PROJECT_NAME} ${SOURCES} ${HEADERS})
|
||||
|
||||
# make the executable
|
||||
cs_add_executable(esim_node src/esim_node.cpp)
|
||||
|
||||
# link the executable to the necessary libs
|
||||
target_link_libraries(esim_node ${PROJECT_NAME} ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})
|
||||
|
||||
cs_install()
|
27
event_camera_simulator/esim_ros/cfg/calib/example.conf
Normal file
27
event_camera_simulator/esim_ros/cfg/calib/example.conf
Normal file
@ -0,0 +1,27 @@
|
||||
label: "simulated_camera"
|
||||
id: 433585ebda8d1431223927a14788a127
|
||||
cameras:
|
||||
- camera:
|
||||
label: dvs0
|
||||
id: a0fba5412e961934d842d3a2a78e5cba
|
||||
line-delay-nanoseconds: 0
|
||||
image_height: 180
|
||||
image_width: 240
|
||||
type: pinhole
|
||||
intrinsics:
|
||||
cols: 1
|
||||
rows: 4
|
||||
data: [198.245521288, 198.277025706, 120.0, 90.0]
|
||||
distortion:
|
||||
type: none
|
||||
parameters:
|
||||
cols: 1
|
||||
rows: 0
|
||||
data: []
|
||||
T_B_C:
|
||||
cols: 4
|
||||
rows: 4
|
||||
data: [1, 0, 0, 0,
|
||||
0, 0, 1, 0,
|
||||
0, -1, 0, 0,
|
||||
0, 0, 0, 1]
|
27
event_camera_simulator/esim_ros/cfg/calib/ijrr.yaml
Normal file
27
event_camera_simulator/esim_ros/cfg/calib/ijrr.yaml
Normal file
@ -0,0 +1,27 @@
|
||||
label: "DAVIS-IJRR17"
|
||||
id: a0652606b3d9fd6b62f5448a9e1304be
|
||||
cameras:
|
||||
- camera:
|
||||
label: dvs
|
||||
id: 07e806d3367b4a6fa18a52178e4bbaf9
|
||||
line-delay-nanoseconds: 0
|
||||
image_height: 180
|
||||
image_width: 240
|
||||
type: pinhole
|
||||
intrinsics:
|
||||
cols: 1
|
||||
rows: 4
|
||||
data: [199.37143467278824, 199.7078674353677, 133.75438071590816, 113.99216995027632]
|
||||
distortion:
|
||||
type: radial-tangential
|
||||
parameters:
|
||||
cols: 1
|
||||
rows: 4
|
||||
data: [-0.38289915571515265, 0.18933636521343228, -0.0010024743349031492, -0.0005637766302076818]
|
||||
T_B_C:
|
||||
cols: 4
|
||||
rows: 4
|
||||
data: [0.999905117246, -0.0122374970355, 0.00632456886338, 0.00674696422488,
|
||||
0.0121780171243, 0.999882045134, 0.00935904469797, 0.0007279224709,
|
||||
-0.00643835413146, -0.00928113597812, 0.99993620202, 0.0342573613538,
|
||||
0.0, 0.0, 0.0, 1.0]
|
27
event_camera_simulator/esim_ros/cfg/calib/pinhole_mono.yaml
Normal file
27
event_camera_simulator/esim_ros/cfg/calib/pinhole_mono.yaml
Normal file
@ -0,0 +1,27 @@
|
||||
label: "simulated_camera"
|
||||
id: 433585ebda8d1431223927a14788a127
|
||||
cameras:
|
||||
- camera:
|
||||
label: dvs0
|
||||
id: a0fba5412e961934d842d3a2a78e5cba
|
||||
line-delay-nanoseconds: 0
|
||||
image_height: 180
|
||||
image_width: 240
|
||||
type: pinhole
|
||||
intrinsics:
|
||||
cols: 1
|
||||
rows: 4
|
||||
data: [198.245521288, 198.277025706, 142.064861206, 100.903484508]
|
||||
distortion:
|
||||
type: equidistant
|
||||
parameters:
|
||||
cols: 1
|
||||
rows: 4
|
||||
data: [-0.0506755889541, 0.0456313630037, -0.0825742639337, 0.0557104403236]
|
||||
T_B_C:
|
||||
cols: 4
|
||||
rows: 4
|
||||
data: [1, 0, 0, 0,
|
||||
0, -1, 0, 0,
|
||||
0, 0, -1, 0,
|
||||
0, 0, 0, 1]
|
@ -0,0 +1,27 @@
|
||||
label: "simulated_camera"
|
||||
id: 433585ebda8d1431223927a14788a127
|
||||
cameras:
|
||||
- camera:
|
||||
label: dvs0
|
||||
id: a0fba5412e961934d842d3a2a78e5cba
|
||||
line-delay-nanoseconds: 0
|
||||
image_height: 180
|
||||
image_width: 240
|
||||
type: pinhole
|
||||
intrinsics:
|
||||
cols: 1
|
||||
rows: 4
|
||||
data: [200.0, 200.0, 120.0, 90.0]
|
||||
distortion:
|
||||
type: none
|
||||
parameters:
|
||||
cols: 1
|
||||
rows: 0
|
||||
data: []
|
||||
T_B_C:
|
||||
cols: 4
|
||||
rows: 4
|
||||
data: [1, 0, 0, 0,
|
||||
0, -1, 0, 0,
|
||||
0, 0, -1, 0,
|
||||
0, 0, 0, 1]
|
@ -0,0 +1,27 @@
|
||||
label: "simulated_camera"
|
||||
id: 433585ebda8d1431223927a14788a127
|
||||
cameras:
|
||||
- camera:
|
||||
label: dvs0
|
||||
id: a0fba5412e961934d842d3a2a78e5cba
|
||||
line-delay-nanoseconds: 0
|
||||
image_height: 180
|
||||
image_width: 240
|
||||
type: pinhole
|
||||
intrinsics:
|
||||
cols: 1
|
||||
rows: 4
|
||||
data: [200.0, 200.0, 120.0, 90.0]
|
||||
distortion:
|
||||
type: none
|
||||
parameters:
|
||||
cols: 1
|
||||
rows: 0
|
||||
data: []
|
||||
T_B_C:
|
||||
cols: 4
|
||||
rows: 4
|
||||
data: [-1, 0, 0, 0,
|
||||
0, 0, -1, 0,
|
||||
0, -1, 0, 0,
|
||||
0, 0, 0, 1]
|
@ -0,0 +1,27 @@
|
||||
label: "simulated_camera"
|
||||
id: 433585ebda8d1431223927a14788a127
|
||||
cameras:
|
||||
- camera:
|
||||
label: dvs0
|
||||
id: a0fba5412e961934d842d3a2a78e5cba
|
||||
line-delay-nanoseconds: 0
|
||||
image_height: 260
|
||||
image_width: 346
|
||||
type: pinhole
|
||||
intrinsics:
|
||||
cols: 1
|
||||
rows: 4
|
||||
data: [235.90001575, 235.84153994, 170.45862273, 130.11022812]
|
||||
distortion:
|
||||
type: equidistant
|
||||
parameters:
|
||||
cols: 1
|
||||
rows: 4
|
||||
data: [-0.13853153, -0.04153486, 0.00805515, 0.00423045]
|
||||
T_B_C:
|
||||
cols: 4
|
||||
rows: 4
|
||||
data: [1, 0, 0, 0,
|
||||
0, 0, 1, 0,
|
||||
0, -1, 0, 0,
|
||||
0, 0, 0, 1]
|
27
event_camera_simulator/esim_ros/cfg/calib/quadrotor.yaml
Normal file
27
event_camera_simulator/esim_ros/cfg/calib/quadrotor.yaml
Normal file
@ -0,0 +1,27 @@
|
||||
label: "simulated_camera"
|
||||
id: 433585ebda8d1431223927a14788a127
|
||||
cameras:
|
||||
- camera:
|
||||
label: dvs0
|
||||
id: a0fba5412e961934d842d3a2a78e5cba
|
||||
line-delay-nanoseconds: 0
|
||||
image_height: 180
|
||||
image_width: 240
|
||||
type: pinhole
|
||||
intrinsics:
|
||||
cols: 1
|
||||
rows: 4
|
||||
data: [250.0, 250.0, 120.0, 90.0]
|
||||
distortion:
|
||||
type: radial-tangential
|
||||
parameters:
|
||||
cols: 1
|
||||
rows: 4
|
||||
data: [0.0,0.0,0.0,0.0]
|
||||
T_B_C:
|
||||
cols: 4
|
||||
rows: 4
|
||||
data: [1, 0, 0, 0,
|
||||
0, -1, 0, 0,
|
||||
0, 0, -1, 0,
|
||||
0, 0, 0, 1]
|
54
event_camera_simulator/esim_ros/cfg/example.conf
Normal file
54
event_camera_simulator/esim_ros/cfg/example.conf
Normal file
@ -0,0 +1,54 @@
|
||||
--vmodule=data_provider_online_render=0
|
||||
--random_seed=50
|
||||
--data_source=0
|
||||
#--path_to_output_bag=/tmp/out.bag
|
||||
|
||||
--contrast_threshold_pos=0.5
|
||||
--contrast_threshold_neg=0.5
|
||||
--contrast_threshold_sigma_pos=0
|
||||
--contrast_threshold_sigma_neg=0
|
||||
|
||||
--exposure_time_ms=12.0
|
||||
--use_log_image=1
|
||||
--log_eps=0.001
|
||||
|
||||
--calib_filename=/home/user/esim_ws/src/rpg_esim/event_camera_simulator/esim_ros/cfg/calib/pinhole_mono_nodistort.yaml
|
||||
|
||||
--renderer_type=0
|
||||
--renderer_texture=/home/user/esim_ws/src/rpg_esim/event_camera_simulator/imp/imp_planar_renderer/textures/office.jpg
|
||||
--renderer_hfov_cam_source_deg=85.0
|
||||
--renderer_preprocess_gaussian_blur=2.0
|
||||
--renderer_preprocess_median_blur=13
|
||||
--renderer_plane_x=0.0
|
||||
--renderer_plane_y=0.0
|
||||
--renderer_plane_z=-1.0
|
||||
--renderer_plane_qw=0.0
|
||||
--renderer_plane_qx=1.0
|
||||
--renderer_plane_qy=0.0
|
||||
--renderer_plane_qz=0.0
|
||||
--renderer_extend_border=1
|
||||
--renderer_zmin=1.0
|
||||
|
||||
--trajectory_type=0
|
||||
--trajectory_length_s=100.0
|
||||
--trajectory_sampling_frequency_hz=5
|
||||
--trajectory_spline_order=5
|
||||
--trajectory_num_spline_segments=100
|
||||
--trajectory_lambda=0.1
|
||||
--trajectory_multiplier_x=0.5
|
||||
--trajectory_multiplier_y=0.5
|
||||
--trajectory_multiplier_z=0.25
|
||||
--trajectory_multiplier_wx=0.15
|
||||
--trajectory_multiplier_wy=0.15
|
||||
--trajectory_multiplier_wz=0.3
|
||||
|
||||
--simulation_minimum_framerate=50.0
|
||||
--simulation_imu_rate=1000.0
|
||||
--simulation_adaptive_sampling_method=0
|
||||
--simulation_adaptive_sampling_lambda=0.5
|
||||
|
||||
--ros_publisher_frame_rate=30
|
||||
--ros_publisher_depth_rate=10
|
||||
--ros_publisher_optic_flow_rate=10
|
||||
--ros_publisher_pointcloud_rate=10
|
||||
--ros_publisher_camera_info_rate=10
|
29
event_camera_simulator/esim_ros/cfg/multi_objects.conf
Normal file
29
event_camera_simulator/esim_ros/cfg/multi_objects.conf
Normal file
@ -0,0 +1,29 @@
|
||||
--vmodule=data_provider_online_simple=0
|
||||
--data_source=1
|
||||
--path_to_output_bag=/tmp/out.bag
|
||||
--path_to_sequence_file=/home/user/esim_ws/src/event_camera_simulator/event_camera_simulator/imp/imp_multi_objects_2d/scenes/example.scene
|
||||
|
||||
--contrast_threshold_pos=0.5
|
||||
--contrast_threshold_neg=0.5
|
||||
--contrast_threshold_sigma_pos=0
|
||||
--contrast_threshold_sigma_neg=0
|
||||
|
||||
--exposure_time_ms=12.0
|
||||
--use_log_image=1
|
||||
--log_eps=0.001
|
||||
|
||||
--renderer_type=0
|
||||
--renderer_preprocess_median_blur=11
|
||||
--renderer_preprocess_gaussian_blur=1.0
|
||||
|
||||
--simulation_minimum_framerate=20.0
|
||||
--simulation_imu_rate=1000.0
|
||||
--simulation_adaptive_sampling_method=1
|
||||
--simulation_adaptive_sampling_lambda=0.5
|
||||
|
||||
--ros_publisher_frame_rate=40
|
||||
--ros_publisher_depth_rate=10
|
||||
--ros_publisher_optic_flow_rate=40
|
||||
--ros_publisher_pointcloud_rate=10
|
||||
--ros_publisher_camera_info_rate=10
|
||||
|
48
event_camera_simulator/esim_ros/cfg/obstacle.conf
Normal file
48
event_camera_simulator/esim_ros/cfg/obstacle.conf
Normal file
@ -0,0 +1,48 @@
|
||||
--v=0
|
||||
--random_seed=2
|
||||
--data_source=0
|
||||
--path_to_output_bag=/tmp/out.bag
|
||||
|
||||
--contrast_threshold_pos=0.5
|
||||
--contrast_threshold_neg=0.5
|
||||
--contrast_threshold_sigma_pos=0
|
||||
--contrast_threshold_sigma_neg=0
|
||||
|
||||
--exposure_time_ms=12.0
|
||||
--use_log_image=1
|
||||
--log_eps=0.001
|
||||
|
||||
--calib_filename=/home/user/esim_ws/src/rpg_esim/event_camera_simulator/esim_ros/cfg/calib/pinhole_mono_nodistort.yaml
|
||||
--renderer_scene=/home/user/esim_ws/src/rpg_esim/event_camera_simulator/imp/imp_opengl_renderer/resources/objects/flying_room/flying_room.obj
|
||||
|
||||
--renderer_type=2
|
||||
--renderer_zmin=0.1
|
||||
--renderer_zmax=40.0
|
||||
|
||||
--renderer_dynamic_objects_dir=/home/user/esim_ws/src/rpg_esim/event_camera_simulator/imp/imp_opengl_renderer/resources/objects/dynamic_objects
|
||||
--renderer_dynamic_objects=americanfootball.obj
|
||||
|
||||
--trajectory_type=1
|
||||
--trajectory_spline_order=3
|
||||
--trajectory_num_spline_segments=10
|
||||
--trajectory_lambda=0.1
|
||||
--trajectory_csv_file=/home/user/esim_ws/src/rpg_esim/event_camera_simulator/imp/imp_opengl_renderer/resources/objects/flying_room/camera_trajectory.csv
|
||||
|
||||
--trajectory_dynamic_objects_type=1
|
||||
--trajectory_dynamic_objects_spline_order=3
|
||||
--trajectory_dynamic_objects_num_spline_segments=1
|
||||
--trajectory_dynamic_objects_lambda=0.1
|
||||
--trajectory_dynamic_objects_csv_dir=/home/user/esim_ws/src/rpg_esim/event_camera_simulator/imp/imp_opengl_renderer/resources/objects/dynamic_objects
|
||||
--trajectory_dynamic_objects_csv_file=americanfootball.csv
|
||||
|
||||
--simulation_minimum_framerate=20.0
|
||||
--simulation_imu_rate=1000.0
|
||||
--simulation_adaptive_sampling_method=1
|
||||
--simulation_adaptive_sampling_lambda=0.5
|
||||
--simulation_post_gaussian_blur_sigma=0.15
|
||||
|
||||
--ros_publisher_frame_rate=30.0
|
||||
--ros_publisher_depth_rate=30.0
|
||||
--ros_publisher_optic_flow_rate=30.0
|
||||
--ros_publisher_pointcloud_rate=1000
|
||||
--ros_publisher_camera_info_rate=10
|
47
event_camera_simulator/esim_ros/cfg/opengl.conf
Normal file
47
event_camera_simulator/esim_ros/cfg/opengl.conf
Normal file
@ -0,0 +1,47 @@
|
||||
--v=0
|
||||
--random_seed=2
|
||||
--data_source=0
|
||||
--path_to_output_bag=/tmp/out.bag
|
||||
|
||||
--contrast_threshold_pos=0.5
|
||||
--contrast_threshold_neg=0.5
|
||||
--contrast_threshold_sigma_pos=0
|
||||
--contrast_threshold_sigma_neg=0
|
||||
|
||||
--exposure_time_ms=12.0
|
||||
--use_log_image=1
|
||||
--log_eps=0.001
|
||||
|
||||
--calib_filename=/home/user/esim_ws/src/rpg_esim/event_camera_simulator/esim_ros/cfg/calib/pinhole_mono_nodistort.yaml
|
||||
--renderer_scene=/home/user/esim_ws/src/rpg_esim/event_camera_simulator/imp/imp_opengl_renderer/resources/objects/flying_room/flying_room.obj
|
||||
--renderer_zmax=20
|
||||
|
||||
--renderer_type=2
|
||||
--renderer_zmin=0.3
|
||||
--renderer_zmax=40.0
|
||||
|
||||
--trajectory_type=0
|
||||
--trajectory_length_s=10.0
|
||||
--trajectory_sampling_frequency_hz=5
|
||||
--trajectory_spline_order=5
|
||||
--trajectory_num_spline_segments=10
|
||||
--trajectory_lambda=0.01
|
||||
--trajectory_multiplier_x=1.8
|
||||
--trajectory_multiplier_y=1.8
|
||||
--trajectory_multiplier_z=0.5
|
||||
--trajectory_multiplier_wx=0.80
|
||||
--trajectory_multiplier_wy=0.80
|
||||
--trajectory_multiplier_wz=0.80
|
||||
--trajectory_offset_z=0.0
|
||||
|
||||
--simulation_minimum_framerate=20.0
|
||||
--simulation_imu_rate=1000.0
|
||||
--simulation_adaptive_sampling_method=1
|
||||
--simulation_adaptive_sampling_lambda=0.5
|
||||
--simulation_post_gaussian_blur_sigma=0.3
|
||||
|
||||
--ros_publisher_frame_rate=30.0
|
||||
--ros_publisher_depth_rate=30.0
|
||||
--ros_publisher_optic_flow_rate=30.0
|
||||
--ros_publisher_pointcloud_rate=10
|
||||
--ros_publisher_camera_info_rate=10
|
48
event_camera_simulator/esim_ros/cfg/panorama.conf
Normal file
48
event_camera_simulator/esim_ros/cfg/panorama.conf
Normal file
@ -0,0 +1,48 @@
|
||||
--v=0
|
||||
--data_source=0
|
||||
--random_seed=0
|
||||
--path_to_output_bag=/tmp/test_panorama.bag
|
||||
|
||||
--contrast_threshold_pos=0.4
|
||||
--contrast_threshold_neg=0.4
|
||||
--contrast_threshold_sigma_pos=0
|
||||
--contrast_threshold_sigma_neg=0
|
||||
|
||||
--exposure_time_ms=10.0
|
||||
--use_log_image=1
|
||||
--log_eps=0.001
|
||||
|
||||
--calib_filename=/home/user/esim_ws/src/rpg_esim/event_camera_simulator/esim_ros/cfg/calib/pinhole_wide_fov.yaml
|
||||
|
||||
--renderer_type=1
|
||||
--renderer_texture=/home/user/esim_ws/src/rpg_esim/event_camera_simulator/imp/imp_panorama_renderer/textures/bicycle_parking.jpg
|
||||
--renderer_preprocess_gaussian_blur=0.1
|
||||
--renderer_preprocess_median_blur=5
|
||||
--renderer_panorama_qw=0.707106781187
|
||||
--renderer_panorama_qx=-0.707106781187
|
||||
--renderer_panorama_qy=0.0
|
||||
--renderer_panorama_qz=0.0
|
||||
|
||||
--trajectory_type=0
|
||||
--trajectory_length_s=100.0
|
||||
--trajectory_sampling_frequency_hz=5
|
||||
--trajectory_spline_order=5
|
||||
--trajectory_num_spline_segments=100
|
||||
--trajectory_lambda=0.01
|
||||
--trajectory_multiplier_x=0.0
|
||||
--trajectory_multiplier_y=0
|
||||
--trajectory_multiplier_z=0
|
||||
--trajectory_multiplier_wx=1.0
|
||||
--trajectory_multiplier_wy=0.0
|
||||
--trajectory_multiplier_wz=4.0
|
||||
|
||||
--simulation_minimum_framerate=30
|
||||
--simulation_imu_rate=1000.0
|
||||
--simulation_adaptive_sampling_method=1
|
||||
--simulation_adaptive_sampling_lambda=0.5
|
||||
|
||||
--ros_publisher_frame_rate=30
|
||||
--ros_publisher_depth_rate=1
|
||||
--ros_publisher_optic_flow_rate=1
|
||||
--ros_publisher_pointcloud_rate=1
|
||||
--ros_publisher_camera_info_rate=10
|
37
event_camera_simulator/esim_ros/cfg/sponza.conf
Normal file
37
event_camera_simulator/esim_ros/cfg/sponza.conf
Normal file
@ -0,0 +1,37 @@
|
||||
--vmodule=model=0
|
||||
--data_source=0
|
||||
--path_to_output_bag=/tmp/out.bag
|
||||
|
||||
--contrast_threshold_pos=0.1
|
||||
--contrast_threshold_neg=0.1
|
||||
--contrast_threshold_sigma_pos=0
|
||||
--contrast_threshold_sigma_neg=0
|
||||
|
||||
--exposure_time_ms=12.0
|
||||
--use_log_image=1
|
||||
--log_eps=0.001
|
||||
|
||||
--calib_filename=/home/user/esim_ws/src/rpg_esim/event_camera_simulator/esim_ros/cfg/calib/pinhole_mono_nodistort.yaml
|
||||
--renderer_scene=/home/user/esim_ws/src/rpg_esim/event_camera_simulator/imp/imp_opengl_renderer/resources/objects/sponza/sponza.obj
|
||||
--renderer_zmax=20
|
||||
|
||||
--renderer_type=2
|
||||
--renderer_zmin=1.0
|
||||
--renderer_zmax=40.0
|
||||
|
||||
--trajectory_type=1
|
||||
--trajectory_spline_order=5
|
||||
--trajectory_num_spline_segments=50
|
||||
--trajectory_lambda=0
|
||||
--trajectory_csv_file=/home/user/esim_ws/src/rpg_esim/event_camera_simulator/imp/imp_opengl_renderer/resources/objects/sponza/camera_trajectory.csv
|
||||
|
||||
--simulation_minimum_framerate=20.0
|
||||
--simulation_imu_rate=1000.0
|
||||
--simulation_adaptive_sampling_method=1
|
||||
--simulation_adaptive_sampling_lambda=0.5
|
||||
|
||||
--ros_publisher_frame_rate=30.0
|
||||
--ros_publisher_depth_rate=30.0
|
||||
--ros_publisher_optic_flow_rate=30.0
|
||||
--ros_publisher_pointcloud_rate=10
|
||||
--ros_publisher_camera_info_rate=10
|
11611
event_camera_simulator/esim_ros/cfg/traj/poster_6dof.csv
Normal file
11611
event_camera_simulator/esim_ros/cfg/traj/poster_6dof.csv
Normal file
File diff suppressed because it is too large
Load Diff
5000
event_camera_simulator/esim_ros/cfg/traj/quadrotor_circles.csv
Normal file
5000
event_camera_simulator/esim_ros/cfg/traj/quadrotor_circles.csv
Normal file
File diff suppressed because it is too large
Load Diff
44
event_camera_simulator/esim_ros/cfg/unrealcv.conf
Normal file
44
event_camera_simulator/esim_ros/cfg/unrealcv.conf
Normal file
@ -0,0 +1,44 @@
|
||||
--data_source=0
|
||||
--vmodule=unrealcv_renderer=0
|
||||
--path_to_output_bag=/tmp/out.bag
|
||||
|
||||
--contrast_threshold_pos=0.6
|
||||
--contrast_threshold_neg=0.6
|
||||
--contrast_threshold_sigma_pos=0
|
||||
--contrast_threshold_sigma_neg=0
|
||||
|
||||
--exposure_time_ms=5.0
|
||||
--use_log_image=1
|
||||
--log_eps=0.001
|
||||
|
||||
--calib_filename=/home/user/esim_ws/src/rpg_esim/event_camera_simulator/esim_ros/cfg/calib/pinhole_mono_nodistort_forward.yaml
|
||||
|
||||
--renderer_type=3
|
||||
|
||||
--trajectory_type=0
|
||||
--trajectory_length_s=100.0
|
||||
--trajectory_sampling_frequency_hz=5
|
||||
--trajectory_spline_order=5
|
||||
--trajectory_num_spline_segments=100
|
||||
--trajectory_lambda=0.1
|
||||
--trajectory_multiplier_x=3.0
|
||||
--trajectory_multiplier_y=3.0
|
||||
--trajectory_multiplier_z=0.5
|
||||
--trajectory_multiplier_wx=0.15
|
||||
--trajectory_multiplier_wy=0.15
|
||||
--trajectory_multiplier_wz=1.
|
||||
|
||||
--x_offset=0.0
|
||||
--y_offset=0.0
|
||||
--z_offset=1.0
|
||||
|
||||
--simulation_minimum_framerate=5.0
|
||||
--simulation_imu_rate=1000.0
|
||||
--simulation_adaptive_sampling_method=1
|
||||
--simulation_adaptive_sampling_lambda=1.0
|
||||
|
||||
--ros_publisher_frame_rate=300
|
||||
--ros_publisher_depth_rate=300
|
||||
--ros_publisher_optic_flow_rate=200
|
||||
--ros_publisher_pointcloud_rate=50
|
||||
--ros_publisher_camera_info_rate=10
|
15
event_camera_simulator/esim_ros/launch/esim.launch
Normal file
15
event_camera_simulator/esim_ros/launch/esim.launch
Normal file
@ -0,0 +1,15 @@
|
||||
<launch>
|
||||
|
||||
<arg name="config" />
|
||||
|
||||
<!-- Event camera simulator -->
|
||||
<node name="esim_node" pkg="esim_ros" type="esim_node" args="
|
||||
--v=1
|
||||
--vmodule=data_provider_from_folder=10
|
||||
--flagfile=$(find esim_ros)/$(arg config)
|
||||
" output="screen"/>
|
||||
|
||||
<include file="$(find esim_ros)/launch/visualization.launch" />
|
||||
|
||||
|
||||
</launch>
|
27
event_camera_simulator/esim_ros/launch/visualization.launch
Normal file
27
event_camera_simulator/esim_ros/launch/visualization.launch
Normal file
@ -0,0 +1,27 @@
|
||||
<launch>
|
||||
|
||||
<!-- Visualization -->
|
||||
<node name="dvs_renderer" pkg="dvs_renderer" type="dvs_renderer" output="screen" required="false">
|
||||
<remap from="events" to="/cam0/events" />
|
||||
<remap from="image" to="/cam0/image_corrupted" />
|
||||
<remap from="dvs_rendering" to="dvs_rendering" />
|
||||
</node>
|
||||
|
||||
<node name="optic_flow_viz" pkg="esim_visualization" type="optic_flow_converter.py" output="screen" required="false">
|
||||
<param name="arrows_step" value="7" />
|
||||
|
||||
<param name="arrows_scale" value="0.07" />
|
||||
<param name="arrows_upsample_factor" value="1" />
|
||||
<param name="publish_rate" value="100" />
|
||||
|
||||
<remap from="flow" to="/cam0/optic_flow" />
|
||||
</node>
|
||||
|
||||
<node pkg="hector_trajectory_server" type="hector_trajectory_server" name="hector_trajectory_server" output="screen" required="false">
|
||||
<param name="target_frame_name" value="map"/>
|
||||
<param name="source_frame_name" value="cam0"/>
|
||||
<param name="trajectory_publish_rate" value="15"/>
|
||||
<param name="trajectory_update_rate" value="15"/>
|
||||
</node>
|
||||
|
||||
</launch>
|
22
event_camera_simulator/esim_ros/package.xml
Normal file
22
event_camera_simulator/esim_ros/package.xml
Normal file
@ -0,0 +1,22 @@
|
||||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>esim_ros</name>
|
||||
<version>0.0.0</version>
|
||||
<description>The event_camera_simulator package</description>
|
||||
|
||||
<maintainer email="rebecq@ifi.uzh.ch">Henri Rebecq</maintainer>
|
||||
|
||||
<license>GPLv3</license>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<buildtool_depend>catkin_simple</buildtool_depend>
|
||||
|
||||
<depend>esim_common</depend>
|
||||
<depend>esim</depend>
|
||||
<depend>esim_data_provider</depend>
|
||||
<depend>esim_visualization</depend>
|
||||
<depend>gflags_catkin</depend>
|
||||
<depend>glog_catkin</depend>
|
||||
<depend>dvs_renderer_advanced</depend>
|
||||
|
||||
</package>
|
124
event_camera_simulator/esim_ros/scripts/test_depth_formula.py
Normal file
124
event_camera_simulator/esim_ros/scripts/test_depth_formula.py
Normal file
@ -0,0 +1,124 @@
|
||||
# -*- coding: utf-8 -*-
|
||||
"""
|
||||
Check the formula used to compute the depth map from a rotation, translation
|
||||
and plane (parameterized by normal + distance).
|
||||
"""
|
||||
|
||||
import cv2
|
||||
from matplotlib import pyplot as plt
|
||||
from math import tan, pi
|
||||
import numpy as np
|
||||
|
||||
np.set_printoptions(suppress=True)
|
||||
|
||||
|
||||
def skew(v):
|
||||
"""Returns the skew-symmetric matrix of a vector"""
|
||||
return np.array([[0, -v[2], v[1]],
|
||||
[v[2], 0, -v[0]],
|
||||
[-v[1], v[0], 0]], dtype=np.float64)
|
||||
|
||||
|
||||
def calibrationMatrixFromHFOV(hfov_deg, W, H):
|
||||
f = 0.5 * W / tan(0.5 * hfov_deg * pi / 180.0)
|
||||
K = np.array([[f, 0, 0.5 * W],
|
||||
[0, f, 0.5 * H],
|
||||
[0, 0, 1]]).astype(np.float64)
|
||||
K_inv = np.linalg.inv(K)
|
||||
return K, K_inv
|
||||
|
||||
|
||||
def computeDepthmapAnalytic(R_01, t_01, n, d, K1, width, height):
|
||||
K1_inv = np.linalg.inv(K1)
|
||||
depth = np.zeros((height,width), dtype=np.float64)
|
||||
for x in range(width):
|
||||
for y in range(height):
|
||||
X1 = np.array([x,y,1]).reshape((3,1))
|
||||
X1 = K1_inv.dot(X1)
|
||||
|
||||
z = -(d+n.T.dot(t_01))/(n.T.dot(R_01).dot(X1))
|
||||
depth[y,x] = z[0,0]
|
||||
|
||||
return depth
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
|
||||
# Index 1 refers to cam (destination image)
|
||||
# Index 0 refers to world (source image)
|
||||
|
||||
plt.close('all')
|
||||
|
||||
img = cv2.imread('../textures/carpet.jpg', 0).astype(np.float32)
|
||||
img = img.astype(np.float32) / 255.0
|
||||
|
||||
hfov_plane_deg = 130.0
|
||||
hfov_camera_deg = 90
|
||||
|
||||
H0, W0 = img.shape
|
||||
K0, K0_inv = calibrationMatrixFromHFOV(hfov_plane_deg, W0, H0)
|
||||
H1, W1 = 260, 346
|
||||
K1, K1_inv = calibrationMatrixFromHFOV(hfov_camera_deg, W1, H1)
|
||||
|
||||
K2, K2_inv = K1, K1_inv
|
||||
W2, H2 = W1, H1
|
||||
|
||||
n = np.array([-0.12,-0.05,1.0]).reshape((3,1))
|
||||
n = n / np.linalg.norm(n)
|
||||
d = -1.0
|
||||
|
||||
w_01 = (np.array([15.0, 5.0, -10.0]) * pi / 180.0).reshape((3,1)).astype(np.float64)
|
||||
t_01 = np.array([-1.0,0.4,-0.1]).reshape((3,1))
|
||||
R_01, _ = cv2.Rodrigues(w_01)
|
||||
|
||||
R_10 = R_01.T
|
||||
t_10 = -R_01.T.dot(t_01)
|
||||
|
||||
R = R_10
|
||||
t = t_10
|
||||
C = -R.T.dot(t)
|
||||
Hn_10 = R-1/d*t.dot(n.T)
|
||||
|
||||
Hn_01 = np.linalg.inv(Hn_10)
|
||||
Hn_01_analytic = (np.eye(3) - 1.0/(d+n.T.dot(C))*C.dot(n.T)).dot(R.T) # analytic inverse
|
||||
|
||||
print('Test analytic inverse of H_01: {}'.format(np.allclose(Hn_01, Hn_01_analytic)))
|
||||
|
||||
H_10 = K1.dot(Hn_10).dot(K0_inv)
|
||||
H_01 = np.linalg.inv(H_10)
|
||||
|
||||
warped = cv2.warpPerspective(img, H_01, dsize=(W1,H1), flags=cv2.INTER_LINEAR + cv2.WARP_INVERSE_MAP)
|
||||
depth = computeDepthmapAnalytic(R_01, t_01, n, d, K1, W1, H1)
|
||||
|
||||
plt.figure()
|
||||
plt.imshow(depth)
|
||||
plt.colorbar()
|
||||
plt.title('Analytical depth map')
|
||||
|
||||
x1,y1 = np.random.randint(0,W1), np.random.randint(0,H1)
|
||||
X1 = np.array([x1,y1,1]).reshape((3,1))
|
||||
X = K1_inv.dot(X1)
|
||||
|
||||
X0 = H_01.dot(X1)
|
||||
X0[...] /= X0[2]
|
||||
|
||||
plt.figure()
|
||||
plt.subplot(121)
|
||||
plt.imshow(warped, cmap='gray')
|
||||
plt.scatter(X1[0], X1[1])
|
||||
plt.title('Warped image')
|
||||
|
||||
plt.subplot(122)
|
||||
plt.imshow(img, cmap='gray')
|
||||
plt.scatter(X0[0], X0[1], color='b')
|
||||
plt.title('Source image')
|
||||
|
||||
# Check that the predicted depth indeed works to project X1 on image 0
|
||||
z1 = depth[y1,x1]
|
||||
P1 = z1 * K1_inv.dot(X1)
|
||||
P0 = R_01.dot(P1) + t_01
|
||||
X0_depth = K0.dot(P0)
|
||||
X0_depth[...] /= X0_depth[2]
|
||||
|
||||
print('Test reprojection with analytical depth: {}'.format(np.allclose(X0, X0_depth)))
|
||||
|
88
event_camera_simulator/esim_ros/src/esim_node.cpp
Normal file
88
event_camera_simulator/esim_ros/src/esim_node.cpp
Normal file
@ -0,0 +1,88 @@
|
||||
#include <esim/esim/simulator.hpp>
|
||||
#include <esim/visualization/ros_publisher.hpp>
|
||||
#include <esim/visualization/rosbag_writer.hpp>
|
||||
#include <esim/visualization/adaptive_sampling_benchmark_publisher.hpp>
|
||||
#include <esim/visualization/synthetic_optic_flow_publisher.hpp>
|
||||
#include <esim/data_provider/data_provider_factory.hpp>
|
||||
|
||||
#include <glog/logging.h>
|
||||
#include <gflags/gflags.h>
|
||||
|
||||
DEFINE_double(contrast_threshold_pos, 1.0,
|
||||
"Contrast threshold (positive)");
|
||||
|
||||
DEFINE_double(contrast_threshold_neg, 1.0,
|
||||
"Contrast threshold (negative))");
|
||||
|
||||
DEFINE_double(contrast_threshold_sigma_pos, 0.021,
|
||||
"Standard deviation of contrast threshold (positive)");
|
||||
|
||||
DEFINE_double(contrast_threshold_sigma_neg, 0.021,
|
||||
"Standard deviation of contrast threshold (negative))");
|
||||
|
||||
DEFINE_int64(refractory_period_ns, 100000,
|
||||
"Refractory period (time during which a pixel cannot fire events just after it fired one), in nanoseconds");
|
||||
|
||||
DEFINE_double(exposure_time_ms, 10.0,
|
||||
"Exposure time in milliseconds, used to simulate motion blur");
|
||||
|
||||
DEFINE_bool(use_log_image, true,
|
||||
"Whether to convert images to log images in the preprocessing step.");
|
||||
|
||||
DEFINE_double(log_eps, 0.001,
|
||||
"Epsilon value used to convert images to log: L = log(eps + I / 255.0).");
|
||||
|
||||
DEFINE_int32(random_seed, 0,
|
||||
"Random seed used to generate the trajectories. If set to 0 the current time(0) is taken as seed.");
|
||||
|
||||
using namespace event_camera_simulator;
|
||||
|
||||
int main(int argc, char** argv)
|
||||
{
|
||||
google::InitGoogleLogging(argv[0]);
|
||||
google::ParseCommandLineFlags(&argc, &argv, true);
|
||||
google::InstallFailureSignalHandler();
|
||||
FLAGS_alsologtostderr = true;
|
||||
FLAGS_colorlogtostderr = true;
|
||||
|
||||
if (FLAGS_random_seed == 0) FLAGS_random_seed = (unsigned int) time(0);
|
||||
srand(FLAGS_random_seed);
|
||||
|
||||
DataProviderBase::Ptr data_provider_ =
|
||||
loadDataProviderFromGflags();
|
||||
CHECK(data_provider_);
|
||||
|
||||
EventSimulator::Config event_sim_config;
|
||||
event_sim_config.Cp = FLAGS_contrast_threshold_pos;
|
||||
event_sim_config.Cm = FLAGS_contrast_threshold_neg;
|
||||
event_sim_config.sigma_Cp = FLAGS_contrast_threshold_sigma_pos;
|
||||
event_sim_config.sigma_Cm = FLAGS_contrast_threshold_sigma_neg;
|
||||
event_sim_config.refractory_period_ns = FLAGS_refractory_period_ns;
|
||||
event_sim_config.use_log_image = FLAGS_use_log_image;
|
||||
event_sim_config.log_eps = FLAGS_log_eps;
|
||||
std::shared_ptr<Simulator> sim;
|
||||
sim.reset(new Simulator(data_provider_->numCameras(),
|
||||
event_sim_config,
|
||||
FLAGS_exposure_time_ms));
|
||||
CHECK(sim);
|
||||
|
||||
Publisher::Ptr ros_publisher = std::make_shared<RosPublisher>(data_provider_->numCameras());
|
||||
Publisher::Ptr rosbag_writer = RosbagWriter::createBagWriterFromGflags(data_provider_->numCameras());
|
||||
Publisher::Ptr adaptive_sampling_benchmark_publisher
|
||||
= AdaptiveSamplingBenchmarkPublisher::createFromGflags();
|
||||
|
||||
Publisher::Ptr synthetic_optic_flow_publisher
|
||||
= SyntheticOpticFlowPublisher::createFromGflags();
|
||||
|
||||
if(ros_publisher) sim->addPublisher(ros_publisher);
|
||||
if(rosbag_writer) sim->addPublisher(rosbag_writer);
|
||||
if(adaptive_sampling_benchmark_publisher) sim->addPublisher(adaptive_sampling_benchmark_publisher);
|
||||
if(synthetic_optic_flow_publisher) sim->addPublisher(synthetic_optic_flow_publisher);
|
||||
|
||||
data_provider_->registerCallback(
|
||||
std::bind(&Simulator::dataProviderCallback, sim.get(),
|
||||
std::placeholders::_1));
|
||||
|
||||
data_provider_->spin();
|
||||
|
||||
}
|
Reference in New Issue
Block a user