Bläddra i källkod

Follow googlecartographer/cartographer_ros#435. (#63)

Wolfgang Hess 8 år sedan
förälder
incheckning
8924c5262c

+ 2 - 2
cartographer_turtlebot/configuration_files/turtlebot_depth_camera_2d.lua

@@ -24,8 +24,8 @@ options = {
   odom_frame = "odom",
   provide_odom_frame = false,
   use_odometry = true,
-  use_laser_scan = true,
-  use_multi_echo_laser_scan = false,
+  num_laser_scans = 1,
+  num_multi_echo_laser_scans = 0,
   num_subdivisions_per_laser_scan = 1,
   num_point_clouds = 0,
   lookup_transform_timeout_sec = 0.2,

+ 2 - 2
cartographer_turtlebot/configuration_files/turtlebot_depth_camera_3d.lua

@@ -24,8 +24,8 @@ options = {
   odom_frame = "odom",
   provide_odom_frame = false,
   use_odometry = true,
-  use_laser_scan = false,
-  use_multi_echo_laser_scan = false,
+  num_laser_scans = 0,
+  num_multi_echo_laser_scans = 0,
   num_subdivisions_per_laser_scan = 1,
   num_point_clouds = 1,
   lookup_transform_timeout_sec = 0.2,

+ 2 - 2
cartographer_turtlebot/configuration_files/turtlebot_urg_lidar_2d.lua

@@ -24,8 +24,8 @@ options = {
   odom_frame = "odom",
   provide_odom_frame = false,
   use_odometry = true,
-  use_laser_scan = true,
-  use_multi_echo_laser_scan = false,
+  num_laser_scans = 1,
+  num_multi_echo_laser_scans = 0,
   num_subdivisions_per_laser_scan = 1,
   num_point_clouds = 0,
   lookup_transform_timeout_sec = 0.2,