/
tutorialMultiPendulum.cpp
399 lines (336 loc) · 11.5 KB
/
tutorialMultiPendulum.cpp
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
/*
* Copyright (c) 2015, Georgia Tech Research Corporation
* All rights reserved.
*
* Author(s): Michael X. Grey <mxgrey@gatech.edu>
*
* Georgia Tech Graphics Lab and Humanoid Robotics Lab
*
* Directed by Prof. C. Karen Liu and Prof. Mike Stilman
* <karenliu@cc.gatech.edu> <mstilman@cc.gatech.edu>
*
* This file is provided under the following "BSD-style" License:
* Redistribution and use in source and binary forms, with or
* without modification, are permitted provided that the following
* conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
* USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#include "kido/kido.hpp"
#include "kido/gui/gui.hpp"
const double default_height = 1.0; // m
const double default_width = 0.2; // m
const double default_depth = 0.2; // m
const double default_torque = 15.0; // N-m
const double default_force = 15.0; // N
const int default_countdown = 200; // Number of timesteps for applying force
const double default_rest_position = 0.0;
const double delta_rest_position = 10.0 * M_PI / 180.0;
const double default_stiffness = 0.0;
const double delta_stiffness = 10;
const double default_damping = 5.0;
const double delta_damping = 1.0;
using namespace kido::dynamics;
using namespace kido::simulation;
class MyWindow : public kido::gui::SimWindow
{
public:
/// Constructor
MyWindow(WorldPtr world)
: mBallConstraint(nullptr),
mPositiveSign(true),
mBodyForce(false)
{
setWorld(world);
// Find the Skeleton named "pendulum" within the World
mPendulum = world->getSkeleton("pendulum");
// Make sure that the pendulum was found in the World
assert(mPendulum != nullptr);
mForceCountDown.resize(mPendulum->getNumDofs(), 0);
ArrowShape::Properties arrow_properties;
arrow_properties.mRadius = 0.05;
mArrow = std::shared_ptr<ArrowShape>(new ArrowShape(
Eigen::Vector3d(-default_height, 0.0, default_height / 2.0),
Eigen::Vector3d(-default_width / 2.0, 0.0, default_height / 2.0),
arrow_properties, kido::Color::Orange(1.0)));
}
void changeDirection()
{
mPositiveSign = !mPositiveSign;
if(mPositiveSign)
{
mArrow->setPositions(
Eigen::Vector3d(-default_height, 0.0, default_height / 2.0),
Eigen::Vector3d(-default_width / 2.0, 0.0, default_height / 2.0));
}
else
{
mArrow->setPositions(
Eigen::Vector3d(default_height, 0.0, default_height / 2.0),
Eigen::Vector3d(default_width / 2.0, 0.0, default_height / 2.0));
}
}
void applyForce(size_t index)
{
if(index < mForceCountDown.size())
mForceCountDown[index] = default_countdown;
}
void changeRestPosition(double /*delta*/)
{
// Lesson 2a
}
void changeStiffness(double /*delta*/)
{
// Lesson 2b
}
void changeDamping(double /*delta*/)
{
// Lesson 2c
}
/// Add a constraint to attach the final link to the world
void addConstraint()
{
// Lesson 3
}
/// Remove any existing constraint, allowing the pendulum to flail freely
void removeConstraint()
{
// Lesson 3
}
/// Handle keyboard input
void keyboard(unsigned char key, int x, int y) override
{
switch(key)
{
case '-':
changeDirection();
break;
case '1':
applyForce(0);
break;
case '2':
applyForce(1);
break;
case '3':
applyForce(2);
break;
case '4':
applyForce(3);
break;
case '5':
applyForce(4);
break;
case '6':
applyForce(5);
break;
case '7':
applyForce(6);
break;
case '8':
applyForce(7);
break;
case '9':
applyForce(8);
break;
case '0':
applyForce(9);
break;
case 'q':
changeRestPosition(delta_rest_position);
break;
case 'a':
changeRestPosition(-delta_rest_position);
break;
case 'w':
changeStiffness(delta_stiffness);
break;
case 's':
changeStiffness(-delta_stiffness);
break;
case 'e':
changeDamping(delta_damping);
break;
case 'd':
changeDamping(-delta_damping);
break;
case 'r':
{
if(mBallConstraint)
removeConstraint();
else
addConstraint();
break;
}
case 'f':
mBodyForce = !mBodyForce;
break;
default:
SimWindow::keyboard(key, x, y);
}
}
void timeStepping() override
{
// Reset all the shapes to be Blue
// Lesson 1a
if(!mBodyForce)
{
// Apply joint torques based on user input, and color the Joint shape red
for(size_t i = 0; i < mPendulum->getNumDofs(); ++i)
{
if(mForceCountDown[i] > 0)
{
// Lesson 1b
--mForceCountDown[i];
}
}
}
else
{
// Apply body forces based on user input, and color the body shape red
for(size_t i = 0; i < mPendulum->getNumBodyNodes(); ++i)
{
if(mForceCountDown[i] > 0)
{
// Lesson 1c
--mForceCountDown[i];
}
}
}
// Step the simulation forward
SimWindow::timeStepping();
}
protected:
/// An arrow shape that we will use to visualize applied forces
std::shared_ptr<ArrowShape> mArrow;
/// The pendulum that we will be perturbing
SkeletonPtr mPendulum;
/// Pointer to the ball constraint that we will be turning on and off
kido::constraint::BallJointConstraint* mBallConstraint;
/// Number of iterations before clearing a force entry
std::vector<int> mForceCountDown;
/// Whether a force should be applied in the positive or negative direction
bool mPositiveSign;
/// True if 1-9 should be used to apply a body force. Otherwise, 1-9 will be
/// used to apply a joint torque.
bool mBodyForce;
};
void setGeometry(const BodyNodePtr& bn)
{
// Create a BoxShape to be used for both visualization and collision checking
std::shared_ptr<BoxShape> box(new BoxShape(
Eigen::Vector3d(default_width, default_depth, default_height)));
box->setColor(kido::Color::Blue());
// Set the location of the Box
Eigen::Isometry3d box_tf(Eigen::Isometry3d::Identity());
Eigen::Vector3d center = Eigen::Vector3d(0, 0, default_height / 2.0);
box_tf.translation() = center;
box->setLocalTransform(box_tf);
// Add it as a visualization and collision shape
bn->addVisualizationShape(box);
bn->addCollisionShape(box);
// Move the center of mass to the center of the object
bn->setLocalCOM(center);
}
BodyNode* makeRootBody(const SkeletonPtr& pendulum, const std::string& name)
{
BallJoint::Properties properties;
properties.mName = name + "_joint";
properties.mRestPositions = Eigen::Vector3d::Constant(default_rest_position);
properties.mSpringStiffnesses = Eigen::Vector3d::Constant(default_stiffness);
properties.mDampingCoefficients = Eigen::Vector3d::Constant(default_damping);
BodyNodePtr bn = pendulum->createJointAndBodyNodePair<BallJoint>(
nullptr, properties, BodyNode::Properties(name)).second;
// Make a shape for the Joint
const double& R = default_width;
std::shared_ptr<EllipsoidShape> ball(
new EllipsoidShape(sqrt(2) * Eigen::Vector3d(R, R, R)));
ball->setColor(kido::Color::Blue());
bn->addVisualizationShape(ball);
// Set the geometry of the Body
setGeometry(bn);
return bn;
}
BodyNode* addBody(const SkeletonPtr& pendulum, BodyNode* parent,
const std::string& name)
{
// Set up the properties for the Joint
RevoluteJoint::Properties properties;
properties.mName = name + "_joint";
properties.mAxis = Eigen::Vector3d::UnitY();
properties.mT_ParentBodyToJoint.translation() =
Eigen::Vector3d(0, 0, default_height);
properties.mRestPosition = default_rest_position;
properties.mSpringStiffness = default_stiffness;
properties.mDampingCoefficient = default_damping;
// Create a new BodyNode, attached to its parent by a RevoluteJoint
BodyNodePtr bn = pendulum->createJointAndBodyNodePair<RevoluteJoint>(
parent, properties, BodyNode::Properties(name)).second;
// Make a shape for the Joint
const double R = default_width / 2.0;
const double h = default_depth;
std::shared_ptr<CylinderShape> cyl(
new CylinderShape(R, h));
cyl->setColor(kido::Color::Blue());
// Line up the cylinder with the Joint axis
Eigen::Isometry3d tf(Eigen::Isometry3d::Identity());
tf.linear() = kido::math::eulerXYZToMatrix(
Eigen::Vector3d(90.0 * M_PI / 180.0, 0, 0));
cyl->setLocalTransform(tf);
bn->addVisualizationShape(cyl);
// Set the geometry of the Body
setGeometry(bn);
return bn;
}
int main(int argc, char* argv[])
{
// Create an empty Skeleton with the name "pendulum"
SkeletonPtr pendulum = Skeleton::create("pendulum");
// Add each body to the last BodyNode in the pendulum
BodyNode* bn = makeRootBody(pendulum, "body1");
bn = addBody(pendulum, bn, "body2");
bn = addBody(pendulum, bn, "body3");
bn = addBody(pendulum, bn, "body4");
bn = addBody(pendulum, bn, "body5");
// Set the initial position of the first DegreeOfFreedom so that the pendulum
// starts to swing right away
pendulum->getDof(1)->setPosition(120 * M_PI / 180.0);
// Create a world and add the pendulum to the world
WorldPtr world(new World);
world->addSkeleton(pendulum);
// Create a window for rendering the world and handling user input
MyWindow window(world);
// Print instructions
std::cout << "space bar: simulation on/off" << std::endl;
std::cout << "'p': replay simulation" << std::endl;
std::cout << "'1' -> '9': apply torque to a pendulum body" << std::endl;
std::cout << "'-': Change sign of applied joint torques" << std::endl;
std::cout << "'q': Increase joint rest positions" << std::endl;
std::cout << "'a': Decrease joint rest positions" << std::endl;
std::cout << "'w': Increase joint spring stiffness" << std::endl;
std::cout << "'s': Decrease joint spring stiffness" << std::endl;
std::cout << "'e': Increase joint damping" << std::endl;
std::cout << "'d': Decrease joint damping" << std::endl;
std::cout << "'r': add/remove constraint on the end of the chain" << std::endl;
std::cout << "'f': switch between applying joint torques and body forces" << std::endl;
// Initialize glut, initialize the window, and begin the glut event loop
glutInit(&argc, argv);
window.initWindow(640, 480, "Multi-Pendulum Tutorial");
glutMainLoop();
}