-
Notifications
You must be signed in to change notification settings - Fork 0
/
arnlServerWithTourCallbacks.cpp
962 lines (748 loc) · 36.7 KB
/
arnlServerWithTourCallbacks.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
#include "Aria.h"
#include "ArNetworking.h"
#include "Arnl.h"
#include "ArPathPlanningTask.h"
#include "ArLocalizationTask.h"
#include "ArDocking.h"
/** Example of an ArASyncTask subclass that runs new threads when ARNL reaches goals.
At each goal, a new thread is created which can perform some action
asyncronously (while the ARNL path planning thread continues).
One instance of this class is created in the program's main() function below
providing the ARNL path planning task, ArRobot object, etc. and it sets everything up in its
constructor.
To do something similar for your application, you can rename this class (and
its instantiation in the main() function below), and modify what is done in
the runThread() method.
Note one instance of this class is created for the
whole program, but new threads may be created at any time (whenever ARNL happens
to reach a goal), these threads are sharing access to the variables withhin the
class, and so this access is synchronized using a mutex. Make certain you do
not keep the mutex locked during any long running operations or operations of
indeterminate duration, and that in all logical paths through the code, the
mutex is eventually unlocked if locked.
This class also adds some parameters to the global ArConfig, so users can
modify them. The parameters are added to a "ARNL Tour Goal Task Example" section.
*/
class TourGoalTaskExample : public virtual ArASyncTask
{
public:
ArPathPlanningTask *myPathPlanner;
ArServerModeGoto *myServerMode;
int myCurrentGoal;
ArFunctor1C<TourGoalTaskExample, ArPose> myGoalDoneCB;
ArRobot *myRobot;
int myApproachDist;
int myNumGoals;
bool myEnabled;
ArMutex myMutex;
void waitForMoveDone() {
while(!myRobot->isMoveDone())
ArUtil::sleep(100);
}
void lock() {
myMutex.lock();
}
void unlock() {
myMutex.unlock();
}
/** A callback is added that performs tasks at each goal, and some parameters
* are addded to ArConfig.
*/
TourGoalTaskExample(ArPathPlanningTask *pp, ArRobot *robot, ArServerModeGoto *servermode = NULL, ArArgumentParser *argParser = NULL) :
myPathPlanner(pp), myServerMode(servermode), myCurrentGoal(1), myGoalDoneCB(this, &TourGoalTaskExample::goalDone),
myRobot(robot), myApproachDist(250), myNumGoals(4), myEnabled(true)
{
// Add some parameters to ArConfig in a new "ARNL ASyncTask Example" section so the user can adjust them from
// MobileEyes:
ArConfig *config = Aria::getConfig();
config->addParam(ArConfigArg("ApproachDist", &myApproachDist, "distance to approach drop point"), "ARNL ASyncTask Example");
config->addParam(ArConfigArg("NumGoals", &myNumGoals, "number of goals in chain"), "ARNL ASyncTask Example");
config->addParam(ArConfigArg("Enabled", &myEnabled, "enable example robot task at all goals"), "ARNL ASyncTask Example");
if(!myEnabled) return;
// Add a callback to be called when ARNL reaches goals:
myPathPlanner->addGoalDoneCB(&myGoalDoneCB);
ArLog::log(ArLog::Normal, "ArTourGoalTaskExample created: will perform tasks at each goal, and then send ARNL to another. ");
}
/* This is the "goal done" callback called by the ARNL path planning thread
* when the a goal point is sucessfully reached. We run a new thread here to
* perform our task.
*/
void goalDone(ArPose pose)
{
runAsync();
}
/* This is called for each new thread, at each goal point.
* It moves the robot forward a bit, tells Actin
* to do the next arm action (numbered from 0 to myNumGoals), waits 2 seconds,
* then backs the mobile robot up. Then it tells the ARNL path planner to
* navigate to the next goal point in the chain (named Goal 0, Goal 1, Goal 2, etc.)
* The last goal point is special, no arm action and the chain of ARNL goals
* stops. The robot will wait at this goal point until sent to the first
* goal manually from MobileEyes.
*/
void *runThread(void *)
{
// Make copies of variables shared between threads
lock();
int currentGoal = myCurrentGoal;
int numGoals = myNumGoals;
int moveDist = myApproachDist;
unlock();
// if at end of chain, stop chain
if(currentGoal == numGoals)
{
ArLog::log(ArLog::Normal, "Waiting to be loaded, end of chain.");
if(myServerMode) myServerMode->setStatus("End of goal chain.");
lock();
myCurrentGoal = 1;
unlock();
return 0; // end of thread
}
/* In this example, we will move the robot forward a bit, wait, then move it
back.
In your application, you could do somethng here like trigger devices, cameras,
sensors, output, speech, etc. You can access the current goal name and
use that to control the activity, or use that goal name to obtain the
goal object from the map ArMap object which has additional properties of
the goal.
*/
// move forward a bit
ArLog::log(ArLog::Normal, "Moving forward a bit");
if(myServerMode) myServerMode->setStatus("Moving forward");
myRobot->clearDirectMotion();
myRobot->move(moveDist);
waitForMoveDone();
myRobot->clearDirectMotion();
ArUtil::sleep(500);
// Wait a bit.
ArLog::log(ArLog::Normal, "Would do goal-specific task at goal %d.", currentGoal);
ArLog::log(ArLog::Normal, "Waiting 3 sec.");
if(myServerMode) myServerMode->setStatus("Waiting 3 sec");
ArUtil::sleep(3000);
// back up a bit
ArLog::log(ArLog::Normal, "Backing up a bit");
if(myServerMode) myServerMode->setStatus("Backing up a bit");
myRobot->clearDirectMotion();
myRobot->move(-moveDist);
waitForMoveDone();
myRobot->clearDirectMotion();
ArUtil::sleep(500);
/* Go to the next goal in the chain. The name is assumed to be "Goal X"
where X is the goal index number. You could use another scheme for
naming goals, or you could store a list of strings in this class
*/
++currentGoal;
if(currentGoal > numGoals) currentGoal = 0;
char name[128];
snprintf(name, 127, "Goal %d", currentGoal);
ArLog::log(ArLog::Normal, "Going to next goal %s", name);
if(myServerMode) myServerMode->setStatus("ASyncTask example done. Going to next goal.");
myPathPlanner->pathPlanToGoal(name);
// Save the new goal index
lock();
myCurrentGoal = currentGoal;
unlock();
// This is the end of the thread.
return 0;
}
};
/* ------------ original arnlServer.cpp code follows -------------------- */
void logOptions(const char *progname)
{
ArLog::log(ArLog::Normal, "Usage: %s [options]\n", progname);
ArLog::log(ArLog::Normal, "[options] are any program options listed below, or any ARNL configuration");
ArLog::log(ArLog::Normal, "parameters as -name <value>, see params/arnl.p for list.");
ArLog::log(ArLog::Normal, "For example, -map <map file>.");
Aria::logOptions();
}
bool gyroErrored = false;
const char* getGyroStatusString(ArRobot* robot)
{
if(!robot || !robot->getOrigRobotConfig() || robot->getOrigRobotConfig()->getGyroType() < 2) return "N/A";
if(robot->getFaultFlags() & ArUtil::BIT4)
{
gyroErrored = true;
return "ERROR/OFF";
}
if(gyroErrored)
{
return "OK but error before";
}
return "OK";
}
int main(int argc, char **argv)
{
// Initialize Aria and Arnl global information
Aria::init();
Arnl::init();
// The robot object
ArRobot robot;
// Parse the command line arguments.
ArArgumentParser parser(&argc, argv);
// Set up our simpleConnector, to connect to the robot and laser
//ArSimpleConnector simpleConnector(&parser);
ArRobotConnector robotConnector(&parser, &robot);
// Connect to the robot
if (!robotConnector.connectRobot())
{
ArLog::log(ArLog::Normal, "Error: Could not connect to robot... exiting");
Aria::exit(3);
}
// Set up where we'll look for files. Arnl::init() set Aria's default
// directory to Arnl's default directory; addDirectories() appends this
// "examples" directory.
char fileDir[1024];
ArUtil::addDirectories(fileDir, sizeof(fileDir), Aria::getDirectory(),
"examples");
// To direct log messages to a file, or to change the log level, use these calls:
//ArLog::init(ArLog::File, ArLog::Normal, "log.txt", true, true);
//ArLog::init(ArLog::File, ArLog::Verbose);
// Add a section to the configuration to change ArLog parameters
ArLog::addToConfig(Aria::getConfig());
// set up a gyro (if the robot is older and its firmware does not
// automatically incorporate gyro corrections, then this object will do it)
ArAnalogGyro gyro(&robot);
// Our networking server
ArServerBase server;
// Set up our simpleOpener, used to set up the networking server
ArServerSimpleOpener simpleOpener(&parser);
// the laser connector
ArLaserConnector laserConnector(&parser, &robot, &robotConnector);
// Tell the laser connector to always connect the first laser since
// this program always requires a laser.
parser.addDefaultArgument("-connectLaser");
// Load default arguments for this computer (from /etc/Aria.args, environment
// variables, and other places)
parser.loadDefaultArguments();
// Parse arguments
if (!Aria::parseArgs() || !parser.checkHelpAndWarnUnparsed())
{
logOptions(argv[0]);
Aria::exit(1);
}
// This causes Aria::exit(9) to be called if the robot unexpectedly
// disconnects
ArGlobalFunctor1<int> shutdownFunctor(&Aria::exit, 9);
robot.addDisconnectOnErrorCB(&shutdownFunctor);
// Create an ArSonarDevice object (ArRangeDevice subclass) and
// connect it to the robot.
ArSonarDevice sonarDev;
robot.addRangeDevice(&sonarDev);
// This object will allow robot's movement parameters to be changed through
// a Robot Configuration section in the ArConfig global configuration facility.
ArRobotConfig robotConfig(&robot);
// Include gyro configuration options in the robot configuration section.
robotConfig.addAnalogGyro(&gyro);
// Start the robot thread.
robot.runAsync(true);
// connect the laser(s) if it was requested, this adds them to the
// robot too, and starts them running in their own threads
if (!laserConnector.connectLasers())
{
ArLog::log(ArLog::Normal, "Could not connect to all lasers... exiting\n");
Aria::exit(2);
}
// find the laser we should use for localization and/or mapping,
// which will be the first laser
robot.lock();
ArLaser *firstLaser = robot.findLaser(1);
if (firstLaser == NULL || !firstLaser->isConnected())
{
ArLog::log(ArLog::Normal, "Did not have laser 1 or it is not connected, cannot start localization and/or mapping... exiting");
Aria::exit(2);
}
robot.unlock();
/* Create and set up map object */
// Set up the map object, this will look for files in the examples
// directory (unless the file name starts with a /, \, or .
// You can take out the 'fileDir' argument to look in the program's current directory
// instead.
// When a configuration file is loaded into ArConfig later, if it specifies a
// map file, then that file will be loaded as the map.
ArMap map(fileDir);
// set it up to ignore empty file names (otherwise if a configuration omits
// the map file, the whole configuration change will fail)
map.setIgnoreEmptyFileName(true);
// ignore the case, so that if someone is using MobileEyes or
// MobilePlanner from Windows and changes the case on a map name,
// it will still work.
map.setIgnoreCase(true);
/* Create localization and path planning threads */
ArPathPlanningTask pathTask(&robot, &sonarDev, &map);
ArLog::log(ArLog::Normal, "Creating laser localization task");
// Laser Monte-Carlo Localization
ArLocalizationTask locTask(&robot, firstLaser, &map);
// Set some options on each laser that the laser connector
// connected to.
std::map<int, ArLaser *>::iterator laserIt;
for (laserIt = robot.getLaserMap()->begin();
laserIt != robot.getLaserMap()->end();
laserIt++)
{
int laserNum = (*laserIt).first;
ArLaser *laser = (*laserIt).second;
// Skip lasers that aren't connected
if(!laser->isConnected())
continue;
// add the disconnectOnError CB to shut things down if the laser
// connection is lost
laser->addDisconnectOnErrorCB(&shutdownFunctor);
// set the number of cumulative readings the laser will take
laser->setCumulativeBufferSize(200);
// add the lasers to the path planning task
pathTask.addRangeDevice(laser, ArPathPlanningTask::BOTH);
// set the cumulative clean offset (so that they don't all fire at once)
laser->setCumulativeCleanOffset(laserNum * 100);
// reset the cumulative clean time (to make the new offset take effect)
laser->resetLastCumulativeCleanTime();
// Add the packet count to the Aria info strings (It will be included in
// MobileEyes custom details so you can monitor whether the laser data is
// being received correctly)
std::string laserPacketCountName;
laserPacketCountName = laser->getName();
laserPacketCountName += " Packet Count";
Aria::getInfoGroup()->addStringInt(
laserPacketCountName.c_str(), 10,
new ArRetFunctorC<int, ArLaser>(laser,
&ArLaser::getReadingCount));
}
// Used for optional multirobot features (see below) (TODO move to multirobot
// example?)
ArClientSwitchManager clientSwitch(&server, &parser);
/* Start the server */
// Open the networking server
if (!simpleOpener.open(&server, fileDir, 240))
{
ArLog::log(ArLog::Normal, "Error: Could not open server.");
exit(2);
}
/* Create various services that provide network access to clients (such as
* MobileEyes), as well as add various additional features to ARNL */
// ARNL can optionally get information about the positions of other robots from a
// "central server" (see central server example program), if command
// line options specifying the address of the central server was given.
// If there is no central server, then the address of each other robot
// can instead be given in the configuration, and the multirobot systems
// will connect to each robot (or "peer") individually.
// TODO move this to multirobot example?
bool usingCentralServer = false;
if(clientSwitch.getCentralServerHostName() != NULL)
usingCentralServer = true;
// if we're using the central server then we want to create the
// multiRobot central classes
if (usingCentralServer)
{
// Make the handler for multi robot information (this sends the
// information to the central server)
//ArServerHandlerMultiRobot *handlerMultiRobot =
new ArServerHandlerMultiRobot(&server, &robot,
&pathTask,
&locTask, &map);
// Normally each robot, and the central server, must all have
// the same map name for the central server to share robot
// information. (i.e. they are operating in the same space).
// This changes the map name that ArServerHandlerMutliRobot
// reports to the central server, in case you want this individual
// robot to load a different map file name, but still report
// the common map file to the central server.
//handlerMultiRobot->overrideMapName("central.map");
// the range device that gets the multi robot information from
// the central server and presents it as virtual range readings
// to ARNL
ArMultiRobotRangeDevice *multiRobotRangeDevice = new ArMultiRobotRangeDevice(&server);
robot.addRangeDevice(multiRobotRangeDevice);
pathTask.addRangeDevice(multiRobotRangeDevice,
ArPathPlanningTask::BOTH);
// Set up options for drawing multirobot information in MobileEyes.
multiRobotRangeDevice->setCurrentDrawingData(
new ArDrawingData("polyDots", ArColor(125, 125, 0),
100, 73, 1000), true);
multiRobotRangeDevice->setCumulativeDrawingData(
new ArDrawingData("polyDots", ArColor(125, 0, 125),
100, 72, 1000), true);
// This sets up the localization to use the known poses of other robots
// for its localization in cases where numerous robots crowd out the map.
locTask.setMultiRobotCallback(multiRobotRangeDevice->getOtherRobotsCB());
}
// if we're not using a central server then create the multirobot peer classes
else
{
// set the path planning so it uses the explicit collision range for how far its planning
pathTask.setUseCollisionRangeForPlanningFlag(true);
// make our thing that gathers information from the other servers
ArServerHandlerMultiRobotPeer *multiRobotPeer = NULL;
ArMultiRobotPeerRangeDevice *multiRobotPeerRangeDevice = NULL;
multiRobotPeerRangeDevice = new ArMultiRobotPeerRangeDevice(&map);
// make our thing that sends information to the other servers
multiRobotPeer = new ArServerHandlerMultiRobotPeer(&server, &robot,
&pathTask, &locTask);
// hook the two together so they both know what priority this robot is
multiRobotPeer->setNewPrecedenceCallback(
multiRobotPeerRangeDevice->getSetPrecedenceCallback());
// hook the two together so they both know what priority this
// robot's fingerprint is
multiRobotPeer->setNewFingerprintCallback(
multiRobotPeerRangeDevice->getSetFingerprintCallback());
// hook the two together so that the range device can call on the
// server handler to change its fingerprint
multiRobotPeerRangeDevice->setChangeFingerprintCB(
multiRobotPeer->getChangeFingerprintCB());
// then add the robot to the places it needs to be
robot.addRangeDevice(multiRobotPeerRangeDevice);
pathTask.addRangeDevice(multiRobotPeerRangeDevice,
ArPathPlanningTask::BOTH);
// Set the range device so that we can see the information its using
// to avoid, you can comment these out in order to not see them
multiRobotPeerRangeDevice->setCurrentDrawingData(
new ArDrawingData("polyDots", ArColor(125, 125, 0),
100, 72, 1000), true);
multiRobotPeerRangeDevice->setCumulativeDrawingData(
new ArDrawingData("polyDots", ArColor(125, 0, 125),
100, 72, 1000), true);
// This sets up the localization to use the known poses of other robots
// for its localization in cases where numerous robots crowd out the map.
locTask.setMultiRobotCallback(
multiRobotPeerRangeDevice->getOtherRobotsCB());
}
/* Add additional range devices to the robot and path planning task (so it
avoids obstacles detected by these devices) */
// Add IR range device to robot and path planning task (so it avoids obstacles
// detected by this device)
robot.lock();
ArIRs irs;
robot.addRangeDevice(&irs);
pathTask.addRangeDevice(&irs, ArPathPlanningTask::CURRENT);
// Add bumpers range device to robot and path planning task (so it avoids obstacles
// detected by this device)
ArBumpers bumpers;
robot.addRangeDevice(&bumpers);
pathTask.addRangeDevice(&bumpers, ArPathPlanningTask::CURRENT);
// Add range device which uses forbidden regions given in the map to give virtual
// range device readings to ARNL. (so it avoids obstacles
// detected by this device)
ArForbiddenRangeDevice forbidden(&map);
robot.addRangeDevice(&forbidden);
pathTask.addRangeDevice(&forbidden, ArPathPlanningTask::CURRENT);
robot.unlock();
// Action to slow down robot when localization score drops but not lost.
ArActionSlowDownWhenNotCertain actionSlowDown(&locTask);
pathTask.getPathPlanActionGroup()->addAction(&actionSlowDown, 140);
// Action to stop the robot when localization is "lost" (score too low)
ArActionLost actionLostPath(&locTask, &pathTask);
pathTask.getPathPlanActionGroup()->addAction(&actionLostPath, 150);
// Arnl uses this object when it must replan its path because its
// path is completely blocked. It will use an older history of sensor
// readings to replan this new path. This should not be used with SONARNL
// since sonar readings are not accurate enough and may prevent the robot
// from planning through space that is actually clear.
ArGlobalReplanningRangeDevice replanDev(&pathTask);
// Service to provide drawings of data in the map display :
ArServerInfoDrawings drawings(&server);
drawings.addRobotsRangeDevices(&robot);
drawings.addRangeDevice(&replanDev);
/* Draw a box around the local path planning area use this
(You can enable this particular drawing from custom commands
which is set up down below in ArServerInfoPath) */
ArDrawingData drawingDataP("polyLine", ArColor(200,200,200), 1, 75);
ArFunctor2C<ArPathPlanningTask, ArServerClient *, ArNetPacket *>
drawingFunctorP(&pathTask, &ArPathPlanningTask::drawSearchRectangle);
drawings.addDrawing(&drawingDataP, "Local Plan Area", &drawingFunctorP);
/* Show the sample points used by MCL */
ArDrawingData drawingDataL("polyDots", ArColor(0,255,0), 100, 75);
ArFunctor2C<ArLocalizationTask, ArServerClient *, ArNetPacket *>
drawingFunctorL(&locTask, &ArLocalizationTask::drawRangePoints);
drawings.addDrawing(&drawingDataL, "Localization Points", &drawingFunctorL);
// "Custom" commands. You can add your own custom commands here, they will
// be available in MobileEyes' custom commands (enable in the toolbar or
// access through Robot Tools)
ArServerHandlerCommands commands(&server);
// These provide various kinds of information to the client:
ArServerInfoRobot serverInfoRobot(&server, &robot);
ArServerInfoSensor serverInfoSensor(&server, &robot);
ArServerInfoPath serverInfoPath(&server, &robot, &pathTask);
serverInfoPath.addSearchRectangleDrawing(&drawings);
serverInfoPath.addControlCommands(&commands);
// Provides localization info and allows the client (MobileEyes) to relocalize at a given
// pose:
ArServerInfoLocalization serverInfoLocalization(&server, &robot, &locTask);
ArServerHandlerLocalization serverLocHandler(&server, &robot, &locTask);
// If you're using MobileSim, ArServerHandlerLocalization sends it a command
// to move the robot's true pose if you manually do a localization through
// MobileEyes. To disable that behavior, use this constructor call instead:
// ArServerHandlerLocalization serverLocHandler(&server, &robot, true, false);
// The fifth argument determines whether to send the command to MobileSim.
// Provide the map to the client (and related controls):
ArServerHandlerMap serverMap(&server, &map);
// These objects add some simple (custom) commands to 'commands' for testing and debugging:
ArServerSimpleComUC uCCommands(&commands, &robot); // Send any command to the microcontroller
ArServerSimpleComMovementLogging loggingCommands(&commands, &robot); // configure logging
ArServerSimpleComLogRobotConfig configCommands(&commands, &robot); // trigger logging of the robot config parameters
// ArServerSimpleServerCommands serverCommands(&commands, &server); // monitor networking behavior (track packets sent etc.)
// service that allows the client to monitor the communication link status
// between the robot and the client.
//
ArServerHandlerCommMonitor handlerCommMonitor(&server);
// service that allows client to change configuration parameters in ArConfig
ArServerHandlerConfig handlerConfig(&server, Aria::getConfig(),
Arnl::getTypicalDefaultParamFileName(),
Aria::getDirectory());
/* Set up the possible modes for remote control from a client such as
* MobileEyes:
*/
// Mode To go to a goal or other specific point:
ArServerModeGoto modeGoto(&server, &robot, &pathTask, &map,
locTask.getRobotHome(),
locTask.getRobotHomeCallback());
// Mode To stop and remain stopped:
ArServerModeStop modeStop(&server, &robot);
// Cause the sonar to turn off automatically
// when the robot is stopped, and turn it back on when commands to move
// are sent. (Note, if using SONARNL to localize, then don't do this
// since localization may get lost)
ArSonarAutoDisabler sonarAutoDisabler(&robot);
// Teleoperation modes To drive by keyboard, joystick, etc:
ArServerModeRatioDrive modeRatioDrive(&server, &robot);
// ArServerModeDrive modeDrive(&server, &robot); // Older mode for compatability
// Prevent normal teleoperation driving if localization is lost using
// a high-priority action, which enables itself when the particular mode is
// active.
// (You have to enter unsafe drive mode to drive when lost.)
ArActionLost actionLostRatioDrive(&locTask, &pathTask, &modeRatioDrive);
modeRatioDrive.getActionGroup()->addAction(&actionLostRatioDrive, 110);
// Add drive mode section to the configuration, and also some custom (simple) commands:
modeRatioDrive.addToConfig(Aria::getConfig(), "Teleop settings");
modeRatioDrive.addControlCommands(&commands);
// Wander mode (also prevent wandering if lost):
ArServerModeWander modeWander(&server, &robot);
ArActionLost actionLostWander(&locTask, &pathTask, &modeWander);
modeWander.getActionGroup()->addAction(&actionLostWander, 110);
// This provides a small table of interesting information for the client
// to display to the operator. You can add your own callbacks to show any
// data you want.
ArServerInfoStrings stringInfo(&server);
Aria::getInfoGroup()->addAddStringCallback(stringInfo.getAddStringFunctor());
// Provide a set of informational data (turn on in MobileEyes with
// View->Custom Details)
Aria::getInfoGroup()->addStringInt(
"Motor Packet Count", 10,
new ArConstRetFunctorC<int, ArRobot>(&robot,
&ArRobot::getMotorPacCount));
Aria::getInfoGroup()->addStringDouble(
"Laser Localization Score", 8,
new ArRetFunctorC<double, ArLocalizationTask>(
&locTask, &ArLocalizationTask::getLocalizationScore),
"%.03f");
Aria::getInfoGroup()->addStringInt(
"Laser Loc Num Samples", 8,
new ArRetFunctorC<int, ArLocalizationTask>(
&locTask, &ArLocalizationTask::getCurrentNumSamples),
"%4d");
// Display gyro status if gyro is enabled and is being handled by the firmware (gyro types 2, 3, or 4).
// (If the firmware detects an error communicating with the gyro or IMU it
// returns a flag, and stops using it.)
// (This gyro type parameter, and fault flag, are only in ARCOS, not Seekur firmware)
if(robot.getOrigRobotConfig() && robot.getOrigRobotConfig()->getGyroType() > 1)
{
Aria::getInfoGroup()->addStringString(
"Gyro/IMU Status", 10,
new ArGlobalRetFunctor1<const char*, ArRobot*>(&getGyroStatusString, &robot)
);
}
// Setup the dock if there is a docking system on board.
ArServerModeDock *modeDock = NULL;
modeDock = ArServerModeDock::createDock(&server, &robot, &locTask,
&pathTask);
if (modeDock != NULL)
{
modeDock->checkDock();
modeDock->addAsDefaultMode();
modeDock->addToConfig(Aria::getConfig());
modeDock->addControlCommands(&commands);
}
// Make Stop mode the default (If current mode deactivates without entering
// a new mode, then Stop Mode will be selected)
modeStop.addAsDefaultMode();
// TODO move up near where stop mode is created?
/* Services that allow the client to initiate scanning with the laser to
create maps in Mapper3 (So not possible with SONARNL): */
ArServerHandlerMapping handlerMapping(&server, &robot, firstLaser,
fileDir, "", true);
// make laser localization stop while mapping
handlerMapping.addMappingStartCallback(
new ArFunctor1C<ArLocalizationTask, bool>
(&locTask, &ArLocalizationTask::setIdleFlag, true));
// and then make it start again when we're doine
handlerMapping.addMappingEndCallback(
new ArFunctor1C<ArLocalizationTask, bool>
(&locTask, &ArLocalizationTask::setIdleFlag, false));
// Make it so our "lost" actions don't stop us while mapping
handlerMapping.addMappingStartCallback(actionLostPath.getDisableCB());
handlerMapping.addMappingStartCallback(actionLostRatioDrive.getDisableCB());
handlerMapping.addMappingStartCallback(actionLostWander.getDisableCB());
// And then let them make us stop as usual when done mapping
handlerMapping.addMappingEndCallback(actionLostPath.getEnableCB());
handlerMapping.addMappingEndCallback(actionLostRatioDrive.getEnableCB());
handlerMapping.addMappingEndCallback(actionLostWander.getEnableCB());
// don't let forbidden lines show up as obstacles while mapping
// (they'll just interfere with driving while mapping, and localization is off anyway)
handlerMapping.addMappingStartCallback(forbidden.getDisableCB());
// let forbidden lines show up as obstacles again as usual after mapping
handlerMapping.addMappingEndCallback(forbidden.getEnableCB());
/*
// If we are on a simulator, move the robot back to its starting position,
// and reset its odometry.
// This will allow localizeRobotAtHomeBlocking() below will (probably) work (it
// tries current odometry (which will be 0,0,0) and all the map
// home points.
// (Ignored by a real robot)
//robot.com(ArCommands::SIM_RESET);
*/
// create a pose storage class, this will let the program keep track
// of where the robot is between runs... after we try and restore
// from this file it will start saving the robot's pose into the
// file
ArPoseStorage poseStorage(&robot);
/// if we could restore the pose from then set the sim there (this
/// won't do anything to the real robot)... if we couldn't restore
/// the pose then just reset the position of the robot (which again
/// won't do anything to the real robot)
if (poseStorage.restorePose("robotPose"))
serverLocHandler.setSimPose(robot.getPose());
else
robot.com(ArCommands::SIM_RESET);
/* File transfer services: */
#ifdef WIN32
// Not implemented for Windows yet.
ArLog::log(ArLog::Normal, "Note, file upload/download services are not implemented for Windows; not enabling them.");
#else
// This block will allow you to set up where you get and put files
// to/from, just comment them out if you don't want this to happen
// /*
ArServerFileLister fileLister(&server, fileDir);
ArServerFileToClient fileToClient(&server, fileDir);
ArServerFileFromClient fileFromClient(&server, fileDir, "/tmp");
ArServerDeleteFileOnServer deleteFileOnServer(&server, fileDir);
// */
#endif
/* Video image streaming, and camera controls (Requires SAVserver or ACTS) */
// Forward any video if either ACTS or SAV server are running.
// You can find out more about SAV and ACTS on our website
// http://robots.activmedia.com. ACTS is for color tracking and is
// a seperate product. SAV just does software A/V transmitting and is
// free to all our customers. Just run ACTS or SAV server before you
// start this program and this class here will forward video from the
// server to the client.
ArHybridForwarderVideo videoForwarder(&server, "localhost", 7070);
// make a camera to use in case we have video. the camera collection collects
// multiple ptz cameras
ArPTZ *camera = NULL;
ArServerHandlerCamera *handlerCamera = NULL;
ArCameraCollection *cameraCollection = NULL;
// if we have video then set up a camera
if (videoForwarder.isForwardingVideo())
{
cameraCollection = new ArCameraCollection();
cameraCollection->addCamera("Cam1", "PTZ", "Camera", "PTZ");
videoForwarder.setCameraName("Cam1");
videoForwarder.addToCameraCollection(*cameraCollection);
camera = new ArVCC4(&robot); //, invertedCamera, ArVCC4::COMM_UNKNOWN, true, true);
// To use an RVision SEE camera instead:
// camera = new ArRVisionPTZ(&robot);
camera->init();
handlerCamera = new ArServerHandlerCamera("Cam1",
&server,
&robot,
camera,
cameraCollection);
pathTask.addGoalFinishedCB(
new ArFunctorC<ArServerHandlerCamera>(
handlerCamera,
&ArServerHandlerCamera::cameraModeLookAtGoalClearGoal));
}
// After all of the cameras / videos have been created and added to the collection,
// then start the collection server.
//
if (cameraCollection != NULL) {
new ArServerHandlerCameraCollection(&server, cameraCollection);
}
/* Load configuration values, map, and begin! */
// When parsing the configuration file, also look at the program's command line options
// from the command-line argument parser as well as the configuration file.
// (So you can use any argument on the command line, namely -map.)
Aria::getConfig()->useArgumentParser(&parser);
puts("xxx");puts("aaa"); fflush(stdout);
// Read in parameter files.
ArLog::log(ArLog::Normal, "Loading config file %s into ArConfig (base directory %s)...", Arnl::getTypicalParamFileName(), Aria::getConfig()->getBaseDirectory());
if (!Aria::getConfig()->parseFile(Arnl::getTypicalParamFileName()))
{
ArLog::log(ArLog::Normal, "Trouble loading configuration file, exiting");
Aria::exit(5);
}
// Warn about unknown params.
if (!simpleOpener.checkAndLog() || !parser.checkHelpAndWarnUnparsed())
{
logOptions(argv[0]);
Aria::exit(6);
}
// Warn if there is no map
if (map.getFileName() == NULL || strlen(map.getFileName()) <= 0)
{
ArLog::log(ArLog::Normal, "");
ArLog::log(ArLog::Normal, "### No map file is set up, you can make a map with the following procedure");
ArLog::log(ArLog::Normal, " 0) You can find this information in README.txt or docs/Mapping.txt");
ArLog::log(ArLog::Normal, " 1) Connect to this server with MobileEyes");
ArLog::log(ArLog::Normal, " 2) Go to Tools->Map Creation->Start Scan");
ArLog::log(ArLog::Normal, " 3) Give the map a name and hit okay");
ArLog::log(ArLog::Normal, " 4) Drive the robot around your space (see docs/Mapping.txt");
ArLog::log(ArLog::Normal, " 5) Go to Tools->Map Creation->Stop Scan");
ArLog::log(ArLog::Normal, " 6) Start up Mapper3");
ArLog::log(ArLog::Normal, " 7) Go to File->Open on Robot");
ArLog::log(ArLog::Normal, " 8) Select the .2d you created");
ArLog::log(ArLog::Normal, " 9) Create a .map");
ArLog::log(ArLog::Normal, " 10) Go to File->Save on Robot");
ArLog::log(ArLog::Normal, " 11) In MobileEyes, go to Tools->Robot Config");
ArLog::log(ArLog::Normal, " 12) Choose the Files section");
ArLog::log(ArLog::Normal, " 13) Enter the path and name of your new .map file for the value of the Map parameter.");
ArLog::log(ArLog::Normal, " 14) Press OK and your new map should become the map used");
ArLog::log(ArLog::Normal, "");
}
// Print a log message notifying user of the directory for map files
ArLog::log(ArLog::Normal, "");
ArLog::log(ArLog::Normal,
"Directory for maps and file serving: %s", fileDir);
ArLog::log(ArLog::Normal, "See the ARNL README.txt for more information");
ArLog::log(ArLog::Normal, "");
// Do an initial localization of the robot. It tries all the home points
// in the map, as well as the robot's current odometric position, as possible
// places the robot is likely to be at startup. If successful, it will
// also save the position it found to be the best localized position as the
// "Home" position, which can be obtained from the localization task (and is
// used by the "Go to home" network request).
locTask.localizeRobotAtHomeBlocking();
// Let the client switch manager (for multirobot) spin off into its own thread
// TODO move to multirobot example?
clientSwitch.runAsync();
// Start the networking server's thread
server.runAsync();
// Add a key handler so that you can exit by pressing
// escape. Note that this key handler, however, prevents this program from
// running in the background (e.g. as a system daemon or run from
// the shell with "&") -- it will lock up trying to read the keys;
// remove this if you wish to be able to run this program in the background.
ArKeyHandler *keyHandler;
if ((keyHandler = Aria::getKeyHandler()) == NULL)
{
keyHandler = new ArKeyHandler;
Aria::setKeyHandler(keyHandler);
robot.lock();
robot.attachKeyHandler(keyHandler);
robot.unlock();
puts("Server running. To exit, press escape.");
}
TourGoalTaskExample TourTaskExample(&pathTask, &robot, &modeGoto, &parser);
// Enable the motors and wait until the robot exits (disconnection, etc.) or this program is
// canceled.
robot.enableMotors();
robot.waitForRunExit();
Aria::exit(0);
}