Fix configuration files. (#52)
Fixes configuration files to work with the latest code changes. Also removes the remapping from turtlebot.launch which does not seem to be useful so far.master
parent
9003b19343
commit
f4d69a738b
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -28,5 +28,4 @@
|
|||
output="screen">
|
||||
<remap from="echoes" to="horizontal_laser_2d" />
|
||||
</node>
|
||||
|
||||
</launch>
|
||||
|
|
|
@ -29,5 +29,4 @@
|
|||
<remap from="points2_1" to="horizontal_laser_3d" />
|
||||
<remap from="points2_2" to="vertical_laser_3d" />
|
||||
</node>
|
||||
|
||||
</launch>
|
||||
|
|
|
@ -23,5 +23,4 @@
|
|||
args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
|
||||
<node name="playbag" pkg="rosbag" type="play"
|
||||
args="--clock $(arg bag_filename)" />
|
||||
|
||||
</launch>
|
||||
|
|
|
@ -23,5 +23,4 @@
|
|||
args="-d $(find cartographer_ros)/configuration_files/demo_3d.rviz" />
|
||||
<node name="playbag" pkg="rosbag" type="play"
|
||||
args="--clock $(arg bag_filename)" />
|
||||
|
||||
</launch>
|
||||
|
|
|
@ -25,8 +25,5 @@
|
|||
type="cartographer_node" args="
|
||||
-configuration_directory $(find cartographer_ros)/configuration_files
|
||||
-configuration_basename turtlebot.lua"
|
||||
output="screen">
|
||||
<remap from="scan" to="horizontal_laser_2d" />
|
||||
</node>
|
||||
|
||||
output="screen" />
|
||||
</launch>
|
||||
|
|
Loading…
Reference in New Issue