-
Notifications
You must be signed in to change notification settings - Fork 1.1k
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #61 from ROBOTIS-GIT/master
merge for sync kinetic-devel and master branch
- Loading branch information
Showing
9 changed files
with
259 additions
and
5 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Binary file not shown.
Binary file not shown.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
255 changes: 255 additions & 0 deletions
255
turtlebot3_description/urdf/turtlebot3_waffle_naked.urdf.xacro
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,255 @@ | ||
<?xml version="1.0" ?> | ||
<robot name="turtlebot3_waffle" xmlns:xacro="http://ros.org/wiki/xacro"> | ||
<xacro:include filename="$(find turtlebot3_description)/urdf/common_properties.xacro"/> | ||
<xacro:include filename="$(find turtlebot3_description)/urdf/turtlebot3_waffle.gazebo.xacro"/> | ||
|
||
<xacro:property name="r200_cam_offset_px" value="0.1" /> | ||
<xacro:property name="r200_cam_offset_py" value="-0.028" /> | ||
<xacro:property name="r200_cam_offset_pz" value="0.110" /> | ||
|
||
<xacro:property name="r200_cam_rgb_px" value="0.005"/> | ||
<xacro:property name="r200_cam_rgb_py" value="0.018"/> | ||
<xacro:property name="r200_cam_rgb_pz" value="0.013"/> | ||
<xacro:property name="r200_cam_depth_offset" value="0.01"/> | ||
|
||
<link name="base_footprint"/> | ||
|
||
<joint name="base_joint" type="fixed"> | ||
<parent link="base_footprint"/> | ||
<child link="base_link" /> | ||
<origin xyz="0 0 0.010" rpy="0 0 0"/> | ||
</joint> | ||
|
||
<link name="base_link"> | ||
<visual> | ||
<origin xyz="-0.064 0 0.0" rpy="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://turtlebot3_description/meshes/bases/waffle_base_naked.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
<material name="light_black"/> | ||
</visual> | ||
<collision> | ||
<origin xyz="-0.064 0 0.048" rpy="0 0 0"/> | ||
<geometry> | ||
<box size="0.265 0.265 0.089"/> | ||
</geometry> | ||
</collision> | ||
<inertial> | ||
<origin xyz="-0.064 0 0" rpy="0 0 0"/> | ||
<mass value="1"/> | ||
<inertia ixx="0.01" ixy="0.0" ixz="0.0" | ||
iyy="0.01" iyz="0.0" | ||
izz="0.01" /> | ||
</inertial> | ||
</link> | ||
|
||
<joint name="wheel_left_joint" type="continuous"> | ||
<parent link="base_link"/> | ||
<child link="wheel_left_link"/> | ||
<origin xyz="0.0 0.144 0.023" rpy="${-M_PI*0.5} 0 0"/> | ||
<axis xyz="0 0 1"/> | ||
</joint> | ||
|
||
<link name="wheel_left_link"> | ||
<visual> | ||
<origin xyz="0 0 0" rpy="${M_PI*0.5} 0 0"/> | ||
<geometry> | ||
<mesh filename="package://turtlebot3_description/meshes/wheels/left_tire.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
<material name="dark"/> | ||
</visual> | ||
<collision> | ||
<origin rpy="0 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<cylinder length="0.018" radius="0.033"/> | ||
</geometry> | ||
</collision> | ||
<inertial> | ||
<origin xyz="0 0 0" /> | ||
<mass value="0.01" /> | ||
<inertia ixx="0.001" ixy="0.0" ixz="0.0" | ||
iyy="0.001" iyz="0.0" | ||
izz="0.001" /> | ||
</inertial> | ||
</link> | ||
|
||
<joint name="wheel_right_joint" type="continuous"> | ||
<parent link="base_link"/> | ||
<child link="wheel_right_link"/> | ||
<origin xyz="0.0 -0.144 0.023" rpy="${-M_PI*0.5} 0 0"/> | ||
<axis xyz="0 0 1"/> | ||
</joint> | ||
|
||
<link name="wheel_right_link"> | ||
<visual> | ||
<origin xyz="0 0 0" rpy="${M_PI*0.5} 0 0"/> | ||
<geometry> | ||
<mesh filename="package://turtlebot3_description/meshes/wheels/right_tire.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
<material name="dark"/> | ||
</visual> | ||
<collision> | ||
<origin rpy="0 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<cylinder length="0.018" radius="0.033"/> | ||
</geometry> | ||
</collision> | ||
<inertial> | ||
<origin xyz="0 0 0" /> | ||
<mass value="0.01" /> | ||
<inertia ixx="0.001" ixy="0.0" ixz="0.0" | ||
iyy="0.001" iyz="0.0" | ||
izz="0.001" /> | ||
</inertial> | ||
</link> | ||
|
||
<joint name="caster_back_right_joint" type="fixed"> | ||
<parent link="base_link"/> | ||
<child link="caster_back_right_link"/> | ||
<origin xyz="-0.177 -0.064 -0.004" rpy="${-M_PI*0.5} 0 0"/> | ||
</joint> | ||
|
||
<link name="caster_back_right_link"> | ||
<collision> | ||
<origin rpy="0 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<box size="0.030 0.010 0.020"/> | ||
</geometry> | ||
</collision> | ||
|
||
<inertial> | ||
<origin xyz="0 0 0" /> | ||
<mass value="0.01" /> | ||
<inertia ixx="0.001" ixy="0.0" ixz="0.0" | ||
iyy="0.001" iyz="0.0" | ||
izz="0.001" /> | ||
</inertial> | ||
</link> | ||
|
||
<joint name="caster_back_left_joint" type="fixed"> | ||
<parent link="base_link"/> | ||
<child link="caster_back_left_link"/> | ||
<origin xyz="-0.177 0.064 -0.004" rpy="${-M_PI*0.5} 0 0"/> | ||
</joint> | ||
|
||
<link name="caster_back_left_link"> | ||
<collision> | ||
<origin rpy="0 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<box size="0.030 0.010 0.020"/> | ||
</geometry> | ||
</collision> | ||
|
||
<inertial> | ||
<origin xyz="0 0 0" /> | ||
<mass value="0.01" /> | ||
<inertia ixx="0.001" ixy="0.0" ixz="0.0" | ||
iyy="0.001" iyz="0.0" | ||
izz="0.001" /> | ||
</inertial> | ||
</link> | ||
|
||
<!-- TurtleBot3 Sensors--> | ||
<!-- <joint name="gyro_joint" type="fixed"> | ||
<parent link="base_link"/> | ||
<child link="gyro_link"/> | ||
<origin xyz="0.064 0 0.057" rpy="0 0 0"/> | ||
</joint> | ||
<link name="gyro_link"> | ||
<inertial> | ||
<origin xyz="0 0 0" /> | ||
<mass value="0.01" /> | ||
<inertia ixx="0.001" ixy="0.0" ixz="0.0" | ||
iyy="0.001" iyz="0.0" | ||
izz="0.001" /> | ||
</inertial> | ||
</link>--> | ||
|
||
<!-- <joint name="scan_joint" type="fixed"> | ||
<parent link="base_link"/> | ||
<child link="base_scan"/> | ||
<origin xyz="-0.064 0 0.121" rpy="0 0 0"/> | ||
</joint> | ||
<link name="base_scan"> | ||
<visual> | ||
<origin xyz="0 0 0.0" rpy="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://turtlebot3_description/meshes/sensors/lds.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
<material name="dark"/> | ||
</visual> | ||
<collision> | ||
<origin rpy="0 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<cylinder length="0.0408" radius="0.070"/> | ||
</geometry> | ||
</collision> | ||
<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_joint" type="fixed"> | ||
<origin xyz="0.064 -0.065 0.094" rpy="0 0 0"/> | ||
<parent link="base_link"/> | ||
<child link="camera_link"/> | ||
</joint> | ||
|
||
<link name="camera_link"> | ||
<visual> | ||
<origin xyz="0 0 0" rpy="${M_PI*0.5} 0 ${M_PI*0.5}"/> | ||
<geometry> | ||
<mesh filename="package://turtlebot3_description/meshes/sensors/r200.dae" /> | ||
</geometry> | ||
</visual> | ||
<collision> | ||
<origin xyz="0.003 0.065 0.010" rpy="0 0 0"/> | ||
<geometry> | ||
<box size="0.008 0.130 0.022"/> | ||
</geometry> | ||
</collision> | ||
|
||
<!-- This inertial field needs doesn't contain reliable data!! --> | ||
<!-- <inertial> | ||
<mass value="0.564" /> | ||
<origin xyz="0 0 0" /> | ||
<inertia ixx="0.003881243" ixy="0.0" ixz="0.0" | ||
iyy="0.000498940" iyz="0.0" | ||
izz="0.003879257" /> | ||
</inertial>--> | ||
</link> | ||
|
||
<joint name="camera_rgb_joint" type="fixed"> | ||
<origin xyz="${r200_cam_rgb_px} ${r200_cam_rgb_py} ${r200_cam_rgb_pz}" rpy="0 0 0"/> | ||
<parent link="camera_link"/> | ||
<child link="camera_rgb_frame"/> | ||
</joint> | ||
<link name="camera_rgb_frame"/> | ||
|
||
<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"/> | ||
|
||
<joint name="camera_depth_joint" type="fixed"> | ||
<origin xyz="0 ${r200_cam_depth_offset} 0" rpy="0 0 0"/> | ||
<parent link="camera_rgb_frame"/> | ||
<child link="camera_depth_frame"/> | ||
</joint> | ||
<link name="camera_depth_frame"/> | ||
|
||
<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"/> | ||
|
||
</robot> |
Binary file not shown.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Binary file not shown.