Skip to content

Commit aae9b13

Browse files
[python] Allow to load robot from file.
1 parent 800b9fc commit aae9b13

File tree

3 files changed

+345
-9
lines changed

3 files changed

+345
-9
lines changed

CMakeLists.txt

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -80,3 +80,8 @@ INSTALL(FILES
8080
config/controller.yaml
8181
config/sot_params.yaml
8282
DESTINATION share/${PROJECT_NAME}/config)
83+
84+
# Install default URDF file
85+
INSTALL(FILES
86+
urdf/ur10.urdf
87+
DESTINATION share/${PROJECT_NAME}/urdf)

src/dynamic_graph/sot/universal_robot/universal_robot.py

Lines changed: 13 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -15,22 +15,26 @@ class UniversalRobot(AbstractRobot):
1515
This class defines a UniversalRobot UR3, UR5, or UR10
1616
"""
1717

18-
defaultFilename = "package://tiago_data/robots/tiago_steel.urdf"
18+
defaultFilename = "package://sot_universal_robot/urdf/ur10.urdf"
1919

20-
def __init__(self, name, device=None, tracer=None):
20+
def __init__(self, name, device=None, tracer=None, loadFromFile=False):
2121
self.OperationalPointsMap = {
2222
'wrist': 'wrist_3_joint',
2323
'gaze': 'wrist_3_joint',
2424
}
2525

26-
print("Using ROS parameter \"/robot_description\"")
2726
rosParamName = "/robot_description"
28-
import rospy
29-
if rosParamName not in rospy.get_param_names():
30-
raise RuntimeError('"' + rosParamName + '" is not a ROS parameter.')
31-
s = rospy.get_param(rosParamName)
32-
self.loadModelFromString(s, rootJointType=None,
33-
removeMimicJoints=True)
27+
if loadFromFile:
28+
print("Loading from file " + self.defaultFilename)
29+
self.loadModelFromUrdf(self.defaultFilename, rootJointType=None)
30+
else:
31+
print("Using ROS parameter \"/robot_description\"")
32+
import rospy
33+
if rosParamName not in rospy.get_param_names():
34+
raise RuntimeError('"' + rosParamName +
35+
'" is not a ROS parameter.')
36+
s = rospy.get_param(rosParamName)
37+
self.loadModelFromString(s, rootJointType=None)
3438
AbstractRobot.__init__(self, name, tracer)
3539

3640
# Create rigid body dynamics model and data (pinocchio)

urdf/ur10.urdf

Lines changed: 327 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,327 @@
1+
<?xml version="1.0" encoding="utf-8"?>
2+
<!-- =================================================================================== -->
3+
<!-- | This document was autogenerated by xacro from /root/catkin_ws/install/share/agimus_demos/urdf/ur10_robot.urdf.xacro | -->
4+
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
5+
<!-- =================================================================================== -->
6+
<robot name="ur10">
7+
<gazebo>
8+
<plugin filename="libgazebo_ros_control.so" name="ros_control">
9+
<!--robotNamespace>/</robotNamespace-->
10+
<!--robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType-->
11+
</plugin>
12+
<!--
13+
<plugin name="gazebo_ros_power_monitor_controller" filename="libgazebo_ros_power_monitor.so">
14+
<alwaysOn>true</alwaysOn>
15+
<updateRate>1.0</updateRate>
16+
<timeout>5</timeout>
17+
<powerStateTopic>power_state</powerStateTopic>
18+
<powerStateRate>10.0</powerStateRate>
19+
<fullChargeCapacity>87.78</fullChargeCapacity>
20+
<dischargeRate>-474</dischargeRate>
21+
<chargeRate>525</chargeRate>
22+
<dischargeVoltage>15.52</dischargeVoltage>
23+
<chargeVoltage>16.41</chargeVoltage>
24+
</plugin>
25+
-->
26+
</gazebo>
27+
<!--
28+
Author: Kelsey Hawkins
29+
Contributers: Jimmy Da Silva, Ajit Krisshna N L, Muhammad Asif Rana
30+
-->
31+
<!-- measured from model -->
32+
<link name="base_link">
33+
<visual>
34+
<geometry>
35+
<mesh filename="package://ur_description/meshes/ur10/visual/base.dae"/>
36+
</geometry>
37+
<material name="LightGrey">
38+
<color rgba="0.7 0.7 0.7 1.0"/>
39+
</material>
40+
</visual>
41+
<collision>
42+
<geometry>
43+
<mesh filename="package://ur_description/meshes/ur10/collision/base.stl" />
44+
</geometry>
45+
</collision>
46+
<inertial>
47+
<mass value="4.0" />
48+
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
49+
<inertia ixx="0.0061063308908" ixy="0.0" ixz="0.0" iyy="0.0061063308908" iyz="0.0" izz="0.01125"/>
50+
</inertial>
51+
</link>
52+
<joint name="shoulder_pan_joint" type="revolute" >
53+
<parent link="base_link"/>
54+
<child link="shoulder_link"/>
55+
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.1273"/>
56+
<axis xyz="0 0 1"/>
57+
<limit effort="330.0" lower="-6.28318530718" upper="6.28318530718" velocity="2.16"/>
58+
<dynamics damping="0.0" friction="0.0"/>
59+
</joint>
60+
<link name="shoulder_link">
61+
<visual>
62+
<geometry>
63+
<mesh filename="package://ur_description/meshes/ur10/visual/shoulder.dae"/>
64+
</geometry>
65+
<material name="LightGrey">
66+
<color rgba="0.7 0.7 0.7 1.0"/>
67+
</material>
68+
</visual>
69+
<collision>
70+
<geometry>
71+
<mesh filename="package://ur_description/meshes/ur10/collision/shoulder.stl"/>
72+
</geometry>
73+
</collision>
74+
<inertial>
75+
<mass value="7.778" />
76+
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
77+
<inertia ixx="0.0314743125769" ixy="0.0" ixz="0.0" iyy="0.0314743125769" iyz="0.0" izz="0.021875625" />
78+
</inertial>
79+
</link>
80+
<joint name="shoulder_lift_joint" type="revolute" >
81+
<parent link="shoulder_link"/>
82+
<child link="upper_arm_link"/>
83+
<origin rpy="0.0 1.57079632679 0.0" xyz="0.0 0.220941 0.0"/>
84+
<axis xyz="0 1 0"/>
85+
<limit effort="330.0" lower="-6.28318530718" upper="6.28318530718" velocity="2.16"/>
86+
<dynamics damping="0.0" friction="0.0" />
87+
</joint>
88+
<link name="upper_arm_link">
89+
<visual>
90+
<geometry>
91+
<mesh filename="package://ur_description/meshes/ur10/visual/upperarm.dae" />
92+
</geometry>
93+
<material name="LightGrey">
94+
<color rgba="0.7 0.7 0.7 1.0"/>
95+
</material>
96+
</visual>
97+
<collision>
98+
<geometry>
99+
<mesh filename="package://ur_description/meshes/ur10/collision/upperarm.stl" />
100+
</geometry>
101+
</collision>
102+
<inertial>
103+
<mass value="12.93" />
104+
<origin rpy="0 0 0" xyz="0.0 -0.045 0.306"/>
105+
<inertia ixx="0.421753803798" ixy="0.0" ixz="0.0" iyy="0.421753803798" iyz="0.0" izz="0.036365625"/>
106+
</inertial>
107+
</link>
108+
<joint name="elbow_joint" type="revolute">
109+
<parent link="upper_arm_link"/>
110+
<child link="forearm_link" />
111+
<origin rpy="0.0 0.0 0.0" xyz="0.0 -0.1719 0.612"/>
112+
<axis xyz="0 1 0"/>
113+
<limit effort="150.0" lower="-3.14159265359" upper="3.14159265359" velocity="3.15"/>
114+
<dynamics damping="0.0" friction="0.0"/>
115+
</joint>
116+
<link name="forearm_link">
117+
<visual>
118+
<geometry>
119+
<mesh filename="package://ur_description/meshes/ur10/visual/forearm.dae"/>
120+
</geometry>
121+
<material name="LightGrey">
122+
<color rgba="0.7 0.7 0.7 1.0"/>
123+
</material>
124+
</visual>
125+
<collision>
126+
<geometry>
127+
<mesh filename="package://ur_description/meshes/ur10/collision/forearm.stl"/>
128+
</geometry>
129+
</collision>
130+
<inertial>
131+
<mass value="3.87"/>
132+
<origin rpy="0 0 0" xyz="0.0 0.0 0.28615"/>
133+
<inertia ixx="0.111069694097" ixy="0.0" ixz="0.0" iyy="0.111069694097" iyz="0.0" izz="0.010884375" />
134+
</inertial>
135+
</link>
136+
<joint name="wrist_1_joint" type="revolute" >
137+
<parent link="forearm_link"/>
138+
<child link="wrist_1_link"/>
139+
<origin rpy="0.0 1.57079632679 0.0" xyz="0.0 0.0 0.5723"/>
140+
<axis xyz="0 1 0"/>
141+
<limit effort="54.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.2"/>
142+
<dynamics damping="0.0" friction="0.0"/>
143+
</joint>
144+
<link name="wrist_1_link">
145+
<visual>
146+
<geometry>
147+
<mesh filename="package://ur_description/meshes/ur10/visual/wrist1.dae"/>
148+
</geometry>
149+
<material name="LightGrey">
150+
<color rgba="0.7 0.7 0.7 1.0"/>
151+
</material>
152+
</visual>
153+
<collision>
154+
<geometry>
155+
<mesh filename="package://ur_description/meshes/ur10/collision/wrist1.stl"/>
156+
</geometry>
157+
</collision>
158+
<inertial>
159+
<mass value="1.96"/>
160+
<origin rpy="0 0 0" xyz="0.0 0.1149 0.0"/>
161+
<inertia ixx="0.0051082479567" ixy="0.0" ixz="0.0" iyy="0.0051082479567" iyz="0.0" izz="0.0055125" />
162+
</inertial>
163+
</link>
164+
<joint name="wrist_2_joint" type="revolute" >
165+
<parent link="wrist_1_link"/>
166+
<child link="wrist_2_link"/>
167+
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.1149 0.0"/>
168+
<axis xyz="0 0 1" />
169+
<limit effort="54.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.2"/>
170+
<dynamics damping="0.0" friction="0.0"/>
171+
</joint>
172+
<link name="wrist_2_link">
173+
<visual>
174+
<geometry>
175+
<mesh filename="package://ur_description/meshes/ur10/visual/wrist2.dae"/>
176+
</geometry>
177+
<material name="LightGrey">
178+
<color rgba="0.7 0.7 0.7 1.0"/>
179+
</material>
180+
</visual>
181+
<collision>
182+
<geometry>
183+
<mesh filename="package://ur_description/meshes/ur10/collision/wrist2.stl"/>
184+
</geometry>
185+
</collision>
186+
<inertial>
187+
<mass value="1.96"/>
188+
<origin rpy="0 0 0" xyz="0.0 0.0 0.1157"/>
189+
<inertia ixx="0.0051082479567" ixy="0.0" ixz="0.0" iyy="0.0051082479567" iyz="0.0" izz="0.0055125" />
190+
</inertial>
191+
</link>
192+
<joint name="wrist_3_joint" type="revolute" >
193+
<parent link="wrist_2_link"/>
194+
<child link="wrist_3_link"/>
195+
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.1157"/>
196+
<axis xyz="0 1 0" />
197+
<limit effort="54.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.2"/>
198+
<dynamics damping="0.0" friction="0.0"/>
199+
</joint>
200+
<link name="wrist_3_link">
201+
<visual>
202+
<geometry>
203+
<mesh filename="package://ur_description/meshes/ur10/visual/wrist3.dae"/>
204+
</geometry>
205+
<material name="LightGrey">
206+
<color rgba="0.7 0.7 0.7 1.0"/>
207+
</material>
208+
</visual>
209+
<collision>
210+
<geometry>
211+
<mesh filename="package://ur_description/meshes/ur10/collision/wrist3.stl"/>
212+
</geometry>
213+
</collision>
214+
<inertial>
215+
<mass value="0.202"/>
216+
<origin rpy="1.57079632679 0 0" xyz="0.0 0.07695 0.0"/>
217+
<inertia ixx="0.000117921661165" ixy="0.0" ixz="0.0" iyy="0.000117921661165" iyz="0.0" izz="0.000204525"/>
218+
</inertial>
219+
</link>
220+
<joint name="ee_fixed_joint" type="fixed">
221+
<parent link="wrist_3_link"/>
222+
<child link="ee_link" />
223+
<origin rpy="0.0 0.0 1.57079632679" xyz="0.0 0.0922 0.0"/>
224+
</joint>
225+
<link name="ee_link">
226+
<collision>
227+
<geometry>
228+
<box size="0.01 0.01 0.01"/>
229+
</geometry>
230+
<origin rpy="0 0 0" xyz="-0.01 0 0"/>
231+
</collision>
232+
</link>
233+
<transmission name="shoulder_pan_trans" >
234+
<type>transmission_interface/SimpleTransmission</type>
235+
<joint name="shoulder_pan_joint">
236+
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
237+
</joint>
238+
<actuator name="shoulder_pan_motor">
239+
<mechanicalReduction>1</mechanicalReduction>
240+
</actuator>
241+
</transmission>
242+
<transmission name="shoulder_lift_trans" >
243+
<type>transmission_interface/SimpleTransmission</type>
244+
<joint name="shoulder_lift_joint">
245+
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
246+
</joint>
247+
<actuator name="shoulder_lift_motor">
248+
<mechanicalReduction>1</mechanicalReduction>
249+
</actuator>
250+
</transmission>
251+
<transmission name="elbow_trans">
252+
<type>transmission_interface/SimpleTransmission</type>
253+
<joint name="elbow_joint" >
254+
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
255+
</joint>
256+
<actuator name="elbow_motor">
257+
<mechanicalReduction>1</mechanicalReduction>
258+
</actuator>
259+
</transmission>
260+
<transmission name="wrist_1_trans">
261+
<type>transmission_interface/SimpleTransmission</type>
262+
<joint name="wrist_1_joint" >
263+
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
264+
</joint>
265+
<actuator name="wrist_1_motor">
266+
<mechanicalReduction>1</mechanicalReduction>
267+
</actuator>
268+
</transmission>
269+
<transmission name="wrist_2_trans">
270+
<type>transmission_interface/SimpleTransmission</type>
271+
<joint name="wrist_2_joint" >
272+
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
273+
</joint>
274+
<actuator name="wrist_2_motor">
275+
<mechanicalReduction>1</mechanicalReduction>
276+
</actuator>
277+
</transmission>
278+
<transmission name="wrist_3_trans">
279+
<type>transmission_interface/SimpleTransmission</type>
280+
<joint name="wrist_3_joint" >
281+
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
282+
</joint>
283+
<actuator name="wrist_3_motor">
284+
<mechanicalReduction>1</mechanicalReduction>
285+
</actuator>
286+
</transmission>
287+
<gazebo reference="shoulder_link">
288+
<selfCollide>true</selfCollide>
289+
</gazebo>
290+
<gazebo reference="upper_arm_link" >
291+
<selfCollide>true</selfCollide>
292+
</gazebo>
293+
<gazebo reference="forearm_link" >
294+
<selfCollide>true</selfCollide>
295+
</gazebo>
296+
<gazebo reference="wrist_1_link" >
297+
<selfCollide>true</selfCollide>
298+
</gazebo>
299+
<gazebo reference="wrist_3_link" >
300+
<selfCollide>true</selfCollide>
301+
</gazebo>
302+
<gazebo reference="wrist_2_link" >
303+
<selfCollide>true</selfCollide>
304+
</gazebo>
305+
<gazebo reference="ee_link" >
306+
<selfCollide>true</selfCollide>
307+
</gazebo>
308+
<!-- ROS base_link to UR 'Base' Coordinates transform -->
309+
<link name="base"/>
310+
<joint name="base_link-base_fixed_joint" type="fixed">
311+
<!-- NOTE: this rotation is only needed as long as base_link itself is
312+
not corrected wrt the real robot (ie: rotated over 180
313+
degrees)
314+
-->
315+
<origin rpy="0 0 -3.14159265359" xyz="0 0 0"/>
316+
<parent link="base_link"/>
317+
<child link="base"/>
318+
</joint>
319+
<!-- Frame coincident with all-zeros TCP on UR controller -->
320+
<link name="tool0"/>
321+
<joint name="wrist_3_link-tool0_fixed_joint" type="fixed">
322+
<origin rpy="-1.57079632679 0 0" xyz="0 0.0922 0"/>
323+
<parent link="wrist_3_link"/>
324+
<child link="tool0"/>
325+
</joint>
326+
</robot>
327+

0 commit comments

Comments
 (0)