forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Acrobot.sdf
125 lines (125 loc) · 3.17 KB
/
Acrobot.sdf
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
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
<?xml version="1.0"?>
<sdf version="1.7">
<model name="Acrobot">
<link name="base_link">
<collision name="base_link_collision">
<geometry>
<box>
<size>0.2 0.2 0.2</size>
</box>
</geometry>
</collision>
<visual name="base_link_visual">
<geometry>
<box>
<size>0.2 0.2 0.2</size>
</box>
</geometry>
</visual>
</link>
<joint name="base_weld" type="fixed">
<child>base_link</child>
<parent>world</parent>
</joint>
<link name="upper_link">
<pose>0 0.15 0 0 0 0</pose>
<inertial>
<pose>0 0 -0.5 0 0 0</pose>
<mass>1</mass>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.083</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
</inertial>
<collision name="upper_link_collision">
<pose>0 0 -0.5 0 0 0</pose>
<geometry>
<cylinder>
<length>1.1</length>
<radius>0.05</radius>
</cylinder>
</geometry>
</collision>
<visual name="upper_link_visual">
<pose>0 0 -0.5 0 0 0</pose>
<geometry>
<cylinder>
<length>1.1</length>
<radius>0.05</radius>
</cylinder>
</geometry>
</visual>
</link>
<joint name="shoulder" type="revolute">
<child>upper_link</child>
<parent>base_link</parent>
<axis>
<xyz expressed_in="__model__">0 1 0</xyz>
<limit>
<effort>0</effort>
</limit>
<dynamics>
<damping>0.1</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name="lower_link">
<pose>0 0.25 -1 0 0 0</pose>
<inertial>
<pose>0 0 -1 0 0 0</pose>
<mass>1</mass>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.33</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
</inertial>
<collision name="lower_link_collision">
<pose>0 0 -1 0 0 0</pose>
<geometry>
<cylinder>
<length>2.1</length>
<radius>0.05</radius>
</cylinder>
</geometry>
</collision>
<visual name="lower_link_visual">
<pose>0 0 -1 0 0 0</pose>
<geometry>
<cylinder>
<length>2.1</length>
<radius>0.05</radius>
</cylinder>
</geometry>
</visual>
</link>
<joint name="elbow" type="revolute">
<child>lower_link</child>
<parent>upper_link</parent>
<axis>
<xyz expressed_in="__model__">0 1 0</xyz>
<limit>
</limit>
<dynamics>
<damping>0.1</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<frame name="hand">
<pose relative_to="lower_link">0 0 -2.1 0 0 0</pose>
</frame>
</model>
</sdf>