int main(int argc, char **argv) { Aria::init(); ArServerBase server; //ArLog::init(ArLog::StdOut, ArLog::Verbose); ArConfig *config; config = Aria::getConfig(); ArRobotP3DX dx; //dx.writeFile("dx.txt"); *Aria::getConfig() = dx; //Aria::getConfig()->writeFile("dxcopy.txt"); if (!server.open(7272)) { printf("Could not open server port\n"); exit(1); } ArServerHandlerConfig configHandler(&server, Aria::getConfig()); server.run(); Aria::shutdown(); return 0; }
int main(int argc, char **argv) { Aria::init(); ArServerBase server; if (!server.open(7272)) { printf("Could not open server port\n"); exit(1); } ArServerHandlerCommands commands(&server); commands.addCommand("Function1", "Call the function that is number 1!", new ArGlobalFunctor(&function1)); commands.addCommand("Function2", "Second function to call", new ArGlobalFunctor(&function2)); commands.addCommand("Function3", "Tree climb", new ArGlobalFunctor(&function3)); commands.addStringCommand("StringFunction4", "Print a string in function 4", new ArGlobalFunctor1< ArArgumentBuilder *>(&function4)); commands.addStringCommand("StringFunction5", "Prints a string given (5)", new ArGlobalFunctor1< ArArgumentBuilder *>(&function5)); commands.addStringCommand("StringFunction6", "Print out a value for function 6", new ArGlobalFunctor1< ArArgumentBuilder *>(&function6)); server.run(); }
int main(int argc, char **argv) { Aria::init(); ArServerBase server; ArConfig *config; config = Aria::getConfig(); std::string section; char joy[512]; sprintf(joy, "Joy"); section = "section1"; config->addParam(ArConfigArg("int", new int, "fun int", 0), section.c_str(), ArPriority::NORMAL); config->addParam(ArConfigArg("double", new double, "fun double", 0, 1), section.c_str(), ArPriority::NORMAL); config->addParam(ArConfigArg("bool", new bool, "fun bool"), section.c_str(), ArPriority::IMPORTANT); config->addParam(ArConfigArg("string", joy, "fun string", sizeof(joy)), section.c_str(), ArPriority::TRIVIAL); section = "section8"; config->addParam(ArConfigArg("int", new int, "fun int", 0), section.c_str(), ArPriority::NORMAL); config->addParam(ArConfigArg("double", new double, "fun double", 0, 1), section.c_str(), ArPriority::NORMAL); config->addParam(ArConfigArg("doubleFOUR", (double).4, "fun double", 0.0, 1.0), section.c_str(), ArPriority::NORMAL); config->addParam(ArConfigArg("double three", new double, "fun double", 0, 1), section.c_str(), ArPriority::NORMAL); config->addParam(ArConfigArg("double two", new double, "fun double", 0, 1), section.c_str(), ArPriority::NORMAL); config->addParam(ArConfigArg("double one", new double, "fun double", 0, 1), section.c_str(), ArPriority::NORMAL); config->addParam(ArConfigArg("double", new double, "fun double", 0, 1), section.c_str(), ArPriority::NORMAL); config->addParam(ArConfigArg("bool", new bool, "fun bool"), section.c_str(), ArPriority::IMPORTANT); config->addParam(ArConfigArg("string", joy, "fun string", sizeof(joy)), section.c_str(), ArPriority::TRIVIAL); section = "some section"; config->setSectionComment("some section", "this is a random section with 4 ints"); config->addParam(ArConfigArg("int1", new int, "fun int"), section.c_str(), ArPriority::TRIVIAL); config->addParam(ArConfigArg("int2", new int, "fun int", -1, 1200), section.c_str(), ArPriority::NORMAL); config->addParam(ArConfigArg("int3", new int, "fun int"), section.c_str(), ArPriority::IMPORTANT); config->addParam(ArConfigArg("int4", new int, "fun int"), section.c_str(), ArPriority::NORMAL); config->addParam(ArConfigArg("int4", new int, "fun int"), section.c_str(), ArPriority::NORMAL); config->addParam(ArConfigArg("int1", new int, "fun int"), section.c_str(), ArPriority::TRIVIAL); section = "another section"; config->setSectionComment("another section", "this is another section with 1 of each type"); config->addParam(ArConfigArg("inta", new int, "fun int"), section.c_str(), ArPriority::NORMAL); config->addParam(ArConfigArg("doublea", new double, "fun double"), section.c_str(), ArPriority::NORMAL); config->addParam(ArConfigArg("boola", new bool, "fun bool"), section.c_str(), ArPriority::NORMAL); config->addParam(ArConfigArg("stringa", new char[512], "fun string", 512), section.c_str(), ArPriority::NORMAL); if (!server.open(7272)) { printf("Could not open server port\n"); exit(1); } config->setBaseDirectory("./"); config->writeFile("default.txt"); config->parseFile("modified.txt"); config->writeFile("modifiedModified.txt"); ArServerHandlerConfig configHandler(&server, Aria::getConfig(), "default.txt"); server.run(); Aria::shutdown(); return 0; }
int main(int argc, char **argv) { Aria::init(); ArServerBase server; if (!server.open(7272)) { printf("Could not open server port\n"); exit(1); } server.run(); return 0; }
int main(int argc, char **argv) { Aria::init(); ArServerBase server; if (!server.open(7272)) { printf("Could not open server port\n"); exit(1); } ArServerFileLister fileLister(&server, "."); ArServerFileToClient fileToClient(&server, "."); ArServerFileFromClient fileFromClient(&server, ".", "/tmp"); ArServerDeleteFileOnServer fileDeleter(&server, "."); server.run(); }
int main(int argc, char **argv) { Aria::init(); ArServerBase robotServer; if (!robotServer.open(5000)) { printf("Could not open robot server port\n"); Aria::exit(1); } ArServerBase clientServer; if (!clientServer.open(7272)) { printf("Could not open robot server port\n"); Aria::exit(1); } ArCentralManager switchManager(&robotServer, &clientServer); switchManager.addForwarderAddedCallback( new ArGlobalFunctor1<ArCentralForwarder *>(&forwarderAdded), 100); switchManager.addForwarderRemovedCallback( new ArGlobalFunctor1<ArCentralForwarder *>(&forwarderRemoved), 100); // Start a small handler to monitor communication between the server and // client. ArServerHandlerCommMonitor commMonitor(&clientServer); ArServerHandlerCommands commands(&clientServer); commands.setPrefix("CentralServer"); ArServerSimpleServerCommands serverCommands(&commands, &clientServer, false); commands.addCommand( "NetworkLogConnections", "Logs the connections to the central server, and to all the forwarded connections", new ArFunctorC<ArCentralManager> (&switchManager, &ArCentralManager::logConnections)); clientServer.runAsync(); robotServer.run(); Aria::exit(0); }
int main(int argc, char **argv) { Aria::init(); ArServerBase server; ArGlobalFunctor2<ArServerClient *, ArNetPacket *> sendEmptyCB(&sendEmpty); if (!server.open(7272)) { printf("Could not open server port\n"); exit(1); } ArServerInfoDrawings drawing(&server); ArDrawingData arrows("polyarrow", ArColor(0, 0, 255), 5, 50); ArDrawingData dots("polydots", ArColor(0, 255, 0), 12, 50); drawing.addDrawing(&arrows, "arrows", &sendEmptyCB); drawing.addDrawing(&dots, "dots", &sendEmptyCB); server.run(); }
int main(int argc, char *argv[]) { // Initialize location of Aria, Arnl and their args. Aria::init(); Arnl::init(); // The robot object ArRobot robot; #ifndef SONARNL // The laser object ArSick sick(181, 361); #endif // Parse them command line arguments. ArArgumentParser parser(&argc, argv); // Set up our simpleConnector ArSimpleConnector simpleConnector(&parser); // Load default arguments for this computer parser.loadDefaultArguments(); // Parse its arguments for the simple connector. simpleConnector.parseArgs(); // sonar, must be added to the robot, for teleop and wander ArSonarDevice sonarDev; // add the sonar to the robot robot.addRangeDevice(&sonarDev); ArMap arMap; #ifndef SONARNL // Initialize the localization ArLocalizationTask locTask(&robot, &sick, &arMap); // Make the path task ArPathPlanningTask pathTask(&robot, &sick, &sonarDev, &arMap); #else // Initialize the localization ArSonarLocalizationTask locTask(&robot, &sonarDev, &arMap); // Make the path task ArPathPlanningTask pathTask(&robot, NULL, &sonarDev, &arMap); #endif // Stop the robot as soon as localization fails. ArFunctor1C<ArPathPlanningTask, int> locaFailed(&pathTask, &ArPathPlanningTask::trackingFailed); locTask.addFailedLocalizationCB(&locaFailed); // Read in param files. Aria::getConfig()->useArgumentParser(&parser); if (!Aria::getConfig()->parseFile(Arnl::getTypicalParamFileName())) { printf("Trouble loading configuration file, exiting\n"); exit(1); } // Warn about unknown params. if (!parser.checkHelpAndWarnUnparsed()) { printf("\nUsage: %s -map mapfilename\n\n", argv[0]); simpleConnector.logOptions(); exit(2); } // Our server ArServerBase server; // First open the server up if (!server.open(7272)) { printf("Could not open server port\n"); exit(1); } // Connect the robot if (!simpleConnector.connectRobot(&robot)) { printf("Could not connect to robot... exiting\n"); Aria::shutdown(); return 1; } robot.com2Bytes(31, 14, 0); robot.com2Bytes(31, 15, 0); ArUtil::sleep(100); robot.com2Bytes(31, 14, 1); robot.com2Bytes(31, 15, 1); robot.enableMotors(); robot.clearDirectMotion(); #ifndef SONARNL // Set up the laser before handing it to the laser mode simpleConnector.setupLaser(&sick); // Add the laser to the robot robot.addRangeDevice(&sick); #endif // Start the robot thread. robot.runAsync(true); #ifndef SONARNL // Start the laser thread. sick.runAsync(); // Connect the laser if (!sick.blockingConnect()) { printf("Couldn't connect to sick, exiting\n"); Aria::shutdown(); return 1; } #endif ArUtil::sleep(300); // If you want to set the number of samples change the line below locTask.setNumSamples(2000); // Localize the robot to home if(locTask.localizeRobotAtHomeBlocking()) { printf("Successfully localized at home.\n"); } else { printf("WARNING: Unable to localize at home position!\n"); } robot.lock(); // attach stuff to the server ArServerInfoRobot serverInfoRobot(&server, &robot); ArServerInfoSensor serverInfoSensor(&server, &robot); ArServerInfoPath serverInfoPath(&server, &robot, &pathTask); ArServerInfoLocalization serverInfoLocalization(&server, &robot, &locTask); #ifndef SONARNL // Set it up to handle maps. ArServerHandlerMap serverMap(&server, &arMap, ArServerHandlerMap::POINTS); #else ArServerHandlerMap serverMap(&server, &arMap, ArServerHandlerMap::LINES); #endif // Set up a service that allows the client to monitor the communication // between the robot and the client. // ArServerHandlerCommMonitor serverCommMonitor(&server); //ArServerModeGoto modeGoto(&server, &robot, &pathTask); //ArServerModeStop modeStop(&server, &robot); //ArServerModeDrive modeDrive(&server, &robot); SimpleTask simpleTask(&robot, &pathTask); robot.unlock(); // Read in param files. Aria::getConfig()->parseFile(Arnl::getTypicalParamFileName()); // Now let it spin off in its own thread server.run(); exit(0); }