summaryrefslogtreecommitdiff
path: root/examples/pybullet/examples/saveRestoreState.py
blob: dd10075279b72fca828e9a87bfa2d368a982e7d1 (plain)
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
126
127
128
129
130
131
132
133
import pybullet as p
import math, time
import difflib,sys

numSteps = 500
numSteps2 = 30
p.connect(p.GUI, options="--width=1024 --height=768")
numObjects = 50
verbose = 0

logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "saveRestoreTimings.log")

def setupWorld():
	p.resetSimulation()
	p.setPhysicsEngineParameter(deterministicOverlappingPairs=1)
	p.loadURDF("planeMesh.urdf")
	kukaId = p.loadURDF("kuka_iiwa/model_free_base.urdf",[0,0,10])
	for i in range (p.getNumJoints(kukaId)):
		p.setJointMotorControl2(kukaId,i,p.POSITION_CONTROL,force=0)
	for i in range (numObjects):
		cube = p.loadURDF("cube_small.urdf",[0,i*0.02,(i+1)*0.2])
		#p.changeDynamics(cube,-1,mass=100)
	p.stepSimulation()
	p.setGravity(0,0,-10)


def dumpStateToFile(file):
	for i in  range (p.getNumBodies()):
		pos,orn = p.getBasePositionAndOrientation(i)
		linVel,angVel = p.getBaseVelocity(i)
		txtPos = "pos="+str(pos)+"\n"
		txtOrn = "orn="+str(orn)+"\n"
		txtLinVel = "linVel"+str(linVel)+"\n"
		txtAngVel = "angVel"+str(angVel)+"\n"
		file.write(txtPos)
		file.write(txtOrn)
		file.write(txtLinVel)
		file.write(txtAngVel)
		
def compareFiles(file1,file2):
	diff = difflib.unified_diff(
            file1.readlines(),
            file2.readlines(),
            fromfile='saveFile.txt',
            tofile='restoreFile.txt',
        )
	numDifferences = 0
	for line in diff:
		numDifferences = numDifferences+1
		sys.stdout.write(line)
	if (numDifferences>0):
		print("Error:", numDifferences, " lines are different between files.")
	else:
		print("OK, files are identical")
	
setupWorld()
for i in range (numSteps):
	p.stepSimulation()	
p.saveBullet("state.bullet")
if verbose:
	p.setInternalSimFlags(1)
p.stepSimulation()
if verbose:
	p.setInternalSimFlags(0)
	print("contact points=")
	for q in p.getContactPoints():
		print(q)

for i in range (numSteps2):
	p.stepSimulation()


file = open("saveFile.txt","w") 
dumpStateToFile(file)
file.close() 

#################################
setupWorld()

#both restore from file or from in-memory state should work
p.restoreState(fileName="state.bullet")
stateId = p.saveState()

if verbose:
	p.setInternalSimFlags(1)
p.stepSimulation()
if verbose:
	p.setInternalSimFlags(0)
	print("contact points restored=")
	for q in p.getContactPoints():
		print(q)
for i in range (numSteps2):
	p.stepSimulation()

	
file = open("restoreFile.txt","w")
dumpStateToFile(file)
file.close() 

p.restoreState(stateId)
if verbose:
	p.setInternalSimFlags(1)
p.stepSimulation()
if verbose:
	p.setInternalSimFlags(0)
	print("contact points restored=")
	for q in p.getContactPoints():
		print(q)
for i in range (numSteps2):
	p.stepSimulation()

	
file = open("restoreFile2.txt","w")
dumpStateToFile(file)
file.close() 

file1 = open("saveFile.txt","r") 
file2 = open("restoreFile.txt","r") 
compareFiles(file1,file2)
file1.close()
file2.close()

file1 = open("saveFile.txt","r") 
file2 = open("restoreFile2.txt","r") 
compareFiles(file1,file2)
file1.close()
file2.close()        

p.stopStateLogging(logId)

#while (p.getConnectionInfo()["isConnected"]):
#	time.sleep(1)