Add support for 2D SLAM with a depth camera. (#54)
This changes the URDF and timeout for the TurtleBot configuration, and adds a Dockerfile with everything that is needed to run 2D SLAM with a depth camera. Verified to work on a TurtleBot 2 with an ASUS Xtion. And tiny style fixes.master
parent
70f40c6ef2
commit
0e26c9feac
|
@ -28,7 +28,7 @@ options = {
|
||||||
horizontal_laser_max_range = 30.,
|
horizontal_laser_max_range = 30.,
|
||||||
horizontal_laser_missing_echo_ray_length = 5.,
|
horizontal_laser_missing_echo_ray_length = 5.,
|
||||||
num_lasers_3d = 0,
|
num_lasers_3d = 0,
|
||||||
lookup_transform_timeout_sec = 0.01,
|
lookup_transform_timeout_sec = 0.2,
|
||||||
submap_publish_period_sec = 0.3,
|
submap_publish_period_sec = 0.3,
|
||||||
pose_publish_period_sec = 5e-3,
|
pose_publish_period_sec = 5e-3,
|
||||||
}
|
}
|
||||||
|
|
|
@ -74,6 +74,6 @@
|
||||||
<test_depend>rosunit</test_depend>
|
<test_depend>rosunit</test_depend>
|
||||||
|
|
||||||
<export>
|
<export>
|
||||||
<rviz plugin="${prefix}/rviz_plugin_description.xml"/>
|
<rviz plugin="${prefix}/rviz_plugin_description.xml" />
|
||||||
</export>
|
</export>
|
||||||
</package>
|
</package>
|
||||||
|
|
|
@ -16,62 +16,62 @@
|
||||||
|
|
||||||
<robot name="cartographer_ros">
|
<robot name="cartographer_ros">
|
||||||
<material name="orange">
|
<material name="orange">
|
||||||
<color rgba="1.0 0.5 0.2 1"/>
|
<color rgba="1.0 0.5 0.2 1" />
|
||||||
</material>
|
</material>
|
||||||
<material name="gray">
|
<material name="gray">
|
||||||
<color rgba="0.2 0.2 0.2 1"/>
|
<color rgba="0.2 0.2 0.2 1" />
|
||||||
</material>
|
</material>
|
||||||
<material name="green">
|
<material name="green">
|
||||||
<color rgba="0.2 0.4 0.2 1"/>
|
<color rgba="0.2 0.4 0.2 1" />
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<link name="imu_link">
|
<link name="imu_link">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0.0 0.0 0.0"/>
|
<origin xyz="0.0 0.0 0.0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.06 0.04 0.02"/>
|
<box size="0.06 0.04 0.02" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="orange"/>
|
<material name="orange" />
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="horizontal_laser_link">
|
<link name="horizontal_laser_link">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0.0 0.0 0.0"/>
|
<origin xyz="0.0 0.0 0.0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.09" radius="0.03"/>
|
<cylinder length="0.09" radius="0.03" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="gray"/>
|
<material name="gray" />
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="vertical_laser_link">
|
<link name="vertical_laser_link">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0.0 0.0 0.0"/>
|
<origin xyz="0.0 0.0 0.0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.09" radius="0.03"/>
|
<cylinder length="0.09" radius="0.03" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="gray"/>
|
<material name="gray" />
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="base_link" />
|
<link name="base_link" />
|
||||||
|
|
||||||
<joint name="imu_link_joint" type="fixed">
|
<joint name="imu_link_joint" type="fixed">
|
||||||
<parent link="base_link"/>
|
<parent link="base_link" />
|
||||||
<child link="imu_link"/>
|
<child link="imu_link" />
|
||||||
<origin xyz="0 0 0" rpy="0 0 3.1416"/>
|
<origin xyz="0 0 0" rpy="0 0 3.1416" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="horizontal_laser_link_joint" type="fixed">
|
<joint name="horizontal_laser_link_joint" type="fixed">
|
||||||
<parent link="base_link"/>
|
<parent link="base_link" />
|
||||||
<child link="horizontal_laser_link"/>
|
<child link="horizontal_laser_link" />
|
||||||
<origin xyz="0.1251 0.0937 0.05262"/>
|
<origin xyz="0.1251 0.0937 0.05262" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="vertical_laser_link_joint" type="fixed">
|
<joint name="vertical_laser_link_joint" type="fixed">
|
||||||
<parent link="base_link"/>
|
<parent link="base_link" />
|
||||||
<child link="vertical_laser_link"/>
|
<child link="vertical_laser_link" />
|
||||||
<origin rpy="0.0 -1.57 3.14" xyz="0.1251 0.0937 0.17772"/>
|
<origin rpy="0.0 -1.57 3.14" xyz="0.1251 0.0937 0.17772" />
|
||||||
</joint>
|
</joint>
|
||||||
</robot>
|
</robot>
|
||||||
|
|
|
@ -16,62 +16,62 @@
|
||||||
|
|
||||||
<robot name="cartographer_ros">
|
<robot name="cartographer_ros">
|
||||||
<material name="orange">
|
<material name="orange">
|
||||||
<color rgba="1.0 0.5 0.2 1"/>
|
<color rgba="1.0 0.5 0.2 1" />
|
||||||
</material>
|
</material>
|
||||||
<material name="gray">
|
<material name="gray">
|
||||||
<color rgba="0.2 0.2 0.2 1"/>
|
<color rgba="0.2 0.2 0.2 1" />
|
||||||
</material>
|
</material>
|
||||||
<material name="green">
|
<material name="green">
|
||||||
<color rgba="0.2 0.4 0.2 1"/>
|
<color rgba="0.2 0.4 0.2 1" />
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<link name="imu_link">
|
<link name="imu_link">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0.0 0.0 0.0"/>
|
<origin xyz="0.0 0.0 0.0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.06 0.04 0.02"/>
|
<box size="0.06 0.04 0.02" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="orange"/>
|
<material name="orange" />
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="horizontal_vlp16_link">
|
<link name="horizontal_vlp16_link">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0.0 0.0 0.0"/>
|
<origin xyz="0.0 0.0 0.0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.07" radius="0.05"/>
|
<cylinder length="0.07" radius="0.05" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="gray"/>
|
<material name="gray" />
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="vertical_vlp16_link">
|
<link name="vertical_vlp16_link">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0.0 0.0 0.0"/>
|
<origin xyz="0.0 0.0 0.0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.07" radius="0.05"/>
|
<cylinder length="0.07" radius="0.05" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="gray"/>
|
<material name="gray" />
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="base_link" />
|
<link name="base_link" />
|
||||||
|
|
||||||
<joint name="imu_link_joint" type="fixed">
|
<joint name="imu_link_joint" type="fixed">
|
||||||
<parent link="base_link"/>
|
<parent link="base_link" />
|
||||||
<child link="imu_link"/>
|
<child link="imu_link" />
|
||||||
<origin xyz="0 0 0" rpy="3.1416 0 0"/>
|
<origin xyz="0 0 0" rpy="3.1416 0 0" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="horizontal_vlp16_link_joint" type="fixed">
|
<joint name="horizontal_vlp16_link_joint" type="fixed">
|
||||||
<parent link="base_link"/>
|
<parent link="base_link" />
|
||||||
<child link="horizontal_vlp16_link"/>
|
<child link="horizontal_vlp16_link" />
|
||||||
<origin xyz="0.01 0. 0.19" rpy="0. -0.1745 3.1416" />
|
<origin xyz="0.01 0. 0.19" rpy="0. -0.1745 3.1416" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="vertical_vlp16_link_joint" type="fixed">
|
<joint name="vertical_vlp16_link_joint" type="fixed">
|
||||||
<parent link="base_link"/>
|
<parent link="base_link" />
|
||||||
<child link="vertical_vlp16_link"/>
|
<child link="vertical_vlp16_link" />
|
||||||
<origin xyz="0.19 0. 0.04" rpy="0. 1.3963 0."/>
|
<origin xyz="0.19 0. 0.04" rpy="0. 1.3963 0." />
|
||||||
</joint>
|
</joint>
|
||||||
</robot>
|
</robot>
|
||||||
|
|
|
@ -16,38 +16,53 @@
|
||||||
|
|
||||||
<robot name="cartographer_ros">
|
<robot name="cartographer_ros">
|
||||||
<material name="orange">
|
<material name="orange">
|
||||||
<color rgba="1.0 0.5 0.2 1"/>
|
<color rgba="1.0 0.5 0.2 1" />
|
||||||
</material>
|
</material>
|
||||||
<material name="gray">
|
<material name="gray">
|
||||||
<color rgba="0.2 0.2 0.2 1"/>
|
<color rgba="0.2 0.2 0.2 1" />
|
||||||
</material>
|
</material>
|
||||||
<material name="green">
|
<material name="green">
|
||||||
<color rgba="0.2 0.4 0.2 1"/>
|
<color rgba="0.2 0.4 0.2 1" />
|
||||||
</material>
|
</material>
|
||||||
|
|
||||||
<link name="horizontal_laser_link">
|
<link name="horizontal_laser_link">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0.0 0.0 0.0"/>
|
<origin xyz="0.0 0.0 0.0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.09" radius="0.03"/>
|
<cylinder length="0.09" radius="0.03" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="gray"/>
|
<material name="gray" />
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="base_link">
|
<link name="base_link">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0. 0. 0."/>
|
<origin xyz="0. 0. 0." />
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.03 0.4 0.8"/>
|
<box size="0.03 0.4 0.8" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="green"/>
|
<material name="green" />
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
|
<link name="camera_link" />
|
||||||
|
<link name="base_footprint" />
|
||||||
|
|
||||||
<joint name="horizontal_laser_link_joint" type="fixed">
|
<joint name="horizontal_laser_link_joint" type="fixed">
|
||||||
<parent link="base_link"/>
|
<parent link="base_link" />
|
||||||
<child link="horizontal_laser_link"/>
|
<child link="horizontal_laser_link" />
|
||||||
<origin xyz="0. 0. 0.6"/>
|
<origin xyz="0. 0. 0.6" />
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="camera_link_joint" type="fixed">
|
||||||
|
<parent link="base_link" />
|
||||||
|
<child link="camera_link" />
|
||||||
|
<origin xyz="0.15 0. 0.6" />
|
||||||
|
</joint>
|
||||||
|
|
||||||
|
<joint name="base_link_base_footprint_joint" type="fixed">
|
||||||
|
<parent link="base_footprint" />
|
||||||
|
<child link="base_link" />
|
||||||
|
<origin xyz="0. 0. 0." />
|
||||||
</joint>
|
</joint>
|
||||||
</robot>
|
</robot>
|
||||||
|
|
|
@ -0,0 +1,23 @@
|
||||||
|
# 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.
|
||||||
|
|
||||||
|
FROM cartographer_ros_image
|
||||||
|
RUN apt-get update && apt-get install -y \
|
||||||
|
ros-indigo-depthimage-to-laserscan \
|
||||||
|
ros-indigo-kobuki \
|
||||||
|
ros-indigo-kobuki-core \
|
||||||
|
ros-indigo-openni2-launch \
|
||||||
|
ros-indigo-turtlebot-bringup \
|
||||||
|
tmux \
|
||||||
|
&& rm -rf /var/lib/apt/lists/*
|
Loading…
Reference in New Issue