int main(void) { ArTcpConnection con; ArRobot robot; int ret; std::string str; JoydriveAction jdAct; FillerThread ft; ft.create(); FillerThread ft2; ft2.create(); Aria::init(); /* if (!jdAct.joystickInited()) { printf("Do not have a joystick, set up the joystick then rerun the program\n\n"); Aria::shutdown(); return 1; } */ if ((ret = con.open()) != 0) { str = con.getOpenMessage(ret); printf("Open failed: %s\n", str.c_str()); Aria::shutdown(); return 1; } robot.setDeviceConnection(&con); if (!robot.blockingConnect()) { printf("Could not connect to robot... exiting\n"); Aria::shutdown(); return 1; } robot.comInt(ArCommands::SONAR, 0); robot.comInt(ArCommands::ENABLE, 1); robot.comInt(ArCommands::SOUNDTOG, 0); lastLoopTime.setToNow(); loopTime = robot.getCycleTime(); robot.addAction(&jdAct, 100); robot.runAsync(true); robot.waitForRunExit(); Aria::shutdown(); return 0; }
int main(int argc, char **argv) { std::string str; int ret; // connection to the robot ArTcpConnection con; // the robot ArRobot robot; // ake the joydrive object, which also creates its own thread Joydrive joyd(&robot); // the connection handler ConnHandler ch(&robot, &joyd); // init aria, which will make a dedicated signal handling thread Aria::init(Aria::SIGHANDLE_THREAD); // open the connection with default args, exit if it fails if ((ret = con.open()) != 0) { str = con.getOpenMessage(ret); printf("Open failed: %s\n", str.c_str()); Aria::shutdown(); return 1; } // set the connection on the robot robot.setDeviceConnection(&con); // run the robot in its own thread robot.runAsync(false); // have the robot connect asyncronously (so its loop is still running) // if this fails it means that the robot isn't running in its own thread if (!robot.asyncConnect()) { printf( "asyncConnect failed because robot is not running in its own thread.\n"); Aria::shutdown(); return 1; } // now we just wait for the robot to be done running printf("Waiting for the robot's run to exit.\n"); robot.waitForRunExit(); // then we exit printf("exiting main\n"); Aria::exit(0); // exit program return 0; }
int main(int argc, char **argv) { Aria::init(); ArArgumentParser parser(&argc, argv); parser.loadDefaultArguments(); ArRobot robot; ArRobotConnector robotConnector(&parser, &robot); if(!robotConnector.connectRobot()) { ArLog::log(ArLog::Terse, "dpptuExample: Could not connect to the robot."); if(parser.checkHelpAndWarnUnparsed()) { Aria::logOptions(); Aria::exit(1); } } if (!Aria::parseArgs() || !parser.checkHelpAndWarnUnparsed()) { Aria::logOptions(); Aria::exit(1); } ArLog::log(ArLog::Normal, "dpptuExample: Connected to robot."); robot.runAsync(true); // an object for keyboard control, class defined above, this also adds itself as a user task KeyPTU ptu(&robot); // turn off the sonar robot.comInt(ArCommands::SONAR, 0); printf("Press '?' for available commands\r\n"); // run, if we lose connection to the robot, exit robot.waitForRunExit(); Aria::exit(0); }
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."); } ArnlASyncTaskExample asyncTaskExample(&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); }
int main(int argc, char **argv) { Aria::init(); ArArgumentParser argParser(&argc, argv); argParser.loadDefaultArguments(); ArRobot robot; ArSick laser; std::ofstream stream; // for loggin time_t timer; char buffer[120]; //for loggin ArRobotConnector robotConnector(&argParser, &robot); ArLaserConnector laserConnector(&argParser, &robot, &robotConnector); int32_t count = 0; readyLog(stream); if (!robotConnector.connectRobot()) { ArLog::log(ArLog::Terse, "Could not connect to the robot."); if (argParser.checkHelpAndWarnUnparsed()) { // -help not given, just exit. Aria::logOptions(); Aria::exit(1); return 1; } } // Trigger argument parsing if (!Aria::parseArgs() || !argParser.checkHelpAndWarnUnparsed()) { Aria::logOptions(); Aria::exit(1); return 1; } ArKeyHandler keyHandler; Aria::setKeyHandler(&keyHandler); robot.attachKeyHandler(&keyHandler); puts("This program will make the robot wander around. It uses some avoidance\n" "actions if obstacles are detected, otherwise it just has a\n" "constant forward velocity.\n\nPress CTRL-C or Escape to exit."); //ArSonarDevice sonar; //robot.addRangeDevice(&sonar); robot.addRangeDevice(&laser); robot.runAsync(true); // try to connect to laser. if fail, warn but continue, using sonar only if (!laserConnector.connectLasers()) { ArLog::log(ArLog::Normal, "Warning: unable to connect to requested lasers, will wander using robot sonar only."); } double sampleAngle, dist; auto sampleRange = laser.currentReadingPolar(-20, 20, &sampleAngle); auto degreeStr = laser.getDegreesChoicesString(); std::cout << "auto sampleRange = laser.currentReadingPolar(-20, 20, &sampleAngle);" << sampleRange << std::endl; std::cout << "auto degreeStr = laser.getDegreesChoicesString(); : " << degreeStr << std::endl; // turn on the motors, turn off amigobot sounds robot.enableMotors(); //robot.getLaserMap() robot.comInt(ArCommands::SOUNDTOG, 0); // add a set of actions that combine together to effect the wander behavior ArActionStallRecover recover; ArActionBumpers bumpers; ArActionAvoidFront avoidFrontNear("Avoid Front Near", 100, 0); ArActionAvoidFront avoidFrontFar; ArActionConstantVelocity constantVelocity("Constant Velocity", 400); robot.addAction(&recover, 100); robot.addAction(&bumpers, 75); robot.addAction(&avoidFrontNear, 50); robot.addAction(&avoidFrontFar, 49); robot.addAction(&constantVelocity, 25); stream << "IMPORTANT !! == robot.getRobotRadius() : " << robot.getRobotRadius << std::endl; std::string timestamp; while (1) { // // time(&timer); strftime(buffer, 80, " - timestamp : %I:%M:%S", localtime(&timer)); timestamp = buffer; dist = robot.checkRangeDevicesCurrentPolar(-70, 70, &sampleAngle) - robot.getRobotRadius(); stream << count << timestamp << "checkRangeDevicesCurrentPolar(-70, 70, &angle) : " << dist << std::endl; Sleep(500); count++; } // wwill add processor here // wait for robot task loop to end before exiting the program robot.waitForRunExit(); Aria::exit(0); return 0; }
int main(int argc, char** argv) { // Initialize some global data Aria::init(); // If you want ArLog to print "Verbose" level messages uncomment this: //ArLog::init(ArLog::StdOut, ArLog::Verbose); // This object parses program options from the command line ArArgumentParser parser(&argc, argv); // Load some default values for command line arguments from /etc/Aria.args // (Linux) or the ARIAARGS environment variable. parser.loadDefaultArguments(); // Central object that is an interface to the robot and its integrated // devices, and which manages control of the robot by the rest of the program. ArRobot robot; // Object that connects to the robot or simulator using program options ArRobotConnector robotConnector(&parser, &robot); // If the robot has an Analog Gyro, this object will activate it, and // if the robot does not automatically use the gyro to correct heading, // this object reads data from it and corrects the pose in ArRobot ArAnalogGyro gyro(&robot); // Connect to the robot, get some initial data from it such as type and name, // and then load parameter files for this robot. if (!robotConnector.connectRobot()) { // Error connecting: // if the user gave the -help argumentp, then just print out what happened, // and continue so options can be displayed later. if (!parser.checkHelpAndWarnUnparsed()) { ArLog::log(ArLog::Terse, "Could not connect to robot, will not have parameter file so options displayed later may not include everything"); } // otherwise abort else { ArLog::log(ArLog::Terse, "Error, could not connect to robot."); Aria::logOptions(); Aria::exit(1); } } // Connector for laser rangefinders ArLaserConnector laserConnector(&parser, &robot, &robotConnector); // Connector for compasses ArCompassConnector compassConnector(&parser); // Parse the command line options. Fail and print the help message if the parsing fails // or if the help was requested with the -help option if (!Aria::parseArgs() || !parser.checkHelpAndWarnUnparsed()) { Aria::logOptions(); exit(1); } // Used to access and process sonar range data ArSonarDevice sonarDev; // Used to perform actions when keyboard keys are pressed ArKeyHandler keyHandler; Aria::setKeyHandler(&keyHandler); // ArRobot contains an exit action for the Escape key. It also // stores a pointer to the keyhandler so that other parts of the program can // use the same keyhandler. robot.attachKeyHandler(&keyHandler); printf("You may press escape to exit\n"); // Attach sonarDev to the robot so it gets data from it. robot.addRangeDevice(&sonarDev); // Start the robot task loop running in a new background thread. The 'true' argument means if it loses // connection the task loop stops and the thread exits. robot.runAsync(true); // Connect to the laser(s) if lasers were configured in this robot's parameter // file or on the command line, and run laser processing thread if applicable // for that laser class. (For the purposes of this demo, add all // possible lasers to ArRobot's list rather than just the ones that were // specified with the connectLaser option (so when you enter laser mode, you // can then interactively choose which laser to use from the list which will // show both connected and unconnected lasers.) if (!laserConnector.connectLasers(false, false, true)) { printf("Could not connect to lasers... exiting\n"); Aria::exit(2); } // Create and connect to the compass if the robot has one. ArTCM2 *compass = compassConnector.create(&robot); if(compass && !compass->blockingConnect()) { compass = NULL; } // Sleep for a second so some messages from the initial responses // from robots and cameras and such can catch up ArUtil::sleep(1000); // We need to lock the robot since we'll be setting up these modes // while the robot task loop thread is already running, and they // need to access some shared data in ArRobot. robot.lock(); // now add all the modes for this demo // these classes are defined in ArModes.cpp in ARIA's source code. ArModeLaser laser(&robot, "laser", 'l', 'L'); ArModeTeleop teleop(&robot, "teleop", 't', 'T'); ArModeUnguardedTeleop unguardedTeleop(&robot, "unguarded teleop", 'u', 'U'); ArModeWander wander(&robot, "wander", 'w', 'W'); ArModeGripper gripper(&robot, "gripper", 'g', 'G'); ArModeCamera camera(&robot, "camera", 'c', 'C'); ArModeSonar sonar(&robot, "sonar", 's', 'S'); ArModeBumps bumps(&robot, "bumps", 'b', 'B'); ArModePosition position(&robot, "position", 'p', 'P', &gyro); ArModeIO io(&robot, "io", 'i', 'I'); ArModeActs actsMode(&robot, "acts", 'a', 'A'); ArModeCommand command(&robot, "command", 'd', 'D'); ArModeTCM2 tcm2(&robot, "tcm2", 'm', 'M', compass); // activate the default mode teleop.activate(); // turn on the motors robot.comInt(ArCommands::ENABLE, 1); robot.unlock(); // Block execution of the main thread here and wait for the robot's task loop // thread to exit (e.g. by robot disconnecting, escape key pressed, or OS // signal) robot.waitForRunExit(); Aria::exit(0); }
int main(int argc, char **argv) { Aria::init(); //ArLog::init(ArLog::StdOut, ArLog::Verbose); // robot ArRobot robot; /// our server ArServerBase server; // set up our parser ArArgumentParser parser(&argc, argv); // set up our simple connector ArSimpleConnector simpleConnector(&parser); // set up a gyro ArAnalogGyro gyro(&robot); // load the default arguments parser.loadDefaultArguments(); // parse the command line... fail and print the help if the parsing fails // or if the help was requested if (!simpleConnector.parseArgs() || !parser.checkHelpAndWarnUnparsed()) { simpleConnector.logOptions(); exit(1); } if (!server.loadUserInfo("userServerTest.userInfo")) { printf("Could not load user info, exiting\n"); exit(1); } server.logUsers(); // first open the server up if (!server.open(7272)) { printf("Could not open server port\n"); exit(1); } // sonar, must be added to the robot ArSonarDevice sonarDev; // add the sonar to the robot robot.addRangeDevice(&sonarDev); ArIRs irs; robot.addRangeDevice(&irs); ArBumpers bumpers; robot.addRangeDevice(&bumpers); // a laser in case one is used ArSick sick(361, 180); // add the laser to the robot robot.addRangeDevice(&sick); // attach stuff to the server ArServerInfoRobot serverInfoRobot(&server, &robot); ArServerInfoSensor serverInfoSensor(&server, &robot); ArServerInfoDrawings drawings(&server); drawings.addRobotsRangeDevices(&robot); // ways of moving the robot ArServerModeStop modeStop(&server, &robot); ArServerModeDrive modeDrive(&server, &robot); ArServerModeRatioDrive modeRatioDrive(&server, &robot); ArServerModeWander modeWander(&server, &robot); modeStop.addAsDefaultMode(); modeStop.activate(); // set up the simple commands ArServerHandlerCommands commands(&server); // add the commands for the microcontroller ArServerSimpleComUC uCCommands(&commands, &robot); // add the commands for logging ArServerSimpleComMovementLogging loggingCommands(&commands, &robot); // add the commands for the gyro ArServerSimpleComGyro gyroCommands(&commands, &robot, &gyro); // add the commands to enable and disable safe driving to the simple commands modeDrive.addControlCommands(&commands); // Forward any video if we have some to forward.. this will forward // from SAV or ACTS, you can find both on our website // http://robots.activmedia.com, ACTS is for color tracking and is // charged for but SAV just does software A/V transmitting and is // free to all our customers... just run ACTS or SAV before you // start this program and this class here will forward video from it // to MobileEyes ArHybridForwarderVideo videoForwarder(&server, "localhost", 7070); // make a camera to use in case we have video ArPTZ *camera = NULL; ArServerHandlerCamera *handlerCamera = NULL; // if we have video then set up a camera if (videoForwarder.isForwardingVideo()) { bool invertedCamera = false; camera = new ArVCC4(&robot, invertedCamera, ArVCC4::COMM_UNKNOWN, true, true); camera->init(); handlerCamera = new ArServerHandlerCamera(&server, &robot, camera); } server.logCommandGroups(); server.logCommandGroupsToFile("userServerTest.commandGroups"); // now let it spin off in its own thread server.runAsync(); // set up the robot for connecting if (!simpleConnector.connectRobot(&robot)) { printf("Could not connect to robot... exiting\n"); Aria::shutdown(); return 1; } // set up the laser before handing it to the laser mode simpleConnector.setupLaser(&sick); robot.enableMotors(); // start the robot running, true so that if we lose connection the run stops robot.runAsync(true); sick.runAsync(); // connect the laser if it was requested if (!simpleConnector.connectLaser(&sick)) { printf("Could not connect to laser... exiting\n"); Aria::shutdown(); return 1; } robot.waitForRunExit(); // now exit Aria::shutdown(); exit(0); }
int main(int argc, char **argv) { Aria::init(); // parse our args and make sure they were all accounted for ArSimpleConnector connector(&argc, argv); ArRobot robot; // the laser. ArActionTriangleDriveTo will use this laser object since it is // named "laser" when added to the ArRobot. ArSick sick; if (!connector.parseArgs() || argc > 1) { connector.logOptions(); exit(1); } // a key handler so we can do our key handling ArKeyHandler keyHandler; // let the global aria stuff know about it Aria::setKeyHandler(&keyHandler); // toss it on the robot robot.attachKeyHandler(&keyHandler); // add the laser to the robot robot.addRangeDevice(&sick); ArSonarDevice sonar; robot.addRangeDevice(&sonar); ArActionTriangleDriveTo triangleDriveTo; ArFunctorC<ArActionTriangleDriveTo> lineGoCB(&triangleDriveTo, &ArActionTriangleDriveTo::activate); keyHandler.addKeyHandler('g', &lineGoCB); keyHandler.addKeyHandler('G', &lineGoCB); ArFunctorC<ArActionTriangleDriveTo> lineStopCB(&triangleDriveTo, &ArActionTriangleDriveTo::deactivate); keyHandler.addKeyHandler('s', &lineStopCB); keyHandler.addKeyHandler('S', &lineStopCB); ArActionLimiterForwards limiter("limiter", 150, 0, 0, 1.3); robot.addAction(&limiter, 70); ArActionLimiterBackwards limiterBackwards; robot.addAction(&limiterBackwards, 69); robot.addAction(&triangleDriveTo, 60); ArActionKeydrive keydrive; robot.addAction(&keydrive, 55); ArActionStop stopAction; robot.addAction(&stopAction, 50); // try to connect, if we fail exit if (!connector.connectRobot(&robot)) { printf("Could not connect to robot... exiting\n"); Aria::shutdown(); return 1; } robot.comInt(ArCommands::SONAR, 1); robot.comInt(ArCommands::ENABLE, 1); // start the robot running, true so that if we lose connection the run stops robot.runAsync(true); // now set up the laser connector.setupLaser(&sick); sick.runAsync(); if (!sick.blockingConnect()) { printf("Could not connect to SICK laser... exiting\n"); Aria::shutdown(); return 1; } printf("If you press the 'g' key it'll go find a triangle, if you press 's' it'll stop.\n"); robot.waitForRunExit(); return 0; }
int main(int argc, char **argv) { Aria::init(); ArArgumentParser parser(&argc, argv); parser.loadDefaultArguments(); ArRobot robot; ArRobotConnector robotConnector(&parser, &robot); ArLaserConnector laserConnector(&parser, &robot, &robotConnector); if(!robotConnector.connectRobot()) { ArLog::log(ArLog::Terse, "lineFinderExample: Could not connect to the robot."); if(parser.checkHelpAndWarnUnparsed()) { // -help not given Aria::logOptions(); Aria::exit(1); } } if (!Aria::parseArgs() || !parser.checkHelpAndWarnUnparsed()) { Aria::logOptions(); Aria::exit(1); } ArLog::log(ArLog::Normal, "lineFinderExample: Connected to robot."); robot.runAsync(true); // Connect to laser(s) as defined in parameter files. // (Some flags are available as arguments to connectLasers() to control error behavior and to control which lasers are put in the list of lasers stored by ArRobot. See docs for details.) if(!laserConnector.connectLasers()) { ArLog::log(ArLog::Terse, "Could not connect to configured lasers. Exiting."); Aria::exit(3); return 3; } ArLog::log(ArLog::Normal, "lineFinderExample: Connected to laser"); ArKeyHandler keyHandler; Aria::setKeyHandler(&keyHandler); robot.attachKeyHandler(&keyHandler); // Create the ArLineFinder object. Set it to log lots of information about its // processing. ArLaser *laser = robot.findLaser(1); if(!laser) { ArLog::log(ArLog::Terse, "lineFinderExample: No laser device connected, exiting."); Aria::exit(4); return 4; } ArLineFinder lineFinder(laser); lineFinder.setVerbose(true); // Add key callbacks that simply call the ArLineFinder::getLinesAndSaveThem() // function, which searches for lines in the current set of laser sensor // readings, and saves them in files with the names 'points' and 'lines'. ArFunctorC<ArLineFinder> findLineCB(&lineFinder, &ArLineFinder::getLinesAndSaveThem); keyHandler.addKeyHandler('f', &findLineCB); keyHandler.addKeyHandler('F', &findLineCB); printf("If you press the 'f' key the points and lines found will be saved\n"); printf("Into the 'points' and 'lines' file in the current working directory\n"); robot.waitForRunExit(); Aria::exit(0); return 0; }
int main(int argc, char **argv) { Aria::init(); ArSimpleConnector connector(&argc, argv); ArRobot robot; ArSick sick; if (!Aria::parseArgs() || argc > 1) { Aria::logOptions(); Aria::exit(1); // exit program with error code 1 return 1; } ArKeyHandler keyHandler; Aria::setKeyHandler(&keyHandler); robot.attachKeyHandler(&keyHandler); robot.addRangeDevice(&sick); // Create the ArLineFinder object. Set it to log lots of information about its // processing. ArLineFinder lineFinder(&sick); lineFinder.setVerbose(true); // Add key callbacks that simply call the ArLineFinder::getLinesAndSaveThem() // function, which searches for lines in the current set of laser sensor // readings, and saves them in files with the names 'points' and 'lines'. ArFunctorC<ArLineFinder> findLineCB(&lineFinder, &ArLineFinder::getLinesAndSaveThem); keyHandler.addKeyHandler('f', &findLineCB); keyHandler.addKeyHandler('F', &findLineCB); ArLog::log(ArLog::Normal, "lineFinderExample: connecting to robot..."); if (!connector.connectRobot(&robot)) { printf("Could not connect to robot... exiting\n"); Aria::exit(1); // exit program with error code 1 return 1; } robot.runAsync(true); // now set up the laser ArLog::log(ArLog::Normal, "lineFinderExample: connecting to SICK laser..."); connector.setupLaser(&sick); sick.runAsync(); if (!sick.blockingConnect()) { printf("Could not connect to SICK laser... exiting\n"); Aria::exit(1); return 1; } printf("If you press the 'f' key the points and lines found will be saved\n"); printf("Into the 'points' and 'lines' file in the current working directory\n"); robot.waitForRunExit(); Aria::exit(0); return 0; }
int main(int argc, char **argv) { Aria::init(); ArArgumentParser argParser(&argc, argv); argParser.loadDefaultArguments(); ArRobot robot; ArRobotConnector robotConnector(&argParser, &robot); ArLaserConnector laserConnector(&argParser, &robot, &robotConnector); if(!robotConnector.connectRobot()) { ArLog::log(ArLog::Terse, "Could not connect to the robot."); if(argParser.checkHelpAndWarnUnparsed()) { // -help not given, just exit. Aria::logOptions(); Aria::exit(1); return 1; } } // Trigger argument parsing if (!Aria::parseArgs() || !argParser.checkHelpAndWarnUnparsed()) { Aria::logOptions(); Aria::exit(1); return 1; } ArKeyHandler keyHandler; Aria::setKeyHandler(&keyHandler); robot.attachKeyHandler(&keyHandler); puts("This program will make the robot wander around. It uses some avoidance\n" "actions if obstacles are detected, otherwise it just has a\n" "constant forward velocity.\n\nPress CTRL-C or Escape to exit."); ArSonarDevice sonar; robot.addRangeDevice(&sonar); robot.runAsync(true); // try to connect to laser. if fail, warn but continue, using sonar only if(!laserConnector.connectLasers()) { ArLog::log(ArLog::Normal, "Warning: unable to connect to requested lasers, will wander using robot sonar only."); } // turn on the motors, turn off amigobot sounds robot.enableMotors(); robot.comInt(ArCommands::SOUNDTOG, 0); // add a set of actions that combine together to effect the wander behavior //działa //general structure: robot.addAction (new Name_of_action (parameters), priority); //to find out more about Actions go to ~/catkin_ws/src/rosaria/local/Aria/docs/index.html // if we're stalled we want to back up and recover robot.addAction(new ArActionStallRecover("stall recover", 100,50,100,30), 100); //basic values 225, 50, 150, 45 //when_stop, cycles_to_move, speed, turn' //slow down when near obstacle robot.addAction(new ArActionLimiterForwards("speed limiter near", 200, 200, 200), 95); // basic values 300,600,250 //stop_distance, slow_distance, slow_speed // react to bumpers robot.addAction(new ArActionLimiterBackwards, 75); // turn avoid very close robot.addAction(new ArActionAvoidFront("speed limiter far", 150,450,20), 47); //basic values 450, 200,15 //when_turn, speed, turn' // turn avoid things near robot.addAction(new ArActionAvoidFront("speed limiter far", 300,450,10), 46); //basic values 450, 200,15 //when_turn, speed, turn' // turn avoid things further away robot.addAction(new ArActionAvoidFront("speed limiter far", 800,450,5), 45); //basic values 450, 200,15 //when_turn, speed, turn' //move forward robot.addAction(new ArActionConstantVelocity("Constant Velocity", 500), 25); // wait for robot task loop to end before exiting the program robot.waitForRunExit(); Aria::exit(0); return 0; }
int main(int argc, char **argv) { // robot ArRobot robot; // the laser ArSick sick; // sonar, must be added to the robot //ArSonarDevice sonar; // the actions we'll use to wander // recover from stalls //ArActionStallRecover recover; // react to bumpers //ArActionBumpers bumpers; // limiter for close obstacles ArActionLimiterForwards limiter("speed limiter near", 1600, 0, 0, 1.3); // limiter for far away obstacles //ArActionLimiterForwards limiterFar("speed limiter near", 300, 1000, 450, 1.1); //ArActionLimiterForwards limiterFar("speed limiter far", 300, 1100, 600, 1.1); // limiter for the table sensors //ArActionLimiterTableSensor tableLimiter; // actually move the robot ArActionConstantVelocity constantVelocity("Constant Velocity", 1500); // turn the orbot if its slowed down ArActionTurn turn; // mandatory init Aria::init(); // Parse all our args ArSimpleConnector connector(&argc, argv); if (!connector.parseArgs() || argc > 1) { connector.logOptions(); exit(1); } // add the sonar to the robot //robot.addRangeDevice(&sonar); // add the laser to the robot robot.addRangeDevice(&sick); // try to connect, if we fail exit if (!connector.connectRobot(&robot)) { printf("Could not connect to robot... exiting\n"); Aria::shutdown(); return 1; } robot.comInt(ArCommands::SONAR, 0); // turn on the motors, turn off amigobot sounds //robot.comInt(ArCommands::SONAR, 0); robot.comInt(ArCommands::SOUNDTOG, 0); // add the actions //robot.addAction(&recover, 100); //robot.addAction(&bumpers, 75); robot.addAction(&limiter, 49); //robot.addAction(&limiter, 48); //robot.addAction(&tableLimiter, 50); robot.addAction(&turn, 30); robot.addAction(&constantVelocity, 20); robot.setStateReflectionRefreshTime(50); limiter.activate(); turn.activate(); constantVelocity.activate(); robot.clearDirectMotion(); //robot.setStateReflectionRefreshTime(50); robot.setRotVelMax(50); robot.setTransAccel(1500); robot.setTransDecel(100); // start the robot running, true so that if we lose connection the run stops robot.runAsync(true); connector.setupLaser(&sick); // now that we're connected to the robot, connect to the laser sick.runAsync(); if (!sick.blockingConnect()) { printf("Could not connect to SICK laser... exiting\n"); Aria::shutdown(); return 1; } sick.lockDevice(); sick.setMinRange(250); sick.unlockDevice(); robot.lock(); ArGlobalFunctor1<ArRobot *> userTaskCB(&userTask, &robot); robot.addUserTask("iotest", 100, &userTaskCB); requestTime.setToNow(); robot.comInt(ArCommands::IOREQUEST, 1); robot.comInt(ArCommands::ENABLE, 1); robot.unlock(); robot.waitForRunExit(); // now exit Aria::shutdown(); return 0; }
int main(int argc, char **argv) { // Initialize Aria and Arnl global information Aria::init(); Arnl::init(); // You can change default ArLog options in this call, but the settings in the parameter file // (arnl.p) which is loaded below (Aria::getConfig()->parseFile()) will override the options. //ArLog::init(ArLog::File, ArLog::Normal, "log.txt", true, true); // Used to parse the command line arguments. ArArgumentParser parser(&argc, argv); // Load default arguments for this computer (from /etc/Aria.args, environment // variables, and other places) parser.loadDefaultArguments(); #ifdef ARNL_LASER // Tell the laser connector to always connect the first laser since // this program always requires a laser. parser.addDefaultArgument("-connectLaser"); #endif // The robot object ArRobot robot; // handle messages from robot controller firmware and log the contents robot.addPacketHandler(new ArGlobalRetFunctor1<bool, ArRobotPacket*>(&handleDebugMessage)); // This object is used to connect to the robot, which can be configured via // command line arguments. 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; #ifdef ARNL_GPSLOC // GPS connector. ArGPSConnector gpsConnector(&parser); #endif // Set up our simpleOpener, used to set up the networking server ArServerSimpleOpener simpleOpener(&parser); #ifdef ARNL_LASER // the laser connector ArLaserConnector laserConnector(&parser, &robot, &robotConnector); #endif // used to connect to camera PTZ control ArPTZConnector ptzConnector(&parser, &robot); #ifdef ARNL_MULTIROBOT // Used to connect to a "central server" which can be used as a proxy // for multiple robot servers, and as a way for them to also communicate with // each other. (objects implementing some of these inter-robot communication // features are created below). // NOTE: If the central server is running on the same host as robot server(s), // then you must use the -serverPort argument to instruct these robot-control // server(s) to use different ports than the default 7272, since the central // server will use that port. ArClientSwitchManager clientSwitch(&server, &parser); #endif // 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); #ifdef ARNL_GPSLOC // On the Seekur, power to the GPS receiver is switched on by this command. // (A third argument of 0 would turn it off). On other robots this command is // ignored. If this fails, you may need to reset the port with ARIA demo or // seekurPower program (turn port off then on again). If the port is already // on, it will have no effect on the GPS (it will remain powered.) // Do this now before connecting to lasers to give it plenty of time to power // on, initialize, and find a good position before GPS localization begins. ArLog::log(ArLog::Normal, "Turning on GPS power... (Seekur/Seekur Jr. power port 6)"); robot.com2Bytes(116, 6, 1); #endif #ifdef ARNL_LASER // connect the laser(s) if it was requested, this adds them to the // robot too, and starts them running in their own threads ArLog::log(ArLog::Normal, "Connecting to laser(s) configured in parameters..."); if (!laserConnector.connectLasers()) { ArLog::log(ArLog::Normal, "Error: Could not connect to laser(s). Exiting."); Aria::exit(2); } ArLog::log(ArLog::Normal, "Done connecting to laser(s)."); #endif #if defined(ARNL_LASERLOC) || defined(ARNL_MAPPING) // 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(); #endif /* 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 threads */ #ifdef ARNL_MULTILOC ArLocalizationManager locManager(&robot, &map); #define LOCTASK locManager #endif #ifdef ARNL_LASERLOC ArLog::log(ArLog::Normal, "Creating laser localization task"); // Laser Monte-Carlo Localization ArLocalizationTask locTask(&robot, firstLaser, &map); #ifdef ARNL_MULTILOC locManager.addLocalizationTask(&locTask); #else #define LOCTASK locTask #endif #endif #ifdef ARNL_SONARLOC ArLog::log(ArLog::Normal, "Creating sonar localization task"); ArSonarLocalizationTask locTask(&robot, &sonarDev, &map); #ifdef ARNL_MULTILOC locManager.addLocalizationTask(&locTask); #else #define LOCTASK locTask #endif #endif #ifndef ARNL_GPSLOC // A callback function, which is called if localization fails ArGlobalFunctor1<int> locFailedCB(&locFailed); locTask.setFailedCallBack(&locFailedCB); //, &locTask); #endif #ifdef ARNL_GPSLOC ArLog::log(ArLog::Normal, "Connecting to GPS..."); // Connect to GPS ArGPS *gps = gpsConnector.createGPS(&robot); if(!gps || !gps->connect()) { ArLog::log(ArLog::Terse, "Error connecting to GPS device." "Try -gpsType, -gpsPort, and/or -gpsBaud command-line arguments." "Use -help for help. Exiting."); Aria::exit(5); } // set up GPS localization task ArLog::log(ArLog::Normal, "Creating GPS localization task"); ArGPSLocalizationTask gpsLocTask(&robot, gps, &map); #ifdef ARNL_MULTILOC locManager.addLocalizationTask(&gpsLocTask); #else #define LOCTASK gpsLocTask #endif #endif #ifdef ARNL_LASER // Set some options and callbacks 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); // 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)); } #endif /* 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 */ robot.unlock(); // Service to provide drawings of data in the map display : ArServerInfoDrawings drawings(&server); drawings.addRobotsRangeDevices(&robot); #ifdef ARNL_LASERLOC /* 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); #endif #ifdef ARNL_GPSLOC /* Show the positions calculated by GPS localization */ ArDrawingData drawingDataG("polyDots", ArColor(100,100,255), 130, 61); ArFunctor2C<ArGPSLocalizationTask, ArServerClient *, ArNetPacket *> drawingFunctorG(&gpsLocTask, &ArGPSLocalizationTask::drawGPSPoints); drawings.addDrawing(&drawingDataG, "GPS Points", &drawingFunctorG); ArDrawingData drawingDataG2("polyDots", ArColor(255,100,100), 100, 62); ArFunctor2C<ArGPSLocalizationTask, ArServerClient *, ArNetPacket *> drawingFunctorG2(&gpsLocTask, &ArGPSLocalizationTask::drawKalmanPoints); drawings.addDrawing(&drawingDataG2, "Kalman Points", &drawingFunctorG2); ArDrawingData drawingDataG3("polyDots", ArColor(100,255,100), 70, 63); ArFunctor2C<ArGPSLocalizationTask, ArServerClient *, ArNetPacket *> drawingFunctorG3(&gpsLocTask, &ArGPSLocalizationTask::drawOdoPoints); drawings.addDrawing(&drawingDataG3, "Odom. Points", &drawingFunctorG3); ArDrawingData drawingDataG4("polyDots", ArColor(255,50,50), 100, 75); ArFunctor2C<ArGPSLocalizationTask, ArServerClient *, ArNetPacket *> drawingFunctorG4(&gpsLocTask, &ArGPSLocalizationTask::drawKalmanRangePoints); drawings.addDrawing(&drawingDataG4, "KalRange Points", &drawingFunctorG4); ArDrawingData drawingDataG5("polySegments", ArColor(100,0,255), 1, 78); ArFunctor2C<ArGPSLocalizationTask, ArServerClient *, ArNetPacket *> drawingFunctorG5(&gpsLocTask, &ArGPSLocalizationTask::drawKalmanVariance); drawings.addDrawing(&drawingDataG5, "VarGPS", &drawingFunctorG5); #endif // "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); // 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()); // This service causes the client to show simple dialog boxes ArServerHandlerPopup popupServer(&server); /* Set up the possible modes for remote control from a client such as * MobileEyes: */ // Mode To stop and remain stopped: ArServerModeStop modeStop(&server, &robot); #ifndef ARNL_SONARLOC // 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); #endif // Teleoperation modes To drive by keyboard, joystick, etc: ArServerModeRatioDrive modeRatioDrive(&server, &robot); // 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, NULL, &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, NULL, &modeWander); modeWander.getActionGroup()->addAction(&actionLostWander, 110); // Tool to log data periodically to a file ArDataLogger dataLogger(&robot, "datalog.txt"); dataLogger.addToConfig(Aria::getConfig()); // make it configurable through ArConfig // Automatically add anything from the global info group to the data logger. Aria::getInfoGroup()->addAddStringCallback(dataLogger.getAddStringFunctor()); // 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()); // The following statements add fields to a set of informational data called // the InfoGroup. These are served to MobileEyes for displayi (turn on by enabling Details // and Custom Details in the View menu of MobileEyes.) Aria::getInfoGroup()->addStringInt( "Motor Packet Count", 10, new ArConstRetFunctorC<int, ArRobot>(&robot, &ArRobot::getMotorPacCount)); #ifdef ARNL_LASERLOC 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"); #elif defined(ARNL_SONARLOC) Aria::getInfoGroup()->addStringDouble( "Sonar Localization Score", 8, new ArRetFunctorC<double, ArSonarLocalizationTask>( &locTask, &ArSonarLocalizationTask::getLocalizationScore), "%.03f"); Aria::getInfoGroup()->addStringInt( "Sonar Loc Num Samples", 8, new ArRetFunctorC<int, ArSonarLocalizationTask>( &locTask, &ArSonarLocalizationTask::getCurrentNumSamples), "%4d"); #endif #ifdef ARNL_GPSLOC const char *dopfmt = "%2.4f"; const char *posfmt = "%2.8f"; const char *altfmt = "%3.6f m"; Aria::getInfoGroup()->addStringString( "GPS Fix Mode", 25, new ArConstRetFunctorC<const char*, ArGPS>(gps, &ArGPS::getFixTypeName) ); Aria::getInfoGroup()->addStringInt( "GPS Num. Satellites", 4, new ArConstRetFunctorC<int, ArGPS>(gps, &ArGPS::getNumSatellitesTracked) ); Aria::getInfoGroup()->addStringDouble( "GPS HDOP", 12, new ArConstRetFunctorC<double, ArGPS>(gps, &ArGPS::getHDOP), dopfmt ); Aria::getInfoGroup()->addStringDouble( "GPS VDOP", 5, new ArConstRetFunctorC<double, ArGPS>(gps, &ArGPS::getVDOP), dopfmt ); Aria::getInfoGroup()->addStringDouble( "GPS PDOP", 5, new ArConstRetFunctorC<double, ArGPS>(gps, &ArGPS::getPDOP), dopfmt ); Aria::getInfoGroup()->addStringDouble( "Latitude", 15, new ArConstRetFunctorC<double, ArGPS>(gps, &ArGPS::getLatitude), posfmt ); Aria::getInfoGroup()->addStringDouble( "Longitude", 15, new ArConstRetFunctorC<double, ArGPS>(gps, &ArGPS::getLongitude), posfmt ); Aria::getInfoGroup()->addStringDouble( "Altitude", 8, new ArConstRetFunctorC<double, ArGPS>(gps, &ArGPS::getAltitude), altfmt ); // only some GPS receivers provide these, but you can uncomment them // here to enable them if yours does. /* const char *errfmt = "%2.4f m"; Aria::getInfoGroup()->addStringDouble( "GPS Lat. Err.", 6, new ArConstRetFunctorC<double, ArGPS>(gps, &ArGPS::getLatitudeError), errfmt ); Aria::getInfoGroup()->addStringDouble( "GPS Lon. Err.", 6, new ArConstRetFunctorC<double, ArGPS>(gps, &ArGPS::getLongitudeError), errfmt ); Aria::getInfoGroup()->addStringDouble( "GPS Alt. Err.", 6, new ArConstRetFunctorC<double, ArGPS>(gps, &ArGPS::getAltitudeError), errfmt ); */ Aria::getInfoGroup()->addStringDouble( "MOGS Localization Score", 8, new ArRetFunctorC<double, ArGPSLocalizationTask>( &gpsLocTask, &ArGPSLocalizationTask::getLocalizationScore), "%.03f" ); #endif // 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) ); } // Display system CPU and wireless network status ArSystemStatus::startPeriodicUpdate(1000); // update every 1 second Aria::getInfoGroup()->addStringDouble("CPU Use", 10, ArSystemStatus::getCPUPercentFunctor(), "% 4.0f%%"); Aria::getInfoGroup()->addStringInt("Wireless Link Quality", 9, ArSystemStatus::getWirelessLinkQualityFunctor(), "%d"); Aria::getInfoGroup()->addStringInt("Wireless Link Noise", 9, ArSystemStatus::getWirelessLinkNoiseFunctor(), "%d"); Aria::getInfoGroup()->addStringInt("Wireless Signal", 9, ArSystemStatus::getWirelessLinkSignalFunctor(), "%d"); // stats on how far its driven since software started Aria::getInfoGroup()->addStringDouble("Distance Travelled (m)", 20, new ArRetFunctorC<double, ArRobot>(&robot, &ArRobot::getOdometerDistanceMeters), "%.2f"); Aria::getInfoGroup()->addStringDouble("Run time (min)", 20, new ArRetFunctorC<double, ArRobot>(&robot, &ArRobot::getOdometerTimeMinutes), "%.2f"); #ifdef ARNL_GPSLOC // Add some "custom commands" for setting up initial GPS offset and heading. gpsLocTask.addLocalizationInitCommands(&commands); // Add some commands for manually creating map objects based on GPS positions: // ArGPSMapTools gpsMapTools(gps, &robot, &commands, &map); // Add command to set simulated GPS position manually if(gpsConnector.getGPSType() == ArGPSConnector::Simulator) { ArSimulatedGPS *simGPS = dynamic_cast<ArSimulatedGPS*>(gps); // simGPS->setDummyPosition(42.80709, -71.579047, 100); commands.addStringCommand("GPS:setDummyPosition", "Manually set a new dummy position for simulated GPS. Provide latitude (required), longitude (required) and altitude (optional)", new ArFunctor1C<ArSimulatedGPS, ArArgumentBuilder*>(simGPS, &ArSimulatedGPS::setDummyPositionFromArgs) ); } #endif // 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? #ifdef ARNL_MAPPING /* 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); #ifdef ARNL_LASERLOC // 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)); #endif #ifdef ARNL_GPSLOC // Save GPS positions in the .2d scan log when making a map handlerMapping.addLocationData("robotGPS", gpsLocTask.getPoseInterpPositionCallback()); // add the starting latitude and longitude info to the .2d scan log handlerMapping.addMappingStartCallback( new ArFunctor1C<ArGPSLocalizationTask, ArServerHandlerMapping *> (&gpsLocTask, &ArGPSLocalizationTask::addScanInfo, &handlerMapping)); #endif // Make it so our "lost" actions don't stop us while mapping handlerMapping.addMappingStartCallback(actionLostRatioDrive.getDisableCB()); handlerMapping.addMappingStartCallback(actionLostWander.getDisableCB()); // And then let them make us stop as usual when done mapping handlerMapping.addMappingEndCallback(actionLostRatioDrive.getEnableCB()); handlerMapping.addMappingEndCallback(actionLostWander.getEnableCB()); #endif // ARNL_MAPPING /* // 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: */ #pragma GPP off #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 #pragma GPP on /* Video image streaming, and camera controls (Requires SAVserver or ACTS) */ // Forward one video stream if either ACTS, ArVideo videoSubServer, // or SAV server are running. // ArHybridForwarderVideo allows this program to be separate from the ArVideo // library. You could replace videoForwarder and the PTZ connection code below // with a call to ArVideo::createVideoServers(), and link the program to the // ArVideo library if you want to include video capture in the same program // as robot control. ArHybridForwarderVideo videoForwarder(&server, "localhost", 7070); // connect to first configured camera PTZ controls (in robot parameter file and // command line options) ptzConnector.connect(); ArCameraCollection cameraCollection; ArPTZ *ptz = ptzConnector.getPTZ(0); if(ptz) { ArLog::log(ArLog::Normal, "Connected to PTZ Camera"); cameraCollection.addCamera("Camera1", ptz->getTypeName(), "Camera", ptz->getTypeName()); videoForwarder.setCameraName("Camera1"); videoForwarder.addToCameraCollection(cameraCollection); new ArServerHandlerCamera("Camera1", &server, &robot, ptz, &cameraCollection); } // Allows client to find any camera servers created above ArServerHandlerCameraCollection cameraCollectionServer(&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); // Read in parameter files. ArLog::log(ArLog::Normal, "Loading config file %s%s into ArConfig...", Aria::getDirectory(), Arnl::getTypicalParamFileName()); if (!Aria::getConfig()->parseFile(Arnl::getTypicalParamFileName())) { ArLog::log(ArLog::Normal, "Could not load ARNL configuration file. Set ARNL environment variable to use non-default installation director.y"); 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"); #ifdef ARNL 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, ""); #elif defined(SONARNL) ArLog::log(ArLog::Normal, " 0) You can find this information in README.txt or docs/SonarMapping.txt"); ArLog::log(ArLog::Normal, " 1) Start up Mapper3Basic"); ArLog::log(ArLog::Normal, " 2) Go to File->New"); ArLog::log(ArLog::Normal, " 3) Draw a line map of your area (make sure it is to scale)"); ArLog::log(ArLog::Normal, " 4) Go to File->Save on Robot"); ArLog::log(ArLog::Normal, " 5) In MobileEyes, go to Tools->Robot Config"); ArLog::log(ArLog::Normal, " 6) Choose the Files section"); ArLog::log(ArLog::Normal, " 7) Enter the path and name of your new .map file for the value of the Map parameter."); ArLog::log(ArLog::Normal, " 8) Press OK and your new map should become the map used"); ArLog::log(ArLog::Normal, ""); #endif #ifdef ARNL_GPSLOC ArLog::log(ArLog::Normal, "\n See docs/GPSMapping.txt for instructions on creating a map for GPS localization"); #endif } // 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. ARNL and SONARNL try 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). // MOGS instead just initializes at the current GPS position. // (You will stil have to drive the robot so it can determine the robot's // heading, however. See GPS Mapping instructions.) LOCTASK.localizeRobotAtHomeBlocking(); #ifdef ARNL_MULTIROBOT // Let the client switch manager (for multirobot) spin off into its own thread // TODO move to multirobot example? clientSwitch.runAsync(); #endif // Start the networking server's thread server.runAsync(); ArLog::log(ArLog::Normal, "Server running. To exit, press CTRL-C."); // Enable the motors and wait until the robot exits (disconnection, etc.) or this program is // canceled. robot.enableMotors(); robot.waitForRunExit(); Aria::exit(0); }
int main(int argc, char** argv) { Aria::init(); ArLog::init(ArLog::StdErr, ArLog::Normal); ArArgumentParser argParser(&argc, argv); ArSimpleConnector connector(&argParser); ArGPSConnector gpsConnector(&argParser); ArRobot robot; ArActionLimiterForwards nearLimitAction("limit near", 300, 600, 250); ArActionLimiterForwards farLimitAction("limit far", 300, 1100, 400); ArActionLimiterBackwards limitBackwardsAction; ArActionJoydrive joydriveAction; ArActionKeydrive keydriveAction; ArSonarDevice sonar; ArSick laser; argParser.loadDefaultArguments(); if(!Aria::parseArgs() || !argParser.checkHelpAndWarnUnparsed()) { Aria::logOptions(); return -1; } robot.addRangeDevice(&sonar); robot.addRangeDevice(&laser); ArLog::log(ArLog::Normal, "gpsRobotTaskExample: Connecting to robot..."); if(!connector.connectRobot(&robot)) { ArLog::log(ArLog::Terse, "gpsRobotTaskExample: Could not connect to the robot. Exiting."); return -2; } ArLog::log(ArLog::Normal, "gpsRobotTaskExample: Connected to the robot."); // Connect to GPS ArLog::log(ArLog::Normal, "gpsRobotTaskExample: Connecting to GPS, it may take a few seconds..."); ArGPS *gps = gpsConnector.createGPS(); if(!gps || !gps->connect()); { ArLog::log(ArLog::Terse, "gpsRobotTaskExample: Error connecting to GPS device. Try -gpsType, -gpsPort, and/or -gpsBaud command-line arguments. Use -help for help. Exiting."); return -3; } // Create an GPSLogTask which will register a task with the robot. GPSLogTask gpsTask(&robot, gps, joydriveAction.getJoyHandler()->haveJoystick() ? joydriveAction.getJoyHandler() : NULL); // Add actions robot.addAction(&nearLimitAction, 100); robot.addAction(&farLimitAction, 90); robot.addAction(&limitBackwardsAction, 80); robot.addAction(&joydriveAction, 50); robot.addAction(&keydriveAction, 40); // allow keydrive action to drive robot even if joystick button isn't pressed joydriveAction.setStopIfNoButtonPressed(false); // Start the robot running robot.runAsync(true); // Connect to the laser connector.setupLaser(&laser); laser.runAsync(); if(!laser.blockingConnect()) ArLog::log(ArLog::Normal, "gpsRobotTaskExample: Warning, could not connect to SICK laser, will not use it."); robot.lock(); robot.enableMotors(); robot.comInt(47, 1); // enable joystick driving on some robots // Add exit callback to reset/unwrap steering wheels on seekur (critical if the robot doesn't have sliprings); does nothing for other robots Aria::addExitCallback(new ArRetFunctor1C<bool, ArRobot, unsigned char>(&robot, &ArRobot::com, (unsigned char)120)); Aria::addExitCallback(new ArRetFunctor1C<bool, ArRobot, unsigned char>(&robot, &ArRobot::com, (unsigned char)120)); robot.unlock(); ArLog::log(ArLog::Normal, "gpsRobotTaskExample: Running... (drive robot with joystick or arrow keys)"); robot.waitForRunExit(); return 0; }
int main(int argc, char **argv) { Aria::init(); ArRobot robot; ArServerBase server; ArArgumentParser parser(&argc, argv); ArSimpleConnector simpleConnector(&parser); ArServerSimpleOpener simpleOpener(&parser); // parse the command line... fail and print the help if the parsing fails // or if help was requested parser.loadDefaultArguments(); if (!simpleConnector.parseArgs() || !simpleOpener.parseArgs() || !parser.checkHelpAndWarnUnparsed()) { simpleConnector.logOptions(); simpleOpener.logOptions(); exit(1); } // Set up where we'll look for files such as config file, user/password file, // etc. char fileDir[1024]; ArUtil::addDirectories(fileDir, sizeof(fileDir), Aria::getDirectory(), "ArNetworking/examples"); // first open the server up if (!simpleOpener.open(&server, fileDir, 240)) { if (simpleOpener.wasUserFileBad()) printf("Error: Bad user/password/permissions file.\n"); else printf("Error: Could not open server port. Use -help to see options.\n"); exit(1); } // Devices ArAnalogGyro gyro(&robot); ArSonarDevice sonarDev; robot.addRangeDevice(&sonarDev); ArIRs irs; robot.addRangeDevice(&irs); ArBumpers bumpers; robot.addRangeDevice(&bumpers); ArSick sick(361, 180); robot.addRangeDevice(&sick); ArServerInfoRobot serverInfoRobot(&server, &robot); ArServerInfoSensor serverInfoSensor(&server, &robot); // This is the service that provides drawing data to the client. ArServerInfoDrawings drawings(&server); // Convenience function that sets up drawings for all the robot's current // range devices (using default shape and color info) drawings.addRobotsRangeDevices(&robot); // Add our custom drawings drawings.addDrawing( // shape: color: size: layer: new ArDrawingData("polyLine", ArColor(255, 0, 0), 2, 49), "exampleDrawing_Home", new ArGlobalFunctor2<ArServerClient*, ArNetPacket*>(&exampleHomeDrawingNetCallback) ); drawings.addDrawing( new ArDrawingData("polyDots", ArColor(0, 255, 0), 250, 48), "exampleDrawing_Dots", new ArGlobalFunctor2<ArServerClient*, ArNetPacket*>(&exampleDotsDrawingNetCallback) ); drawings.addDrawing( new ArDrawingData("polySegments", ArColor(0, 0, 0), 4, 52), "exampleDrawing_XMarksTheSpot", new ArGlobalFunctor2<ArServerClient*, ArNetPacket*>(&exampleXDrawingNetCallback) ); drawings.addDrawing( new ArDrawingData("polyArrows", ArColor(255, 0, 255), 500, 100), "exampleDrawing_Arrows", new ArGlobalFunctor2<ArServerClient*, ArNetPacket*>(&exampleArrowsDrawingNetCallback) ); // modes for moving the robot ArServerModeStop modeStop(&server, &robot); ArServerModeDrive modeDrive(&server, &robot); ArServerModeRatioDrive modeRatioDrive(&server, &robot); ArServerModeWander modeWander(&server, &robot); modeStop.addAsDefaultMode(); modeStop.activate(); // Connect to the robot. if (!simpleConnector.connectRobot(&robot)) { printf("Error: Could not connect to robot... exiting\n"); Aria::shutdown(); return 1; } // set up the laser before handing it to the laser mode simpleConnector.setupLaser(&sick); robot.enableMotors(); // start the robot cycle running in a background thread robot.runAsync(true); // start the laser processing cycle in a background thread sick.runAsync(); // connect the laser if it was requested if (!simpleConnector.connectLaser(&sick)) { printf("Error: Could not connect to laser... exiting\n"); Aria::shutdown(); return 1; } // log whatever we wanted to before the runAsync simpleOpener.checkAndLog(); // run the server thread in the background server.runAsync(); printf("Server is now running...\n"); // Add a key handler mostly that windows can exit by pressing // escape, note that the key handler prevents you from running this program // in the background on Linux. ArKeyHandler *keyHandler; if ((keyHandler = Aria::getKeyHandler()) == NULL) { keyHandler = new ArKeyHandler; Aria::setKeyHandler(keyHandler); robot.lock(); robot.attachKeyHandler(keyHandler); robot.unlock(); printf("To exit, press escape.\n"); } robot.waitForRunExit(); Aria::shutdown(); exit(0); }
int main(int argc, char **argv) { int t, cnt; double laser_dist[900]; double laser_angle[900]; std::list<ArSensorReading *> *readings; std::list<ArSensorReading *>::iterator it; ArKeyHandler keyHandler; Aria::init(); // Add the key handler to Aria so other things can find it Aria::setKeyHandler(&keyHandler); robot.attachKeyHandler(&keyHandler); // add the laser to the robot robot.addRangeDevice(&sick); // Parse all our args ArSimpleConnector connector(&argc, argv); if (!connector.parseArgs() || argc > 1) { connector.logOptions(); exit(1); } robot.addRangeDevice(&sick); // try to connect, if we fail exit if (!connector.connectRobot(&robot)) { printf("Could not connect to robot... exiting\n"); Aria::shutdown(); return 1; } // start the robot running, true so that if we lose connection the run stops robot.runAsync(true); // now set up the laser sick.configureShort(true,ArSick::BAUD38400,ArSick::DEGREES180,ArSick::INCREMENT_ONE); connector.setupLaser(&sick); sick.runAsync(); if (!sick.blockingConnect()) { printf("Could not connect to SICK laser... exiting\n"); Aria::shutdown(); return 1; } cnt = 1; while(cnt<10000){ readings=(list<ArSensorReading *,allocator<ArSensorReading *> > *)sick.getRawReadings();//CurrentBuffer.. while (readings == NULL){ readings = (list<ArSensorReading *, allocator<ArSensorReading *> > *)sick.getRawReadings(); } t=0; for(it=readings->begin(); it!=readings->end(); it++){ //cout << "t: " << t << endl; laser_dist[t]=(*it)->getRange(); laser_angle[t]=-90+t; //cout << "laser angle: " << laser_angle[t] << " laser dist.: " << laser_dist[t] <<" "<<"\n"; t++; } cout << "count: " << cnt << endl; //for some reason this line needs to be here cnt++; } for (t=0; t<181; t++){ cout << "laser angle: " << laser_angle[t] << " laser dist.: " << laser_dist[t] <<" "<<"\n"; } robot.waitForRunExit(); Aria::shutdown(); return 0; }
int main(int argc, char **argv) { Aria::init(); ArArgumentParser parser(&argc, argv); parser.loadDefaultArguments(); ArRobot robot; ArRobotConnector robotConnector(&parser, &robot); ArLaserConnector laserConnector(&parser, &robot, &robotConnector); ArAnalogGyro analogGyro(&robot); // Always connect to the laser, and add half-degree increment and 180 degrees as default arguments for // laser parser.addDefaultArgument("-connectLaser -laserDegrees 180 -laserIncrement half"); if(!robotConnector.connectRobot()) { ArLog::log(ArLog::Terse, "sickLagger: Could not connect to the robot."); if(parser.checkHelpAndWarnUnparsed()) { Aria::logOptions(); Aria::exit(1); } } if(!Aria::parseArgs() || !parser.checkHelpAndWarnUnparsed()) { Aria::logOptions(); Aria::exit(1); } ArKeyHandler keyHandler; Aria::setKeyHandler(&keyHandler); robot.attachKeyHandler(&keyHandler); #ifdef WIN32 printf("Pausing 5 seconds so you can disconnect VNC if you are using it.\n"); ArUtil::sleep(5000); #endif std::string filename = "1scans.2d"; if (argc > 1) filename = argv[1]; printf("Logging to file %s\n", filename.c_str()); ArActionGroupRatioDriveUnsafe group(&robot); group.activateExclusive(); robot.runAsync(true); if(!laserConnector.connectLasers(false, false, true)) { ArLog::log(ArLog::Terse, "sickLogger: Error: Could not connect to laser(s). Use -help to list options."); Aria::exit(3); } // Allow some time for first set of laser reading to arrive ArUtil::sleep(500); // enable the motors, disable amigobot sounds robot.comInt(ArCommands::SONAR, 0); robot.comInt(ArCommands::ENABLE, 1); robot.comInt(ArCommands::SOUND, 32); robot.comInt(ArCommands::SOUNDTOG, 0); // enable the joystick driving from the one connected to the microcontroller robot.comInt(ArCommands::JOYDRIVE, 1); // Create the logging object // This must be created after the robot and laser are connected so it can get // correct parameters from them. // The third argmument is how far the robot must travel before a new laser // scan is logged. // The fourth argument is how many degrees the robot must rotate before a new // laser scan is logged. The sixth boolean argument is whether to place a goal // when the g or G key is pressed (by adding a handler to the global // ArKeyHandler) or when the robots joystick button is // pressed. ArLaser *laser = robot.findLaser(1); if(!laser) { ArLog::log(ArLog::Terse, "sickLogger: Error, not connected to any lasers."); Aria::exit(2); } ArLaserLogger logger(&robot, laser, 300, 25, filename.c_str(), true); // just hang out and wait for the end robot.waitForRunExit(); Aria::exit(0); }
int main(int argc, char **argv) { //----------------------initialized robot server------------------------------------------ Aria::init(); Arnl::init(); ArServerBase server; //----------------------------------------------------------------------------------- VCCHandler ptz(&robot); //create keyboard for control vcc50i G_PTZHandler->reset(); ArUtil::sleep(300); G_PTZHandler->panSlew(30); //----------------------------------------------------------------------------------- argc = 2 ; argv[0] = "-map"; argv[1] = "map20121111.map"; // Parse the command line arguments. ArArgumentParser parser(&argc, argv); // Set up our simpleConnector ArSimpleConnector simpleConnector(&parser); // Set up our simpleOpener ArServerSimpleOpener simpleOpener(&parser); //******* // Set up our client for the central server // ArClientSwitchManager clientSwitch(&server, &parser); //************ // Load default arguments for this computer (from /etc/Aria.args, environment // variables, and other places) // parser.loadDefaultArguments(); // set up a gyro ArAnalogGyro gyro(&robot); //gyro.activate(); // Parse arguments for the simple connector. // if (!Aria::parseArgs() || !parser.checkHelpAndWarnUnparsed()) // { // ArLog::log(ArLog::Normal, "\nUsage: %s -map mapfilename\n", argv[0]); // Aria::logOptions(); // Aria::exit(1); // } // The laser object, will be used if we have one // Add the laser to the robot robot.addRangeDevice(&sick); // Sonar, must be added to the robot, used by teleoperation and wander to // detect obstacles, and for localization if SONARNL ArSonarDevice sonarDev; // Add the sonar to the robot robot.addRangeDevice(&sonarDev); // Set up where we'll look for files char fileDir[1024]; ArUtil::addDirectories(fileDir, sizeof(fileDir), "./", "maps"); ArLog::log(ArLog::Normal, "Installation directory is: %s\nMaps directory is: %s\n", Aria::getDirectory(), fileDir); // Set up the map, 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 current directory // instead ArMap arMap(fileDir); // set it up to ignore empty file names (otherwise the parseFile // on the config will fail) arMap.setIgnoreEmptyFileName(true); //******************************** //Localization //******************************** ArLocalizationManager locManager(&robot, &arMap); ArLog::log(ArLog::Normal, "Creating laser localization task"); ArLocalizationTask locTask (&robot, &sick, &arMap); locManager.addLocalizationTask(&locTask); //******************************* //Path planning //******************************* // Make the path task planning task ArPathPlanningTask pathTask(&robot, &sick, &sonarDev, &arMap); G_PathPlanning = &pathTask; // Set up things so data can be logged (only do it with the laser // since it can overrun a 9600 serial connection which the sonar is // more likely to have) ArDataLogger dataLogger(&robot); dataLogger.addToConfig(Aria::getConfig()); // add our logging to the config // ArLog::addToConfig(Aria::getConfig()); // First open the server if (!simpleOpener.open(&server, fileDir, 240)) { if (simpleOpener.wasUserFileBad()) ArLog::log(ArLog::Normal, "Bad user file"); else ArLog::log(ArLog::Normal, "Could not open server port"); exit(2); } // Connect the robot if (!simpleConnector.connectRobot(&robot)) { ArLog::log(ArLog::Normal, "Could not connect to robot... exiting"); Aria::exit(3); } //----------------------------------------------- //************************** // Set up a class that'll put the movement and gyro parameters into ArConfig ArRobotConfig robotConfig(&robot); robotConfig.addAnalogGyro(&gyro); //***************************** robot.enableMotors(); robot.clearDirectMotion(); // if we are connected to a simulator, reset it to its start position robot.comInt(ArCommands::RESETSIMTOORIGIN, 1); robot.moveTo(ArPose(0,0,0)); // Set up laser using connector (command line arguments, etc.) simpleConnector.setupLaser(&sick); // Start the robot thread. robot.runAsync(true); // Start the laser thread. sick.runAsync(); // Try to connect the laser if (!sick.blockingConnect()) ArLog::log(ArLog::Normal, "Warning: Couldn't connect to SICK laser, it won't be used"); else ArLog::log(ArLog::Normal, "Connected to laser."); //*************************************** // Add additional range devices to the robot and path planning task. // IRs if the robot has them. robot.lock(); // ArIRs irs; // robot.addRangeDevice(&irs); // pathTask.addRangeDevice(&irs, ArPathPlanningTask::CURRENT); //****************************************** // Forbidden regions from the map ArForbiddenRangeDevice forbidden(&arMap); robot.addRangeDevice(&forbidden); // This is the place to add a range device which will hold sensor data // and delete it appropriately to replan around blocked paths. ArGlobalReplanningRangeDevice replanDev(&pathTask); // Create objects that add network services: // Drawing in the map display: ArServerInfoDrawings drawings(&server); drawings.addRobotsRangeDevices(&robot); drawings.addRangeDevice(&replanDev); /* If you want to draw the destination put this code back in: ArServerDrawingDestination destination( &drawings, &pathTask, "destination", 500, 500, new ArDrawingData("polyDots", ArColor(0xff, 0xff, 0x0), 800, // size 49), // just below the robot */ /* If you want to see 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); */ /* If you want to see the points making up the local path in addition to the * main path use this. ArDrawingData drawingDataP2("polyDots", ArColor(0,128,0), 100, 70); ArFunctor2C<ArPathPlanningTask, ArServerClient *, ArNetPacket *> drawingFunctorP2(pathTask, &ArPathPlanningTask::drawPathPoints); drawings.addDrawing(&drawingDataP2, "Path Points", &drawingFunctorP2); */ // Misc. simple commands: 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); //-------------------------receive commands or events from client--------------------- // ArServerHandlerCommands commands(&server); server.addData("RobotVideo" ,"", new ArGlobalFunctor2<ArServerClient *, ArNetPacket*>(&VideoServerBase::RobotVideoCB) ,"",""); server.addData("turn" ,"", new ArGlobalFunctor2<ArServerClient *, ArNetPacket*>(&turn_func) ,"",""); server.addData("RobotMotion" ,"", new ArGlobalFunctor2<ArServerClient *, ArNetPacket*>(&S_RobotMotion) ,"",""); server.addData("CameraMotion" ,"", new ArGlobalFunctor2<ArServerClient *, ArNetPacket*>(&S_CameraMotion) ,"",""); server.addData("RobotTurnLeft" ,"", new ArGlobalFunctor2<ArServerClient *, ArNetPacket*>(&S_RobotTurnLeft) ,"",""); server.addData("RobotTurnRight" ,"", new ArGlobalFunctor2<ArServerClient *, ArNetPacket*>(&S_RobotTurnRight) ,"",""); server.addData("TargetApproach" ,"", new ArGlobalFunctor2<ArServerClient *, ArNetPacket*>(&S_TargetApproach) ,"",""); server.addData("TargetApproachObstacles" ,"", new ArGlobalFunctor2<ArServerClient *, ArNetPacket*>(&S_TargetApproach_Obstacles) ,"",""); server.addData("GlassesCancel" ,"", new ArGlobalFunctor2<ArServerClient *, ArNetPacket*>(&S_GlassesCancel) ,"",""); server.addData("Calibration" ,"", new ArGlobalFunctor2<ArServerClient *, ArNetPacket*>(&S_Calibration) ,"",""); server.addClientRemovedCallback(new ArGlobalFunctor1< ArServerClient * >(&clientCloseCallback)); //-------------------------receive commands or events from client--------------------- //*********************** ArServerInfoLocalization serverInfoLocalization (&server, &robot, &locManager); ArServerHandlerLocalization serverLocHandler (&server, &robot, &locManager); // Provide the map to the client (and related controls): // This uses both lines and points now, since everything except // sonar localization uses both (path planning with sonar still uses both) ArServerHandlerMap serverMap(&server, &arMap); // Add some simple (custom) commands for testing and debugging: ArServerSimpleComUC uCCommands(&commands, &robot); // Send any command to the microcontroller ArServerSimpleComMovementLogging loggingCommands(&commands, &robot); // configure logging ArServerSimpleComGyro gyroCommands(&commands, &robot, &gyro); // monitor the gyro ArServerSimpleComLogRobotConfig configCommands(&commands, &robot); // trigger logging of the robot config parameters ArServerSimpleServerCommands serverCommands(&commands, &server); // monitor networking behavior (track packets sent etc.) /* 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, &arMap, ArPose(0,0,0)); // Add a simple (custom) command that allows you to give a list of // goals to tour, instead of all. Useful for testing and debugging. modeGoto.addTourGoalsInListSimpleCommand(&commands); // 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, this should not be done if you need the sonar // data to localize, or for other purposes while stopped) ArSonarAutoDisabler sonarAutoDisabler(&robot); // Teleoperation modes To drive by keyboard, joystick, etc: ArServerModeRatioDrive modeRatioDrive(&server, &robot); // New, improved mode ArServerModeDrive modeDrive(&server, &robot); // Older mode for compatability // Drive mode's configuration and custom (simple) commands: modeRatioDrive.addToConfig(Aria::getConfig(), "Teleop settings"); modeDrive.addControlCommands(&commands); modeRatioDrive.addControlCommands(&commands); // Wander mode // ArServerModeWander modeWander(&server, &robot); //********************************* // Prevent driving if localization is lost: ArActionLost actionLostRatioDrive (&locManager, NULL, &modeRatioDrive); modeRatioDrive.getActionGroup ()->addAction (&actionLostRatioDrive, 110); // Prevent wandering if lost: // ArActionLost // actionLostWander (&locManager, NULL, &modeWander); // modeWander.getActionGroup ()->addAction (&actionLostWander, 110); // This provides a small table of interesting information for the client // to display to the operator: ArServerInfoStrings stringInfo(&server); Aria::getInfoGroup()->addAddStringCallback(stringInfo.getAddStringFunctor()); Aria::getInfoGroup()->addStringInt( "Motor Packet Count", 10, new ArConstRetFunctorC<int, ArRobot>(&robot, &ArRobot::getMotorPacCount)); // Make Stop mode the default (If current mode deactivates without entering // a new mode, then Stop Mode will be selected) modeStop.addAsDefaultMode(); // Create the service that allows the client to monitor the communication // between the robot and the client. // ArServerHandlerCommMonitor handlerCommMonitor(&server); // Create service that allows client to change configuration parameters in ArConfig ArServerHandlerConfig handlerConfig(&server, Aria::getConfig(), Arnl::getTypicalDefaultParamFileName(), Aria::getDirectory()); // Read in parameter files. read the paras from input Aria::getConfig()->useArgumentParser(&parser); 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()) { ArLog::log(ArLog::Normal, "\nUsage: %s -map mapfilename\n", argv[0]); simpleConnector.logOptions(); simpleOpener.logOptions(); Aria::exit(6); } // Warn if there is no map if (arMap.getFileName() == NULL || strlen(arMap.getFileName()) <= 0) { ArLog::log(ArLog::Normal, ""); ArLog::log(ArLog::Normal, "### Warning, No map file is set up, you can make a map with sickLogger or arnlServer, and Mapper3; More info in docs/Mapping.txt and README.txt. Set the map with the -map command line option, or by changing the config with MobileEyes or by editing the config file."); ArLog::log(ArLog::Normal, ""); } // find out where we'll want to put 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, ""); // If you want MobileSim to try and load up the same map as you are // using in guiServer then uncomment out the next line and this object // will send a command to MobileSim to do so, but make sure you start // MobileSim from the Arnl/examples directory or use the --cwd option, // so that the map names used by MobileSim match the map names used // by guiServer //ArSimMapSwitcher mapSwitcher(&robot, &arMap); /****************************************************** * **************************************************** * Camera * **************************************************** * *****************************************************/ robot.unlock(); // Localize robot at home. locTask.localizeRobotAtHomeBlocking(); locTask.forceUpdatePose(ArPose(0,0,0)); resetMotion(); // robot.enableMotors(); // robot.runAsync(true); //locTask.localizeRobotAtHomeBlocking(); server.runAsync(); VideoServerBase videoserver; videoserver.runAsync(); robot.comInt(ArCommands::SOUNDTOG, 0); //G_PathPlanning->pathPlanToPose(ArPose(1500, -1500 , -32),true,true); //while(G_PathPlanning->getState() != ArPathPlanningTask::REACHED_GOAL ); //S_TargetApproach_Obstacles1(); //ArUtil::sleep(5000); // G_PTZHandler->panRel(60); // ArUtil::sleep(3000); //while(1) //S_TargetApproach1(); cout << "done!!!!!!!---------------------" <<endl; robot.waitForRunExit(); Aria::exit(0); }
int main(int argc, char **argv) { Aria::init(); ArRobot robot; ArSonarDevice sonar; ArSick sick; robot.addRangeDevice(&sonar); ArServerBase server; // Argument parser: ArArgumentParser parser(&argc, argv); parser.loadDefaultArguments(); // Connector and server opener: ArRobotConnector robotConnector(&parser, &robot); if(!robotConnector.connectRobot()) { ArLog::log(ArLog::Terse, "popupExample: Could not connect to the robot."); if(parser.checkHelpAndWarnUnparsed()) { Aria::logOptions(); } Aria::exit(1); } ArLaserConnector laserConnector(&parser, &robot, &robotConnector); ArServerSimpleOpener simpleOpener(&parser); // Get command-line and other parameters if(!Aria::parseArgs() || !parser.checkHelpAndWarnUnparsed()) { Aria::logOptions(); Aria::exit(1); } robot.runAsync(true); // connect to the laser if(!laserConnector.connectLasers()) { ArLog::log(ArLog::Normal, "popupExample: Warning: Could not connect to lasers."); } // Open the server if(!simpleOpener.open(&server)) { ArLog::log(ArLog::Terse, "popupExample: Error, could not open server."); return 1; } server.runAsync(); ArLog::log(ArLog::Normal, "popupExample: Server running. Press control-C to exit."); ArLog::log(ArLog::Normal, "popupExample: Each time an obstacle is detected near the robot, a new popup message will be created. Connect with MobileEyes to see them."); // Sends robot position etc. ArServerInfoRobot robotInfoServer(&server, &robot); // This service sends drawings e.g. showing range device positions ArServerInfoDrawings drawingsServer(&server); drawingsServer.addRobotsRangeDevices(&robot); // This service can send messages to clients to display as popup dialogs: ArServerHandlerPopup popupServer(&server); // This object contains the robot sensor interpretation task and creates // popups: SensorDetectPopup(&robot, &popupServer); // modes for controlling robot movement ArServerModeStop modeStop(&server, &robot); ArServerModeRatioDrive modeRatioDrive(&server, &robot); ArServerModeWander modeWander(&server, &robot); modeStop.addAsDefaultMode(); modeStop.activate(); // allow configuration of driving and other settings ArServerHandlerConfig serverHandlerConfig(&server, Aria::getConfig()); // make a config handler ArLog::addToConfig(Aria::getConfig()); // let people configure logging modeRatioDrive.addToConfig(Aria::getConfig(), "Teleop settings"); // able to configure teleop settings robot.enableMotors(); robot.waitForRunExit(); Aria::exit(0); }
int main(int argc, char **argv) { int ret; std::string str; // the serial connection (robot) ArSerialConnection serConn; // tcp connection (sim) ArTcpConnection tcpConn; // the robot ArRobot robot; // the laser ArSick sick; // the laser connection ArSerialConnection laserCon; bool useSimForLaser = false; std::string hostname = "prod.local.net"; // timeouts in minutes int wanderTime = 0; int restTime = 0; // check arguments if (argc == 3 || argc == 4) { wanderTime = atoi(argv[1]); restTime = atoi(argv[2]); if (argc == 4) hostname = argv[3]; } else { printf("\nUsage:\n\tpeoplebotTest <wanderTime> <restTime> <hostname>\n\n"); printf("Times are in minutes. Hostname is the machine to pipe the ACTS display to\n\n"); wanderTime = 15; restTime = 45; } printf("Wander time - %d minutes\nRest time - %d minutes\n", wanderTime, restTime); printf("Sending display to %s.\n\n", hostname.c_str()); // sonar, must be added to the robot ArSonarDevice sonar; // the actions we'll use to wander ArActionStallRecover recover; ArActionBumpers bumpers; ArActionAvoidFront avoidFrontNear("Avoid Front Near", 225, 0); ArActionAvoidFront avoidFrontFar; // Make a key handler, so that escape will shut down the program // cleanly ArKeyHandler keyHandler; // mandatory init Aria::init(); // Add the key handler to Aria so other things can find it Aria::setKeyHandler(&keyHandler); // Attach the key handler to a robot now, so that it actually gets // some processing time so it can work, this will also make escape // exit robot.attachKeyHandler(&keyHandler); // First we see if we can open the tcp connection, if we can we'll // assume we're connecting to the sim, and just go on... if we // can't open the tcp it means the sim isn't there, so just try the // robot // modify this next line if you're not using default tcp connection tcpConn.setPort(); // see if we can get to the simulator (true is success) if (tcpConn.openSimple()) { // we could get to the sim, so set the robots device connection to the sim printf("Connecting to simulator through tcp.\n"); robot.setDeviceConnection(&tcpConn); } else { // we couldn't get to the sim, so set the port on the serial // connection and then set the serial connection as the robots // device // modify the next line if you're not using the first serial port // to talk to your robot serConn.setPort(); printf( "Could not connect to simulator, connecting to robot through serial.\n"); robot.setDeviceConnection(&serConn); } // add the sonar to the robot robot.addRangeDevice(&sonar); // add the laser robot.addRangeDevice(&sick); // try to connect, if we fail exit if (!robot.blockingConnect()) { printf("Could not connect to robot... exiting\n"); Aria::shutdown(); return 1; } // turn on the motors, turn off amigobot sounds //robot.comInt(ArCommands::ENABLE, 1); robot.comInt(ArCommands::SOUNDTOG, 0); // turn off the sonar to start with robot.comInt(ArCommands::SONAR, 0); // add the actions robot.addAction(&recover, 100); robot.addAction(&bumpers, 75); robot.addAction(&avoidFrontNear, 50); robot.addAction(&avoidFrontFar, 49); // start the robot running, true so that if we lose connection the run stops robot.runAsync(true); if (!useSimForLaser) { sick.setDeviceConnection(&laserCon); if ((ret = laserCon.open("/dev/ttyS2")) != 0) { str = tcpConn.getOpenMessage(ret); printf("Open failed: %s\n", str.c_str()); Aria::shutdown(); return 1; } sick.configureShort(false); } else { sick.configureShort(true); } sick.runAsync(); if (!sick.blockingConnect()) { printf("Could not connect to SICK laser... exiting\n"); Aria::shutdown(); return 1; } robot.lock(); robot.comInt(ArCommands::ENABLE, 1); robot.unlock(); // add the peoplebot test PeoplebotTest pbTest(&robot, wanderTime, restTime, hostname); robot.waitForRunExit(); // now exit Aria::shutdown(); return 0; }
int main (int argc, char** argv) { Aria::init(); Arnl::init(); ArRobot robot; ArArgumentParser parser(&argc, argv); parser.loadDefaultArguments(); ArRobotConnector robotConnector(&parser, &robot); if (!robotConnector.connectRobot()) { ArLog::log(ArLog::Terse, "Could not connect to the robot."); if(parser.checkHelpAndWarnUnparsed()) { // -help not given, just exit. Aria::logOptions(); Aria::exit(1); return 1; } } ArSonarDevice sonarDev; ArLog::log(ArLog::Normal, "OK"); char fileDir[1024]; ArUtil::addDirectories(fileDir, sizeof(fileDir), Aria::getDirectory(), "examples"); ArLog::log(ArLog::Normal, "Installation directory is: %s\nMaps directory is: %s\n", Aria::getDirectory(), fileDir); // strcpy(fileDir, "columbia.map"); ArLog::log(ArLog::Normal, "file Maps directory is: %s\n",fileDir); ArMap map(fileDir); map.readFile("columbia.map"); // set it up to ignore empty file names (otherwise the parseFile // on the config will fail) map.setIgnoreEmptyFileName(true); robot.addRangeDevice(&sonarDev); // set home pose robot.moveTo(ArPose(0,0,0)); ArPathPlanningTask pathPlan(&robot, &sonarDev, &map); ArActionGoto gotoPoseAction("goto"); // gotoPoseAction.activate(); // pathPlan.getPathPlanActionGroup()->addAction(&gotoPoseAction, 50); // pathPlan.getPathPlanAction()->activate(); ArForbiddenRangeDevice forbidden(&map); robot.addRangeDevice(&forbidden); pathPlan.addRangeDevice(&forbidden, ArPathPlanningTask::CURRENT); // pathPlan.planAndSetupAction(ArPose(0, 0, 0)); // pathPlan. /* if (pathPlan.pathPlanToPose(ArPose(1000, 1000, 0), true, true)) ArLog::log(ArLog::Normal, "OK"); else ArLog::log(ArLog::Normal, "FAILED"); */ // create functor ArGlobalFunctor1<ArPose> goalDone(&addGoalDone);// = new ArGlobalFunctor1(&addGoalDone); ArGlobalFunctor1<ArPose> goalFail(&addGoalFailed); ArGlobalFunctor1<ArPose> goalFinished(&addGoalFinished); ArGlobalFunctor1<ArPose> goalInterrupted(&addGoalInterrupted); // add functor pathPlan.addGoalDoneCB(&goalDone); pathPlan.addGoalFailedCB(&goalFail); pathPlan.addGoalFinishedCB(&goalFinished); pathPlan.addGoalInterruptedCB(&goalInterrupted); robot.runAsync(true); robot.enableMotors(); pathPlan.runAsync(); // ArPathPlanningTask::PathPlanningState state = pathPlan.getState(); // while(!pathPlan.pathPlanToPose(ArPose(1000, 1000, 0), true, true)); pathPlan.pathPlanToPose(ArPose(1000, 1000, 0), true, true); ArPathPlanningTask::PathPlanningState state = pathPlan.getState(); char* s = ""; switch(state) { case ArPathPlanningTask::NOT_INITIALIZED: {s = "NOT_INITIALIZED"; break;} case ArPathPlanningTask::PLANNING_PATH: { s = "PLANNING_PATH";break;} case ArPathPlanningTask::MOVING_TO_GOAL:{s = "MOVING_TO_GOAL";break;} case ArPathPlanningTask::REACHED_GOAL: {s = "REACHED_GOAL";break;} case ArPathPlanningTask::FAILED_PLAN: { s = "FAILED_PLAN";break;} case ArPathPlanningTask::FAILED_MOVE: { s="FAILED_MOVE";break;} case ArPathPlanningTask::ABORTED_PATHPLAN:{s = "ABORTED_PATHPLAN";break;} // case ArPathPlanningTask::INVALID: // default: // return "UNKNOWN"; } ArLog::log(ArLog::Normal,s); robot.waitForRunExit(); // pathPlan. // char* text = new char[512]; // pathPlan.getStatusString(text, sizeof(text)); // printf("Planning status: %s.\n", text); // while(pathPlan.pathPlanToPose(ArPose(1000, 1000, 0), true, true)); Aria::shutdown(); // Arnl::s; Aria::exit(0); }
int main(int argc, char *argv[]) { // Initialize location of Aria, Arnl and their args. Aria::init(); Arnl::init(); // The robot object ArRobot robot; // Parse the command line arguments. ArArgumentParser parser(&argc, argv); // Read data_index if exists int data_index; bool exist_data_index; parser.checkParameterArgumentInteger("dataIndex",&data_index,&exist_data_index); // Load default arguments for this computer (from /etc/Aria.args, environment // variables, and other places) parser.loadDefaultArguments(); // Object that connects to the robot or simulator using program options ArRobotConnector robotConnector(&parser, &robot); // set up a gyro ArAnalogGyro gyro(&robot); ArLog::init(ArLog::File,ArLog::Normal,"run.log",false,true,true); // Parse arguments for the simple connector. if (!Aria::parseArgs() || !parser.checkHelpAndWarnUnparsed()) { ArLog::log(ArLog::Normal, "\nUsage: %s -map mapfilename\n", argv[0]); Aria::logOptions(); Aria::exit(1); } // Collision avoidance actions at higher priority ArActionAvoidFront avoidAction("avoid",200); ArActionLimiterForwards limiterAction("speed limiter near", 150, 500, 150); ArActionLimiterForwards limiterFarAction("speed limiter far", 300, 1100, 400); ArActionLimiterTableSensor tableLimiterAction; //robot.addAction(&tableLimiterAction, 100); //robot.addAction(&avoidAction,100); //robot.addAction(&limiterAction, 95); //robot.addAction(&limiterFarAction, 90); // Goto action at lower priority ArActionGoto gotoPoseAction("goto"); //robot.addAction(&gotoPoseAction, 50); gotoPoseAction.setCloseDist(750); // Stop action at lower priority, so the robot stops if it has no goal ArActionStop stopAction("stop"); //robot.addAction(&stopAction, 40); // Connect the robot if (!robotConnector.connectRobot()) { ArLog::log(ArLog::Normal, "Could not connect to robot... exiting"); Aria::exit(3); } if(!robot.isConnected()) { ArLog::log(ArLog::Terse, "Internal error: robot connector succeeded but ArRobot::isConnected() is false!"); } // Connector for laser rangefinders ArLaserConnector laserConnector(&parser, &robot, &robotConnector); // Sonar, must be added to the robot, used by teleoperation and wander to // detect obstacles, and for localization if SONARNL ArSonarDevice sonarDev; // Add the sonar to the robot robot.addRangeDevice(&sonarDev); // Start the robot thread. robot.runAsync(true); // Connect to the laser(s) if lasers were configured in this robot's parameter // file or on the command line, and run laser processing thread if applicable // for that laser class. For the purposes of this demo, add all // possible lasers to ArRobot's list rather than just the ones that were // connected by this call so when you enter laser mode, you // can then interactively choose which laser to use from that list of all // lasers mentioned in robot parameters and on command line. Normally, // only connected lasers are put in ArRobot's list. if (!laserConnector.connectLasers( false, // continue after connection failures true, // add only connected lasers to ArRobot true // add all lasers to ArRobot )) { ArLog::log(ArLog::Normal ,"Could not connect to lasers... exiting\n"); Aria::exit(2); } // Puntero a laser ArSick* sick=(ArSick*)robot.findLaser(1); // Conectamos el laser sick->asyncConnect(); //Esperamos a que esté encendido while(!sick->isConnected()) { ArUtil::sleep(100); } ArLog::log(ArLog::Normal ,"Laser conectado\n"); // Set up things so data can be logged (only do it with the laser // since it can overrun a 9600 serial connection which the sonar is // more likely to have) ArDataLogger dataLogger(&robot); dataLogger.addToConfig(Aria::getConfig()); // add our logging to the config //ArLog::addToConfig(Aria::getConfig()); // Set up a class that'll put the movement and gyro parameters into ArConfig ArRobotConfig robotConfig(&robot); robotConfig.addAnalogGyro(&gyro); // Add additional range devices to the robot and path planning task. // IRs if the robot has them. robot.lock(); ArIRs irs; robot.addRangeDevice(&irs); // Bumpers. ArBumpers bumpers; robot.addRangeDevice(&bumpers); // cause the sonar to turn off automatically // when the robot is stopped, and turn it back on when commands to move // are sent. (Note, this should not be done if you need the sonar // data to localize, or for other purposes while stopped) ArSonarAutoDisabler sonarAutoDisabler(&robot); // Read in parameter files. Aria::getConfig()->useArgumentParser(&parser); if (!Aria::getConfig()->parseFile(Arnl::getTypicalParamFileName())) { ArLog::log(ArLog::Normal, "Trouble loading configuration file, exiting"); Aria::exit(5); } //Configuracion del laser sick->setMinDistBetweenCurrent(0); robot.enableMotors(); robot.setAbsoluteMaxTransVel(1000); /* Finally, get ready to run the robot: */ robot.unlock(); Controlador driver(&robot); if(exist_data_index){ driver.setDataIndex(data_index); } driver.runAsync(); ControlHandler handler(&driver,&robot); // Use manual key handler //handler.addKeyHandlers(&robot); robot.addSensorInterpTask("ManualKeyHandler",50,handler.getFunctor()); ArLog::log(ArLog::Normal ,"Añadido manejador teclado\n"); // double x,y,dist,angle; // ArPose punto; // ArPose origen=robot.getPose(); // sick->lockDevice(); // for(int i=-90;i<90;i++){ // // Obtengo la medida de distancia y angulo // dist=sick->currentReadingPolar(i,i+1,&angle); // // Obtengo coordenadas del punto usando el laser como referencia // x=dist*ArMath::cos(angle); // y=dist*ArMath::sin(angle); // //Roto los puntos // ArMath::pointRotate(&x,&y,-origen.getTh()); // punto.setX(x); // punto.setY(y); // punto=punto + origen; // printf("Medida: %d\t Angulo:%.2f\t Angulo:%.2f\t Distancia:%0.2f\t X:%0.2f\t Y:%0.2f\n",i,angle,angle+origen.getTh(),dist,punto.getX(),punto.getY()); // } // printf("Medidas adquiridas\n"); // sick->unlockDevice(); robot.waitForRunExit(); //ArUtil::sleep(10000); return 0; }
int main(int argc, char **argv) { Aria::init(); ArRobot robot; ArArgumentParser parser(&argc, argv); ArSimpleConnector simpleConnector(&parser); // The base server object, manages all connections to clients. ArServerBase server; // This object simplifies configuration and opening of the ArServerBase // object. ArServerSimpleOpener simpleOpener(&parser); // parse the command line. fail and print the help if the parsing fails // or if the help was requested with -help parser.loadDefaultArguments(); if (!simpleConnector.parseArgs() || !simpleOpener.parseArgs() || !parser.checkHelpAndWarnUnparsed()) { simpleConnector.logOptions(); simpleOpener.logOptions(); exit(1); } // Use the ArSimpleOpener to open the server port if (!simpleOpener.open(&server)) { ArLog::log(ArLog::Terse, "Error: Could not open server on port %d", simpleOpener.getPort()); exit(1); } // // Create services attached to the base server: // // Robot position etc.: ArServerInfoRobot serverInfoRobot(&server, &robot); // Robot control modes (only one mode can be active at once): ArServerModeStop modeStop(&server, &robot); // old ArServerModeDrive modeDrive(&server, &robot); ArServerModeRatioDrive modeRatioDrive(&server, &robot); ArServerModeWander modeWander(&server, &robot); modeStop.addAsDefaultMode(); modeStop.activate(); // This provides a simple way to add new commands. ArServerHandlerCommands commands(&server); // Add our custom command. ArServerHandlerCommands also has other methods // for adding commands taht take different kinds of arguments, or no // arguments. ArGlobalFunctor1<ArArgumentBuilder*> customCommandFunctor(&customCommandHandler); commands.addStringCommand("ExampleCustomCommand", "Example of a custom command. simpleServerExample will print out the text sent with the command.", &customCommandFunctor); // These objects provide various debugging and diagnostic custom commands: ArServerSimpleComUC uCCommands(&commands, &robot); // Get information about the robot ArServerSimpleComMovementLogging loggingCommands(&commands, &robot); // Control logging modeRatioDrive.addControlCommands(&commands); // Drive mode diagnostics // This provides the client (e.g. MobileEyes) with a simple table of string values // (called an InfoGroup). An InfoGroup is kept globally by Aria. // The values in the table sent to clients are retrieved periodically by calling a // functor. ArServerInfoStrings stringInfo(&server); Aria::getInfoGroup()->addAddStringCallback(stringInfo.getAddStringFunctor()); // Here are some example entries in the InfoGroup: Aria::getInfoGroup()->addStringInt( "Motor Packet Count", 10, new ArConstRetFunctorC<int, ArRobot>(&robot, &ArRobot::getMotorPacCount)); // // Connect to the robot: // if (!simpleConnector.connectRobot(&robot)) { printf("Error: Could not connect to robot... exiting\n"); Aria::shutdown(); return 1; } robot.enableMotors(); robot.runAsync(true); // The simple opener might have information to display right before starting // the server thread: simpleOpener.checkAndLog(); // now let the server base run in a new thread, accepting client connections. server.runAsync(); ArLog::log(ArLog::Normal, "Server is now running... Press Ctrl-C to exit."); robot.waitForRunExit(); Aria::shutdown(); exit(0); }
int main(int argc, char **argv) { // mandatory init Aria::init(); //ArLog::init(ArLog::StdOut, ArLog::Verbose); // set up our parser ArArgumentParser parser(&argc, argv); // load the default arguments parser.loadDefaultArguments(); // robot ArRobot robot; // set up our simple connector ArRobotConnector robotConnector(&parser, &robot); // add a gyro, it'll see if it should attach to the robot or not ArAnalogGyro gyro(&robot); // set up the robot for connecting if (!robotConnector.connectRobot()) { printf("Could not connect to robot... exiting\n"); Aria::exit(1); } ArDataLogger dataLogger(&robot, "dataLog.txt"); dataLogger.addToConfig(Aria::getConfig()); // our base server object ArServerBase server; ArLaserConnector laserConnector(&parser, &robot, &robotConnector); ArServerSimpleOpener simpleOpener(&parser); ArClientSwitchManager clientSwitchManager(&server, &parser); // parse the command line... fail and print the help if the parsing fails // or if the help was requested if (!Aria::parseArgs() || !parser.checkHelpAndWarnUnparsed()) { Aria::logOptions(); Aria::exit(1); } // Set up where we'll look for files such as user/password char fileDir[1024]; ArUtil::addDirectories(fileDir, sizeof(fileDir), Aria::getDirectory(), "ArNetworking/examples"); // first open the server up if (!simpleOpener.open(&server, fileDir, 240)) { if (simpleOpener.wasUserFileBad()) printf("Bad user/password/permissions file\n"); else printf("Could not open server port\n"); exit(1); } // Range devices: ArSonarDevice sonarDev; robot.addRangeDevice(&sonarDev); ArIRs irs; robot.addRangeDevice(&irs); ArBumpers bumpers; robot.addRangeDevice(&bumpers); // attach services to the server ArServerInfoRobot serverInfoRobot(&server, &robot); ArServerInfoSensor serverInfoSensor(&server, &robot); ArServerInfoDrawings drawings(&server); // modes for controlling robot movement ArServerModeStop modeStop(&server, &robot); ArServerModeRatioDrive modeRatioDrive(&server, &robot); ArServerModeWander modeWander(&server, &robot); modeStop.addAsDefaultMode(); modeStop.activate(); // set up the simple commands ArServerHandlerCommands commands(&server); ArServerSimpleComUC uCCommands(&commands, &robot); // send commands directly to microcontroller ArServerSimpleComMovementLogging loggingCommands(&commands, &robot); // control debug logging ArServerSimpleComGyro gyroCommands(&commands, &robot, &gyro); // configure gyro ArServerSimpleComLogRobotConfig configCommands(&commands, &robot); // control more debug logging ArServerSimpleServerCommands serverCommands(&commands, &server); // control ArNetworking debug logging ArServerSimpleLogRobotDebugPackets logRobotDebugPackets(&commands, &robot, "."); // debugging tool // ArServerModeDrive is an older drive mode. ArServerModeRatioDrive is newer and generally performs better, // but you can use this for old clients if neccesary. //ArServerModeDrive modeDrive(&server, &robot); //modeDrive.addControlCommands(&commands); // configure the drive modes (e.g. enable/disable safe drive) ArServerHandlerConfig serverHandlerConfig(&server, Aria::getConfig()); // make a config handler ArLog::addToConfig(Aria::getConfig()); // let people configure logging modeRatioDrive.addToConfig(Aria::getConfig(), "Teleop settings"); // able to configure teleop settings modeRatioDrive.addControlCommands(&commands); // Forward 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 separate 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); // Control a pan/tilt/zoom camera, if one is installed, and the video // forwarder was enabled above. ArPTZ *camera = NULL; ArServerHandlerCamera *handlerCamera = NULL; ArCameraCollection *cameraCollection = NULL; if (videoForwarder.isForwardingVideo()) { bool invertedCamera = false; camera = new ArVCC4(&robot, invertedCamera, ArVCC4::COMM_UNKNOWN, true, true); camera->init(); cameraCollection = new ArCameraCollection(); cameraCollection->addCamera("Cam1", "VCC4", "Camera", "VCC4"); handlerCamera = new ArServerHandlerCamera("Cam1", &server, &robot, camera, cameraCollection); } // You can use this class to send a set of arbitrary strings // for MobileEyes to display, this is just a small example ArServerInfoStrings stringInfo(&server); Aria::getInfoGroup()->addAddStringCallback(stringInfo.getAddStringFunctor()); Aria::getInfoGroup()->addStringInt( "Motor Packet Count", 10, new ArConstRetFunctorC<int, ArRobot>(&robot, &ArRobot::getMotorPacCount)); /* Aria::getInfoGroup()->addStringInt( "Laser Packet Count", 10, new ArRetFunctorC<int, ArSick>(&sick, &ArSick::getSickPacCount)); */ // start the robot running, true means that if we lose connection the run thread stops robot.runAsync(true); // connect the laser(s) if it was requested if (!laserConnector.connectLasers()) { printf("Could not connect to lasers... exiting\n"); Aria::exit(2); } drawings.addRobotsRangeDevices(&robot); // log whatever we wanted to before the runAsync simpleOpener.checkAndLog(); // now let it spin off in its own thread server.runAsync(); printf("Server is now running...\n"); // Add a key handler so that you can exit by pressing // escape. Note that a key handler prevents you from running // a program in the background on Linux, since it expects an // active terminal to read keys from; remove this if you want // to run it in the background. ArKeyHandler *keyHandler; if ((keyHandler = Aria::getKeyHandler()) == NULL) { keyHandler = new ArKeyHandler; Aria::setKeyHandler(keyHandler); robot.lock(); robot.attachKeyHandler(keyHandler); robot.unlock(); printf("To exit, press escape.\n"); } // Read in parameter files. std::string configFile = "serverDemoConfig.txt"; Aria::getConfig()->setBaseDirectory("./"); if (Aria::getConfig()->parseFile(configFile.c_str(), true, true)) { ArLog::log(ArLog::Normal, "Loaded config file %s", configFile.c_str()); } else { if (ArUtil::findFile(configFile.c_str())) { ArLog::log(ArLog::Normal, "Trouble loading configuration file %s, continuing", configFile.c_str()); } else { ArLog::log(ArLog::Normal, "No configuration file %s, will try to create if config used", configFile.c_str()); } } clientSwitchManager.runAsync(); robot.lock(); robot.enableMotors(); robot.unlock(); robot.waitForRunExit(); Aria::exit(0); }
int main(int argc, char **argv) { Aria::init(); ArRobot robot; ArArgumentParser parser(&argc, argv); parser.loadDefaultArguments(); ArLog::log(ArLog::Terse, "WARNING: this program does no sensing or avoiding of obstacles, the robot WILL collide with any objects in the way! Make sure the robot has approximately 3 meters of free space on all sides."); // ArRobotConnector connects to the robot, get some initial data from it such as type and name, // and then loads parameter files for this robot. ArRobotConnector robotConnector(&parser, &robot); if(!robotConnector.connectRobot()) { ArLog::log(ArLog::Terse, "simpleMotionCommands: Could not connect to the robot."); if(parser.checkHelpAndWarnUnparsed()) { Aria::logOptions(); Aria::exit(1); return 1; } } if (!Aria::parseArgs()) { Aria::logOptions(); Aria::exit(1); return 1; } ArLog::log(ArLog::Normal, "simpleMotionCommands: Connected."); // Start the robot processing cycle running in the background. // True parameter means that if the connection is lost, then the // run loop ends. robot.runAsync(true); // Print out some data from the SIP. // We must "lock" the ArRobot object // before calling its methods, and "unlock" when done, to prevent conflicts // with the background thread started by the call to robot.runAsync() above. // See the section on threading in the manual for more about this. // Make sure you unlock before any sleep() call or any other code that will // take some time; if the robot remains locked during that time, then // ArRobot's background thread will be blocked and unable to communicate with // the robot, call tasks, etc. robot.lock(); ArLog::log(ArLog::Normal, "simpleMotionCommands: Pose=(%.2f,%.2f,%.2f), Trans. Vel=%.2f, Rot. Vel=%.2f, Battery=%.2fV", robot.getX(), robot.getY(), robot.getTh(), robot.getVel(), robot.getRotVel(), robot.getBatteryVoltage()); robot.unlock(); // Sleep for 3 seconds. ArLog::log(ArLog::Normal, "simpleMotionCommands: Will start driving in 3 seconds..."); ArUtil::sleep(3000); // Set forward velocity to 50 mm/s ArLog::log(ArLog::Normal, "simpleMotionCommands: Driving forward at 250 mm/s for 5 sec..."); robot.lock(); robot.enableMotors(); robot.setVel(250); robot.unlock(); ArUtil::sleep(5000); ArLog::log(ArLog::Normal, "simpleMotionCommands: Stopping."); robot.lock(); robot.stop(); robot.unlock(); ArUtil::sleep(1000); ArLog::log(ArLog::Normal, "simpleMotionCommands: Rotating at 10 deg/s for 5 sec..."); robot.lock(); robot.setRotVel(10); robot.unlock(); ArUtil::sleep(5000); ArLog::log(ArLog::Normal, "simpleMotionCommands: Rotating at -10 deg/s for 10 sec..."); robot.lock(); robot.setRotVel(-10); robot.unlock(); ArUtil::sleep(10000); ArLog::log(ArLog::Normal, "simpleMotionCommands: Driving forward at 150 mm/s for 5 sec..."); robot.lock(); robot.setRotVel(0); robot.setVel(150); robot.unlock(); ArUtil::sleep(5000); ArLog::log(ArLog::Normal, "simpleMotionCommands: Stopping."); robot.lock(); robot.stop(); robot.unlock(); ArUtil::sleep(1000); // Other motion command functions include move(), setHeading(), // setDeltaHeading(). You can also adjust acceleration and deceleration // values used by the robot with setAccel(), setDecel(), setRotAccel(), // setRotDecel(). See the ArRobot class documentation for more. robot.lock(); ArLog::log(ArLog::Normal, "simpleMotionCommands: Pose=(%.2f,%.2f,%.2f), Trans. Vel=%.2f, Rot. Vel=%.2f, Battery=%.2fV", robot.getX(), robot.getY(), robot.getTh(), robot.getVel(), robot.getRotVel(), robot.getBatteryVoltage()); robot.unlock(); ArLog::log(ArLog::Normal, "simpleMotionCommands: Ending robot thread..."); robot.stopRunning(); // wait for the thread to stop robot.waitForRunExit(); // exit ArLog::log(ArLog::Normal, "simpleMotionCommands: Exiting."); Aria::exit(0); return 0; }
int main(int argc, char **argv) { Aria::init(); ArArgumentParser argParser(&argc, argv); argParser.loadDefaultArguments(); ArRobot robot; ArRobotConnector robotConnector(&argParser, &robot); ArLaserConnector laserConnector(&argParser, &robot, &robotConnector); // Always try to connect to the first laser: argParser.addDefaultArgument("-connectLaser"); if(!robotConnector.connectRobot()) { ArLog::log(ArLog::Terse, "Could not connect to the robot."); if(argParser.checkHelpAndWarnUnparsed()) { // -help not given, just exit. Aria::logOptions(); Aria::exit(1); } } // Trigger argument parsing if (!Aria::parseArgs() || !argParser.checkHelpAndWarnUnparsed()) { Aria::logOptions(); Aria::exit(1); } ArKeyHandler keyHandler; Aria::setKeyHandler(&keyHandler); robot.attachKeyHandler(&keyHandler); puts("This program will make the robot wander around. It uses some avoidance\n" "actions if obstacles are detected, otherwise it just has a\n" "constant forward velocity.\n\nPress CTRL-C or Escape to exit."); ArSonarDevice sonar; robot.addRangeDevice(&sonar); robot.runAsync(true); // try to connect to laser. if fail, warn but continue, using sonar only if(!laserConnector.connectLasers()) { ArLog::log(ArLog::Normal, "Warning: unable to connect to requested lasers, will wander using robot sonar only."); } // turn on the motors, turn off amigobot sounds robot.enableMotors(); robot.comInt(ArCommands::SOUNDTOG, 0); // add a set of actions that combine together to effect the wander behavior ArActionStallRecover recover; ArActionBumpers bumpers; ArActionAvoidFront avoidFrontNear("Avoid Front Near", 225, 0); ArActionAvoidFront avoidFrontFar; ArActionConstantVelocity constantVelocity("Constant Velocity", 400); robot.addAction(&recover, 100); robot.addAction(&bumpers, 75); robot.addAction(&avoidFrontNear, 50); robot.addAction(&avoidFrontFar, 49); robot.addAction(&constantVelocity, 25); // wait for robot task loop to end before exiting the program robot.waitForRunExit(); Aria::exit(0); }
int main(int argc, char **argv) { Aria::init(); ros::init(argc, argv, "teleoparm"); ArLog::init(ArLog::StdErr, ArLog::Normal); ArArgumentParser parser(&argc, argv); parser.loadDefaultArguments(); //ArRobot robot; ArRobotConnector robotConnector(&parser, &robot); if(!robotConnector.connectRobot()) { ArLog::log(ArLog::Terse, "terabotArmDemo: Could not connect to the robot."); if(parser.checkHelpAndWarnUnparsed()) { Aria::logOptions(); Aria::exit(1); } } if (!Aria::parseArgs() || !parser.checkHelpAndWarnUnparsed()) { Aria::logOptions(); Aria::exit(1); } //ArTerabotArm arm(&robot); ArLog::log(ArLog::Normal, "terabotArmDemo: Connected to mobile robot."); if(!arm.open()) { ArLog::log(ArLog::Terse, "terabotArmDemo: Error opening serial connection to arm"); Aria::exit(1); } robot.runAsync(true); arm.powerOn(); arm.reset(); arm.enable(); arm.setAllJointSpeeds(defaultJointSpeed); ArLog::log(ArLog::Terse, "\nWARNING\n\nAbout to move the manipulator arm to the front of the robot in 5 seconds. Press Control-C to cancel and exit the program.\n..."); ArUtil::sleep(5000); ArLog::log(ArLog::Terse, "Now moving the arm..."); // arm.moveArm(forwardReady); //arm.moveArm(park); ArUtil::sleep(500); // need to have read some data from the arm for key handler to work robot.lock(); ArModeUnguardedTeleop unguardedTeleopMode(&robot, "unguarded teleop", 'u', 'U'); ArModeTeleop teleopMode(&robot, "teleop", 't', 'T'); ArModeLaser laserMode(&robot, "laser", 'l', 'L'); ArModeCommand commandMode(&robot, "direct robot commands", 'd', 'D'); ros::NodeHandle n; sensor_msgs::JointState joints; ros::Rate loop_rate(10); ros::Publisher joint_pub = n.advertise<sensor_msgs::JointState>("/joint_states", 50);//50 1000 ros::Subscriber arm_sub_ = n.subscribe<sensor_msgs::JointState>("/joint_states", 10, move_arm);//it was 100 float positions[5]; // float park1 [5]= {50, -95,-50, -149, 0}; float park1 [5]= {149, -94, 155, -149, 0};//this is th real park float initial [5]= {-30.0, 0.0, 0.0, 0.0, 0.0}; // std::cout<<"Gripper Status before:"<<arm.getGripperStatus()<<"\n"; // std::cout<<"Gripper Status before:"<<arm.getGripperStatus()<<"\n"; // std::cout<<"Gripper Status before:"<<arm.getGripperStatus()<<"\n"; // std::cout<<"Gripper Status before:"<<arm.getGripperStatus()<<"\n"; // arm.grip(-100); // std::cout<<"Gripper Status after:"<<arm.getGripperStatus()<<"\n"; // std::cout<<"Gripper Status after:"<<arm.getGripperStatus()<<"\n"; // std::cout<<"Gripper Status after:"<<arm.getGripperStatus()<<"\n"; // std::cout<<"Gripper Status after:"<<arm.getGripperStatus()<<"\n"; //*********testing************************** // arm.moveArm(start); //arm.closeGripper(); // arm.moveArm(park1); arm.moveArm(forwardReady);// used when the manual control GUI is used ArUtil::sleep(20000);// time for the non blocking predefined movements to take place //****************************************** while(ros::ok()) { joints.name.push_back("j1"); joints.name.push_back("j2"); joints.name.push_back("j3"); joints.name.push_back("j4"); joints.name.push_back("j5"); // why is there no joint //joints.position.push_back(11);//<< joints.position.clear(); joints.position.push_back(positions[0]); joints.position.push_back(positions[1]); joints.position.push_back(positions[2]); joints.position.push_back(positions[3]); joints.position.push_back(positions[4]); joint_pub.publish(joints); //arm.getJointStatus(&j1,&j2,&j3,&j4,&j5); arm.getArmPos(positions); // std::cout<<"j1:"<<j1<<"j2:"<<j2<<"j3:"<<j3<<"j4:"<<j4<<"j5:"<<j5<<"\n"; fflush(stdout); std::cout<<"position1:"<<positions[0]<<"position2:"<<positions[1]<<"position3:"<<positions[2]<<"position4:"<<positions[3]<<"position5:"<<positions[4]<<"\n"; fflush(stdout); //ros::spin(); ros::spinOnce(); loop_rate.sleep(); // std::cout<<"loopend\n"; } robot.enableMotors(); robot.unlock(); robot.waitForRunExit(); ArLog::log(ArLog::Normal, "terabotArmDemo: Either mobile robot or arm disconnected. Exiting."); Aria::exit(0); }