Hot-keys on this page

r m x p   toggle line displays

j k   next/prev highlighted chunk

0   (zero) top of page

1   (one) first highlighted chunk

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

198

199

200

from director import imageview 

from director import vtkAll as vtk 

from director import transformUtils 

from director import visualization as vis 

from director import viewbehaviors 

from director import vtkNumpy as vnp 

from director.debugVis import DebugData 

from director.timercallback import TimerCallback 

import PythonQt 

import numpy as np 

 

 

def computeDepthImageAndPointCloud(depthBuffer, colorBuffer, camera): 

    ''' 

    Input args are an OpenGL depth buffer and color buffer as vtkImageData objects, 

    and the vtkCamera instance that was used to render the scene.  The function returns 

    returns a depth image and a point cloud as vtkImageData and vtkPolyData. 

    ''' 

    depthImage = vtk.vtkImageData() 

    pts = vtk.vtkPoints() 

    ptColors = vtk.vtkUnsignedCharArray() 

    vtk.vtkDepthImageUtils.DepthBufferToDepthImage(depthBuffer, colorBuffer, camera, depthImage, pts, ptColors) 

 

    pts = vnp.numpy_support.vtk_to_numpy(pts.GetData()) 

    polyData = vnp.numpyToPolyData(pts, createVertexCells=True) 

    ptColors.SetName('rgb') 

    polyData.GetPointData().AddArray(ptColors) 

 

    return depthImage, polyData 

 

 

class DepthScanner(object): 

 

    def __init__(self, view): 

        self.view = view 

 

        self.depthImage = None 

        self.pointCloudObj = None 

        self.renderObserver = None 

 

        self.windowToDepthBuffer = vtk.vtkWindowToImageFilter() 

        self.windowToDepthBuffer.SetInput(self.view.renderWindow()) 

        self.windowToDepthBuffer.SetInputBufferTypeToZBuffer() 

        self.windowToDepthBuffer.ShouldRerenderOff() 

 

        self.windowToColorBuffer = vtk.vtkWindowToImageFilter() 

        self.windowToColorBuffer.SetInput(self.view.renderWindow()) 

        self.windowToColorBuffer.SetInputBufferTypeToRGB() 

        self.windowToColorBuffer.ShouldRerenderOff() 

 

        useBackBuffer = False 

        if useBackBuffer: 

            self.windowToDepthBuffer.ReadFrontBufferOff() 

            self.windowToColorBuffer.ReadFrontBufferOff() 

 

        self.initDepthImageView() 

        self.initPointCloudView() 

 

        self._block = False 

        self.singleShotTimer = TimerCallback() 

        self.singleShotTimer.callback = self.update 

 

    def getDepthBufferImage(self): 

        return self.windowToDepthBuffer.GetOutput() 

 

    def getDepthImage(self): 

        return self.depthScaleFilter.GetOutput() 

 

    def getColorBufferImage(self): 

        return self.windowToColorBuffer.GetOutput() 

 

    def updateBufferImages(self): 

        for f in [self.windowToDepthBuffer, self.windowToColorBuffer]: 

            f.Modified() 

            f.Update() 

 

    def initDepthImageView(self): 

 

        self.depthImageColorByRange = [0.0, 4.0] 

 

        lut = vtk.vtkLookupTable() 

        lut.SetNumberOfColors(256) 

        lut.SetHueRange(0, 0.667) # red to blue 

        lut.SetRange(self.depthImageColorByRange) # map red (near) to blue (far) 

        lut.SetRampToLinear() 

        lut.Build() 

 

        self.depthScaleFilter = vtk.vtkImageShiftScale() 

        self.depthScaleFilter.SetScale(1000) 

        self.depthScaleFilter.SetOutputScalarTypeToUnsignedShort() 

 

        self.depthImageLookupTable = lut 

        self.imageMapToColors = vtk.vtkImageMapToColors() 

        self.imageMapToColors.SetLookupTable(self.depthImageLookupTable) 

        self.imageMapToColors.SetInputConnection(self.depthScaleFilter.GetOutputPort()) 

 

        self.imageView = imageview.ImageView() 

        self.imageView.view.setWindowTitle('Depth image') 

        self.imageView.setImage(self.imageMapToColors.GetOutput()) 

 

    def initPointCloudView(self): 

        self.pointCloudView = PythonQt.dd.ddQVTKWidgetView() 

        self.pointCloudView.setWindowTitle('Pointcloud') 

        self.pointCloudViewBehaviors = viewbehaviors.ViewBehaviors(self.pointCloudView) 

 

    def update(self): 

 

        if not self.renderObserver: 

            def onEndRender(obj, event): 

                if self._block: 

                    return 

                if not self.singleShotTimer.singleShotTimer.isActive(): 

                    self.singleShotTimer.singleShot(0) 

            self.renderObserver = self.view.renderWindow().AddObserver('EndEvent', onEndRender) 

 

        self._block = True 

        self.view.forceRender() 

        self.updateBufferImages() 

        self._block = False 

 

        depthImage, polyData = computeDepthImageAndPointCloud(self.getDepthBufferImage(), self.getColorBufferImage(), self.view.camera()) 

 

        self.depthScaleFilter.SetInput(depthImage) 

        self.depthScaleFilter.Update() 

 

        self.depthImageLookupTable.SetRange(self.depthScaleFilter.GetOutput().GetScalarRange()) 

        self.imageMapToColors.Update() 

        self.imageView.resetCamera() 

        #self.imageView.view.render() 

 

        if not self.pointCloudObj: 

            self.pointCloudObj = vis.showPolyData(polyData, 'point cloud', colorByName='rgb', view=self.pointCloudView) 

        else: 

            self.pointCloudObj.setPolyData(polyData) 

        self.pointCloudView.render() 

 

 

 

def main(globalsDict=None): 

 

    from director import mainwindowapp 

    from PythonQt import QtCore, QtGui 

 

    app = mainwindowapp.construct() 

    app.gridObj.setProperty('Visible', True) 

    app.viewOptions.setProperty('Orientation widget', False) 

    app.viewOptions.setProperty('View angle', 30) 

    app.sceneBrowserDock.setVisible(False) 

    app.propertiesDock.setVisible(False) 

    app.mainWindow.setWindowTitle('Depth Scanner') 

    app.mainWindow.show() 

    app.mainWindow.resize(920,600) 

    app.mainWindow.move(0,0) 

 

    view = app.view 

    view.setParent(None) 

    mdiArea = QtGui.QMdiArea() 

    app.mainWindow.setCentralWidget(mdiArea) 

    subWindow = mdiArea.addSubWindow(view) 

    subWindow.setMinimumSize(300,300) 

    subWindow.setWindowTitle('Camera image') 

    subWindow.resize(640, 480) 

    mdiArea.tileSubWindows() 

 

    #affordanceManager = affordancemanager.AffordanceObjectModelManager(view) 

 

    depthScanner = DepthScanner(view) 

    depthScanner.update() 

 

    dock = app.app.addWidgetToDock(depthScanner.imageView.view, QtCore.Qt.RightDockWidgetArea) 

    dock.setMinimumWidth(300) 

    dock.setMinimumHeight(300) 

 

    dock = app.app.addWidgetToDock(depthScanner.pointCloudView, QtCore.Qt.RightDockWidgetArea) 

    dock.setMinimumWidth(300) 

    dock.setMinimumHeight(300) 

 

 

    # add some test data 

    def addTestData(): 

        d = DebugData() 

        d.addArrow((0,0,0), (0,0,1), color=[1,0,0]) 

        d.addArrow((0,0,1), (0,.5,1), color=[0,1,0]) 

        vis.showPolyData(d.getPolyData(), 'debug data', colorByName='RGB255') 

        view.resetCamera() 

 

    addTestData() 

 

    # xvfb command 

    # /usr/bin/Xvfb  :99 -ac -screen 0 1280x1024x16 

 

    if globalsDict is not None: 

        globalsDict.update(dict(app=app, view=view, depthScanner=depthScanner)) 

 

    app.app.start(restoreWindow=False) 

 

 

 

if __name__ == '__main__': 

    main(globals())