Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions create_description/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,3 +9,7 @@ install(DIRECTORY meshes
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
install(DIRECTORY urdf
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

if(CATKIN_ENABLE_TESTING)
catkin_add_nosetests(test)
endif()
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@
<created>2011-04-04T13:58:47.183927</created>
<modified>2011-04-04T13:58:47.183946</modified>
<unit meter="1.0" name="meter"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_effects>
<effect id="create_tga-fx" name="create_tga-fx">
Expand Down Expand Up @@ -65,7 +64,7 @@
</library_effects>
<library_images>
<image id="create_tga-img" name="create_tga-img">
<init_from>create_body.tga</init_from>
<init_from>create_1.tga</init_from>
</image>
</library_images>
<library_materials>
Expand Down
472 changes: 472 additions & 0 deletions create_description/meshes/create_2.dae

Large diffs are not rendered by default.

15 changes: 15 additions & 0 deletions create_description/test/test_urdf.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
import subprocess

import nose.tools

import rospkg


def test_create_urdf():
urdf_file = rospkg.RosPack().get_path('create_description') + '/urdf/create.urdf.xacro'
subprocess.check_call(['rosrun', 'xacro', 'xacro', '--inorder', '--xacro-ns', urdf_file])


def test_create_2_urdf():
urdf_file = rospkg.RosPack().get_path('create_description') + '/urdf/create_2.urdf.xacro'
subprocess.check_call(['rosrun', 'xacro', 'xacro', '--inorder', '--xacro-ns', urdf_file])
310 changes: 7 additions & 303 deletions create_description/urdf/create.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,304 +1,8 @@
<?xml version="1.0"?>
<robot name="turtlebot_hardware" xmlns:xacro="http://ros.org/wiki/xacro">

<!-- Macro for TurtleBot body. Including Gazebo extensions, but does not include Kinect -->
<xacro:include filename="$(find create_description)/urdf/create_gazebo.urdf.xacro"/>

<xacro:property name="base_x" value="0.33" />
<xacro:property name="base_y" value="0.33" />

<xacro:macro name="create">
<material name="Green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>

<!-- base_footprint is a fictitious link(frame) that is on the ground right below base_link origin, navigation stack depends on this frame -->
<link name="base_footprint">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
<material name="Green" />
</visual>

<collision>
<origin xyz="0 0 0.017" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</collision>
</link>

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

<visual>
<origin xyz=" 0 0 0.0308" rpy="0 0 0" />
<geometry>
<mesh filename="package://create_description/meshes/create_body.dae"/>
</geometry>
</visual>

<collision>
<origin xyz="0.0 0.0 0.0308" rpy="0 0 0" />
<geometry>
<cylinder length="0.0611632" radius="0.16495"/>
</geometry>
</collision>
</link>

<link name="wall_sensor_link">
<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>


<link name="left_cliff_sensor_link">
<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>

<link name="right_cliff_sensor_link">
<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>



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

<link name="rightfront_cliff_sensor_link">
<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="base_footprint_joint" type="fixed">
<origin xyz="0 0 0.017" rpy="0 0 0" />
<parent link="base_footprint"/>
<child link="base_link" />
</joint>

<joint name="base_wall_sensor_joint" type="fixed">
<origin xyz="0.09 -0.120 0.042" rpy="0 0 -1.0" />
<parent link="base_link"/>
<child link="wall_sensor_link" />
</joint>

<joint name="base_left_cliff_sensor_joint" type="fixed">
<origin xyz="0.07 0.14 0.01" rpy="0 1.57079 0" />
<parent link="base_link"/>
<child link="left_cliff_sensor_link" />
</joint>

<joint name="base_right_cliff_sensor_joint" type="fixed">
<origin xyz="0.07 -0.14 0.01" rpy="0 1.57079 0" />
<parent link="base_link"/>
<child link="right_cliff_sensor_link" />
</joint>

<joint name="base_leftfront_cliff_sensor_joint" type="fixed">
<origin xyz="0.15 0.04 0.01" rpy="0 1.57079 0" />
<parent link="base_link"/>
<child link="leftfront_cliff_sensor_link" />
</joint>

<joint name="base_rightfront_cliff_sensor_joint" type="fixed">
<origin xyz="0.15 -0.04 0.01" rpy="0 1.57079 0" />
<parent link="base_link"/>
<child link="rightfront_cliff_sensor_link" />
</joint>

<link name="left_wheel_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>

<visual>
<origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
<geometry>
<cylinder radius="0.033" length = "0.023"/>
</geometry>
</visual>

<collision>
<origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
<geometry>
<cylinder radius="0.033" length = "0.023"/>
</geometry>
</collision>
</link>

<joint name="left_wheel_joint" type="continuous">
<origin xyz="0 0.13 0.015" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="left_wheel_link"/>
<axis xyz="0 1 0"/>
</joint>

<link name="right_wheel_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>

<visual>
<origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
<geometry>
<cylinder radius="0.033" length = "0.023"/>
</geometry>
</visual>

<collision>
<origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
<geometry>
<cylinder radius="0.033" length = "0.023"/>
</geometry>
</collision>
</link>

<joint name="right_wheel_joint" type="continuous">
<origin xyz="0 -0.13 0.015" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="right_wheel_link"/>
<axis xyz="0 1 0"/>
</joint>

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

<visual>
<origin xyz="0 0 0" rpy="0 1.5707 1.5707"/>
<geometry>
<sphere radius="0.015" />
</geometry>
</visual>

<collision>
<origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
<geometry>
<sphere radius="0.015" />
</geometry>
</collision>
</link>
<!-- fixed because there's no transmission -->
<joint name="rear_castor_joint" type="fixed">
<origin xyz="-0.13 0 0.0" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="rear_wheel_link"/>
<axis xyz="0 1 0"/>
</joint>

<link name="front_wheel_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>

<visual>
<origin xyz="0 0 0" rpy="0 1.5707 1.5707"/>
<geometry>
<sphere radius="0.018" />
</geometry>
</visual>

<collision>
<origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
<geometry>
<sphere radius="0.018" />
</geometry>
</collision>
</link>

<!-- fixed because there's no transmission -->
<joint name="front_castor_joint" type="fixed">
<origin xyz="0.13 0 0.0" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="front_wheel_link"/>
<axis xyz="0 1 0"/>
</joint>

<joint name="gyro_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="0 0 0.04" rpy="0 0 0" />
<parent link="base_link"/>
<child link="gyro_link"/>
</joint>
<link name="gyro_link">
<inertial>
<mass value="0.001" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.0001" />
</inertial>
</link>

<joint name="laser_joint" type="fixed">
<origin xyz="-0.065 0 0.075" rpy="0 0 0" />
<parent link="base_link" />
<child link="laser" />
</joint>

<link name="laser">
<visual>
<geometry>
<box size="0.02 0.035 0.002" />
</geometry>
<material name="Green" />
</visual>
<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>

<!-- Simulation sensors -->
<sim_create/>
<sim_create_wall_sensor/>
<sim_create_cliff_sensors/>
<sim_imu/>
</xacro:macro>
<?xml version="1.0" ?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="create">
<xacro:include filename="$(find create_description)/urdf/create_base.urdf.xacro" />

<xacro:create_base base_radius="0.3302" wheel_separation="0.26" wheel_radius="0.033">
<mesh filename="package://create_description/meshes/create_1.dae" />
</xacro:create_base>
</robot>
8 changes: 8 additions & 0 deletions create_description/urdf/create_2.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="create_2">
<xacro:include filename="$(find create_description)/urdf/create_base.urdf.xacro" />

<xacro:create_base base_radius="0.3302" wheel_separation="0.235" wheel_radius="0.036">
<mesh filename="package://create_description/meshes/create_2.dae" />
</xacro:create_base>
</robot>
Loading