youbot_wrapper.cpp
Go to the documentation of this file.
00001 /******************************************************************************
00002  * Copyright (c) 2011
00003  * Locomotec
00004  *
00005  * Author:
00006  * Sebastian Blumenthal
00007  *
00008  *
00009  * This software is published under a dual-license: GNU Lesser General Public
00010  * License LGPL 2.1 and BSD license. The dual-license implies that users of this
00011  * code may choose which terms they prefer.
00012  *
00013  * Redistribution and use in source and binary forms, with or without
00014  * modification, are permitted provided that the following conditions are met:
00015  *
00016  * * Redistributions of source code must retain the above copyright
00017  * notice, this list of conditions and the following disclaimer.
00018  * * Redistributions in binary form must reproduce the above copyright
00019  * notice, this list of conditions and the following disclaimer in the
00020  * documentation and/or other materials provided with the distribution.
00021  * * Neither the name of Locomotec nor the names of its
00022  * contributors may be used to endorse or promote products derived from
00023  * this software without specific prior written permission.
00024  *
00025  * This program is free software: you can redistribute it and/or modify
00026  * it under the terms of the GNU Lesser General Public License LGPL as
00027  * published by the Free Software Foundation, either version 2.1 of the
00028  * License, or (at your option) any later version or the BSD license.
00029  *
00030  * This program is distributed in the hope that it will be useful,
00031  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00032  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
00033  * GNU Lesser General Public License LGPL and the BSD license for more details.
00034  *
00035  * You should have received a copy of the GNU Lesser General Public
00036  * License LGPL and BSD license along with this program.
00037  *
00038  ******************************************************************************/
00039 
00040 
00041 #include <YouBotOODLWrapper.h>
00042 #include <stdlib.h>
00043 
00044 int main(int argc, char **argv)
00045 {
00046 
00047   youbot::Logger::toConsole = false;
00048   youbot::Logger::toFile = false;
00049   youbot::Logger::toROS = true;
00050   ros::init(argc, argv, "youbot_wrapper");
00051   ros::NodeHandle n;
00052   youBot::YouBotOODLWrapper youBot(n);
00053   std::vector<std::string> armNames;
00054 
00055   /* configuration */
00056   bool youBotHasBase;
00057   bool youBotHasArms;
00058   double youBotDriverCycleFrequencyInHz;        //the driver recives commands and publishes them with a fixed frequency
00059   n.param("youBotHasBase", youBotHasBase, true);
00060   n.param("youBotHasArms", youBotHasArms, true);
00061   n.param("youBotDriverCycleFrequencyInHz", youBotDriverCycleFrequencyInHz, 50.0);
00062 
00063   //get the config file path from an environment variable
00064   char* configLocation = getenv("YOUBOT_CONFIG_FOLDER_LOCATION");
00065   if (configLocation == NULL)
00066     throw std::runtime_error("youbot_wrapper.cpp: Could not find environment variable YOUBOT_CONFIG_FOLDER_LOCATION");
00067 
00068   n.param < std::string
00069       > ("youBotConfigurationFilePath", youBot.youBotConfiguration.configurationFilePath, configLocation);
00070 
00071   n.param < std::string > ("youBotBaseName", youBot.youBotConfiguration.baseConfiguration.baseID, "youbot-base");
00072 
00073   // Retrieve all defined arm names from the launch file params
00074   int i = 1;
00075   std::stringstream armNameParam;
00076   armNameParam << "youBotArmName" << i; // youBotArmName1 is first checked param... then youBotArmName2, etc.
00077   while (n.hasParam(armNameParam.str()))
00078   {
00079     std::string armName;
00080     n.getParam(armNameParam.str(), armName);
00081     armNames.push_back(armName);
00082     armNameParam.str("");
00083     armNameParam << "youBotArmName" << (++i);
00084   }
00085 
00086   ros::ServiceServer reconnectService = n.advertiseService("reconnect", &youBot::YouBotOODLWrapper::reconnectCallback,
00087                                                            &youBot);
00088 
00089   ROS_ASSERT((youBotHasBase == true) || (youBotHasArms == true)); // At least one should be true, otherwise nothing to be started.
00090   if (youBotHasBase == true)
00091   {
00092     youBot.initializeBase(youBot.youBotConfiguration.baseConfiguration.baseID);
00093   }
00094 
00095   if (youBotHasArms == true)
00096   {
00097     std::vector<std::string>::iterator armNameIter;
00098     for (armNameIter = armNames.begin(); armNameIter != armNames.end(); ++armNameIter)
00099     {
00100       youBot.initializeArm(*armNameIter);
00101     }
00102   }
00103 
00104   /* coordination */
00105   ros::Rate rate(youBotDriverCycleFrequencyInHz); //Input and output at the same time... (in Hz)
00106   while (n.ok())
00107   {
00108     ros::spinOnce();
00109     youBot.computeOODLSensorReadings();
00110     youBot.publishOODLSensorReadings();
00111     youBot.publishArmAndBaseDiagnostics(2.0);    //publish only every 2 seconds
00112     rate.sleep();
00113 
00114     //automatically attempt a reconnect if ethercat dies
00115     if (!youBot.youBotConfiguration.isEtherCATOkay()) {
00116       std_srvs::Empty::Request req;
00117       std_srvs::Empty::Response res;
00118       youBot.reconnectCallback(req,res);
00119     }
00120 
00121   }
00122 
00123   youBot.stop();
00124 
00125   return 0;
00126 }
00127 


youbot_oodl
Author(s): Sebastian Blumenthal
autogenerated on Mon Oct 6 2014 09:06:15