Skip to content

Commit 540fbd1

Browse files
committed
fix dobot robot URDF and pybullet setup
1 parent 91b29a1 commit 540fbd1

File tree

4 files changed

+48
-24
lines changed

4 files changed

+48
-24
lines changed

data/dobot/cad/Dobot/A10.stl

0 Bytes
Binary file not shown.

data/dobot/cad/Dobot/A9.stl

0 Bytes
Binary file not shown.

data/dobot/dobot.urdf

Lines changed: 15 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,6 @@
11
<?xml version="0.0" ?>
2-
<robot name="urdf_door">
3-
4-
2+
<robot name="dobot_arm_kickstarter">
3+
<!-- URDF copyright Erwin Coumans for http://pybullet.org -->
54
<link name="baseLink">
65
<inertial>
76
<origin rpy="0 0 0" xyz="0 0 0"/>
@@ -88,7 +87,7 @@
8887
<visual>
8988
<origin rpy="0 1.57 0" xyz="0 0 0"/>
9089
<geometry>
91-
<cylinder length="0.03" radius="0.002"/>
90+
<cylinder length="0.03" radius="0.02"/>
9291
</geometry>
9392
<material name="black">
9493
<color rgba="0.2 0.2 0.2 1"/>
@@ -119,7 +118,7 @@
119118
<visual>
120119
<origin rpy="0 1.57 0" xyz="0 0 0"/>
121120
<geometry>
122-
<cylinder length="0.03" radius="0.002"/>
121+
<cylinder length="0.03" radius="0.02"/>
123122
</geometry>
124123
<material name="black">
125124
<color rgba="0.2 0.2 0.2 1"/>
@@ -148,14 +147,14 @@
148147
<inertia ixx="0.048966669" ixy="0" ixz="0" iyy="0.046466667" iyz="0" izz="0.0041666669"/>
149148
</inertial>
150149
<visual>
151-
<origin rpy="0 0 0" xyz="0 0 0.08"/>
150+
<origin rpy="0 0 0" xyz="0 0 0.075"/>
152151
<geometry>
153152
<mesh filename="cad/Dobot/A9.stl" scale="1 1 1"/>
154153
</geometry>
155154
<material name="blue"/>
156155
</visual>
157156
<collision>
158-
<origin rpy="0 0 0" xyz="0 0 0.09"/>
157+
<origin rpy="0 0 0" xyz="0 0 0.07"/>
159158
<geometry>
160159
<box size="0.005 0.02 0.18"/>
161160
</geometry>
@@ -166,7 +165,7 @@
166165
<parent link="linkA"/>
167166
<child link="linkA9"/>
168167
<dynamics damping="1.0" friction="0.0001"/>
169-
<origin xyz="0 -0.035 0.045"/>
168+
<origin xyz="0 -0.026 0.054"/>
170169
<axis xyz="1 0 0"/>
171170
</joint>
172171

@@ -243,7 +242,7 @@
243242

244243
<link name="linkC">
245244
<inertial>
246-
<origin rpy="0 0 0" xyz="0 0 0.075"/>
245+
<origin rpy="0 0 0" xyz="0 0 0.08"/>
247246
<mass value=".1"/>
248247
<inertia ixx="0.048966669" ixy="0" ixz="0" iyy="0.046466667" iyz="0" izz="0.0041666669"/>
249248
</inertial>
@@ -268,7 +267,7 @@
268267
<collision>
269268
<origin rpy="0 0 0" xyz="0 0 0.075"/>
270269
<geometry>
271-
<box size="0.026 0.026 0.150"/>
270+
<box size="0.026 0.026 0.21"/>
272271
</geometry>
273272
</collision>
274273
</link>
@@ -283,7 +282,7 @@
283282

284283
<link name="linkD">
285284
<inertial>
286-
<origin rpy="0 0 0" xyz="0 0 0.035"/>
285+
<origin rpy="0 0 0" xyz="0 0 0.02"/>
287286
<mass value=".1"/>
288287
<inertia ixx="0.048966669" ixy="0" ixz="0" iyy="0.046466667" iyz="0" izz="0.0041666669"/>
289288
</inertial>
@@ -305,9 +304,9 @@
305304
</visual>
306305

307306
<collision>
308-
<origin rpy="0 0 0" xyz="0 0 0.035"/>
307+
<origin rpy="0 0 0" xyz="0.00 0.045 -0.017"/>
309308
<geometry>
310-
<box size="0.01 0.02 0.08"/>
309+
<box size="0.02 0.08 0.005"/>
311310
</geometry>
312311
</collision>
313312
</link>
@@ -323,19 +322,19 @@
323322

324323
<link name="linkA10">
325324
<inertial>
326-
<origin rpy="0 0 0" xyz="0 0 0.075"/>
325+
<origin rpy="0 0 0" xyz="0 0 0.08"/>
327326
<mass value=".1"/>
328327
<inertia ixx="0.048966669" ixy="0" ixz="0" iyy="0.046466667" iyz="0" izz="0.0041666669"/>
329328
</inertial>
330329
<visual>
331-
<origin rpy="0 0 0" xyz="0 0 0.075"/>
330+
<origin rpy="0 0 0" xyz="0 0 0.08"/>
332331
<geometry>
333332
<mesh filename="cad/Dobot/A10.stl" scale="1 1 1"/>
334333
</geometry>
335334
<material name="blue"/>
336335
</visual>
337336
<collision>
338-
<origin rpy="0 0 0" xyz="0 0 0.075"/>
337+
<origin rpy="0 0 0" xyz="0 0 0.08"/>
339338
<geometry>
340339
<box size="0.005 0.02 0.17"/>
341340
</geometry>
@@ -347,7 +346,6 @@
347346
<child link="linkA10"/>
348347
<dynamics damping="1.0" friction="0.0001"/>
349348
<origin xyz="0 0.026 0.014"/>
350-
351349
<axis xyz="1 0 0"/>
352350
</joint>
353351

dobot.py

Lines changed: 33 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,13 @@
1+
#Created and copyright by Erwin Coumans for http://pybullet.org
12
import pybullet as p
23
p.connect(p.GUI)
34
#p.loadURDF("plane_transparent2.urdf")
45
p.loadURDF("plane.urdf")
5-
dobot = p.loadURDF("dobot/dobot.urdf",[0,0,0.1], useFixedBase=True)
6+
dobot = p.loadURDF("dobot/dobot.urdf",useFixedBase=True)
67
p.setRealTimeSimulation(1)
8+
p.setPhysicsEngineParameter(numSolverIterations=300)
9+
p.setPhysicsEngineParameter(numSubSteps=10)
10+
711
for i in range (p.getNumJoints(dobot)):
812
print(p.getJointInfo(dobot,i))
913
p.setJointMotorControl2(dobot,i,p.VELOCITY_CONTROL,targetVelocity=0,force=20)
@@ -15,16 +19,38 @@
1519
p.setJointMotorControl2(dobot,3,p.VELOCITY_CONTROL,targetVelocity=0,force=0)
1620
p.setJointMotorControl2(dobot,5,p.VELOCITY_CONTROL,targetVelocity=0,force=0)
1721
p.setJointMotorControl2(dobot,6,p.VELOCITY_CONTROL,targetVelocity=0,force=0)
18-
#p.resetJointState(dobot,4,1.57)
19-
p.resetJointState(dobot,7,-1.57)
20-
p.resetJointState(dobot,8,2.57)
22+
p.setJointMotorControl2(dobot,8,p.VELOCITY_CONTROL,targetVelocity=0,force=0)
2123

24+
p.resetJointState(dobot,6,-1.57)
25+
p.resetJointState(dobot,7,-1.57)
26+
p.resetJointState(dobot,8,1.57)
2227

23-
c = p.createConstraint(dobot,6,dobot,8,jointType=p.JOINT_POINT2POINT,jointAxis =[1,0,0],parentFramePosition=[-0.05,0,0.075],childFramePosition=[-0.05,0.025,-0.0242])
28+
#colors for debugging
29+
#p.changeVisualShape(dobot,4,rgbaColor=[1,1,1,1])
30+
#p.changeVisualShape(dobot,3,rgbaColor=[0,1,0,1])
31+
#p.changeVisualShape(dobot,6,rgbaColor=[0,1,0,1])
32+
#p.changeVisualShape(dobot,5,rgbaColor=[1,1,0,1])
2433

25-
c = p.createConstraint(dobot,3,dobot,5,jointType=p.JOINT_POINT2POINT,jointAxis =[1,0,0],parentFramePosition=[-0.05,0,0.085],childFramePosition=[-0.05,-0.026,0.014])
34+
c = p.createConstraint(dobot,6,dobot,8,jointType=p.JOINT_POINT2POINT,jointAxis =[1,0,0],parentFramePosition=[-0.05,0,0.08],childFramePosition=[-0.05,0.026,-0.006])#0.014-0.02 (inertial com)
2635

36+
c = p.createConstraint(dobot,3,dobot,5,jointType=p.JOINT_POINT2POINT,jointAxis =[1,0,0],parentFramePosition=[-0.05,0,0.075],childFramePosition=[-0.05,-0.026,0.014])
2737

38+
0.150
39+
p.getCameraImage(320,200)#160,100)
40+
p.resetDebugVisualizerCamera(1,85.6,0,[-0.61,0.12,0.25])
41+
p.setJointMotorControl2(dobot,6,p.VELOCITY_CONTROL,targetVelocity=0,force=0)
42+
for i in range (p.getNumJoints(dobot)):
43+
worldLinkFramePosition = p.getLinkState(dobot,i)[4]
44+
worldLinkFrameOrientation = p.getLinkState(dobot,i)[5]
45+
print(i,worldLinkFramePosition)
46+
2847
while (1):
2948
p.setGravity(0,0,0)
30-
p.getCameraImage(320,200)#160,100)
49+
ls = p.getLinkState(dobot,5)
50+
linkOrn = ls[1]
51+
eul = p.getEulerFromQuaternion(linkOrn)
52+
#print(eul)
53+
54+
55+
56+

0 commit comments

Comments
 (0)