-
Notifications
You must be signed in to change notification settings - Fork 2
/
graspitServer.cpp
1434 lines (1235 loc) · 39.3 KB
/
graspitServer.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
//
// $Id: graspitServer.cpp,v 1.7.4.1 2009/07/23 21:18:01 cmatei Exp $
//
//######################################################################
/*! \file
\brief Implements the application's TCP server.
*/
#include <QDateTime>
#include <QTextStream>
#include <QApplication>
#include <iostream>
#include "graspitServer.h"
#include "graspitGUI.h"
#include "ivmgr.h"
#include "world.h"
#include "robot.h"
#include "grasp.h"
#include "contact.h"
#include "onLinePlanner.h"
#include "searchStateUtils.h"
#include <sstream>
#include <Inventor/nodes/SoCoordinate3.h>
#include <Inventor/nodes/SoMaterial.h>
#include <Inventor/nodes/SoSphere.h>
#include <Inventor/SoPrimitiveVertex.h>
#include <Inventor/nodes/SoCamera.h>
#include <Inventor/nodes/SoPointSet.h>
#include <Inventor/nodes/SoDrawStyle.h>
#include <Inventor/fields/SoSFVec3f.h>
#include <QMutexLocker>
#include "BCI/bciService.h"
//helper function to get current world planner
EGPlanner* currentWorldPlanner(){ return graspItGUI->getIVmgr()->getWorld()->getCurrentPlanner();}
ClientSocket::ClientSocket( QObject *parent, QTcpSocket * socket, unsigned int maximum_len) :
QObject( parent),
sock(socket),
maxLen(maximum_len)
{
connect( sock, SIGNAL(readyRead()), this, SLOT(readClient()) );
connect( sock, SIGNAL(connectionClosed()), this, SLOT(connectionClosed()) );
}
/*!
Stub destructor.
*/
ClientSocket::~ClientSocket()
{
#ifdef GRASPITDBG
std::cout << "client socket destroyed"<<std::endl;
#endif
}
/*!
This reads the next portion of a command line after the command to collect
the body indices, and returns a vector of pointers to those bodies. If
this portion starts with the word "ALL", then all the bodies in the world
are added to the body vector. Otherwise it reads the number of body
indices, and reads each index in turn, adding the corresponding body
pointer to the vector. If an index is read that does not exist, an error
message is sent back and this method returns FAILURE.
*/
int
ClientSocket::readBodyIndList(std::vector<Body *> &bodyVec)
{
QTextStream os(sock);
int i,numBodies,bodNum;
bool ok;
World *world = graspItGUI->getIVmgr()->getWorld();
std::cout << "ReadBodyIndList Line:"<<line.latin1() << std::endl;
/* if the index list is empty, use every body and send
back the count
*/
if (strPtr == lineStrList.end()) return FAILURE;
if ((*strPtr).startsWith("ALL")) {
strPtr++;
for (i=0;i<world->getNumBodies();i++)
bodyVec.push_back(world->getBody(i));
std::cout << "Sending num bodies: "<<world->getNumBodies()<<std::endl;
os << world->getNumBodies() << endl;
return SUCCESS;
}
numBodies = (*strPtr).toInt(&ok);
if (!ok) return FAILURE;
strPtr++;
for (i=0;i<numBodies;i++) {
if (strPtr == lineStrList.end()) return FAILURE;
bodNum = (*strPtr).toInt(&ok);
if (!ok) return FAILURE;
if (bodNum>=0 && bodNum<world->getNumBodies()) {
bodyVec.push_back(world->getBody(bodNum));
if (world->getBody(bodNum)==NULL) {
os << "Error: Cannot find body " << bodNum <<"\n";
return FAILURE;
}
}
else {
os << "Error: Cannot find body " << bodNum <<"\n";
return FAILURE;
}
strPtr++;
}
return SUCCESS;
}
// read in 7 param transf given as pos(x y z) Qauternion(w x y z)
int ClientSocket::readTransf(transf * tr){
bool ok = true;
try{
*tr = transf(Quaternion((*(strPtr + 3)).toDouble(&ok), //qw
(*(strPtr + 4)).toDouble(&ok), //qx
(*(strPtr + 5)).toDouble(&ok), //qy
(*(strPtr + 6)).toDouble(&ok)), //qz
vec3((*strPtr).toDouble(&ok), //x
(*(strPtr+1)).toDouble(&ok), //y
(*(strPtr + 2)).toDouble(&ok))); //z
strPtr +=7;
}
catch(...){
if (!ok)
return FAILURE;
else
std::cout <<"unknown error in ClientSocket::readTransf \n";
}
return SUCCESS;
}
/*!
This reads the next portion of a command line after the command to collect
the robot indices, and returns a vector of pointers to those robots. If
this portion starts with the word "ALL", then all the robots in the world
are added to the robot vector. Otherwise it reads the number of robot
indices, and reads each index in turn, adding the corresponding robot
pointer to the vector. If an index is read that does not exist, an error
message is sent back and this method returns FAILURE.
*/
int
ClientSocket::readRobotIndList(std::vector<Robot *> &robVec)
{
QTextStream os(sock);
int i,robNum,numRobots;
bool ok;
World *world = graspItGUI->getIVmgr()->getWorld();
std::cout << "ReadRobotIndList Line:"<<line.latin1() << std::endl;
/* if the index list is empty, use every robot and send
back the count
*/
if (strPtr == lineStrList.end()) return FAILURE;
if ((*strPtr).startsWith("ALL")) {
strPtr++;
for (i=0;i<world->getNumRobots();i++)
robVec.push_back(world->getRobot(i));
std::cout << "Sending num robots: "<<world->getNumRobots()<<std::endl;
os << world->getNumRobots() << endl;
return SUCCESS;
}
numRobots = (*strPtr).toInt(&ok);
if (!ok) return FAILURE;
strPtr++;
for (i=0;i<numRobots;i++) {
if (strPtr == lineStrList.end()) return FAILURE;
robNum = (*strPtr).toInt(&ok);
if (!ok) return FAILURE;
if (robNum>=0 && robNum<world->getNumRobots()) {
robVec.push_back(world->getRobot(robNum));
if (world->getRobot(robNum)==NULL) {
os << "Error: Cannot find robot " << robNum <<"\n";
return FAILURE;
}
}
else {
os << "Error: Cannot find robot " << robNum <<"\n";
return FAILURE;
}
strPtr++;
}
return SUCCESS;
}
/*!
This is the main routine for parsing input on the clientSocket.
There should be one command for each line of input. This reads one
line, and looks at the first word (up to the first space character) to
determine the command. Then if there are body or robot indices to read,
it calls a support routine to read those and return a vector of bodies or
robots. These are then passed to the appropriate routine to carry out the
action and write out any necessary results.
*/
void
ClientSocket::readClient()
{
int i,numData,numBodies,numRobots;
double time;
std::vector<Body *> bodyVec;
std::vector<Robot *> robVec;
bool ok;
while ( sock->canReadLine() ) {
line = sock->readLine();
line.truncate(line.length()-1); //strip newline character
lineStrList =
QStringList::split(' ',line);
if (!lineStrList.size() > 0)
return;
strPtr = lineStrList.begin();
#ifdef GRASPITDBG
std::cout <<"Command parser line: "<<line << std::endl;
#endif
if (*strPtr == "getContacts") {
strPtr++; if (strPtr == lineStrList.end()) continue;
numData = (*strPtr).toInt(&ok); strPtr++;
if (!ok) continue;
#ifdef GRASPITDBG
std::cout << "Num data: "<<numData<<std::endl;
#endif
if (readBodyIndList(bodyVec)) continue;
numBodies = bodyVec.size();
for (i=0;i<numBodies;i++)
sendContacts(bodyVec[i],numData);
}
else if (*strPtr == "getAverageContacts") {
strPtr++;
if (readBodyIndList(bodyVec)) continue;
numBodies = bodyVec.size();
for (i=0;i<numBodies;i++)
sendAverageContacts(bodyVec[i]);
}
else if (*strPtr == "getBodyName") {
strPtr++;
if (readBodyIndList(bodyVec)) continue;
numBodies = bodyVec.size();
for (i=0;i<numBodies;i++)
sendBodyName(bodyVec[i]);
}
else if(*strPtr == "setBodyName") {
strPtr++;
int body_index;
if(strPtr != lineStrList.end()){
body_index = strPtr->toInt(&ok);
strPtr++;
if(strPtr == lineStrList.end())
return;
if (body_index == -1 || body_index >= graspItGUI->getIVmgr()->getWorld()->getNumBodies())
{
body_index = graspItGUI->getIVmgr()->getWorld()->getNumBodies() - 1;
}
graspItGUI->getIVmgr()->getWorld()->getBody(body_index)->setName(*strPtr);
}
}
else if (*strPtr == "getRobotName") {
strPtr++;
if (readRobotIndList(robVec)) continue;
numRobots = robVec.size();
for (i=0;i<numRobots;i++)
sendRobotName(robVec[i]);
}
else if (*strPtr == "getDOFVals") {
strPtr++;
if (readRobotIndList(robVec)) continue;
numRobots = robVec.size();
for (i=0;i<numRobots;i++)
sendDOFVals(robVec[i]);
}
else if (*strPtr == "moveDOFs") {
strPtr++;
readDOFVals();
}
else if (*strPtr == "render")
graspItGUI->getIVmgr()->getViewer()->render();
else if (*strPtr == "setDOFForces") {
strPtr++;
if (readRobotIndList(robVec)) continue;
numRobots = robVec.size();
for (i=0;i<numRobots;i++)
if (readDOFForces(robVec[i])==FAILURE) continue;
}
else if ((*strPtr) == "moveDynamicBodies") {
strPtr++;
if (strPtr == lineStrList.end()) ok = FALSE;
else {
time = (*strPtr).toDouble(&ok); strPtr++;
}
if (!ok)
moveDynamicBodies(-1);
else
moveDynamicBodies(time);
}
else if (*strPtr == "computeNewVelocities") {
#ifdef GRASPITDBG
std::cout << "cnv" << std::endl;
#endif
strPtr++; if (strPtr == lineStrList.end()) continue;
time = (*strPtr).toDouble(&ok); strPtr++;
if (!ok) continue;
#ifdef GRASPITDBG
std::cout << time <<std::endl;
#endif
computeNewVelocities(time);
}
else if ((*strPtr) == "outputPlannerResults"){
strPtr++;
outputPlannerResults(0);
}
else if ((*strPtr) == "outputCurrentGrasp"){
strPtr++;
outputCurrentGrasp();
}
else if ((*strPtr) == "sendBodyTransf"){
strPtr++;
verifyInput(1);
sendBodyTransf();
}
else if ((*strPtr) == "setBodyTransf"){
strPtr++;
verifyInput(7);
setBodyTransf();
}
else if ((*strPtr) == "addObstacle"){
strPtr++;
verifyInput(1);
addObstacle(*(strPtr+1));
strPtr+=2;
}
else if ((*strPtr) == "addObject"){
verifyInput(2);
addGraspableBody(*(strPtr+1), *(strPtr+2));
strPtr+=3;
verifyInput(7);
transf object_pose;
readTransf(&object_pose);
World * w = graspItGUI->getIVmgr()->getWorld();
w->getGB(w->getNumGB() - 1)->setTran(object_pose);
}
else if ((*strPtr) == "getCurrentHandTran"){
strPtr++;
getCurrentHandTran();
}
else if ((*strPtr) == "signalGraspUnreachable"){
strPtr+=4;
std::cout << line.toStdString() << std::endl;
graspItGUI->getIVmgr()->blinkBackground();
}
else if ((*strPtr) == "setBackgroundColor"){
++strPtr;
bool ok;
double r = strPtr->toDouble(&ok);
++strPtr;
double g = strPtr->toDouble(&ok);
++strPtr;
double b = strPtr->toDouble(&ok);
++strPtr;
graspItGUI->getIVmgr()->getViewer()->setBackgroundColor(SbColor(r,g,b));
}
else if ((*strPtr) == "getPlannerTarget"){
strPtr+=1;
QTextStream os(sock) ;
os << graspItGUI->getIVmgr()->getWorld()->getCurrentHand()->getGrasp()->getObject()->getName() << "\n";
}
else if ((*strPtr) == "setPlannerTarget"){
QTextStream os(sock);
os << setPlannerTarget(*(strPtr+1)) << "\n";
strPtr+=2;
}
else if ((*strPtr) == "rotateHandLat"){
strPtr+=1;
rotateHandLat();
}
else if ((*strPtr) == "rotateHandLong"){
strPtr+=1;
rotateHandLong();
}
else if ((*strPtr) == "exec"){
strPtr+=1;
exec();
}
else if ((*strPtr) == "next"){
strPtr+=1;
next();
}
else if ((*strPtr) == "addPointCloud")
{
strPtr += 1;
addPointCloud();
//QTextStream os(sock);
//os << addPointCloud() <<" \n";
}
else if ((*strPtr) == "setCameraOrigin")
{
strPtr += 1;
setCameraOrigin();
}
else if ((*strPtr) == "removeBodies"){
strPtr += 1;
removeBodies();
}
else if ((*strPtr) == "clearGraspableBodies"){
strPtr += 1;
removeBodies(true);
}
else if ((*strPtr) == "setGraspAttribute"){
strPtr += 1;
verifyInput(3);
setGraspAttribute();
}
else if ((*strPtr) == "drawCircle"){
strPtr += 1;
drawCircle();
}
else if ((*strPtr) == "drawCursor"){
strPtr += 1;
drawCursor();
}
else if ((*strPtr) == "connectToPlanner")
{
connect(graspItGUI->getIVmgr(), SIGNAL( analyzeApproachDir(GraspPlanningState *) ), this, SLOT(analyzeApproachDir(GraspPlanningState*)));
connect(graspItGUI->getIVmgr(), SIGNAL( analyzeGrasp(const GraspPlanningState *) ), this, SLOT(analyzeGrasp(const GraspPlanningState*)));
connect(graspItGUI->getIVmgr(), SIGNAL( analyzeNextGrasp() ), this, SLOT(analyzeNextGrasp()));
connect(graspItGUI->getIVmgr(), SIGNAL( processWorldPlanner(int) ), this, SLOT( outputPlannerResults(int)));
connect(graspItGUI->getIVmgr(), SIGNAL( runObjectRecognition() ), this, SLOT( runObjectRecognition() ));
connect(graspItGUI->getIVmgr(), SIGNAL( sendString(const QString &) ), this, SLOT( sendString(const QString &) ));
QTextStream os(sock);
os << "1 \n";
os.flush();
}
else if ((*strPtr) =="setRobotColor")
{
setRobotColor();
}
}
}
void ClientSocket::drawCircle()
{
QString circleName = *strPtr;
strPtr++;
bool ok;
double x = .9*(2*strPtr->toDouble(&ok) - 1);
strPtr++;
double y = .9*(2*strPtr->toDouble(&ok) - 1);
strPtr++;
double radius = strPtr->toDouble(&ok);
strPtr++;
double r = strPtr->toDouble(&ok);
strPtr++;
double g = strPtr->toDouble(&ok);
strPtr++;
double b = strPtr->toDouble(&ok);
strPtr++;
double thickness = strPtr->toDouble(&ok);
strPtr++;
double transparency = strPtr->toDouble(&ok);
SbColor circleColor(r,g,b);
graspItGUI->getIVmgr()->drawCircle(circleName, x, y, radius, circleColor, thickness, transparency);
}
void ClientSocket::drawCursor()
{
bool ok;
double x = (strPtr->toDouble(&ok));
strPtr++;
double y = (strPtr->toDouble(&ok));
BCIService::getInstance()->emitCursorPosition(x,y);
}
void ClientSocket::setGraspAttribute()
{
double graspIdentifier = strPtr->toDouble();
strPtr += 1;
QString attributeString = *strPtr;
strPtr += 1;
double value = strPtr->toDouble();
strPtr += 1;
if (!currentWorldPlanner())
return;
QMutexLocker lock(¤tWorldPlanner()->mListAttributeMutex);
for(int i = 0; i < currentWorldPlanner()->getListSize(); i++ )
{
const GraspPlanningState * gs = currentWorldPlanner()->getGrasp(i);
if (gs->getAttribute("graspId") == graspIdentifier)
{
currentWorldPlanner()->setGraspAttribute(i,attributeString, value);
std::cout << "SetGraspAttribute graspId " << graspIdentifier << " attributeString " << value << "\n";
break;
}
}
analyzeNextGrasp();
}
/*!
Given a pointer to a body, this examines all the contacts on that body and
finds the average wrench acting on the body through those contacts and the
average contact location in body coordinates. This is written to the
socket on 2 separate lines.
*/
void
ClientSocket::sendAverageContacts(Body* bod)
{
QTextStream os(sock);
std::list<Contact *> contactList;
std::list<Contact *>::iterator cp;
int i,numContacts;
double totalWrench[6]={0.0,0.0,0.0,0.0,0.0,0.0};
double *wrench;
vec3 totalLoc = vec3::ZERO;
numContacts = bod->getNumContacts();
contactList = bod->getContacts();
for (cp=contactList.begin();cp!=contactList.end();cp++) {
wrench = (*cp)->getDynamicContactWrench();
for (i=0;i<6;i++) totalWrench[i] += wrench[i];
totalLoc += (*cp)->getContactFrame().translation();
}
if (numContacts>1) {
for (i=0;i<6;i++) totalWrench[i] /= numContacts;
totalLoc = totalLoc / numContacts;
}
os << totalWrench[0]<<" "<<totalWrench[1]<<" "<<totalWrench[2]<<
" "<<totalWrench[3]<<" "<<totalWrench[4]<<" "<<totalWrench[5]<<"\n";
os << totalLoc[0] << " "<<totalLoc[1] << " " <<totalLoc[2]<<"\n";
}
/*!
Given a pointer to a body, this writes the name of the body and a newline
to the socket.
*/
void
ClientSocket::sendBodyName(Body* bod)
{
QTextStream os(sock);
std::cout << "sending " << bod->getName().latin1() << "\n";
os << bod->getName().latin1() << "\n";
}
/*!
Given a pointer to a robot, this writes the name of the robot and a newline
to the socket.
*/
void
ClientSocket::sendRobotName(Robot* rob)
{
QTextStream os(sock);
std::cout << "sending " << rob->getName().latin1() << "\n";
os << rob->getName().latin1() << "\n";
}
/*!
Given a pointer to a body, this first writes a line containing the number
of contacts on the body. Then it writes \a numData lines for each contact.
The first line contains the 6 numbers of the contact wrench. The next line
(if required) contains the 3 numbers specifying the contact location in
body coordinates, and the last line (if required) contains the scalar
constraint error for that contact.
*/
void
ClientSocket::sendContacts(Body *bod,int numData)
{
QTextStream os(sock);
std::list<Contact *> contactList;
std::list<Contact *>::iterator cp;
vec3 loc;
double err;
double *wrench;
#ifdef GRASPITDBG
std::cout << "sending numContacts: "<<bod->getNumContacts()<<std::endl;
#endif
os << bod->getNumContacts()<<"\n";
contactList = bod->getContacts();
for (cp=contactList.begin();cp!=contactList.end();cp++) {
wrench = (*cp)->getDynamicContactWrench();
loc = (*cp)->getContactFrame().translation();
err = (*cp)->getConstraintError();
os << wrench[0]<<" "<<wrench[1]<<" "<<wrench[2]<<" "<<wrench[3]<<" "<<
wrench[4]<<" "<<wrench[5]<<"\n";
if (numData > 1)
os << loc[0] << " "<< loc[1] << " " << loc[2]<<"\n";
if (numData > 2)
os << err << "\n";
}
}
/*!
Given a pointer to robot, this first writes a line to the socket containing
the number of %DOF's in the robot, then for each %DOF, it writes a line
containting the current value of that %DOF.
*/
void
ClientSocket::sendDOFVals(Robot *rob)
{
QTextStream os(sock);
int i;
os << rob->getNumDOF() << "\n";
for (i=0;i<rob->getNumDOF();i++)
os << rob->getDOF(i)->getVal() << "\n";
}
/*!
After the readDOFVals command was read by readClient, this expects to
read a valid robot index, then the correct number of %DOF's for this robot,
then a desired value for each %DOF, and finally a value for each DOF to step
by during the move. It performs the %DOF moves, finds the new contacts,
updates the grasp, and then it sends one line for each %DOF containing
the actual value for the %DOF after the move.
*/
int
ClientSocket::readDOFVals()
{
Robot *rob;
double *val,*stepby;
QTextStream os(sock);
int numDOF,i,robNum;
bool ok=TRUE;
#ifdef GRASPITDBG
std::cout << "in read dof vals"<<std::endl;
#endif
if (strPtr == lineStrList.end()) ok=FALSE;
if (ok) robNum = (*strPtr).toInt(&ok);
if (!ok || robNum < 0 ||
robNum >= graspItGUI->getIVmgr()->getWorld()->getNumRobots()) {
os <<"Error: Robot does not exist.\n";
return FAILURE;
}
rob = graspItGUI->getIVmgr()->getWorld()->getRobot(robNum);
#ifdef GRASPITDBG
std::cout << "robnum: "<<robNum<<std::endl;
#endif
strPtr++;
if (strPtr == lineStrList.end()) return FAILURE;
numDOF=(*strPtr).toInt(&ok);
if (!ok) return FAILURE;
strPtr++;
#ifdef GRASPITDBG
std::cout << "read robot has: "<< numDOF << " DOF?"<<std::endl;
#endif
if (numDOF < 1) {
#ifdef GRASPITDBG
std::cout << "numDOF was zero."<<std::endl;
#endif
return FAILURE;
}
if (numDOF != rob->getNumDOF()) {
os <<"Error: robot has " << rob->getNumDOF() <<" DOF."<<endl;
return FAILURE;
}
val = new double[numDOF];
stepby = new double[numDOF];
for (i=0;i<rob->getNumDOF();i++) {
if (strPtr == lineStrList.end()) return FAILURE;
val[i] = (*strPtr).toDouble(&ok);
if (!ok) return FAILURE;
strPtr++;
#ifdef GRASPITDBG
std::cout<<val[i]<<" ";
#endif
}
#ifdef GRASPITDBG
std::cout<<std::endl;
#endif
for (i=0;i<rob->getNumDOF();i++) {
if (strPtr == lineStrList.end()) return FAILURE;
stepby[i] = (*strPtr).toDouble(&ok);
if (!ok) return FAILURE;
strPtr++;
}
rob->moveDOFToContacts(val,stepby,true);
// these should be separate commands
graspItGUI->getIVmgr()->getWorld()->findAllContacts();
graspItGUI->getIVmgr()->getWorld()->updateGrasps();
for (i=0;i<rob->getNumDOF();i++) {
os << rob->getDOF(i)->getVal() << "\n";
#ifdef GRASPITDBG
std::cout << "Sending: "<< rob->getDOF(i)->getVal() << "\n";
#endif
}
delete [] val;
delete [] stepby;
return SUCCESS;
}
/*!
After the readDOFForces command was read by readClient, this expects to
the correct number of %DOF's for this robot, and then a desired force for
each %DOF. It sets each %DOF force and sends a line for each containing
the current force.
*/
int
ClientSocket::readDOFForces(Robot *rob)
{
double val;
bool ok;
// QTextStream is(this);
QTextStream os(sock);
int numDOF,i;
if (strPtr == lineStrList.end()) return FAILURE;
numDOF=(*strPtr).toInt(&ok);
if (!ok) return FAILURE;
strPtr++;
#ifdef GRASPITDBG
std::cout << "read robot has: "<< numDOF << " DOF?"<<std::endl;
#endif
if (numDOF < 1) {
#ifdef GRASPITDBG
std::cout << "numDOF was zero."<<std::endl;
#endif
return FAILURE;
}
if (numDOF != rob->getNumDOF()) {
os <<"Error: robot has " << rob->getNumDOF() <<" DOF."<<endl;
return FAILURE;
}
for (i=0;i<rob->getNumDOF();i++) {
if (strPtr == lineStrList.end()) return FAILURE;
val = (*strPtr).toDouble(&ok);
if (!ok) return FAILURE;
strPtr++;
rob->getDOF(i)->setForce(val);
#ifdef GRASPITDBG
std::cout<<val<<" ";
#endif
}
#ifdef GRASPITDBG
std::cout<<std::endl;
#endif
for (i=0;i<rob->getNumDOF();i++) {
os << rob->getDOF(i)->getForce() << "\n";
#ifdef GRASPITDBG
std::cout << "Sending: "<< rob->getDOF(i)->getForce() << "\n";
#endif
}
return SUCCESS;
}
/*
//not finished yet
void
ClientSocket::moveBody(Body *bod)
{
double x,y,z,ax,ay,az,r;
QTextStream is(this);
is>>x>>y>>z>>ax>>ay>>az>>r;
bod = NULL; // unused parameter warning
}
*/
/*!
If given a positive time step value, this will move the dynamic world bodies
with that value. Otherwise it uses the world default time step. A line
with the actual length of that timestep is then sent back.
*/
void
ClientSocket::moveDynamicBodies(double timeStep)
{
QTextStream os(sock);
if (timeStep<0)
timeStep = graspItGUI->getIVmgr()->getWorld()->getTimeStep();
double actualTimeStep =
graspItGUI->getIVmgr()->getWorld()->moveDynamicBodies(timeStep);
if (actualTimeStep < 0)
os << "Error: Timestep failsafe reached.\n";
else
os << actualTimeStep << "\n";
}
/*!
This calls the computeNewVelocities routine in the dynamics with the given
value of the timestep. Afterwards, it sends out a line containing the
result code from that operation.
*/
void
ClientSocket::computeNewVelocities(double timeStep)
{
QTextStream os(sock);
int result = graspItGUI->getIVmgr()->getWorld()->computeNewVelocities(timeStep);
os << result << "\n";
}
void
ClientSocket::updatePlannerParams(QStringList & qsl)
{
/*parse arguments */
//confidence arguments
return;
}
void
ClientSocket::outputPlannerResults(int solution_index)
{
QTextStream os(sock);
//Test for existence of planner
if(!currentWorldPlanner()){
os << "No Planner Set \n";
return;
}
//Iterate through solutions list outputing each one
//WARNING:: THIS IS NOT REALLY THREADSAFE BECAUSE THE PLANNER KEEPS RUNNING
//FIXME
//os << currentWorldPlanner()->getListSize() << "\n";
os << "doGrasp {";
// for(int solution_index =0; solution_index < currentWorldPlanner()->getListSize(); ++solution_index)
// {
os << *(currentWorldPlanner()->getGrasp(solution_index)) << ',';
// }
os << '}';
os << '\n';
std::cout << "sent grasp\n";
return;
}
/*Signal object recognition to run.
*/
void ClientSocket::runObjectRecognition()
{
QTextStream os(sock);
os << "runObjectRecognition \n";
return;
}
void ClientSocket::sendString(const QString & message)
{
QTextStream os(sock);
os << message << "\n";
os.flush();
sock->flush();
return;
}
void
ClientSocket::outputCurrentGrasp()
{
QTextStream os(sock);
GraspPlanningState g(graspItGUI->getIVmgr()->getWorld()->getCurrentHand());
g.setPostureType(POSE_DOF, false);
g.saveCurrentHandState();
os << "doGrasp{";
os << g <<',';
os << '}';
os << '\n';
std::cout << "sent grasp: " << g << " \n";
}
/*!
This is not complete yet.
void
ClientSocket::readTorques()
{
QString line;
line = readLine();
int numDOF = line.toInt();
if (numDOF < 0) {} //unused parameter warning
}
*/
//Body transforms are sent backwards by the planner for some reason compared to the overloading
//of << for transfs
void ClientSocket::setBodyTransf(){
//FIXME add checking for badly formatted input here.
std::vector <Body *> bd;
readBodyIndList(bd);
transf object_pose;
for(std::vector<Body *>::iterator bp = bd.begin(); bp != bd.end(); ++bp){
readTransf(&object_pose);
(*bp)->setTran(object_pose);
}
QTextStream os(sock);
os << "1 \n";
os.flush();
}
void ClientSocket::sendBodyTransf(){
std::vector <Body *> bd;
readBodyIndList(bd);
QTextStream os(sock);
for(std::vector<Body *>::iterator bp = bd.begin(); bp != bd.end(); ++bp){
//this is a hack around the overloading for standard strings and not qstrings.
//this should be templated
std::stringstream ss(std::stringstream::in | std::stringstream::out);
ss << (*bp)->getTran().translation() << (*bp)->getTran().rotation() << "\n";
std::cout << ss.str() << "\n";
os << QString(ss.str().c_str());
}
os << "\n";
os.flush();