-
Notifications
You must be signed in to change notification settings - Fork 22
/
pendularm1.html
350 lines (271 loc) · 11.7 KB
/
pendularm1.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
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
<!--|\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/|
|\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/|
||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/
/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\
Pendularm 1 simulation
Simple 1 DOF pendulum dynamics and control in HTML5/JavaScript and threejs
@author ohseejay / https://github.com/ohseejay
/ https://bitbucket.org/ohseejay
Chad Jenkins
Laboratory for Perception RObotics and Grounded REasoning Systems
University of Michigan
License: Michigan Honor License
|\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/|
||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/
/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\
\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\/||\-->
<html>
<body>
<!-- //////////////////////////////////////////////////
///// JAVASCRIPT INCLUDES
////////////////////////////////////////////////// -->
<!-- threejs - https://github.com/mrdoob/three.js/ -->
<script src="js/three.min.js"></script>
<!-- threejs camera controls helpers -->
<script src="js/OrbitControls.js"></script>
<!-- threejs keyboard input helper -->
<script src="js/THREEx.KeyboardState.js"></script>
<!-- functions to be implemented -->
<script src="update_pendulum_state.js"></script>
<script>
//////////////////////////////////////////////////
///// MAIN FUNCTION CALLS
//////////////////////////////////////////////////
// initialize threejs scene, user input, and robot kinematics
init();
// main animation loop maintained by threejs
animate();
//////////////////////////////////////////////////
///// INITIALIZATION FUNCTION DEFINITONS
//////////////////////////////////////////////////
function init() {
// create pendulum object and its kinematic and dynamic parameters
pendulum = {length:2.0, mass:2.0, angle:Math.PI/2, angle_dot:0.0, angle_previous:0.0};
// initialize pendulum controls
pendulum.control = 0;
pendulum.desired = -Math.PI/2.5;
// initialize integral term accumulated error to zero
accumulated_error = 0;
// set gravity
gravity = 9.81; // Earth gravity
// initialize pendulum PID servo gains
pendulum = set_PID_parameters(pendulum)
// initialize time and set timestep
t = 0;
dt = 0.05; // default
// initialize method of numerical integration of dynamics
numerical_integrator = "none";
//numerical_integrator = "euler";
//numerical_integrator = "verlet";
//numerical_integrator = "velocity verlet";
//numerical_integrator = "runge-kutta";
// OPTIONAL servo controller additional features
steady_state_error_reset = false; // integral term resets after desired met
servo_error_threshold = 0.001; // threshold for achieving desired
servo_active_persist = false; // toggle to turn on servo controller
servo_active_state = {}; // string with current state of servo activation
//STENCIL: for verlet integration, a first step in time is needed
if (typeof numerical_integrator !== "undefined") {
if (numerical_integrator === "verlet") {
var result = init_verlet_integrator(pendulum, t, gravity);
pendulum = result[0]; t = result[1];
}
}
document.addEventListener('keydown', function(e) {
if (e.keyCode == 88) // 'x' == 88
servo_active_persist = !servo_active_persist;
}, true);
// initialize rendering scene and user interface
createScene();
}
//////////////////////////////////////////////////
///// ANIMATION AND INTERACTION LOOP
//////////////////////////////////////////////////
function animate() {
// note: three.js includes requestAnimationFrame shim
// alternative to using setInterval for updating in-browser drawing
// this effectively request that the animate function be called again for next draw
// http://learningwebgl.com/blog/?p=3189
requestAnimationFrame( animate );
// switch between numerical integrators based on user input
if (keyboard.pressed("0"))
numerical_integrator = "none";
if (keyboard.pressed("1"))
numerical_integrator = "euler";
if (keyboard.pressed("2"))
numerical_integrator = "verlet";
if (keyboard.pressed("3"))
numerical_integrator = "velocity verlet";
if (keyboard.pressed("4"))
numerical_integrator = "runge-kutta";
// zero the controls for the current time step
pendulum.control = 0;
// update servo desired state from user interaction
if ( keyboard.pressed("e") )
pendulum.desired += 0.05; // move the desired angle for the servo
if ( keyboard.pressed("q") )
pendulum.desired += -0.05; // move the desired angle for the servo
// add user force from user interaction
if ( keyboard.pressed("d") )
pendulum.control += 50.0; // add a motor force to the pendulum motor
else if ( keyboard.pressed("a") )
pendulum.control += -50.0; // add a motor force to the pendulum motor
// STENCIL: implement servo controller
var result = PID(pendulum, accumulated_error, dt);
pendulum = result[0]; accumulated_error = result[1];
// toggle activation of servo controller from user interaction
if (keyboard.pressed("c"))
servo_active_persist = !servo_active_persist;
// disable motor from user interaction
if (keyboard.pressed("s")||!servo_active_persist) {
pendulum.control = 0;
accumulated_error = 0;
servo_active_state = "disabled";
}
else
servo_active_state = "active";
pendulum.angle_dot_dot = pendulum_acceleration(pendulum, gravity);
pendulum = update_pendulum_state(numerical_integrator, pendulum, dt, gravity);
// set the angles of the pendulum
pendulum.geom.rotation.y = pendulum.angle; // threejs cylinders have their axes along the y-axis
// advance time
t = t + dt;
textbar.innerHTML =
"System <br> " +
" t = " + t.toFixed(2) +
" dt = " + dt.toFixed(2) +
"<br>" +
" integrator = " + numerical_integrator +
"<br>" +
" x = " + pendulum.angle.toFixed(2) +
"<br>" +
" x_dot = " + pendulum.angle_dot.toFixed(2) +
"<br>" +
" x_desired = " + pendulum.desired.toFixed(2) +
"<br><br> Servo: " + servo_active_state + " <br> " +
" u = " + pendulum.control.toFixed(2) +
"<br>" +
" kp = " + pendulum.servo.kp.toFixed(2) +
"<br>" +
" kd = " + pendulum.servo.kd.toFixed(2) +
"<br>" +
" ki = " + pendulum.servo.ki.toFixed(2) +
"<br><br> Pendulum <br> " +
" mass = " + pendulum.mass.toFixed(2) +
"<br>" +
" length = " + pendulum.length.toFixed(2) +
"<br>" +
" gravity = " + gravity.toFixed(2) +
"<br><br> Keys <br> " +
" [0-4] - select integrator " +
"<br>" +
" a/d - apply user force " +
"<br>" +
" q/e - adjust desired angle " +
"<br>" +
" c|x - toggle servo " +
"<br>" +
" s - disable servo "
;
// threejs rendering update
renderer.render( scene, camera );
}
function createScene() {
// instantiate threejs scene graph
scene = new THREE.Scene();
// instantiate threejs camera and set its position in the world
camera = new THREE.PerspectiveCamera( 75, window.innerWidth / window.innerHeight, 1, 10000 );
camera.position.y = 1;
camera.position.z = 4;
var light1 = new THREE.PointLight( 0xffffff, 0.3, 1000 );
light1.position.set( 10, 10, 10 );
scene.add( light1 );
var light2 = new THREE.PointLight( 0xffffff, 0.3, 1000 );
light2.position.set( 10, -10, 10 );
scene.add( light2 );
var light3 = new THREE.PointLight( 0xffffff, 0.3, 1000 );
light3.position.set( -10, -10, 10 );
scene.add( light3 );
var light4 = new THREE.PointLight( 0xffffff, 0.3, 1000 );
light4.position.set( -10, 10, 10 );
scene.add( light4 );
// instantiate threejs renderer and its dimensions
renderer = new THREE.WebGLRenderer();
renderer.setSize( window.innerWidth, window.innerHeight );
// attach threejs renderer to DOM
document.body.appendChild( renderer.domElement );
// instantiate threejs camera controls
camera_controls = new THREE.OrbitControls( camera );
camera_controls.addEventListener( 'change', renderer );
// instantiate threejs keyboard controls, for continuous interactive controls
keyboard = new THREEx.KeyboardState();
textbar = document.createElement('div');
textbar.style.position = 'absolute';
//textbar.style.zIndex = 1; // if you still don't see the label, try uncommenting this
textbar.style.width = window.width-10;
textbar.style["font-family"] = "Monospace";
textbar.style.height = 20;
//textbar.style.backgroundColor = "black";
textbar.style.color = "#000000";
textbar.innerHTML = "M4PRoGReS - pendularm!";
textbar.style.top = 10 + 'px';
textbar.style.left = 10 + 'px';
document.body.appendChild(textbar);
temp_geom = new THREE.CylinderGeometry(0.2, 0.2, 3.5, 20, 20, false);
temp_material = new THREE.MeshLambertMaterial( { } );
temp_material.color.r = 1;
temp_material.color.g = 1;
temp_material.color.b = 1;
temp_material.color.b = 1;
temp_material.transparent = true;
temp_material.opacity = 0.3;
leg1 = new THREE.Mesh(temp_geom, temp_material);
leg2 = new THREE.Mesh(temp_geom, temp_material);
leg3 = new THREE.Mesh(temp_geom, temp_material);
leg4 = new THREE.Mesh(temp_geom, temp_material);
leg1.position = {x:2,z:1,y:0};
leg2.position = {x:-2,z:1,y:0};
leg3.position = {x:-2,z:-1,y:0};
leg4.position = {x:2,z:-1,y:0};
scene.add(leg1);
scene.add(leg2);
scene.add(leg3);
scene.add(leg4);
temp_geom = new THREE.CylinderGeometry(0.2, 0.2, 4.0, 20, 20, false);
sidebar1 = new THREE.Mesh(temp_geom, temp_material);
sidebar1.rotateOnAxis(new THREE.Vector3(0,0,1),Math.PI/2);
sidebar1.position = {x:-2,z:0,y:1.5};
leg1.add(sidebar1);
sidebar2 = new THREE.Mesh(temp_geom, temp_material);
sidebar2.rotateOnAxis(new THREE.Vector3(0,0,1),Math.PI/2);
sidebar2.position = {x:2,z:0,y:1.5};
leg3.add(sidebar2);
temp_geom = new THREE.CylinderGeometry(0.2, 0.2, 2.0, 20, 20, false);
crossbar = new THREE.Mesh(temp_geom, temp_material);
crossbar.rotateOnAxis(new THREE.Vector3(1,0,0),Math.PI/2);
crossbar.position = {x:0,z:-1,y:0};
sidebar1.add(crossbar);
temp_geom = new THREE.CylinderGeometry(0.3, 0.3, 0.3, 20, 20, false);
temp_material = new THREE.MeshLambertMaterial( { } );
temp_material.color.r = 1;
temp_material.color.g = 0;
temp_material.color.b = 0;
temp_material.transparent = false;
pendulum.geom = new THREE.Mesh(temp_geom, temp_material);
pendulum.geom.rotateOnAxis(new THREE.Vector3(1,0,0),Math.PI/2);
//crossbar.add(pendulum.geom);
scene.add(pendulum.geom);
pendulum.geom.position = {x:0,y:1.5,z:0};
temp_geom = new THREE.CylinderGeometry(0.2, 0.2, pendulum.length, 20, 20, false);
pendulum_link = new THREE.Mesh(temp_geom, temp_material);
pendulum_link.rotateOnAxis(new THREE.Vector3(1,0,0),-Math.PI/2);
pendulum_link.position = {x:0,z:pendulum.length/2,y:0};
pendulum.geom.add(pendulum_link);
temp_geom = new THREE.SphereGeometry(Math.sqrt(pendulum.mass*0.1));
pendulum_mass = new THREE.Mesh(temp_geom, temp_material);
pendulum_mass.position = {x:0,y:-pendulum.length/2,z:0};
pendulum_link.add(pendulum_mass);
}
</script>
</body>
</html>