-
Notifications
You must be signed in to change notification settings - Fork 153
/
render_physics.py
197 lines (158 loc) · 7.33 KB
/
render_physics.py
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
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
## Issue related to time resolution/smoothness
# http://bulletphysics.org/mediawiki-1.5.8/index.php/Stepping_The_World
import pybullet as p
import time
import random
import zmq
import argparse
import os
import json
import numpy as np
import settings
from transforms3d import euler, quaternions
from realenv.core.physics.physics_object import PhysicsObject
from realenv.core.render.profiler import Profiler
from numpy import sin, cos
class PhysRenderer(object):
def __init__(self, obj_path, framePerSec, debug, human):
context = zmq.Context()
self.visn_socket = context.socket(zmq.REQ)
self.visn_socket.bind("tcp://*:5556")
self.debug_sliders = {}
if debug:
p.connect(p.GUI)
p.configureDebugVisualizer(p.COV_ENABLE_KEYBOARD_SHORTCUTS, 0)
self._startDebugRoomMap()
else:
# Headless training mode
p.connect(p.DIRECT)
p.setRealTimeSimulation(0)
collisionId = p.createCollisionShape(p.GEOM_MESH, fileName=obj_path, meshScale=[1, 1, 1], flags=p.GEOM_FORCE_CONCAVE_TRIMESH)
if debug:
visualId = p.createVisualShape(p.GEOM_MESH, fileName=obj_path, meshScale=[1, 1, 1], rgbaColor = [1, 0.2, 0.2, 0.3], specularColor=[0.4, 4.0])
boundaryUid = p.createMultiBody(baseCollisionShapeIndex = collisionId, baseVisualShapeIndex = visualId)
print("Exterior boundary", boundaryUid)
p.changeVisualShape(boundaryUid, -1, rgbaColor=[1, 0.2, 0.2, 0.3], specularColor=[1, 1, 1])
#p.changeVisualShape(visualId, -1, rgbaColor=[1, 0.2, 0.2, 0.3])
else:
visualId = 0
#p.setGravity(0,0,-10)
p.setRealTimeSimulation(0)
self.framePerSec = framePerSec
file_dir = os.path.dirname(os.path.abspath(__file__))
self.objectUid = p.loadURDF(os.path.join(file_dir, "models/quadrotor.urdf"), globalScaling = 0.8)
#self.objectUid = p.loadURDF(os.path.join(file_dir, "models/husky.urdf"), globalScaling = 0.8)
self.viewMatrix = p.computeViewMatrixFromYawPitchRoll([0, 0, 0], 10, 0, 90, 0, 2)
self.projMatrix = p.computeProjectionMatrix(-0.01, 0.01, -0.01, 0.01, 0.01, 128)
p.getCameraImage(256, 256, viewMatrix = self.viewMatrix, projectionMatrix = self.projMatrix)
self.target_pos = np.array([-4.35, -1.71, 0.8])
self.human = human
def initialize(self, pose):
pos, quat_xyzw = pose[0], pose[1]
v_t = 1 # 1m/s max speed
v_r = np.pi/5 # 36 degrees/s
self.cart = PhysicsObject(self.objectUid, p, pos, quat_xyzw, v_t, v_r, self.framePerSec)
print("Generated cart", self.objectUid)
#p.setTimeStep(1.0/framePerSec)
p.setTimeStep(1.0/settings.STEPS_PER_SEC)
def _camera_init_orientation(self, quat):
to_z_facing = euler.euler2quat(np.pi/2, np.pi, 0)
return quaternions.qmult(to_z_facing, quat_wxyz)
def _setPosViewOrientation(objectUid, pos, rot):
return
def _sendPoseToViewPort(self, pose):
self.visn_socket.send_string(json.dumps(pose))
self.visn_socket.recv()
def _getInitialPositionOrientation(self):
print("waiting to receive initial")
self.visn_socket.send_string("Initial")
pos, quat = json.loads(self.visn_socket.recv().decode("utf-8"))
print("received initial", pos, quat)
return pos, quat
def _stepNsteps(self, N, pObject):
for _ in range(N):
p.stepSimulation()
pObject.parseActionAndUpdate()
pObject.clearUpDelta()
def _startDebugRoomMap(self):
cameraDistSlider = p.addUserDebugParameter("Distance",0,15,4)
cameraYawSlider = p.addUserDebugParameter("Camera Yaw",-180,180,-45)
cameraPitchSlider = p.addUserDebugParameter("Camera Pitch",-90,90,-30)
self.debug_sliders = {
'dist' :cameraDistSlider,
'yaw' : cameraYawSlider,
'pitch': cameraPitchSlider
}
def renderOffScreen(self, action, restart=False):
## Execute one frame
#print("physics engine get action", action)
self.cart.parseActionAndUpdate(action)
self._stepNsteps(int(settings.STEPS_PER_SEC/self.framePerSec), self.cart)
pos_xyz, quat_wxyz = self.cart.getViewPosAndOrientation()
state = {
'distance_to_target': np.sum(np.square(pos_xyz - self.target_pos))
}
return [pos_xyz, quat_wxyz], state
def renderToScreen(self, action, restart=False):
if self.human:
self.cart.getUpdateFromKeyboard(restart=restart)
else:
self.cart.parseActionAndUpdate(action)
self._stepNsteps(int(settings.STEPS_PER_SEC/self.framePerSec), self.cart)
pos_xyz, quat_wxyz = self.cart.getViewPosAndOrientation()
cameraDist = p.readUserDebugParameter(self.debug_sliders['dist'])
cameraYaw = p.readUserDebugParameter(self.debug_sliders['yaw'])
cameraPitch = p.readUserDebugParameter(self.debug_sliders['pitch'])
p.getCameraImage(256, 256, viewMatrix = self.viewMatrix, projectionMatrix = self.projMatrix)
p.resetDebugVisualizerCamera(cameraDist, cameraYaw, cameraPitch, pos_xyz)
state = {
'distance_to_target': np.sum(np.square(pos_xyz - self.target_pos))
}
return [pos_xyz, quat_wxyz], state
## DEPRECATED
def _getCollisionFromUpdate(self):
message = self.visn_socket.recv().decode("utf-8")
x, y, z, r_w, r_x, r_y, r_z = map(float, message.split())
p.resetBasePositionAndOrientation(self.objectUid, [x, y, z], [r_w, r_x, r_y, r_z])
p.stepSimulation()
print("step simulation done")
collisions = p.getContactPoints(boundaryUid, self.objectUid)
if len(collisions) == 0:
print("No collisions")
else:
print("Collisions!")
print("collision length", len(collisions))
self.visn_socket.send_string(str(len(collisions)))
return
## DEPRECATED
def _synchronizeWithViewPort(self):
#step
view_pose = json.loads(self.visn_socket.recv().decode("utf-8"))
changed = view_pose['changed']
## Always send pose from last frame
pos, rot = p.getBasePositionAndOrientation(self.objectUid)
print("receiving changed ?", changed)
print("receiving from view", view_pose['pos'])
print("original view posit", pos)
print("receiving from view", view_pose['quat'])
print("original view posit", rot)
if changed:
## Apply the changes
new_pos = view_pose['pos']
new_quat = view_pose['quat']
#new_quat = [0, 0, 0, 1]
p.resetBasePositionAndOrientation(self.objectUid, new_pos, new_quat)
p.stepSimulation()
pos, rot = p.getBasePositionAndOrientation(self.objectUid)
print("after applying pose", pos)
print("")
#print(changed, pos, rot)
self.visn_socket.send_string(json.dumps([pos, rot]))
if __name__ == '__main__':
parser = argparse.ArgumentParser()
parser.add_argument('--objpath' , required = True, help='dataset path')
opt = parser.parse_args()
framePerSec = 13
r_physics = PhysRenderer(opt.objpath, framePerSec)
r_physics.initialize(pose_init)
r_physics.renderToScreen()