diff --git a/cartographer_ros/configuration_files/backpack_3d.lua b/cartographer_ros/configuration_files/backpack_3d.lua
index 2aef7c6..3eaf22c 100644
--- a/cartographer_ros/configuration_files/backpack_3d.lua
+++ b/cartographer_ros/configuration_files/backpack_3d.lua
@@ -34,15 +34,15 @@ options = {
}
options.map_builder.use_trajectory_builder_3d = true
-options.sparse_pose_graph.optimize_every_n_scans = 320
-options.sparse_pose_graph.constraint_builder.sampling_ratio = 0.03
-options.sparse_pose_graph.optimization_problem.ceres_solver_options.max_num_iterations = 10
+options.map_builder.sparse_pose_graph.optimize_every_n_scans = 320
+options.map_builder.sparse_pose_graph.constraint_builder.sampling_ratio = 0.03
+options.map_builder.sparse_pose_graph.optimization_problem.ceres_solver_options.max_num_iterations = 10
-- Reuse the coarser 3D voxel filter to speed up the computation of loop closure
-- constraints.
-options.sparse_pose_graph.constraint_builder.adaptive_voxel_filter = TRAJECTORY_BUILDER_3D.high_resolution_adaptive_voxel_filter
-options.sparse_pose_graph.constraint_builder.min_score = 0.62
-options.sparse_pose_graph.constraint_builder.log_matches = true
+options.map_builder.sparse_pose_graph.constraint_builder.adaptive_voxel_filter = TRAJECTORY_BUILDER_3D.high_resolution_adaptive_voxel_filter
+options.map_builder.sparse_pose_graph.constraint_builder.min_score = 0.62
+options.map_builder.sparse_pose_graph.constraint_builder.log_matches = true
-options.trajectory_builder.scans_per_accumulation = 20
+options.map_builder.trajectory_builder_3d.scans_per_accumulation = 20
return options
diff --git a/cartographer_ros/configuration_files/turtlebot.lua b/cartographer_ros/configuration_files/turtlebot.lua
index b1e61d2..0e76314 100644
--- a/cartographer_ros/configuration_files/turtlebot.lua
+++ b/cartographer_ros/configuration_files/turtlebot.lua
@@ -34,7 +34,7 @@ options = {
}
options.map_builder.use_trajectory_builder_2d = true
-options.trajectory_builder.expect_imu_data = false
-options.trajectory_builder.use_online_correlative_scan_matching = true
+options.map_builder.trajectory_builder_2d.use_imu_data = false
+options.map_builder.trajectory_builder_2d.use_online_correlative_scan_matching = true
return options
diff --git a/cartographer_ros/launch/backpack_2d.launch b/cartographer_ros/launch/backpack_2d.launch
index 41d8674..99b65f7 100644
--- a/cartographer_ros/launch/backpack_2d.launch
+++ b/cartographer_ros/launch/backpack_2d.launch
@@ -28,5 +28,4 @@
output="screen">
-
diff --git a/cartographer_ros/launch/backpack_3d.launch b/cartographer_ros/launch/backpack_3d.launch
index 87fb752..579c69b 100644
--- a/cartographer_ros/launch/backpack_3d.launch
+++ b/cartographer_ros/launch/backpack_3d.launch
@@ -29,5 +29,4 @@
-
diff --git a/cartographer_ros/launch/demo_2d.launch b/cartographer_ros/launch/demo_2d.launch
index 5202e10..248e14b 100644
--- a/cartographer_ros/launch/demo_2d.launch
+++ b/cartographer_ros/launch/demo_2d.launch
@@ -23,5 +23,4 @@
args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
-
diff --git a/cartographer_ros/launch/demo_3d.launch b/cartographer_ros/launch/demo_3d.launch
index 47a635a..f5bfc3a 100644
--- a/cartographer_ros/launch/demo_3d.launch
+++ b/cartographer_ros/launch/demo_3d.launch
@@ -23,5 +23,4 @@
args="-d $(find cartographer_ros)/configuration_files/demo_3d.rviz" />
-
diff --git a/cartographer_ros/launch/turtlebot.launch b/cartographer_ros/launch/turtlebot.launch
index 194fe35..d9d3a26 100644
--- a/cartographer_ros/launch/turtlebot.launch
+++ b/cartographer_ros/launch/turtlebot.launch
@@ -25,8 +25,5 @@
type="cartographer_node" args="
-configuration_directory $(find cartographer_ros)/configuration_files
-configuration_basename turtlebot.lua"
- output="screen">
-
-
-
+ output="screen" />