Skip to content

Commit

Permalink
Return back kinect tf publishing to the xacro file. We also correct the
Browse files Browse the repository at this point in the history
discrepancies between the xacro file and the real thing as explained
here:
https://groups.google.com/forum/?fromgroups#!topic/ros-sig-turtlebot/qASjCIBTsK8
  • Loading branch information
corot committed Jul 2, 2012
1 parent 1192eae commit bb2a91c
Show file tree
Hide file tree
Showing 2 changed files with 65 additions and 1 deletion.
2 changes: 1 addition & 1 deletion kobuki_bringup/resources/launch/components/kinect.launch
Expand Up @@ -4,7 +4,7 @@
<!-- Load standard constellation of processing nodelets -->
<include file="$(find openni_launch)/launch/openni.launch" ns="/">
<arg name="camera" value="camera"/>
<arg name="publish_tf" default="true"/>
<arg name="publish_tf" default="false"/>
</include>

<!-- throttling -->
Expand Down
64 changes: 64 additions & 0 deletions kobuki_description/urdf/kinect.urdf.xacro
Expand Up @@ -38,6 +38,70 @@

</link>

<joint name="camera_depth_joint" type="fixed">
<origin xyz="0 0.0125 0" rpy="0 0 0" />
<parent link="camera_link" />
<child link="camera_depth_frame" />
</joint>

<link name="camera_depth_frame">
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.001" />
</inertial>
</link>

<joint name="camera_depth_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_depth_frame" />
<child link="camera_depth_optical_frame" />
</joint>

<link name="camera_depth_optical_frame">
<inertial>
<mass value="0.001" />
<origin xyz="0 0 0" />
<inertia ixx="0.0001" ixy="0.0" ixz="0.0"
iyy="0.0001" iyz="0.0"
izz="0.0001" />
</inertial>
</link>

<joint name="camera_rgb_joint" type="fixed">
<origin xyz="0 -0.0125 0" rpy="0 0 0" />
<parent link="camera_link" />
<child link="camera_rgb_frame" />
</joint>

<link name="camera_rgb_frame">
<inertial>
<mass value="0.001" />
<origin xyz="0 0 0" />
<inertia ixx="0.0001" ixy="0.0" ixz="0.0"
iyy="0.0001" iyz="0.0"
izz="0.0001" />
</inertial>
</link>

<joint name="camera_rgb_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_rgb_frame" />
<child link="camera_rgb_optical_frame" />
</joint>

<link name="camera_rgb_optical_frame">
<inertial>
<mass value="0.001" />
<origin xyz="0 0 0" />
<inertia ixx="0.0001" ixy="0.0" ixz="0.0"
iyy="0.0001" iyz="0.0"
izz="0.0001" />
</inertial>
</link>

<!-- Kinect sensor for simulation -->
<turtlebot_sim_kinect/>
</xacro:macro>
Expand Down

0 comments on commit bb2a91c

Please sign in to comment.