Browse Source

Updates configurations. (#22)

Damon Kohler 9 years ago
parent
commit
caecfdf150

+ 7 - 6
cartographer_turtlebot/configuration_files/turtlebot_depth_camera_2d.lua

@@ -16,20 +16,21 @@ include "map_builder.lua"
 
 options = {
   map_builder = MAP_BUILDER,
+  sensor_bridge = {
+    horizontal_laser_min_range = 0.1,
+    horizontal_laser_max_range = 4.,
+    horizontal_laser_missing_echo_ray_length = 2.,
+    constant_odometry_translational_variance = 1e-7,
+    constant_odometry_rotational_variance = 1e-7,
+  },
   map_frame = "map",
   tracking_frame = "gyro_link",
   published_frame = "odom",
   odom_frame = "odom",
   provide_odom_frame = false,
   use_odometry_data = true,
-  use_constant_odometry_variance = true,
-  constant_odometry_translational_variance = 1e-7,
-  constant_odometry_rotational_variance = 1e-7,
   use_horizontal_laser = true,
   use_horizontal_multi_echo_laser = false,
-  horizontal_laser_min_range = 0.1,
-  horizontal_laser_max_range = 4.,
-  horizontal_laser_missing_echo_ray_length = 2.,
   num_lasers_3d = 0,
   lookup_transform_timeout_sec = 0.2,
   submap_publish_period_sec = 0.3,

+ 7 - 6
cartographer_turtlebot/configuration_files/turtlebot_depth_camera_3d.lua

@@ -16,20 +16,21 @@ include "map_builder.lua"
 
 options = {
   map_builder = MAP_BUILDER,
+  sensor_bridge = {
+    horizontal_laser_min_range = 0.,
+    horizontal_laser_max_range = 30.,
+    horizontal_laser_missing_echo_ray_length = 5.,
+    constant_odometry_translational_variance = 1e-7,
+    constant_odometry_rotational_variance = 1e-7,
+  },
   map_frame = "map",
   tracking_frame = "gyro_link",
   published_frame = "odom",
   odom_frame = "odom",
   provide_odom_frame = false,
   use_odometry_data = true,
-  use_constant_odometry_variance = true,
-  constant_odometry_translational_variance = 1e-7,
-  constant_odometry_rotational_variance = 1e-7,
   use_horizontal_laser = false,
   use_horizontal_multi_echo_laser = false,
-  horizontal_laser_min_range = 0.,
-  horizontal_laser_max_range = 30.,
-  horizontal_laser_missing_echo_ray_length = 5.,
   num_lasers_3d = 1,
   lookup_transform_timeout_sec = 0.2,
   submap_publish_period_sec = 0.3,

+ 7 - 6
cartographer_turtlebot/configuration_files/turtlebot_urg_lidar_2d.lua

@@ -16,20 +16,21 @@ include "map_builder.lua"
 
 options = {
   map_builder = MAP_BUILDER,
+  sensor_bridge = {
+    horizontal_laser_min_range = 0.1,
+    horizontal_laser_max_range = 8.,
+    horizontal_laser_missing_echo_ray_length = 5.,
+    constant_odometry_translational_variance = 1e-7,
+    constant_odometry_rotational_variance = 1e-7,
+  },
   map_frame = "map",
   tracking_frame = "gyro_link",
   published_frame = "odom",
   odom_frame = "odom",
   provide_odom_frame = false,
   use_odometry_data = true,
-  use_constant_odometry_variance = true,
-  constant_odometry_translational_variance = 1e-7,
-  constant_odometry_rotational_variance = 1e-7,
   use_horizontal_laser = true,
   use_horizontal_multi_echo_laser = false,
-  horizontal_laser_min_range = 0.1,
-  horizontal_laser_max_range = 8.,
-  horizontal_laser_missing_echo_ray_length = 5.,
   num_lasers_3d = 0,
   lookup_transform_timeout_sec = 0.2,
   submap_publish_period_sec = 0.3,