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
17 changes: 17 additions & 0 deletions ridgeback_baxter_description/launch/ridgeback_baxter_world.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<?xml version="1.0" encoding="utf-8"?>
<launch>

<!-- Load the combined ridgeback-baxter URDF's to the param server -->
<param name="robot_description"
command="$(find xacro)/xacro.py --inorder
$(find ridgeback_baxter_description)/urdf/ridgeback_baxter.urdf.xacro gazebo:=true"/>

<!-- Launch baxter_simulator -->
<include file="$(find baxter_gazebo)/launch/baxter_world.launch">
<arg name="load_robot_description" value="false"/>
</include>

<!-- Launch ridgeback_simulator -->
<!-- TODO -->

Copy link
Copy Markdown
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I am fine with this simulator launch file being placed elsewhere that makes more sense. I just put it here as a placeholder.

Copy link
Copy Markdown
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The launchfile produces this simulation of Baxter & Ridgeback in Gazebo. Of course, none of the Ridgeback controllers are loaded:
baxter_ridgeback_gazebo

</launch>
100 changes: 100 additions & 0 deletions ridgeback_baxter_description/meshes/pedestal_stand.dae

Large diffs are not rendered by default.

Binary file not shown.
61 changes: 61 additions & 0 deletions ridgeback_baxter_description/meshes/pedestal_stand_collision.dae
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Blender User</author>
<authoring_tool>Blender 2.74.0 commit date:2015-03-31, commit time:13:39, hash:000dfc0</authoring_tool>
</contributor>
<created>2015-12-14T15:14:05</created>
<modified>2015-12-14T15:14:05</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_images/>
<library_geometries>
<geometry id="PEDESTAL-L_001-mesh" name="PEDESTAL-L.001">
<mesh>
<source id="PEDESTAL-L_001-mesh-positions">
<float_array id="PEDESTAL-L_001-mesh-positions-array" count="135">0.1556287 -0.04569661 -0.06152492 0.1621989 0 -0.6466 0.1621989 0 -0.06152492 0.1556287 0.04569661 -0.6466 0.1556287 0.04569661 -0.06152492 0.1364504 0.08769136 -0.6466 0.1364504 0.08769136 -0.06152492 0.1062177 0.1225817 -0.6466 0.1062177 0.1225817 -0.06152492 0.06737983 0.1475413 -0.6466 0.06737983 0.1475413 -0.06152492 0.0230832 0.160548 -0.6466 0.0230832 0.160548 -0.06152492 -0.0230832 0.160548 -0.6466 -0.0230832 0.160548 -0.06152492 -0.06737983 0.1475413 -0.6466 -0.06737983 0.1475413 -0.06152492 -0.1062177 0.1225817 -0.6466 -0.1062177 0.1225817 -0.06152492 -0.1364504 0.08769136 -0.6466 -0.1364504 0.08769136 -0.06152492 -0.1556287 0.04569661 -0.6466 -0.1556287 0.04569661 -0.06152492 -0.1621989 0 -0.6466 -0.1621989 0 -0.06152492 -0.1556287 -0.04569661 -0.6466 -0.1556287 -0.04569661 -0.06152492 -0.1364504 -0.08769136 -0.6466 -0.1364504 -0.08769136 -0.06152492 -0.1062177 -0.1225817 -0.6466 -0.1062177 -0.1225817 -0.06152492 -0.06737983 -0.1475413 -0.6466 -0.06737983 -0.1475413 -0.06152492 -0.0230832 -0.160548 -0.6466 -0.0230832 -0.160548 -0.06152492 0.0230832 -0.160548 -0.6466 0.0230832 -0.160548 -0.06152492 0.06737983 -0.1475413 -0.6466 0.06737983 -0.1475413 -0.06152492 0.1062177 -0.1225817 -0.6466 0.1062177 -0.1225817 -0.06152492 0.1364504 -0.08769136 -0.6466 0.1364504 -0.08769136 -0.06152492 0.1556287 -0.04569661 -0.6466 -0.1621989 0 -0.06152492</float_array>
<technique_common>
<accessor source="#PEDESTAL-L_001-mesh-positions-array" count="45" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="PEDESTAL-L_001-mesh-normals">
<float_array id="PEDESTAL-L_001-mesh-normals-array" count="192">0.9898214 -0.1423152 0 0.9898214 0.1423152 0 0.9898214 0.1423152 0 0.9096323 0.4154145 0 0.9096323 0.4154145 0 0.7557491 0.6548613 0 0.7557491 0.6548613 0 0.5406412 0.8412533 0 0.5406412 0.8412533 0 0.2817336 0.9594927 0 0.2817336 0.9594927 0 0 1 0 0 1 0 -0.2817336 0.9594927 0 -0.2817336 0.9594927 0 -0.5406412 0.8412533 0 -0.5406412 0.8412533 0 -0.7557491 0.6548613 0 -0.7557491 0.6548613 0 -0.9096323 0.4154145 0 -0.9096323 0.4154145 0 -0.9898214 0.1423152 0 -0.9898214 0.1423152 0 -0.9898214 -0.1423152 0 -0.9898214 -0.1423152 0 -0.9096323 -0.4154145 0 -0.9096323 -0.4154145 0 -0.7557491 -0.6548613 0 -0.7557491 -0.6548613 0 -0.5406412 -0.8412533 0 -0.5406412 -0.8412533 0 -0.2817336 -0.9594927 0 -0.2817336 -0.9594927 0 0 -1 0 0 -1 0 0.2817336 -0.9594927 0 0.2817336 -0.9594927 0 0.5406412 -0.8412533 0 0.5406412 -0.8412533 0 0.7557491 -0.6548613 0 0.7557491 -0.6548613 0 0.9096323 -0.4154145 0 0.9096323 -0.4154145 0 0.9898214 -0.1423152 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1</float_array>
<technique_common>
<accessor source="#PEDESTAL-L_001-mesh-normals-array" count="64" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="PEDESTAL-L_001-mesh-vertices">
<input semantic="POSITION" source="#PEDESTAL-L_001-mesh-positions"/>
</vertices>
<polylist count="64">
<input semantic="VERTEX" source="#PEDESTAL-L_001-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#PEDESTAL-L_001-mesh-normals" offset="1"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 1 0 2 0 2 1 1 1 3 1 2 2 3 2 4 2 4 3 3 3 5 3 4 4 5 4 6 4 6 5 5 5 7 5 6 6 7 6 8 6 8 7 7 7 9 7 8 8 9 8 10 8 10 9 9 9 11 9 10 10 11 10 12 10 12 11 11 11 13 11 12 12 13 12 14 12 14 13 13 13 15 13 14 14 15 14 16 14 16 15 15 15 17 15 16 16 17 16 18 16 18 17 17 17 19 17 18 18 19 18 20 18 20 19 19 19 21 19 20 20 21 20 22 20 22 21 21 21 23 21 22 22 23 22 24 22 24 23 23 23 25 23 24 24 25 24 26 24 26 25 25 25 27 25 26 26 27 26 28 26 28 27 27 27 29 27 28 28 29 28 30 28 30 29 29 29 31 29 30 30 31 30 32 30 32 31 31 31 33 31 32 32 33 32 34 32 34 33 33 33 35 33 34 34 35 34 36 34 36 35 35 35 37 35 36 36 37 36 38 36 38 37 37 37 39 37 38 38 39 38 40 38 40 39 39 39 41 39 40 40 41 40 42 40 42 41 41 41 43 41 42 42 43 42 0 42 0 43 43 43 1 43 10 44 12 44 30 44 22 45 44 45 26 45 12 46 14 46 30 46 30 47 14 47 16 47 30 48 16 48 28 48 10 49 30 49 8 49 8 50 30 50 32 50 8 51 32 51 34 51 34 52 36 52 8 52 8 53 36 53 38 53 8 54 38 54 40 54 22 55 26 55 20 55 28 56 16 56 26 56 26 57 16 57 18 57 26 58 18 58 20 58 0 59 2 59 4 59 40 60 42 60 8 60 8 61 42 61 0 61 8 62 0 62 6 62 6 63 0 63 4 63</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="pedestaLstand_collision" name="pedestaLstand_collision" type="NODE">
<matrix sid="transform">1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#PEDESTAL-L_001-mesh"/>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>
Binary file not shown.
53 changes: 47 additions & 6 deletions ridgeback_baxter_description/urdf/ridgeback_baxter.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,15 +1,56 @@
<?xml version="1.0"?>
<robot name="ridgeback_baxter" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="pedestal_height" value="0.565" />
<xacro:arg name="gazebo" default="false"/>
<xacro:arg name="pedestal" default="false"/>
<xacro:arg name="with_baxter" default="true"/>

<xacro:property name="pedestal_height" value="-0.92" />
<xacro:property name="pedestal_diameter" value="0.203" />
<xacro:property name="pedestal_offset_x" value="0.2" />
<xacro:property name="pedestal_offset_x" value="-0.2" />

<!-- Ridgeback URDF -->
<xacro:include filename="$(find ridgeback_description)/urdf/ridgeback.urdf.xacro" />
<xacro:include filename="$(find baxter_description)/urdf/baxter.urdf" />

<joint name="ridgeback_base_to_baxter" type="fixed">
<xacro:if value="$(arg with_baxter)">
<!-- Baxter URDF -->
<xacro:include filename="$(find baxter_description)/urdf/baxter.urdf.xacro">
<xacro:arg name="gazebo" value="${gazebo}"/>
<xacro:arg name="pedestal" value="${pedestal}"/>
</xacro:include>
</xacro:if>

<!-- Ridgeback-Baxter Joint URDF -->
<joint name="pedestal_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0" />
<parent link="torso" />
<child link="pedestal_stand" />
</joint>
<link name="pedestal_stand">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://ridgeback_baxter_description/meshes/pedestal_stand.dae"/>
</geometry>
<material name="darkgray">
<color rgba=".2 .2 .2 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://ridgeback_baxter_description/meshes/pedestal_stand_collision.dae"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="30.0"/>
Copy link
Copy Markdown
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I am actually not sure if this is the right mass or inertia for the pedestal stand...

<inertia ixx="5.0635929" ixy="0.00103417" ixz="0.80199628" iyy="6.08689388" iyz="0.00105311" izz="4.96191932"/>
</inertial>
</link>
<joint name="baxter_to_ridgeback_base" type="fixed">
<origin rpy="0 0 0" xyz="${pedestal_offset_x} 0 ${pedestal_height}" />
<parent link="mid_mount" />
<child link="base" />
<parent link="pedestal_stand" />
<child link="base_link" />
</joint>

</robot>