ソースを参照

Update the configurations. (#16)

The publish_occupancy_grid option is no longer necessary and got removed.
Wolfgang Hess 9 年 前
コミット
0db4992dab

+ 0 - 1
cartographer_turtlebot/configuration_files/turtlebot_depth_camera_2d.lua

@@ -25,7 +25,6 @@ options = {
   use_constant_odometry_variance = true,
   use_constant_odometry_variance = true,
   constant_odometry_translational_variance = 1e-7,
   constant_odometry_translational_variance = 1e-7,
   constant_odometry_rotational_variance = 1e-7,
   constant_odometry_rotational_variance = 1e-7,
-  publish_occupancy_grid = false,
   use_horizontal_laser = true,
   use_horizontal_laser = true,
   use_horizontal_multi_echo_laser = false,
   use_horizontal_multi_echo_laser = false,
   horizontal_laser_min_range = 0.1,
   horizontal_laser_min_range = 0.1,

+ 0 - 1
cartographer_turtlebot/configuration_files/turtlebot_depth_camera_3d.lua

@@ -25,7 +25,6 @@ options = {
   use_constant_odometry_variance = true,
   use_constant_odometry_variance = true,
   constant_odometry_translational_variance = 1e-7,
   constant_odometry_translational_variance = 1e-7,
   constant_odometry_rotational_variance = 1e-7,
   constant_odometry_rotational_variance = 1e-7,
-  publish_occupancy_grid = false,
   use_horizontal_laser = false,
   use_horizontal_laser = false,
   use_horizontal_multi_echo_laser = false,
   use_horizontal_multi_echo_laser = false,
   horizontal_laser_min_range = 0.,
   horizontal_laser_min_range = 0.,

+ 0 - 1
cartographer_turtlebot/configuration_files/turtlebot_urg_lidar_2d.lua

@@ -25,7 +25,6 @@ options = {
   use_constant_odometry_variance = true,
   use_constant_odometry_variance = true,
   constant_odometry_translational_variance = 1e-7,
   constant_odometry_translational_variance = 1e-7,
   constant_odometry_rotational_variance = 1e-7,
   constant_odometry_rotational_variance = 1e-7,
-  publish_occupancy_grid = false,
   use_horizontal_laser = true,
   use_horizontal_laser = true,
   use_horizontal_multi_echo_laser = false,
   use_horizontal_multi_echo_laser = false,
   horizontal_laser_min_range = 0.1,
   horizontal_laser_min_range = 0.1,