forked from RobotWebTools/ros3djs
-
Notifications
You must be signed in to change notification settings - Fork 0
/
ros3d.js
3675 lines (3274 loc) · 113 KB
/
ros3d.js
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
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/**
* @author Russell Toris - rctoris@wpi.edu
* @author David Gossow - dgossow@willowgarage.com
*/
var ROS3D = ROS3D || {
REVISION : '0.13.0-SNAPSHOT'
};
// Marker types
ROS3D.MARKER_ARROW = 0;
ROS3D.MARKER_CUBE = 1;
ROS3D.MARKER_SPHERE = 2;
ROS3D.MARKER_CYLINDER = 3;
ROS3D.MARKER_LINE_STRIP = 4;
ROS3D.MARKER_LINE_LIST = 5;
ROS3D.MARKER_CUBE_LIST = 6;
ROS3D.MARKER_SPHERE_LIST = 7;
ROS3D.MARKER_POINTS = 8;
ROS3D.MARKER_TEXT_VIEW_FACING = 9;
ROS3D.MARKER_MESH_RESOURCE = 10;
ROS3D.MARKER_TRIANGLE_LIST = 11;
// Interactive marker feedback types
ROS3D.INTERACTIVE_MARKER_KEEP_ALIVE = 0;
ROS3D.INTERACTIVE_MARKER_POSE_UPDATE = 1;
ROS3D.INTERACTIVE_MARKER_MENU_SELECT = 2;
ROS3D.INTERACTIVE_MARKER_BUTTON_CLICK = 3;
ROS3D.INTERACTIVE_MARKER_MOUSE_DOWN = 4;
ROS3D.INTERACTIVE_MARKER_MOUSE_UP = 5;
// Interactive marker control types
ROS3D.INTERACTIVE_MARKER_NONE = 0;
ROS3D.INTERACTIVE_MARKER_MENU = 1;
ROS3D.INTERACTIVE_MARKER_BUTTON = 2;
ROS3D.INTERACTIVE_MARKER_MOVE_AXIS = 3;
ROS3D.INTERACTIVE_MARKER_MOVE_PLANE = 4;
ROS3D.INTERACTIVE_MARKER_ROTATE_AXIS = 5;
ROS3D.INTERACTIVE_MARKER_MOVE_ROTATE = 6;
// Interactive marker rotation behavior
ROS3D.INTERACTIVE_MARKER_INHERIT = 0;
ROS3D.INTERACTIVE_MARKER_FIXED = 1;
ROS3D.INTERACTIVE_MARKER_VIEW_FACING = 2;
// Collada loader types
ROS3D.COLLADA_LOADER = 1;
ROS3D.COLLADA_LOADER_2 = 2;
/**
* Create a THREE material based on the given RGBA values.
*
* @param r - the red value
* @param g - the green value
* @param b - the blue value
* @param a - the alpha value
* @returns the THREE material
*/
ROS3D.makeColorMaterial = function(r, g, b, a) {
var color = new THREE.Color();
color.setRGB(r, g, b);
if (a <= 0.99) {
return new THREE.MeshBasicMaterial({
color : color.getHex(),
opacity : a + 0.1,
transparent : true,
depthWrite : true,
blendSrc : THREE.SrcAlphaFactor,
blendDst : THREE.OneMinusSrcAlphaFactor,
blendEquation : THREE.ReverseSubtractEquation,
blending : THREE.NormalBlending
});
} else {
return new THREE.MeshLambertMaterial({
color : color.getHex(),
opacity : a,
blending : THREE.NormalBlending
});
}
};
/**
* Return the intersection between the mouseray and the plane.
*
* @param mouseRay - the mouse ray
* @param planeOrigin - the origin of the plane
* @param planeNormal - the normal of the plane
* @returns the intersection point
*/
ROS3D.intersectPlane = function(mouseRay, planeOrigin, planeNormal) {
var vector = new THREE.Vector3();
var intersectPoint = new THREE.Vector3();
vector.subVectors(planeOrigin, mouseRay.origin);
var dot = mouseRay.direction.dot(planeNormal);
// bail if ray and plane are parallel
if (Math.abs(dot) < mouseRay.precision) {
return undefined;
}
// calc distance to plane
var scalar = planeNormal.dot(vector) / dot;
intersectPoint.addVectors(mouseRay.origin, mouseRay.direction.clone().multiplyScalar(scalar));
return intersectPoint;
};
/**
* Find the closest point on targetRay to any point on mouseRay. Math taken from
* http://paulbourke.net/geometry/lineline3d/
*
* @param targetRay - the target ray to use
* @param mouseRay - the mouse ray
* @param the closest point between the two rays
*/
ROS3D.findClosestPoint = function(targetRay, mouseRay) {
var v13 = new THREE.Vector3();
v13.subVectors(targetRay.origin, mouseRay.origin);
var v43 = mouseRay.direction.clone();
var v21 = targetRay.direction.clone();
var d1343 = v13.dot(v43);
var d4321 = v43.dot(v21);
var d1321 = v13.dot(v21);
var d4343 = v43.dot(v43);
var d2121 = v21.dot(v21);
var denom = d2121 * d4343 - d4321 * d4321;
// check within a delta
if (Math.abs(denom) <= 0.0001) {
return undefined;
}
var numer = d1343 * d4321 - d1321 * d4343;
var mua = numer / denom;
return mua;
};
/**
* Find the closest point between the axis and the mouse.
*
* @param axisRay - the ray from the axis
* @param camera - the camera to project from
* @param mousePos - the mouse position
* @returns the closest axis point
*/
ROS3D.closestAxisPoint = function(axisRay, camera, mousePos) {
var projector = new THREE.Projector();
// project axis onto screen
var o = axisRay.origin.clone();
projector.projectVector(o, camera);
var o2 = axisRay.direction.clone().add(axisRay.origin);
projector.projectVector(o2, camera);
// d is the axis vector in screen space (d = o2-o)
var d = o2.clone().sub(o);
// t is the 2d ray param of perpendicular projection of mousePos onto o
var tmp = new THREE.Vector2();
// (t = (mousePos - o) * d / (d*d))
var t = tmp.subVectors(mousePos, o).dot(d) / d.dot(d);
// mp is the final 2d-projected mouse pos (mp = o + d*t)
var mp = new THREE.Vector2();
mp.addVectors(o, d.clone().multiplyScalar(t));
// go back to 3d by shooting a ray
var vector = new THREE.Vector3(mp.x, mp.y, 0.5);
projector.unprojectVector(vector, camera);
var mpRay = new THREE.Ray(camera.position, vector.sub(camera.position).normalize());
return ROS3D.findClosestPoint(axisRay, mpRay);
};
/**
* @author Julius Kammerl - jkammerl@willowgarage.com
*/
/**
* The DepthCloud object.
*
* @constructor
* @param options - object with following keys:
*
* * url - the URL of the stream
* * f (optional) - the camera's focal length (defaults to standard Kinect calibration)
* * pointSize (optional) - point size (pixels) for rendered point cloud
* * width (optional) - width of the video stream
* * height (optional) - height of the video stream
* * whiteness (optional) - blends rgb values to white (0..100)
* * varianceThreshold (optional) - threshold for variance filter, used for compression artifact removal
*/
ROS3D.DepthCloud = function(options) {
options = options || {};
THREE.Object3D.call(this);
this.url = options.url;
this.f = options.f || 526;
this.pointSize = options.pointSize || 3;
this.width = options.width || 1024;
this.height = options.height || 1024;
this.whiteness = options.whiteness || 0;
this.varianceThreshold = options.varianceThreshold || 0.000016667;
var metaLoaded = false;
this.video = document.createElement('video');
this.video.addEventListener('loadedmetadata', this.metaLoaded.bind(this), false);
this.video.loop = true;
this.video.src = this.url;
this.video.crossOrigin = 'Anonymous';
this.video.setAttribute('crossorigin', 'Anonymous');
// define custom shaders
this.vertex_shader = [
'uniform sampler2D map;',
'',
'uniform float width;',
'uniform float height;',
'uniform float nearClipping, farClipping;',
'',
'uniform float pointSize;',
'uniform float zOffset;',
'',
'uniform float focallength;',
'',
'varying vec2 vUvP;',
'varying vec2 colorP;',
'',
'varying float depthVariance;',
'varying float maskVal;',
'',
'float sampleDepth(vec2 pos)',
' {',
' float depth;',
' ',
' vec2 vUv = vec2( pos.x / (width*2.0), pos.y / (height*2.0)+0.5 );',
' vec2 vUv2 = vec2( pos.x / (width*2.0)+0.5, pos.y / (height*2.0)+0.5 );',
' ',
' vec4 depthColor = texture2D( map, vUv );',
' ',
' depth = ( depthColor.r + depthColor.g + depthColor.b ) / 3.0 ;',
' ',
' if (depth>0.99)',
' {',
' vec4 depthColor2 = texture2D( map, vUv2 );',
' float depth2 = ( depthColor2.r + depthColor2.g + depthColor2.b ) / 3.0 ;',
' depth = 0.99+depth2;',
' }',
' ',
' return depth;',
' }',
'',
'float median(float a, float b, float c)',
' {',
' float r=a;',
' ',
' if ( (a<b) && (b<c) )',
' {',
' r = b;',
' }',
' if ( (a<c) && (c<b) )',
' {',
' r = c;',
' }',
' return r;',
' }',
'',
'float variance(float d1, float d2, float d3, float d4, float d5, float d6, float d7, float d8, float d9)',
' {',
' float mean = (d1 + d2 + d3 + d4 + d5 + d6 + d7 + d8 + d9) / 9.0;',
' float t1 = (d1-mean);',
' float t2 = (d2-mean);',
' float t3 = (d3-mean);',
' float t4 = (d4-mean);',
' float t5 = (d5-mean);',
' float t6 = (d6-mean);',
' float t7 = (d7-mean);',
' float t8 = (d8-mean);',
' float t9 = (d9-mean);',
' float v = (t1*t1+t2*t2+t3*t3+t4*t4+t5*t5+t6*t6+t7*t7+t8*t8+t9*t9)/9.0;',
' return v;',
' }',
'',
'vec2 decodeDepth(vec2 pos)',
' {',
' vec2 ret;',
' ',
' ',
' float depth1 = sampleDepth(vec2(position.x-1.0, position.y-1.0));',
' float depth2 = sampleDepth(vec2(position.x, position.y-1.0));',
' float depth3 = sampleDepth(vec2(position.x+1.0, position.y-1.0));',
' float depth4 = sampleDepth(vec2(position.x-1.0, position.y));',
' float depth5 = sampleDepth(vec2(position.x, position.y));',
' float depth6 = sampleDepth(vec2(position.x+1.0, position.y));',
' float depth7 = sampleDepth(vec2(position.x-1.0, position.y+1.0));',
' float depth8 = sampleDepth(vec2(position.x, position.y+1.0));',
' float depth9 = sampleDepth(vec2(position.x+1.0, position.y+1.0));',
' ',
' float median1 = median(depth1, depth2, depth3);',
' float median2 = median(depth4, depth5, depth6);',
' float median3 = median(depth7, depth8, depth9);',
' ',
' ret.x = median(median1, median2, median3);',
' ret.y = variance(depth1, depth2, depth3, depth4, depth5, depth6, depth7, depth8, depth9);',
' ',
' return ret;',
' ',
' }',
'',
'',
'void main() {',
' ',
' vUvP = vec2( position.x / (width*2.0), position.y / (height*2.0)+0.5 );',
' colorP = vec2( position.x / (width*2.0)+0.5 , position.y / (height*2.0) );',
' ',
' vec4 pos = vec4(0.0,0.0,0.0,0.0);',
' depthVariance = 0.0;',
' ',
' if ( (vUvP.x<0.0)|| (vUvP.x>0.5) || (vUvP.y<0.5) || (vUvP.y>0.0))',
' {',
' vec2 smp = decodeDepth(vec2(position.x, position.y));',
' float depth = smp.x;',
' depthVariance = smp.y;',
' ',
' float z = -depth;',
' ',
' pos = vec4(',
' ( position.x / width - 0.5 ) * z * (1000.0/focallength) * -1.0,',
' ( position.y / height - 0.5 ) * z * (1000.0/focallength),',
' (- z + zOffset / 1000.0) * 2.0,',
' 1.0);',
' ',
' vec2 maskP = vec2( position.x / (width*2.0), position.y / (height*2.0) );',
' vec4 maskColor = texture2D( map, maskP );',
' maskVal = ( maskColor.r + maskColor.g + maskColor.b ) / 3.0 ;',
' }',
' ',
' gl_PointSize = pointSize;',
' gl_Position = projectionMatrix * modelViewMatrix * pos;',
' ',
'}'
].join('\n');
this.fragment_shader = [
'uniform sampler2D map;',
'uniform float varianceThreshold;',
'uniform float whiteness;',
'',
'varying vec2 vUvP;',
'varying vec2 colorP;',
'',
'varying float depthVariance;',
'varying float maskVal;',
'',
'',
'void main() {',
' ',
' vec4 color;',
' ',
' if ( (depthVariance>varianceThreshold) || (maskVal>0.5) ||(vUvP.x<0.0)|| (vUvP.x>0.5) || (vUvP.y<0.5) || (vUvP.y>1.0))',
' { ',
' discard;',
' }',
' else ',
' {',
' color = texture2D( map, colorP );',
' ',
' float fader = whiteness /100.0;',
' ',
' color.r = color.r * (1.0-fader)+ fader;',
' ',
' color.g = color.g * (1.0-fader)+ fader;',
' ',
' color.b = color.b * (1.0-fader)+ fader;',
' ',
' color.a = 1.0;//smoothstep( 20000.0, -20000.0, gl_FragCoord.z / gl_FragCoord.w );',
' }',
' ',
' gl_FragColor = vec4( color.r, color.g, color.b, color.a );',
' ',
'}'
].join('\n');
};
ROS3D.DepthCloud.prototype.__proto__ = THREE.Object3D.prototype;
/**
* Callback called when video metadata is ready
*/
ROS3D.DepthCloud.prototype.metaLoaded = function() {
this.metaLoaded = true;
this.initStreamer();
};
/**
* Callback called when video metadata is ready
*/
ROS3D.DepthCloud.prototype.initStreamer = function() {
if (this.metaLoaded) {
this.texture = new THREE.Texture(this.video);
this.geometry = new THREE.Geometry();
for (var i = 0, l = this.width * this.height; i < l; i++) {
var vertex = new THREE.Vector3();
vertex.x = (i % this.width);
vertex.y = Math.floor(i / this.width);
this.geometry.vertices.push(vertex);
}
this.material = new THREE.ShaderMaterial({
uniforms : {
'map' : {
type : 't',
value : this.texture
},
'width' : {
type : 'f',
value : this.width
},
'height' : {
type : 'f',
value : this.height
},
'focallength' : {
type : 'f',
value : this.f
},
'pointSize' : {
type : 'f',
value : this.pointSize
},
'zOffset' : {
type : 'f',
value : 0
},
'whiteness' : {
type : 'f',
value : this.whiteness
},
'varianceThreshold' : {
type : 'f',
value : this.varianceThreshold
}
},
vertexShader : this.vertex_shader,
fragmentShader : this.fragment_shader
});
this.mesh = new THREE.ParticleSystem(this.geometry, this.material);
this.mesh.position.x = 0;
this.mesh.position.y = 0;
this.add(this.mesh);
var that = this;
setInterval(function() {
if (that.video.readyState === that.video.HAVE_ENOUGH_DATA) {
that.texture.needsUpdate = true;
}
}, 1000 / 30);
}
};
/**
* Start video playback
*/
ROS3D.DepthCloud.prototype.startStream = function() {
this.video.play();
};
/**
* Stop video playback
*/
ROS3D.DepthCloud.prototype.stopStream = function() {
this.video.pause();
};
/**
* @author David Gossow - dgossow@willowgarage.com
*/
/**
* The main interactive marker object.
*
* @constructor
* @param options - object with following keys:
*
* * handle - the ROS3D.InteractiveMarkerHandle for this marker
* * camera - the main camera associated with the viewer for this marker
* * path (optional) - the base path to any meshes that will be loaded
* * loader (optional) - the Collada loader to use (e.g., an instance of ROS3D.COLLADA_LOADER
* ROS3D.COLLADA_LOADER_2) -- defaults to ROS3D.COLLADA_LOADER_2
*/
ROS3D.InteractiveMarker = function(options) {
THREE.Object3D.call(this);
THREE.EventDispatcher.call(this);
var that = this;
options = options || {};
var handle = options.handle;
this.name = handle.name;
var camera = options.camera;
var path = options.path || '/';
var loader = options.loader || ROS3D.COLLADA_LOADER_2;
this.dragging = false;
// set the initial pose
this.onServerSetPose({
pose : handle.pose
});
// information on where the drag started
this.dragStart = {
position : new THREE.Vector3(),
orientation : new THREE.Quaternion(),
positionWorld : new THREE.Vector3(),
orientationWorld : new THREE.Quaternion(),
event3d : {}
};
// add each control message
handle.controls.forEach(function(controlMessage) {
that.add(new ROS3D.InteractiveMarkerControl({
parent : that,
handle : handle,
message : controlMessage,
camera : camera,
path : path,
loader : loader
}));
});
// check for any menus
if (handle.menuEntries.length > 0) {
this.menu = new ROS3D.InteractiveMarkerMenu({
menuEntries : handle.menuEntries,
menuFontSize : handle.menuFontSize
});
// forward menu select events
this.menu.addEventListener('menu-select', function(event) {
that.dispatchEvent(event);
});
}
};
ROS3D.InteractiveMarker.prototype.__proto__ = THREE.Object3D.prototype;
/**
* Show the interactive marker menu associated with this marker.
*
* @param control - the control to use
* @param event - the event that caused this
*/
ROS3D.InteractiveMarker.prototype.showMenu = function(control, event) {
if (this.menu) {
this.menu.show(control, event);
}
};
/**
* Move the axis based on the given event information.
*
* @param control - the control to use
* @param origAxis - the origin of the axis
* @param event3d - the event that caused this
*/
ROS3D.InteractiveMarker.prototype.moveAxis = function(control, origAxis, event3d) {
if (this.dragging) {
var currentControlOri = control.currentControlOri;
var axis = origAxis.clone().applyQuaternion(currentControlOri);
// get move axis in world coords
var originWorld = this.dragStart.event3d.intersection.point;
var axisWorld = axis.clone().applyQuaternion(this.dragStart.orientationWorld.clone());
var axisRay = new THREE.Ray(originWorld, axisWorld);
// find closest point to mouse on axis
var t = ROS3D.closestAxisPoint(axisRay, event3d.camera, event3d.mousePos);
// offset from drag start position
var p = new THREE.Vector3();
p.addVectors(this.dragStart.position, axis.clone().applyQuaternion(this.dragStart.orientation)
.multiplyScalar(t));
this.setPosition(control, p);
event3d.stopPropagation();
}
};
/**
* Move with respect to the plane based on the contorl and event.
*
* @param control - the control to use
* @param origNormal - the normal of the origin
* @param event3d - the event that caused this
*/
ROS3D.InteractiveMarker.prototype.movePlane = function(control, origNormal, event3d) {
if (this.dragging) {
var currentControlOri = control.currentControlOri;
var normal = origNormal.clone().applyQuaternion(currentControlOri);
// get plane params in world coords
var originWorld = this.dragStart.event3d.intersection.point;
var normalWorld = normal.clone().applyQuaternion(this.dragStart.orientationWorld);
// intersect mouse ray with plane
var intersection = ROS3D.intersectPlane(event3d.mouseRay, originWorld, normalWorld);
// offset from drag start position
var p = new THREE.Vector3();
p.subVectors(intersection, originWorld);
p.add(this.dragStart.positionWorld);
this.setPosition(control, p);
event3d.stopPropagation();
}
};
/**
* Rotate based on the control and event given.
*
* @param control - the control to use
* @param origOrientation - the orientation of the origin
* @param event3d - the event that caused this
*/
ROS3D.InteractiveMarker.prototype.rotateAxis = function(control, origOrientation, event3d) {
if (this.dragging) {
control.updateMatrixWorld();
var currentControlOri = control.currentControlOri;
var orientation = currentControlOri.clone().multiply(origOrientation.clone());
var normal = (new THREE.Vector3(1, 0, 0)).applyQuaternion(orientation);
// get plane params in world coords
var originWorld = this.dragStart.event3d.intersection.point;
var normalWorld = normal.applyQuaternion(this.dragStart.orientationWorld);
// intersect mouse ray with plane
var intersection = ROS3D.intersectPlane(event3d.mouseRay, originWorld, normalWorld);
// offset local origin to lie on intersection plane
var normalRay = new THREE.Ray(this.dragStart.positionWorld, normalWorld);
var rotOrigin = ROS3D.intersectPlane(normalRay, originWorld, normalWorld);
// rotates from world to plane coords
var orientationWorld = this.dragStart.orientationWorld.clone().multiply(orientation);
var orientationWorldInv = orientationWorld.clone().inverse();
// rotate original and current intersection into local coords
intersection.sub(rotOrigin);
intersection.applyQuaternion(orientationWorldInv);
var origIntersection = this.dragStart.event3d.intersection.point.clone();
origIntersection.sub(rotOrigin);
origIntersection.applyQuaternion(orientationWorldInv);
// compute relative 2d angle
var a1 = Math.atan2(intersection.y, intersection.z);
var a2 = Math.atan2(origIntersection.y, origIntersection.z);
var a = a2 - a1;
var rot = new THREE.Quaternion();
rot.setFromAxisAngle(normal, a);
// rotate
this.setOrientation(control, rot.multiply(this.dragStart.orientationWorld));
// offset from drag start position
event3d.stopPropagation();
}
};
/**
* Dispatch the given event type.
*
* @param type - the type of event
* @param control - the control to use
*/
ROS3D.InteractiveMarker.prototype.feedbackEvent = function(type, control) {
this.dispatchEvent({
type : type,
position : this.position.clone(),
orientation : this.quaternion.clone(),
controlName : control.name
});
};
/**
* Start a drag action.
*
* @param control - the control to use
* @param event3d - the event that caused this
*/
ROS3D.InteractiveMarker.prototype.startDrag = function(control, event3d) {
if (event3d.domEvent.button === 0) {
event3d.stopPropagation();
this.dragging = true;
this.updateMatrixWorld(true);
var scale = new THREE.Vector3();
this.matrixWorld
.decompose(this.dragStart.positionWorld, this.dragStart.orientationWorld, scale);
this.dragStart.position = this.position.clone();
this.dragStart.orientation = this.quaternion.clone();
this.dragStart.event3d = event3d;
this.feedbackEvent('user-mousedown', control);
}
};
/**
* Stop a drag action.
*
* @param control - the control to use
* @param event3d - the event that caused this
*/
ROS3D.InteractiveMarker.prototype.stopDrag = function(control, event3d) {
if (event3d.domEvent.button === 0) {
event3d.stopPropagation();
this.dragging = false;
this.dragStart.event3d = {};
this.onServerSetPose(this.bufferedPoseEvent);
this.bufferedPoseEvent = undefined;
this.feedbackEvent('user-mouseup', control);
}
};
/**
* Handle a button click.
*
* @param control - the control to use
* @param event3d - the event that caused this
*/
ROS3D.InteractiveMarker.prototype.buttonClick = function(control, event3d) {
event3d.stopPropagation();
this.feedbackEvent('user-button-click', control);
};
/**
* Handle a user pose change for the position.
*
* @param control - the control to use
* @param event3d - the event that caused this
*/
ROS3D.InteractiveMarker.prototype.setPosition = function(control, position) {
this.position = position;
this.feedbackEvent('user-pose-change', control);
};
/**
* Handle a user pose change for the orientation.
*
* @param control - the control to use
* @param event3d - the event that caused this
*/
ROS3D.InteractiveMarker.prototype.setOrientation = function(control, orientation) {
orientation.normalize();
this.quaternion = orientation;
this.feedbackEvent('user-pose-change', control);
};
/**
* Update the marker based when the pose is set from the server.
*
* @param event - the event that caused this
*/
ROS3D.InteractiveMarker.prototype.onServerSetPose = function(event) {
if (event !== undefined) {
// don't update while dragging
if (this.dragging) {
this.bufferedPoseEvent = event;
} else {
var pose = event.pose;
this.position.x = pose.position.x;
this.position.y = pose.position.y;
this.position.z = pose.position.z;
this.quaternion = new THREE.Quaternion(pose.orientation.x, pose.orientation.y,
pose.orientation.z, pose.orientation.w);
this.updateMatrixWorld(true);
}
}
};
THREE.EventDispatcher.prototype.apply( ROS3D.InteractiveMarker.prototype );
/**
* @author David Gossow - dgossow@willowgarage.com
*/
/**
* A client for an interactive marker topic.
*
* @constructor
* @param options - object with following keys:
*
* * ros - a handle to the ROS connection
* * tfClient - a handle to the TF client
* * topic (optional) - the topic to subscribe to, like '/basic_controls'
* * path (optional) - the base path to any meshes that will be loaded
* * camera - the main camera associated with the viewer for this marker client
* * rootObject (optional) - the root THREE 3D object to render to
* * loader (optional) - the Collada loader to use (e.g., an instance of ROS3D.COLLADA_LOADER
* ROS3D.COLLADA_LOADER_2) -- defaults to ROS3D.COLLADA_LOADER_2
* * menuFontSize (optional) - the menu font size
*/
ROS3D.InteractiveMarkerClient = function(options) {
var that = this;
options = options || {};
this.ros = options.ros;
this.tfClient = options.tfClient;
this.topic = options.topic;
this.path = options.path || '/';
this.camera = options.camera;
this.rootObject = options.rootObject || new THREE.Object3D();
this.loader = options.loader || ROS3D.COLLADA_LOADER_2;
this.menuFontSize = options.menuFontSize || '0.8em';
this.interactiveMarkers = {};
this.updateTopic = null;
this.feedbackTopic = null;
// check for an initial topic
if (this.topic) {
this.subscribe(this.topic);
}
};
/**
* Subscribe to the given interactive marker topic. This will unsubscribe from any current topics.
*
* @param topic - the topic to subscribe to, like '/basic_controls'
*/
ROS3D.InteractiveMarkerClient.prototype.subscribe = function(topic) {
// unsubscribe to the other topics
this.unsubscribe();
this.updateTopic = new ROSLIB.Topic({
ros : this.ros,
name : topic + '/tunneled/update',
messageType : 'visualization_msgs/InteractiveMarkerUpdate',
compression : 'png'
});
this.updateTopic.subscribe(this.processUpdate.bind(this));
this.feedbackTopic = new ROSLIB.Topic({
ros : this.ros,
name : topic + '/feedback',
messageType : 'visualization_msgs/InteractiveMarkerFeedback',
compression : 'png'
});
this.feedbackTopic.advertise();
this.initService = new ROSLIB.Service({
ros : this.ros,
name : topic + '/tunneled/get_init',
serviceType : 'demo_interactive_markers/GetInit'
});
var request = new ROSLIB.ServiceRequest({});
this.initService.callService(request, this.processInit.bind(this));
};
/**
* Unsubscribe from the current interactive marker topic.
*/
ROS3D.InteractiveMarkerClient.prototype.unsubscribe = function() {
if (this.updateTopic) {
this.updateTopic.unsubscribe();
}
if (this.feedbackTopic) {
this.feedbackTopic.unadvertise();
}
// erase all markers
for (var intMarkerName in this.interactiveMarkers) {
this.eraseIntMarker(intMarkerName);
}
this.interactiveMarkers = {};
};
/**
* Process the given interactive marker initialization message.
*
* @param initMessage - the interactive marker initialization message to process
*/
ROS3D.InteractiveMarkerClient.prototype.processInit = function(initMessage) {
var message = initMessage.msg;
// erase any old markers
message.erases = [];
for (var intMarkerName in this.interactiveMarkers) {
message.erases.push(intMarkerName);
}
message.poses = [];
// treat it as an update
this.processUpdate(message);
};
/**
* Process the given interactive marker update message.
*
* @param initMessage - the interactive marker update message to process
*/
ROS3D.InteractiveMarkerClient.prototype.processUpdate = function(message) {
var that = this;
// erase any markers
message.erases.forEach(function(name) {
that.eraseIntMarker(name);
});
// updates marker poses
message.poses.forEach(function(poseMessage) {
var marker = that.interactiveMarkers[poseMessage.name];
if (marker) {
marker.setPoseFromServer(poseMessage.pose);
}
});
// add new markers
message.markers.forEach(function(msg) {
// get rid of anything with the same name
var oldhandle = that.interactiveMarkers[msg.name];
if (oldhandle) {
that.eraseIntMarker(oldhandle.name);
}
// create the handle
var handle = new ROS3D.InteractiveMarkerHandle({
message : msg,
feedbackTopic : that.feedbackTopic,
tfClient : that.tfClient,
menuFontSize : that.menuFontSize
});
that.interactiveMarkers[msg.name] = handle;
// create the actual marker
var intMarker = new ROS3D.InteractiveMarker({
handle : handle,
camera : that.camera,
path : that.path,
loader : that.loader
});
// add it to the scene
intMarker.name = msg.name;
that.rootObject.add(intMarker);
// listen for any pose updates from the server
handle.on('pose', function(pose) {
intMarker.onServerSetPose({
pose : pose
});
});
intMarker.addEventListener('user-pose-change', handle.setPoseFromClient.bind(handle));
intMarker.addEventListener('user-mousedown', handle.onMouseDown.bind(handle));
intMarker.addEventListener('user-mouseup', handle.onMouseUp.bind(handle));
intMarker.addEventListener('user-button-click', handle.onButtonClick.bind(handle));
intMarker.addEventListener('menu-select', handle.onMenuSelect.bind(handle));
// now list for any TF changes
handle.subscribeTf();
});
};
/**
* Erase the interactive marker with the given name.
*
* @param intMarkerName - the interactive marker name to delete
*/
ROS3D.InteractiveMarkerClient.prototype.eraseIntMarker = function(intMarkerName) {
if (this.interactiveMarkers[intMarkerName]) {
// remove the object
this.rootObject.remove(this.rootObject.getObjectByName(intMarkerName));
delete this.interactiveMarkers[intMarkerName];
}
};
/**
* @author David Gossow - dgossow@willowgarage.com
*/
/**
* The main marker control object for an interactive marker.
*
* @constructor
* @param options - object with following keys:
*
* * parent - the parent of this control
* * message - the interactive marker control message
* * camera - the main camera associated with the viewer for this marker client
* * path (optional) - the base path to any meshes that will be loaded
* * loader (optional) - the Collada loader to use (e.g., an instance of ROS3D.COLLADA_LOADER
* ROS3D.COLLADA_LOADER_2) -- defaults to ROS3D.COLLADA_LOADER_2