youbot_oodl.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 #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   /* configuration */
00055   bool youBotHasBase;
00056   bool youBotHasArms;
00057   double youBotDriverCycleFrequencyInHz;        //the driver recives commands and publishes them with a fixed frequency
00058   n.param("youBotHasBase", youBotHasBase, true);
00059   n.param("youBotHasArms", youBotHasArms, true);
00060   n.param("youBotDriverCycleFrequencyInHz", youBotDriverCycleFrequencyInHz, 50.0);
00061 
00062   //get the config file path from an environment variable
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   // Retrieve all defined arm names from the launch file params
00073   int i = 1;
00074   std::stringstream armNameParam;
00075   armNameParam << "youBotArmName" << i; // youBotArmName1 is first checked param... then youBotArmName2, etc.
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)); // At least one should be true, otherwise nothing to be started.
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   /* coordination */
00104   ros::Rate rate(youBotDriverCycleFrequencyInHz); //Input and output at the same time... (in Hz)
00105   while (n.ok())
00106   {
00107     ros::spinOnce();
00108     youBot.computeOODLSensorReadings();
00109     youBot.publishOODLSensorReadings();
00110     youBot.publishArmAndBaseDiagnostics(2.0);    //publish only every 2 seconds
00111     rate.sleep();
00112   }
00113 
00114   youBot.stop();
00115 
00116   return 0;
00117 }
00118 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


youbot_oodl
Author(s): Sebastian Blumenthal
autogenerated on Fri Jul 26 2013 12:00:42