Unverified Commit b87607aa authored by kijonggil's avatar kijonggil
Browse files

ADded burger camera urdf


Signed-off-by: default avatarkijonggil <kkjong@robotis.com>
No related merge requests found
Showing with 201 additions and 0 deletions
+201 -0
<?xml version="1.0"?>
<!-- TurtleBot3 Burger -->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="burger" params="prefix">
<xacro:property
name="meshes_file_direction"
value="package://turtlebot3_description/meshes/burger"/>
<link name="${prefix}base_footprint"/>
<joint name="${prefix}base_joint" type="fixed">
<parent link="${prefix}base_footprint"/>
<child link="${prefix}base_link" />
<origin xyz="0 0 0.010" rpy="0 0 0"/>
</joint>
<link name="${prefix}base_link">
<visual>
<origin xyz="-0.032 0 0.0" rpy="0 0 0"/>
<geometry>
<mesh filename="${meshes_file_direction}/base.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="light_black"/>
</visual>
<collision>
<origin xyz="-0.032 0 0.070" rpy="0 0 0"/>
<geometry>
<box size="0.140 0.140 0.143"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="8.2573504e-01"/>
<inertia ixx="2.2124416e-03" ixy="-1.2294101e-05" ixz="3.4938785e-05"
iyy="2.1193702e-03" iyz="-5.0120904e-06"
izz="2.0064271e-03" />
</inertial>
</link>
<joint name="${prefix}wheel_left_joint" type="continuous">
<parent link="${prefix}base_link"/>
<child link="${prefix}wheel_left_link"/>
<origin xyz="0.0 0.08 0.023" rpy="-1.57 0 0"/>
<axis xyz="0 0 1"/>
</joint>
<link name="${prefix}wheel_left_link">
<visual>
<origin xyz="0 0 0" rpy="1.57 0 0"/>
<geometry>
<mesh filename="${meshes_file_direction}/left_tire.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dark"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.018" radius="0.033"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="2.8498940e-02" />
<inertia ixx="1.1175580e-05" ixy="-4.2369783e-11" ixz="-5.9381719e-09"
iyy="1.1192413e-05" iyz="-1.4400107e-11"
izz="2.0712558e-05" />
</inertial>
</link>
<joint name="${prefix}wheel_right_joint" type="continuous">
<parent link="${prefix}base_link"/>
<child link="${prefix}wheel_right_link"/>
<origin xyz="0.0 -0.080 0.023" rpy="-1.57 0 0"/>
<axis xyz="0 0 1"/>
</joint>
<link name="${prefix}wheel_right_link">
<visual>
<origin xyz="0 0 0" rpy="1.57 0 0"/>
<geometry>
<mesh filename="${meshes_file_direction}/right_tire.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dark"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.018" radius="0.033"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="2.8498940e-02" />
<inertia ixx="1.1175580e-05" ixy="-4.2369783e-11" ixz="-5.9381719e-09"
iyy="1.1192413e-05" iyz="-1.4400107e-11"
izz="2.0712558e-05" />
</inertial>
</link>
<joint name="${prefix}caster_back_joint" type="fixed">
<parent link="${prefix}base_link"/>
<child link="${prefix}caster_back_link"/>
<origin xyz="-0.081 0 -0.004" rpy="-1.57 0 0"/>
</joint>
<link name="${prefix}caster_back_link">
<collision>
<origin xyz="0 0.001 0" rpy="0 0 0"/>
<geometry>
<box size="0.030 0.009 0.020"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="0.005" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.001" />
</inertial>
</link>
<joint name="${prefix}imu_joint" type="fixed">
<parent link="${prefix}base_link"/>
<child link="${prefix}imu_link"/>
<origin xyz="-0.032 0 0.068" rpy="0 0 0"/>
</joint>
<link name="${prefix}imu_link"/>
<joint name="${prefix}scan_joint" type="fixed">
<parent link="${prefix}base_link"/>
<child link="${prefix}base_scan"/>
<origin xyz="-0.032 0 0.172" rpy="0 0 0"/>
</joint>
<link name="${prefix}base_scan">
<visual>
<origin xyz="0 0 0.0" rpy="0 0 0"/>
<geometry>
<mesh filename="${meshes_file_direction}/ladar.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="dark"/>
</visual>
<collision>
<origin xyz="0.015 0 -0.0065" rpy="0 0 0"/>
<geometry>
<cylinder length="0.0315" radius="0.055"/>
</geometry>
</collision>
<inertial>
<mass value="0.114" />
<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="${prefix}camera_joint" type="fixed">
<origin xyz="0.040 -0.011 0.130" rpy="0 0 0"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}camera_link"/>
</joint>
<link name="${prefix}camera_link">
<collision>
<origin xyz="0.005 0.011 0.013" rpy="0 0 0"/>
<geometry>
<box size="0.015 0.030 0.027"/>
</geometry>
</collision>
</link>
<joint name="${prefix}camera_rgb_joint" type="fixed">
<origin xyz="0.003 0.011 0.009" rpy="0 0 0"/>
<parent link="${prefix}camera_link"/>
<child link="${prefix}camera_rgb_frame"/>
</joint>
<link name="${prefix}camera_rgb_frame"/>
<joint name="${prefix}camera_rgb_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-1.57 0 -1.57"/>
<parent link="${prefix}camera_rgb_frame"/>
<child link="${prefix}camera_rgb_optical_frame"/>
</joint>
<link name="${prefix}camera_rgb_optical_frame"/>
</xacro:macro>
</robot>
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment