-
Notifications
You must be signed in to change notification settings - Fork 81
/
world.cpp
1999 lines (1818 loc) · 61.8 KB
/
world.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
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
//######################################################################
//
// GraspIt!
// Copyright (C) 2002-2009 Columbia University in the City of New York.
// All rights reserved.
//
// GraspIt! is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// (at your option) any later version.
//
// GraspIt! is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.
//
// You should have received a copy of the GNU General Public License
// along with GraspIt!. If not, see <http://www.gnu.org/licenses/>.
//
// Author(s): Andrew T. Miller and Matei T. Ciocarlie
//
// $Id: world.cpp,v 1.87 2009/11/20 17:49:49 cmatei Exp $
//
//######################################################################
/*! \file
\brief Implements the simulation world....
*/
#include <string>
#include <algorithm>
#include <QStringList>
#include <QSettings>
#include <QPushButton>
#include <Q3GroupBox>
#include <QFile>
#include <QDateTime>
#include <QTextStream>
#include <Inventor/sensors/SoIdleSensor.h>
#include <Inventor/SbBox.h>
#include <Inventor/actions/SoGetBoundingBoxAction.h>
#include "graspit/matvecIO.h"
#include "graspit/world.h"
#include "graspit/worldElement.h"
#include "graspit/mytools.h"
#include "graspit/body.h"
#include "graspit/robot.h"
#include "graspit/robots/humanHand.h"
#include "graspit/contact/contact.h"
#include "graspit/contactSetting.h"
#include "graspit/ivmgr.h"
#include "graspit/grasp.h"
#include "graspit/ivmgr.h"
#include "graspit/robots/barrett.h"
#include "graspit/matvec3D.h"
#include "graspit/bBox.h"
#include "graspit/Collision/collisionInterface.h"
#include "tinyxml.h"
#include "graspit/worldElementFactory.h"
#include "graspit/dynamics/dynamics.h"
#include "graspit/dynamics/dynJoint.h"
#include "graspit/dynamics/dynamicsEngine.h"
#ifdef PQP_COLLISION
#include "graspit/PQPCollision.h"
#endif
#ifdef GRASPIT_COLLISION
#include "graspit/Collision/Graspit/graspitCollision.h"
#endif
#ifdef GRASPIT_DYNAMICS
#include "graspit/dynamics/graspitDynamics.h"
#endif
#ifdef BULLET_DYNAMICS
#include "graspit/dynamics/bulletDynamics.h"
#endif
//simulations of arches with John Ochsendorf
#include "graspit/arch.h"
#ifdef USE_DMALLOC
#include "dmalloc.h"
#endif
FILE *errFP = NULL;
#include "graspit/debug.h"
//#define PROF_ENABLED
#include "graspit/profiling.h"
PROF_DECLARE(WORLD_FIND_CONTACTS);
PROF_DECLARE(WORLD_COLLISION_REPORT);
PROF_DECLARE(WORLD_NO_COLLISION);
PROF_DECLARE(WORLD_GET_DIST);
PROF_DECLARE(WORLD_POINT_TO_BODY_DISTANCE);
PROF_DECLARE(WORLD_FIND_VIRTUAL_CONTACTS);
PROF_DECLARE(WORLD_FIND_REGION);
PROF_DECLARE(DYNAMICS);
#define MAXBODIES 256
#define TIMER_MILLISECONDS 100.0
char graspitVersionStr[] = "GraspIt! version 2.1";
/*! Prepares an empty world. \a mgr is the instance of the inventor manager
that will handle all user interaction. Also initialized collision detection
system and reads in global settings such as friction coefficients
*/
World::World(QObject *parent, const char *name) :
QObject(parent, name),
myIVmgr(NULL)
{
numBodies = numGB = numRobots = numHands = 0;
numSelectedBodyElements = numSelectedRobotElements = 0;
numSelectedElements = 0;
numSelectedBodies = 0;
currentHand = NULL;
isTendonSelected = false;
selectedTendon = NULL;
worldTime = 0.0;
modified = false;
allCollisionsOFF = false;
softContactsON = true;
cofTable = kcofTable = NULL;
// set up the world parameters
readSettings();
#ifdef PQP_COLLISION
mCollisionInterface = new PQPCollision();
#endif
#ifdef GRASPIT_COLLISION
mCollisionInterface = new GraspitCollision();
#endif
IVRoot = new SoSeparator;
IVRoot->ref();
idleSensor = NULL;
dynamicsOn = false;
// This has to happen at runtime, so it's placed here
// maybe we can find a better solution at some point.
WorldElementFactory::registerBuiltinCreators();
#ifdef GRASPIT_DYNAMICS
mDynamicsEngine = new GraspitDynamics(this);
#endif
#ifdef BULLET_DYNAMICS
mDynamicsEngine = new BulletDynamics(this);
#endif
}
/*! Saves the global settings and parameters and deletes the world
along with all the objects that populate it.
*/
World::~World()
{
int i;
DBGP("Deleting world");
saveSettings();
for (i = 0; i < numMaterials; i++) {
free(cofTable[i]);
free(kcofTable[i]);
}
free(cofTable);
free(kcofTable);
for (i = numRobots - 1; i >= 0; i--) {
destroyElement(robotVec[i]);
}
for (i = numBodies - 1; i >= 0; i--) {
DBGP("Deleting body: " << i << " " << bodyVec[i]->getName().latin1());
destroyElement(bodyVec[i]);
}
if (idleSensor) { delete idleSensor; }
delete mCollisionInterface;
delete mDynamicsEngine;
IVRoot->unref();
}
/*! Returns axis-aligned bounding box min and max points of the world
*/
void World::getBoundingBox(vec3 &minPoint, vec3 &maxPoint)
{
minPoint.x() = 0;
minPoint.y() = 0;
minPoint.z() = 0;
maxPoint.x() = 0;
maxPoint.y() = 0;
maxPoint.z() = 0;
// viewport required for any viewport-dependent
// nodes (eg text), but not required for others
SbViewportRegion anyVP(0, 0);
SoGetBoundingBoxAction bbAction(anyVP);
bbAction.apply(IVRoot);
SbBox3f bbox = bbAction.getBoundingBox();
const SbVec3f &minIV = bbox.getMin();
const SbVec3f &maxIV = bbox.getMax();
minPoint.x() = minIV[0];
minPoint.y() = minIV[1];
minPoint.z() = minIV[2];
maxPoint.x() = maxIV[0];
maxPoint.y() = maxIV[1];
maxPoint.z() = maxIV[2];
}
/*! Returns the material id of a material with name \a matName
*/
int
World::getMaterialIdx(const QString &matName) const
{
for (int i = 0; i < numMaterials; i++) {
if (materialNames[i] == matName) { return i; }
}
return -1;
}
/*! Returns the material name of a material with id \a matIdx
*/
/**
int
World::getMaterialName(int matIdx, QString &matName) const
{
if(i<0||i>=numMaterials)
return FAILURE;
matName = materialNames[i];
return SUCCESS;
}
*/
/*! Sets all the default (hard-coded) coefficients and parameters. If the user later
changes them, they are saved when the world is destroyed, and automatically loaded
later, when the application is started again.
*/
void
World::setDefaults()
{
int i;
dynamicsTimeStep = 0.0025;
if (cofTable) {
for (i = 0; i < numMaterials; i++) {
free(cofTable[i]);
free(kcofTable[i]);
}
free(cofTable);
free(kcofTable);
}
numMaterials = 7;
cofTable = (double **)malloc(numMaterials * sizeof(double *));
kcofTable = (double **)malloc(numMaterials * sizeof(double *));
for (i = 0; i < numMaterials; i++) {
cofTable[i] = (double *)malloc(numMaterials * sizeof(double));
kcofTable[i] = (double *)malloc(numMaterials * sizeof(double));
}
materialNames.clear();
materialNames.push_back("frictionless");
materialNames.push_back("glass");
materialNames.push_back("metal");
materialNames.push_back("plastic");
materialNames.push_back("wood");
materialNames.push_back("rubber");
materialNames.push_back("stone");
//frictionless
for (i = 0; i < 7; i++) {
cofTable[0][i] = cofTable[i][0] = 0.0;
kcofTable[0][i] = kcofTable[i][0] = 0.0;
}
//stone
cofTable[6][6] = 0.7;
cofTable[6][1] = cofTable[1][6] = 0.3;
cofTable[6][2] = cofTable[2][6] = 0.4;
cofTable[6][3] = cofTable[3][6] = 0.4;
cofTable[6][4] = cofTable[4][6] = 0.6;
cofTable[6][5] = cofTable[5][6] = 1.5;
kcofTable[6][6] = 0.6;
kcofTable[6][1] = kcofTable[1][6] = 0.2;
kcofTable[6][2] = kcofTable[2][6] = 0.3;
kcofTable[6][3] = kcofTable[3][6] = 0.3;
kcofTable[6][4] = kcofTable[4][6] = 0.5;
kcofTable[6][5] = kcofTable[5][6] = 1.4;
//glass
cofTable[1][1] = 0.2;
cofTable[1][2] = cofTable[2][1] = 0.2;
cofTable[1][3] = cofTable[3][1] = 0.2;
cofTable[1][4] = cofTable[4][1] = 0.3;
cofTable[1][5] = cofTable[5][1] = 1.0;
kcofTable[1][1] = 0.1;
kcofTable[1][2] = kcofTable[2][1] = 0.1;
kcofTable[1][3] = kcofTable[3][1] = 0.1;
kcofTable[1][4] = kcofTable[4][1] = 0.2;
kcofTable[1][5] = kcofTable[5][1] = 0.9;
//metal
cofTable[2][2] = 0.2;
cofTable[2][3] = cofTable[3][2] = 0.2;
cofTable[2][4] = cofTable[4][2] = 0.3;
cofTable[2][5] = cofTable[5][2] = 1.0;
kcofTable[2][2] = 0.1;
kcofTable[2][3] = kcofTable[3][2] = 0.1;
kcofTable[2][4] = kcofTable[4][2] = 0.2;
kcofTable[2][5] = kcofTable[5][2] = 0.9;
//plastic
cofTable[3][3] = 0.3;
cofTable[3][4] = cofTable[4][3] = 0.4;
cofTable[3][5] = cofTable[5][3] = 1.0;
kcofTable[3][3] = 0.2;
kcofTable[3][4] = kcofTable[4][3] = 0.3;
kcofTable[3][5] = kcofTable[5][3] = 0.9;
//wood
cofTable[4][4] = 0.4;
cofTable[4][5] = cofTable[5][4] = 1.0;
kcofTable[4][4] = 0.3;
kcofTable[4][5] = kcofTable[5][4] = 0.9;
//rubber
cofTable[5][5] = 2.0;
kcofTable[5][5] = 1.9;
}
/*! Reads in previously saved coefficients and parameters, if they exist. In Windows,
they are read from the registry, in Linux they should be read from a file. It seems
that currently only the Window implementation is here. If they don't exist, the
default values are used.
*/
void
World::readSettings()
{
QString organization = "graspit";
QString application = "graspit";
QSettings settings(organization, application);
int i, j, newNumMaterials;
double **newcofTable, **newkcofTable;
std::vector<QString> newMaterialNames;
setDefaults();
dynamicsTimeStep = settings.readDoubleEntry(QString("/GraspIt/") + QString("World/dynamicsTimeStep"), dynamicsTimeStep);
newNumMaterials = settings.readNumEntry(QString("/GraspIt/") + QString("World/numMaterials"), numMaterials);
newcofTable = (double **)malloc(newNumMaterials * sizeof(double *));
newkcofTable = (double **)malloc(newNumMaterials * sizeof(double *));
newMaterialNames.resize(newNumMaterials, QString::null);
for (i = 0; i < newNumMaterials; i++) {
newcofTable[i] = (double *)malloc(newNumMaterials * sizeof(double));
newkcofTable[i] = (double *)malloc(newNumMaterials * sizeof(double));
}
for (i = 0; i < numMaterials; i++) {
newMaterialNames[i] = settings.readEntry(QString("/GraspIt/") + QString("World/material%1").arg(i), materialNames[i]);
for (j = i; j < numMaterials; j++) {
newcofTable[i][j] = newcofTable[j][i] =
settings.readDoubleEntry(QString("/GraspIt/") + QString("World/cof%1%2").arg(i).arg(j), cofTable[i][j]);
newkcofTable[i][j] = newkcofTable[j][i] =
settings.readDoubleEntry(QString("/GraspIt/") + QString("World/kcof%1%2").arg(i).arg(j), kcofTable[i][j]);
}
for (; j < newNumMaterials; j++) {
newcofTable[i][j] = newcofTable[j][i] =
settings.readDoubleEntry(QString("/GraspIt/") + QString("World/cof%1%2").arg(i).arg(j));
newkcofTable[i][j] = newkcofTable[j][i] =
settings.readDoubleEntry(QString("/GraspIt/") + QString("World/kcof%1%2").arg(i).arg(j));
}
}
for (; i < newNumMaterials; i++) {
newMaterialNames.push_back(settings.readEntry(QString("/GraspIt/") + QString("World/material%1").arg(i)));
for (j = i; j < newNumMaterials; j++) {
newcofTable[i][j] = newcofTable[j][i] =
settings.readDoubleEntry(QString("/GraspIt/") + QString("World/cof%1%2").arg(i).arg(j));
newkcofTable[i][j] = newkcofTable[j][i] =
settings.readDoubleEntry(QString("/GraspIt/") + QString("World/kcof%1%2").arg(i).arg(j));
}
}
for (i = 0; i < numMaterials; i++) {
free(cofTable[i]);
free(kcofTable[i]);
}
free(cofTable);
free(kcofTable);
materialNames = newMaterialNames;
numMaterials = newNumMaterials;
cofTable = newcofTable;
kcofTable = newkcofTable;
}
/*! Saves current global settings to the registry */
void
World::saveSettings()
{
QString organization = "graspit";
QString application = "graspit";
QSettings settings(organization, application);
int i, j;
settings.writeEntry(QString("/GraspIt/") + QString("World/numMaterials"), numMaterials);
for (i = 0; i < numMaterials; i++) {
settings.writeEntry(QString("/GraspIt/") + QString("World/material%1").arg(i), materialNames[i]);
for (j = i; j < numMaterials; j++) {
settings.writeEntry(QString("/GraspIt/") + QString("World/cof%1%2").arg(i).arg(j), cofTable[i][j]);
settings.writeEntry(QString("/GraspIt/") + QString("World/kcof%1%2").arg(i).arg(j), kcofTable[i][j]);
}
}
}
/*! Removes a world element (a robot or any kind of body) from the World.
Also removes it from the scene graph and the collision detection system.
If \a deleteElement is true, it also deletes it at the end. If it is a
graspable body and there is a grasp that references it, it associates
the grasp with the first GB or NULL if none are left.
*/
void
World::destroyElement(WorldElement *e, bool deleteElement)
{
std::vector<Body *>::iterator bp;
std::vector<GraspableBody *>::iterator gp;
std::vector<Robot *>::iterator rp;
std::vector<Hand *>::iterator hp;
DBGP("In remove element: " << e->className());
if (e->inherits("Body")) {
DBGP("found a body");
for (bp = bodyVec.begin(); bp != bodyVec.end(); bp++) {
if (*bp == e) {
mCollisionInterface->removeBody( (Body*) e);
bodyVec.erase(bp); numBodies--;
DBGP("removed body " << ((Body *)e)->getName().toStdString().c_str() << " from world");
break;
}
}
for (gp = GBVec.begin(); gp != GBVec.end(); gp++) {
if (*gp == e) {
GBVec.erase(gp); numGB--;
for (hp = handVec.begin(); hp != handVec.end(); hp++) {
if ((*hp)->getGrasp()->getObject() == e) {
if (numGB > 0) {
(*hp)->getGrasp()->setObject(GBVec[0]);
}
else {
(*hp)->getGrasp()->setObject(NULL);
}
}
}
DBGP("removed GB " << ((Body *)e)->getName().toStdString().c_str() << " from world");
break;
}
}
}
if (e->inherits("Robot")) {
DBGP(" found a robot");
for (hp = handVec.begin(); hp != handVec.end(); hp++) {
if (*hp == e) {
handVec.erase(hp); numHands--;
if (currentHand == e) {
if (numHands > 0) { currentHand = handVec[0]; }
else { currentHand = NULL; }
}
DBGP("removed hand " << ((Robot *)e)->getName().toStdString().c_str() << " from world");
Q_EMIT handRemoved();
break;
}
}
for (rp = robotVec.begin(); rp != robotVec.end(); rp++) {
if (*rp == e) {
robotVec.erase(rp); numRobots--;
DBGP("removed robot " << ((Robot *)e)->getName().toStdString().c_str() << " from world");
break;
}
}
}
int idx = IVRoot->findChild(e->getIVRoot());
if (deleteElement) { delete e; }
else { e->getIVRoot()->ref(); }
if (idx > -1) {
IVRoot->removeChild(idx);
}
if (!deleteElement) { e->getIVRoot()->unrefNoDelete(); }
Q_EMIT numElementsChanged();
modified = true;
}
/*! Loads a simulation world file. These usually consists of one or more robots,
graspable bodies and obstacles, each with its own transform. Optionally,
a camera position might also be specified. Also restores any connections
between robots.
*/
int
World::load(const QString &filename)
{
QString graspitRoot = getenv("GRASPIT");
graspitRoot.replace("\\", "/");
if (graspitRoot.at(graspitRoot.size() - 1) != '/') {
graspitRoot += "/";
}
//load the graspit specific information in XML format
TiXmlDocument doc(filename);
if (doc.LoadFile() == false) {
QTWARNING("Could not open file " + filename);
return FAILURE;
}
const TiXmlElement *root = doc.RootElement();
if (root == NULL) {
QTWARNING("Empty XML");
return FAILURE;
}
if (loadFromXml(root, graspitRoot) == FAILURE) {
return FAILURE;
}
return SUCCESS;
}
int
World::loadFromXml(const TiXmlElement *root, QString rootPath)
{
const TiXmlElement *child = root->FirstChildElement();
const TiXmlElement *xmlElement;
QString buf, elementType, matStr, elementPath, elementName, mountFilename;
Link *mountPiece;
QString line;
WorldElement *element = NULL;
transf tr;
int prevRobNum, chainNum, nextRobNum;
bool cameraFound;
while (child != NULL) {
elementType = child->Value();
if (elementType.isNull()) {
QTWARNING("Empty Element Type");
}
if (elementType == "obstacle") {
xmlElement = findXmlElement(child, "filename");
bool loadFromFile = false;
if (xmlElement) {
elementName = xmlElement->GetText();
elementPath = rootPath + elementName;
elementPath = elementPath.stripWhiteSpace();
DBGP("importing " << elementPath.latin1());
element = importBody("Body", elementPath);
if (!element) {
QTWARNING("Could not open " + elementPath);
return FAILURE;
}
loadFromFile = true;
}
xmlElement = findXmlElement(child, "body");
if (loadFromFile) {
if (xmlElement) {
QTWARNING("Contains both filename and body info: Load From File");
}
} else { //load from body info
if (!xmlElement) {
QTWARNING("Neither filename nor body info found");
return FAILURE;
}
DBGP("importing obstacle from body info");
element = importBodyFromXml("Body", xmlElement, rootPath);
if (!element) {
QTWARNING("Could not open file " + elementPath);
return FAILURE;
}
}
xmlElement = findXmlElement(child, "transform");
if (xmlElement) {
if (getTransform(xmlElement, tr) == false) {
QTWARNING("Obstacle transformation Error");
return FAILURE;
}
element->setTran(tr);
}
}
else if (elementType == "graspableBody") {
xmlElement = findXmlElement(child, "filename");
bool loadFromFile = false;
if (xmlElement) {
elementName = xmlElement->GetText();
elementPath = rootPath + elementName;
elementPath = elementPath.stripWhiteSpace();
DBGP("importing " << elementPath.latin1());
element = importBody("GraspableBody", elementPath);
if (!element) {
QTWARNING("Could not open " + elementPath);
return FAILURE;
}
loadFromFile = true;
}
xmlElement = findXmlElement(child, "body");
if (loadFromFile) {
if (xmlElement) {
QTWARNING("Contains both filename and body info: Load From File");
}
}
else { //load from body info
if (!xmlElement) {
QTWARNING("Neither filename nor body info found");
return FAILURE;
}
DBGP("importing graspable body from body info");
element = importBodyFromXml("GraspableBody", xmlElement, rootPath);
if (!element) {
QTWARNING("Could not open " + elementPath);
return FAILURE;
}
}
xmlElement = findXmlElement(child, "transform");
if (xmlElement) {
if (getTransform(xmlElement, tr) == false) {
QTWARNING("GraspableBody transformation Error");
return FAILURE;
}
element->setTran(tr);
}
}
else if (elementType == "robot") {
Robot *robot;
xmlElement = findXmlElement(child, "filename");
if (!xmlElement) {
QTWARNING("Robot filename not found");
return FAILURE;
}
elementName = xmlElement->GetText();
elementPath = rootPath + elementName;
DBGP("importing " << elementPath.latin1());
if ((robot = importRobot(elementPath)) == NULL) {
QTWARNING("Could not open " + elementPath);
return FAILURE;
}
element = robot;
xmlElement = findXmlElement(child, "dofValues");
if (xmlElement) {
QString dofValues = xmlElement->GetText();
dofValues = dofValues.stripWhiteSpace().simplifyWhiteSpace();
QTextStream lineStream(&dofValues, QIODevice::ReadOnly);
robot->readDOFVals(lineStream);
}
xmlElement = findXmlElement(child, "transform");
if (xmlElement) {
if (getTransform(xmlElement, tr) == false) {
QTWARNING("Robot transformation Error");
return FAILURE;
}
element->setTran(tr);
}
}
else if (elementType == "connection") {
if (!getInt(child, "parentRobot", prevRobNum)) {
QTWARNING("Failed to load Parent Robot Number");
return FAILURE;
}
if (!getInt(child, "parentChain", chainNum)) {
QTWARNING("Failed to load Parent Robot's Chain Number");
return FAILURE;
}
if (!getInt(child, "childRobot", nextRobNum)) {
QTWARNING("Failed to load Child Robot Number");
return FAILURE;
}
if (prevRobNum < 0 || prevRobNum >= numRobots || nextRobNum < 0 ||
nextRobNum >= numRobots || chainNum < 0 ||
chainNum >= robotVec[prevRobNum]->getNumChains()) {
QTWARNING("Error reading connection transform"); break;
}
xmlElement = findXmlElement(child, "transform");
if (xmlElement) {
if (!getTransform(xmlElement, tr)) {
QTWARNING("Error reading connection transform"); break;
}
}
DBGP("offset tran " << tr);
xmlElement = findXmlElement(child, "mountFilename");
if (xmlElement) {
mountFilename = xmlElement->GetText();
if (!mountFilename.isEmpty()) {
mountFilename = mountFilename.stripWhiteSpace();
KinematicChain *prevChain = robotVec[prevRobNum]->getChain(chainNum);
mountFilename = rootPath + mountFilename;
DBGA("Mount filename: " << mountFilename.latin1());
if ((mountPiece = robotVec[nextRobNum]->importMountPiece(mountFilename))) {
addLink(mountPiece);
toggleCollisions(false, prevChain->getLink(prevChain->getNumLinks() - 1), mountPiece);
toggleCollisions(false, mountPiece, robotVec[nextRobNum]->getBase());
}
mountFilename = (char *)NULL;
}
}
robotVec[prevRobNum]->attachRobot(robotVec[nextRobNum], chainNum, tr);
}
else if (elementType == "camera") {
double px, py, pz, q1, q2, q3, q4, fd;
QStringList l;
xmlElement = findXmlElement(child, "position");
if (!xmlElement) {
QTWARNING("Camera Position not found");
return FAILURE;
}
QString position = xmlElement->GetText();
position = position.simplifyWhiteSpace().stripWhiteSpace();
l = QStringList::split(' ', position);
if (l.count() != 3) {
QTWARNING("Invalid camera position input");
return FAILURE;
}
bool ok1, ok2, ok3, ok4;
px = l[0].toDouble(&ok1);
py = l[1].toDouble(&ok2);
pz = l[2].toDouble(&ok3);
if (!ok1 || !ok2 || !ok3) {
QTWARNING("Invalid camera position input");
return FAILURE;
}
xmlElement = findXmlElement(child, "orientation");
if (!xmlElement) {
QTWARNING("Camera orientation not found");
return FAILURE;
}
QString orientation = xmlElement->GetText();
position = orientation.simplifyWhiteSpace().stripWhiteSpace();
l = QStringList::split(' ', orientation);
if (l.count() != 4) {
QTWARNING("Invalid camera orientation input");
return FAILURE;
}
q1 = l[0].toDouble(&ok1);
q2 = l[1].toDouble(&ok2);
q3 = l[2].toDouble(&ok3);
q4 = l[3].toDouble(&ok4);
if (!ok1 || !ok2 || !ok3 || !ok4) {
QTWARNING("Invalid camera position input");
return FAILURE;
}
if (!getDouble(child, "focalDistance", fd)) {
QTWARNING("Failed to load focal distance");
return FAILURE;
}
if (myIVmgr) {
myIVmgr->setCamera(px, py, pz, q1, q2, q3, q4, fd);
} else {
DBGA("Could not set camera");
}
cameraFound = true;
}
else {
QTWARNING(elementType + " is not a valid WorldElement type");
return FAILURE;
}
child = child->NextSiblingElement();
}
if (!cameraFound) {
if (myIVmgr) {
myIVmgr->getViewer()->viewAll();
}
}
findAllContacts();
modified = false;
resetDynamics();
return SUCCESS;
}
/*! Saves this world to a file. This includes all the world elements as well as
positions in the world, and the positions and orientation of the camera. It
does not save the dynamic state of the bodies.
*/
int
World::save(const QString &filename)
{
QFile file(filename);
int i, j, k, l;
if (!file.open(QIODevice::WriteOnly)) {
QTWARNING("could not open " + filename + "for writing");
return FAILURE;
}
QTextStream stream(&file);
stream << "<?xml version=\"1.0\" ?>" << endl;
stream << "<world>" << endl;
for (i = 0; i < numBodies; i++) {
if (bodyVec[i]->isA("Body")) {
stream << "\t<obstacle>" << endl;
if (bodyVec[i]->getFilename() == "unspecified") {
stream << "\t\t<body>" << endl;
if (bodyVec[i]->saveToXml(stream) == FAILURE) {
QTWARNING("Failed to save body info");
return FAILURE;
}
stream << "\t\t</body>" << endl;
}
else {
stream << "\t\t<filename>" << bodyVec[i]->getFilename().latin1() << "</filename>" << endl;
}
stream << "\t\t<transform>" << endl;
stream << "\t\t\t<fullTransform>" << bodyVec[i]->getTran() << "</fullTransform>" << endl;
stream << "\t\t</transform>" << endl;
stream << "\t</obstacle>" << endl;
}
else if (bodyVec[i]->inherits("GraspableBody")) {
stream << "\t<graspableBody>" << endl;
if (bodyVec[i]->getFilename() == "unspecified") {
stream << "\t\t<body>" << endl;
if (bodyVec[i]->saveToXml(stream) == FAILURE) {
QTWARNING("Failed to save body info");
return FAILURE;
}
stream << "\t\t</body>" << endl;
}
else {
stream << "\t\t<filename>" << bodyVec[i]->getFilename().latin1() << "</filename>" << endl;
}
stream << "\t\t<transform>" << endl;
stream << "\t\t\t<fullTransform>" << bodyVec[i]->getTran() << "</fullTransform>" << endl;
stream << "\t\t</transform>" << endl;
stream << "\t</graspableBody>" << endl;
}
}
for (i = 0; i < numRobots; i++) {
stream << "\t<robot>" << endl;
stream << "\t\t<filename>" << robotVec[i]->getFilename().latin1() << "</filename>" << endl;
stream << "\t\t<dofValues>";
robotVec[i]->writeDOFVals(stream);
stream << "</dofValues>" << endl;
stream << "\t\t<transform>" << endl;
stream << "\t\t\t<fullTransform>" << robotVec[i]->getTran() << "</fullTransform>" << endl;
stream << "\t\t</transform>" << endl;
stream << "\t</robot>" << endl;
}
for (i = 0; i < numRobots; i++) {
for (j = 0; j < robotVec[i]->getNumChains(); j++) {
KinematicChain *chain = robotVec[i]->getChain(j);
for (k = 0; k < chain->getNumAttachedRobots(); k++) {
stream << "\t<connection>" << endl;
stream << "\t\t<parentRobot>" << i << "</parentRobot>" << endl;
stream << "\t\t<parentChain>" << j << "</parentChain>" << endl;
for (l = 0; l < numRobots; l++)
if (chain->getAttachedRobot(k) == robotVec[l]) { break; }
stream << "\t\t<childRobot>" << l << "</childRobot>" << endl;
if (chain->getAttachedRobot(k)->getMountPiece()) {
stream << "\t\t<mountFilename>" << chain->getAttachedRobot(k)->getMountPiece()->getFilename() << "</mountFilename>" << endl;
}
stream << "\t\t<transform>" << endl;
stream << "\t\t\t<fullTransform>" << chain->getAttachedRobotOffset(k) << "</fullTransform>" << endl;
stream << "\t\t</transform>" << endl;
stream << "\t</connection>" << endl;
}
}
}
stream << "\t<camera>" << endl;
if (myIVmgr) {
float px, py, pz, q1, q2, q3, q4, fd;
myIVmgr->getCamera(px, py, pz, q1, q2, q3, q4, fd);
stream << "\t\t<position>" << px << " " << py << " " << pz << "</position>" << endl;
stream << "\t\t<orientation>" << q1 << " " << q2 << " " << q3 << " " << q4 << "</orientation>" << endl;
stream << "\t\t<focalDistance>" << fd << "</focalDistance>" << endl;
} else {
// the object will be viewed along the negative z-axis from a distance
// determined by a target angle between the view point and the
// x-coordinate corners of the world bounding box.
static float angle = 60; // angle (degrees) between rays cast to two corners of the bounding box
if (fabs(angle) < 1e-05) {
DBGA("Cannot choose zero angle, forcing to 10 as minimum");
angle = 10;
}
vec3 minPoint, maxPoint, center; // min/max points of AABB
getBoundingBox(minPoint, maxPoint);
center = (minPoint + maxPoint) * 0.5;
float xLen = fabs(maxPoint.x() - minPoint.x()); // lenght of BB along x
float zLen = fabs(maxPoint.z() - minPoint.z()); // lenght of BB along z
float dist = fabs(xLen * 0.5 / tan(angle * 0.5 * M_PI / 180)); // distance along z
// std::cout<<"xLen: "<<xLen<<", zLen: "<<zLen<<", dist = "<<dist<<std::endl;
// write results to stream
vec3 pos(center.x(), center.y(), center.z() + zLen * 0.5 + dist);
stream << "\t\t<position>" << pos.x() << " " << pos.y() << " " << pos.z() << "</position>" << endl;
// orientation along negative z (with y as up vector) is default in Inventor, so
// keep identity quaternion
stream << "\t\t<orientation>" << 0 << " " << 0 << " " << 0 << " " << 1 << "</orientation>" << endl;
stream << "\t\t<focalDistance>" << dist << "</focalDistance>" << endl;
}
stream << "\t</camera>" << endl;
stream << "</world>" << endl;
file.close();
modified = false;
return SUCCESS;
}
/*! Imports a body which is loaded from a file. \bodyType must be a class name
from the Body hierarchy (e.g. "Body", "DynamicBody", etc). \a filename is
the complete path to the file containing the body. The new body is created,
loaded from the file, initialized, and added to the collision detection and
scene graph.
*/
Body *
World::importBody(QString bodyType, QString filename)
{
Body *newBody = (Body *) getWorldElementFactory().createElement(bodyType.toStdString(), this, NULL);
if (!newBody) { return NULL; }
if (newBody->load(filename) == FAILURE) { return NULL; }
newBody->addToIvc();
addBody(newBody);
return newBody;
}
/*! Imports a body which is loaded from a xml file. \bodyType must be a class name
from the Body hierarchy (e.g. "Body", "DynamicBody", etc). \a rootPath and \a
child are parsed to loadFromXml. The new body is created, loaded from the
XML element, initialized, and added to the collision detection and scene graph.
*/
Body *
World::importBodyFromXml(QString bodyType, const TiXmlElement *child, QString rootPath)
{
Body *newBody = (Body *) getWorldElementFactory().createElement(bodyType.toStdString(), this, NULL);
if (!newBody) { return NULL; }
if (newBody->loadFromXml(child, rootPath) == FAILURE) { return NULL; }
newBody->addIVMat();
newBody->addToIvc();
addBody(newBody);
return newBody;
}
/*! Adds to this world a body that is already created, initialized and somehow
populated. This usually means a body obtained by loading from a file or
cloning another body. It does NOT add the new body to the collision detection
system, it is the caller's responsability to do that. Also does not initialize
dynamics.
*/
void
World::addBody(Body *newBody)
{
newBody->setDefaultViewingParameters();
bodyVec.push_back(newBody);
numBodies++;
if (newBody->inherits("GraspableBody")) {
GBVec.push_back((GraspableBody *)newBody);
if (numGB == 0) {
for (int i = 0; i < numHands; i++) {
handVec[i]->getGrasp()->setObject((GraspableBody *)newBody);
}
}
numGB++;
}
IVRoot->addChild(newBody->getIVRoot());
modified = true;
Q_EMIT numElementsChanged();
mDynamicsEngine->addBody(newBody);
}
/*! Adds a robot link. No need to add it to scene graph, since the robot
will add it to its own tree. The robot will also init dynamics and
add the link to collision detection.
*/
void
World::addLink(Link *newLink)
{
bodyVec.push_back(newLink);
numBodies++;
mDynamicsEngine->addBody(newLink);
}
/*! Loads a robot from a file and adds it to the world. \a filename must
contain the full path to the robot. The file is expected to be in XML
format. This function will open the file and read the robot file so
that it initializes an instance of the correct class. It will then
pass the XML root of the robot structure to the robot who will load
its own information from the file.