Skip to content

Commit

Permalink
Adds spinning lidar example setup
Browse files Browse the repository at this point in the history
  • Loading branch information
skohlbr committed Aug 29, 2016
1 parent ff65a1e commit 90bd6a7
Show file tree
Hide file tree
Showing 3 changed files with 118 additions and 0 deletions.
45 changes: 45 additions & 0 deletions cartographer_ros/configuration_files/robot_spin_lidar.lua
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
-- Copyright 2016 The Cartographer Authors
--
-- Licensed under the Apache License, Version 2.0 (the "License");
-- you may not use this file except in compliance with the License.
-- You may obtain a copy of the License at
--
-- http://www.apache.org/licenses/LICENSE-2.0
--
-- Unless required by applicable law or agreed to in writing, software
-- distributed under the License is distributed on an "AS IS" BASIS,
-- WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-- See the License for the specific language governing permissions and
-- limitations under the License.

include "trajectory_builder_3d.lua"
include "sparse_pose_graph.lua"

options = {
sparse_pose_graph = SPARSE_POSE_GRAPH,
trajectory_builder = TRAJECTORY_BUILDER_3D,
map_frame = "map",
odom_frame = "odom",
tracking_frame = "base_link",
provide_odom_frame = false,
expect_odometry_data = true,
laser_min_range = 0.6,
laser_max_range = 30.,
laser_missing_echo_ray_length = 1.,
num_lasers_3d = 1
}

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
-- 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


-- Set this depending on the LIDAR rotation rate
options.trajectory_builder.scans_per_accumulation = 180

return options
29 changes: 29 additions & 0 deletions cartographer_ros/launch/demo_robot_spin_lidar.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
<!--
Copyright 2016 The Cartographer Authors
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
-->

<launch>
<param name="/use_sim_time" value="true" />

<include file="$(find cartographer_ros)/launch/robot_spin_lidar.launch" />

<node name="rviz" pkg="rviz" type="rviz" required="true"
args="-d $(find cartographer_ros)/configuration_files/demo_3d.rviz" />

<node name="playbag" pkg="rosbag" type="play"
args="$(arg bag_filename) --clock" />


</launch>
44 changes: 44 additions & 0 deletions cartographer_ros/launch/robot_spin_lidar.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
<!--
Copyright 2016 The Cartographer Authors
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
-->

<launch>
<!--
<param name="robot_description"
textfile="$(find cartographer_ros)/urdf/backpack_3d.urdf" />
<node name="robot_state_publisher" pkg="robot_state_publisher"
type="robot_state_publisher" />
-->

<!--Required as cartographer 3D mode only works with point cloud subscribers-->
<node pkg="vigir_laserscan_to_pointcloud" type="laserscan_to_pointcloud_node" name="lidar_to_cloud_converter" respawn="true" output="screen">
<param name="min_range" value="1.0" />
<param name="use_high_fidelity_projection" value="false" />
<param name="target_frame" value="base_link" />
<remap from="scan" to="/spin_laser/scan" />
<remap from="scan_cloud" to="/spinning_laser_3d" />
</node>

<node name="cartographer" pkg="cartographer_ros"
type="cartographer_node" args="
-configuration_directory $(find cartographer_ros)/configuration_files
-configuration_basename robot_spin_lidar.lua"
output="screen" >
<remap from="points2" to="spinning_laser_3d" />
<remap from="imu" to="/imu/data" />
</node>

</launch>

0 comments on commit 90bd6a7

Please sign in to comment.