Add a double pendulum model attached to a base that rests on the ground

This commit is contained in:
Steve Peters 2013-02-13 15:13:01 -08:00
parent d9690f1a94
commit 9cb8eb7722
3 changed files with 117 additions and 0 deletions

View File

@ -41,6 +41,7 @@ coke_can
cordless_drill
create
cube_20k
double_pendulum_with_base
dumpster
fast_food
gas_station

View File

@ -0,0 +1,98 @@
<sdf version="1.3">
<model name="double_pendulum_with_base">
<link name="base">
<inertial>
<mass>100</mass>
</inertial>
<collision name="box_on_ground">
<pose>0 0 0.01 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.8</radius>
<length>0.02</length>
</cylinder>
</geometry>
</collision>
</link>
<!-- upper link, length 1, IC -90 degrees -->
<link name="upper_link">
<pose>0 0 2.1 -1.5708 0 0</pose>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0.5 0 0 0</pose>
</inertial>
<visual name="visual_cylinder">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.9</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<collision name="collision_cylinder">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.9</length>
</cylinder>
</geometry>
</collision>
</link>
<!-- lower link, length 1, IC ~-120 degrees more -->
<link name="lower_link">
<pose>0 1.0 2.1 -2 0 0</pose>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0.5 0 0 0</pose>
</inertial>
<visual name="visual_cylinder">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.9</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<collision name="collision_cylinder">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.9</length>
</cylinder>
</geometry>
</collision>
</link>
<!-- pin joint for upper link, at origin of upper link -->
<joint name="upper_joint" type="revolute">
<parent>base</parent>
<child>upper_link</child>
<axis>
<xyz>1.0 0 0</xyz>
</axis>
</joint>
<!-- pin joint for lower link, at origin of child link -->
<joint name="lower_joint" type="revolute">
<parent>upper_link</parent>
<child>lower_link</child>
<axis>
<xyz>1.0 0 0</xyz>
</axis>
</joint>
</model>
</sdf>

View File

@ -0,0 +1,18 @@
<?xml version="1.0"?>
<model>
<name>Double pendulum with base</name>
<version>1.0</version>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>Steve Peters</name>
<email>scpeters@osrfoundation.org</email>
</author>
<description>
A double pendulum with cylindrical shapes and rotation on the x axis.
The pendulum is attached to a heavy base that rests on the ground.
</description>
</model>