Selaa lähdekoodia

Follow googlecartographer/cartographer#259. (#50)

Wolfgang Hess 8 vuotta sitten
vanhempi
commit
aa58397fc8

+ 3 - 3
cartographer_turtlebot/configuration_files/turtlebot_depth_camera_2d.lua

@@ -32,9 +32,9 @@ options = {
 
 MAP_BUILDER.use_trajectory_builder_2d = true
 
-TRAJECTORY_BUILDER_2D.laser_min_range = 0.1
-TRAJECTORY_BUILDER_2D.laser_max_range = 4.0
-TRAJECTORY_BUILDER_2D.laser_missing_echo_ray_length = 2.0
+TRAJECTORY_BUILDER_2D.min_range = 0.1
+TRAJECTORY_BUILDER_2D.max_range = 4.0
+TRAJECTORY_BUILDER_2D.missing_data_ray_length = 2.0
 TRAJECTORY_BUILDER_2D.use_imu_data = true
 TRAJECTORY_BUILDER_2D.motion_filter.max_time_seconds = 0.3
 TRAJECTORY_BUILDER_2D.motion_filter.max_distance_meters = 0.2

+ 5 - 5
cartographer_turtlebot/configuration_files/turtlebot_depth_camera_3d.lua

@@ -34,13 +34,13 @@ MAP_BUILDER.use_trajectory_builder_3d = true
 MAP_BUILDER.num_background_threads = 30
 
 MAX_3D_LASER_RANGE = 3.5
-TRAJECTORY_BUILDER_3D.laser_min_range = 0.1
-TRAJECTORY_BUILDER_3D.laser_max_range = MAX_3D_LASER_RANGE
-TRAJECTORY_BUILDER_3D.low_resolution_adaptive_voxel_filter.max_range = MAX_3D_LASER_RANGE
+TRAJECTORY_BUILDER_3D.min_range = 0.1
+TRAJECTORY_BUILDER_3D.max_range = MAX_3D_RANGE
+TRAJECTORY_BUILDER_3D.low_resolution_adaptive_voxel_filter.max_range = MAX_3D_RANGE
 TRAJECTORY_BUILDER_3D.low_resolution_adaptive_voxel_filter.min_num_points = 500
-TRAJECTORY_BUILDER_3D.high_resolution_adaptive_voxel_filter.max_range = MAX_3D_LASER_RANGE
+TRAJECTORY_BUILDER_3D.high_resolution_adaptive_voxel_filter.max_range = MAX_3D_RANGE
 TRAJECTORY_BUILDER_3D.high_resolution_adaptive_voxel_filter.min_num_points = 250
-TRAJECTORY_BUILDER_3D.submaps.high_resolution_max_range = MAX_3D_LASER_RANGE
+TRAJECTORY_BUILDER_3D.submaps.high_resolution_max_range = MAX_3D_RANGE
 
 TRAJECTORY_BUILDER_3D.motion_filter.max_time_seconds = 0.25
 TRAJECTORY_BUILDER_3D.motion_filter.max_angle_radians = math.rad(0.1)

+ 3 - 3
cartographer_turtlebot/configuration_files/turtlebot_urg_lidar_2d.lua

@@ -32,9 +32,9 @@ options = {
 
 MAP_BUILDER.use_trajectory_builder_2d = true
 
-TRAJECTORY_BUILDER_2D.laser_min_range = 0.1
-TRAJECTORY_BUILDER_2D.laser_max_range = 8.
-TRAJECTORY_BUILDER_2D.laser_missing_echo_ray_length = 5.
+TRAJECTORY_BUILDER_2D.min_range = 0.1
+TRAJECTORY_BUILDER_2D.max_range = 8.
+TRAJECTORY_BUILDER_2D.missing_data_ray_length = 5.
 TRAJECTORY_BUILDER_2D.use_imu_data = true
 TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
 TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(0.1)