bullet3/examples/pybullet/gym/pybullet_data/pendulum5.urdf
2020-02-12 13:05:51 -08:00

149 lines
3.9 KiB
XML

<?xml version="1.0" encoding="utf-8"?>
<robot name="pendulum">
<!--
Author: Erwin Coumans <erwincoumans@google.com>
Contributers:
-->
<link name="world"/>
<material name="Blue">
<color rgba="0.28 0.52 0.92 1.0"/>
</material>
<link name="link0">
<visual>
<geometry>
<sphere radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
<material name="Blue"/>
</visual>
<collision>
<geometry>
<sphere radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.5 0.0"/>
<mass value="1."/>
<inertia ixx="0.00494875" ixy="0" ixz="0" iyy="0.00494174" iyz="0" izz="0.002219"/>
</inertial>
</link>
<joint name="joint0" type="continuous">
<parent link="world"/>
<child link="link0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="1 0 0"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<link name="link1">
<visual>
<geometry>
<sphere radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
<material name="Red"/>
</visual>
<collision>
<geometry>
<sphere radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
<mass value="2.16"/>
<inertia ixx="0.00539427" ixy="0" ixz="0" iyy="0.0048979" iyz="0" izz="0.00311573"/>
</inertial>
</link>
<joint name="joint1" type="continuous">
<parent link="link0"/>
<child link="link1"/>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
<axis xyz="1 0 0"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<link name="link2">
<visual>
<geometry>
<sphere radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
<material name="Red"/>
</visual>
<collision>
<geometry>
<sphere radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
<mass value="2.16"/>
<inertia ixx="0.00539427" ixy="0" ixz="0" iyy="0.0048979" iyz="0" izz="0.00311573"/>
</inertial>
</link>
<joint name="joint2" type="continuous">
<parent link="link1"/>
<child link="link2"/>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
<axis xyz="1 0 0"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<link name="link3">
<visual>
<geometry>
<sphere radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
<material name="Red"/>
</visual>
<collision>
<geometry>
<sphere radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
<mass value="2.16"/>
<inertia ixx="0.00539427" ixy="0" ixz="0" iyy="0.0048979" iyz="0" izz="0.00311573"/>
</inertial>
</link>
<joint name="joint3" type="continuous">
<parent link="link2"/>
<child link="link3"/>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
<axis xyz="1 0 0"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
<link name="link4">
<visual>
<geometry>
<sphere radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
<material name="Red"/>
</visual>
<collision>
<geometry>
<sphere radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
<mass value="2.16"/>
<inertia ixx="0.00539427" ixy="0" ixz="0" iyy="0.0048979" iyz="0" izz="0.00311573"/>
</inertial>
</link>
<joint name="joint4" type="continuous">
<parent link="link3"/>
<child link="link4"/>
<origin rpy="0 0 0" xyz="0 0.5 0"/>
<axis xyz="1 0 0"/>
<dynamics damping="1.0" friction="1.0"/>
</joint>
</robot>