-
Notifications
You must be signed in to change notification settings - Fork 215
/
navsatfix.html
80 lines (70 loc) · 2.42 KB
/
navsatfix.html
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
<!DOCTYPE html>
<html>
<head>
<meta charset="utf-8" />
<script src="https://cdn.jsdelivr.net/npm/[email protected]/build/three.min.js"></script>
<script src="https://cdn.jsdelivr.net/npm/[email protected]/dist/eventemitter3.umd.min.js"></script>
<script src="https://cdn.jsdelivr.net/npm/roslib@1/build/roslib.js"></script>
<script src="../build/ros3d.js"></script>
<script>
/**
* Setup all visualization elements when the page is loaded.
*/
function init() {
// Connect to ROS.
var ros = new ROSLIB.Ros({
url : 'ws://localhost:9090'
});
// Create the main viewer.
var viewer = new ROS3D.Viewer({
divID : 'viewer',
width : 800,
height : 600,
antialias : true
});
// Zoom out the camera to see the trajectory
viewer.cameraControls.zoomOut(20);
// Place the cartesian origin near the gps fixes of the kitti rosbag
var lon0 = 8.4320 * Math.PI/180;
var lat0 = 49.0145 * Math.PI/180;
var alt0 = 116;
// Earth radius for the LLA -> ENU approximate conversion (no earth flattening)
var radius = 6378137;
// This object will be translated to the gps position
var geom = new THREE.SphereGeometry( 0.5, 32, 32 );
var material = new THREE.MeshBasicMaterial( {color: 0xffff00} );
var object3d = new THREE.Mesh(geom, material);
// This function converts the longitude/latitude/altitude of the gps fix
// to the cartesian frame of its rootObject
function convert(lon,lat,alt){
lon = lon * Math.PI/180;
lat = lat * Math.PI/180;
return new THREE.Vector3(
(lon-lon0) * radius * Math.cos(lat),
(lat-lat0) * radius,
(alt-alt0)
);
}
var navsatfix = new ROS3D.NavSatFix({
ros: ros,
topic: '/kitti/oxts/gps/fix',
rootObject: viewer.scene,
object3d: object3d,
convert: convert,
material: { color: 0x00ffff, linewidth: 2 },
keep: 50,
});
}
</script>
</head>
<body onload="init()">
<h1><a href="http://www.cvlibs.net/datasets/kitti">Kitti</a> NavSatFix Example</h1>
<p>Run the following commands in the terminal then refresh the page.</p>
<ol>
<li><tt>roslaunch ros3djs.launch</tt></li>
<li><tt>rosparam set use_sim_time true</tt></li>
<li><tt>rosbag play -l --clock <a href="https://github.com/tomas789/kitti2bag">kitti_2011_09_26_drive_0002_synced.bag</a></tt></li>
</ol>
<div id="viewer"></div>
</body>
</html>