Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #include <youbot_oodl/YouBotOODLWrapper.h>
00041 #include <stdlib.h>
00042
00043 int main(int argc, char **argv)
00044 {
00045
00046 youbot::Logger::toConsole = false;
00047 youbot::Logger::toFile = false;
00048 youbot::Logger::toROS = true;
00049 ros::init(argc, argv, "youbot_oodl_driver");
00050 ros::NodeHandle n;
00051 youBot::YouBotOODLWrapper youBot(n);
00052 std::vector<std::string> armNames;
00053
00054
00055 bool youBotHasBase;
00056 bool youBotHasArms;
00057 double youBotDriverCycleFrequencyInHz;
00058 n.param("youBotHasBase", youBotHasBase, true);
00059 n.param("youBotHasArms", youBotHasArms, true);
00060 n.param("youBotDriverCycleFrequencyInHz", youBotDriverCycleFrequencyInHz, 50.0);
00061
00062
00063 char* configLocation = getenv("YOUBOT_CONFIG_FOLDER_LOCATION");
00064 if (configLocation == NULL)
00065 throw std::runtime_error("YouBotArmTest.cpp: Could not find environment variable YOUBOT_CONFIG_FOLDER_LOCATION");
00066
00067 n.param < std::string
00068 > ("youBotConfigurationFilePath", youBot.youBotConfiguration.configurationFilePath, configLocation);
00069
00070 n.param < std::string > ("youBotBaseName", youBot.youBotConfiguration.baseConfiguration.baseID, "youbot-base");
00071
00072
00073 int i = 1;
00074 std::stringstream armNameParam;
00075 armNameParam << "youBotArmName" << i;
00076 while (n.hasParam(armNameParam.str()))
00077 {
00078 std::string armName;
00079 n.getParam(armNameParam.str(), armName);
00080 armNames.push_back(armName);
00081 armNameParam.str("");
00082 armNameParam << "youBotArmName" << (++i);
00083 }
00084
00085 ros::ServiceServer reconnectService = n.advertiseService("reconnect", &youBot::YouBotOODLWrapper::reconnectCallback,
00086 &youBot);
00087
00088 ROS_ASSERT((youBotHasBase == true) || (youBotHasArms == true));
00089 if (youBotHasBase == true)
00090 {
00091 youBot.initializeBase(youBot.youBotConfiguration.baseConfiguration.baseID);
00092 }
00093
00094 if (youBotHasArms == true)
00095 {
00096 std::vector<std::string>::iterator armNameIter;
00097 for (armNameIter = armNames.begin(); armNameIter != armNames.end(); ++armNameIter)
00098 {
00099 youBot.initializeArm(*armNameIter);
00100 }
00101 }
00102
00103
00104 ros::Rate rate(youBotDriverCycleFrequencyInHz);
00105 while (n.ok())
00106 {
00107 ros::spinOnce();
00108 youBot.computeOODLSensorReadings();
00109 youBot.publishOODLSensorReadings();
00110 youBot.publishArmAndBaseDiagnostics(2.0);
00111 rate.sleep();
00112 }
00113
00114 youBot.stop();
00115
00116 return 0;
00117 }
00118