-
Notifications
You must be signed in to change notification settings - Fork 8
Expand file tree
/
Copy pathmodel.sdf
More file actions
110 lines (106 loc) · 3.96 KB
/
model.sdf
File metadata and controls
110 lines (106 loc) · 3.96 KB
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
<?xml version="1.0"?>
<sdf version="1.7">
<model name="single_pendulum">
<!-- <pose>0 0 0.2 0 0 0</pose> -->
<joint name="fixed_base" type="fixed">
<parent>world</parent>
<child>base_link</child>
</joint>
<link name='base_link'>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>100</mass>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
</inertial>
<collision name='base_link_fixed_joint_lump__base_collision'>
<pose>0 0 1 0 0 0</pose>
<geometry>
<box>
<size>0.15 0.15 2.15</size>
</box>
</geometry>
</collision>
<visual name='base_link_fixed_joint_lump__base_visual'>
<pose>0 0 1 0 0 0</pose>
<geometry>
<box>
<size>0.15 0.15 2.15</size>
</box>
</geometry>
</visual>
</link>
<joint name='upper_joint' type='revolute'>
<pose relative_to='base_link'>0.15 0 2 -1.5708 0 0</pose>
<parent>base_link</parent>
<child>upper_link</child>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>-5</lower>
<upper>5</upper>
<effort>100</effort>
<velocity>100</velocity>
</limit>
<dynamics>
<damping>0.0</damping>
<spring_reference>0</spring_reference>
<spring_stiffness>0.0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='upper_link'>
<pose relative_to='upper_joint'>0 0 0 0 0 0</pose>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0.5 0 0 0</pose>
<mass>1</mass>
<inertia>
<ixx>0.0852</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0852</iyy>
<iyz>0</iyz>
<izz>0.0037</izz>
</inertia>
</inertial>
<collision name='upper_link_collision'>
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<box>
<size>0.15 0.15 1.0</size>
</box>
</geometry>
</collision>
<visual name='upper_link_visual'>
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<box>
<size>0.15 0.15 1.0</size>
</box>
</geometry>
</visual>
</link>
<!-- Launch the other YARP devices, in this case a controlBoard_nws_yarp to expose the
controlboard functionalities via YARP ports -->
<plugin name="gzyarp::ControlBoard" filename="gz-sim-yarp-controlboard-system">
<yarpConfigurationFile>
model://single_pendulum/conf/gazebo_controlboard.ini
</yarpConfigurationFile>
<!-- This initialConfiguration is specified here, but it is overriden in single_pendulum_world
to show how to spawn the model in a different configuration from the default one of the model -->
<initialConfiguration>0.0</initialConfiguration>
</plugin>
<plugin name="gzyarp::RobotInterface" filename="gz-sim-yarp-robotinterface-system">
<yarpRobotInterfaceConfigurationFile>
model://single_pendulum/conf/single_pendulum_nws.xml
</yarpRobotInterfaceConfigurationFile>
</plugin>
</model>
</sdf>