-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
Acrobot_no_collision.urdf
65 lines (65 loc) · 1.74 KB
/
Acrobot_no_collision.urdf
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
<?xml version="1.0"?>
<robot name="Acrobot">
<link name="base_link">
<visual>
<geometry>
<box size="0.2 0.2 0.2"/>
</geometry>
<material name="green">
<color rgba="0 1 0 1"/>
</material>
</visual>
</link>
<link name="upper_link">
<inertial>
<origin xyz="0 0 -.5" rpy="0 0 0"/>
<mass value="1"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="0.083" iyz="0" izz="1"/>
</inertial>
<visual>
<origin xyz="0 0 -0.5" rpy="0 0 0"/>
<geometry>
<cylinder length="1.1" radius="0.05"/>
</geometry>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
</visual>
</link>
<link name="lower_link">
<inertial>
<origin xyz="0 0 -1" rpy="0 0 0"/>
<mass value="1"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="0.33" iyz="0" izz="1"/>
</inertial>
<visual>
<origin xyz="0 0 -1" rpy="0 0 0"/>
<geometry>
<cylinder length="2.1" radius=".05"/>
</geometry>
<material name="blue">
<color rgba="0 0 1 1"/>
</material>
</visual>
</link>
<joint name="shoulder" type="continuous">
<parent link="base_link"/>
<child link="upper_link"/>
<origin xyz="0 0.15 0"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.1"/>
</joint>
<joint name="elbow" type="continuous">
<parent link="upper_link"/>
<child link="lower_link"/>
<origin xyz="0 0.1 -1"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.1"/>
</joint>
<transmission type="SimpleTransmission" name="elbow_trans">
<actuator name="elbow"/>
<joint name="elbow"/>
<mechanicalReduction>1</mechanicalReduction>
</transmission>
<frame name="hand" link="lower_link" xyz="0 0 -2.1" rpy="0 0 0"/>
</robot>