OptionContainer.hpp
Go to the documentation of this file.
00001 /*
00002  * OptionContainer.h
00003  *
00004  *  Created on: Oct 11, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef OPTIONCONTAINER_HPP_
00009 #define OPTIONCONTAINER_HPP_
00010 
00011 #include <telekyb_defines/telekyb_defines.hpp>
00012 
00013 #include <telekyb_base/Options/BoundsOption.hpp>
00014 //#include <telekyb_base/Options/OptionListener.hpp>
00015 
00016 #include <telekyb_base/ROS/ROSOptionContainer.hpp>
00017 
00018 // stl
00019 #include <vector>
00020 #include <set>
00021 
00022 // ros
00023 #include <ros/console.h>
00024 
00025 // boost
00026 #include <boost/foreach.hpp>
00027 #include <boost/lexical_cast.hpp>
00028 
00029 // YAML
00030 #include <yaml-cpp/yaml.h>
00031 
00032 
00033 #define UNDEF_OCNAMESPACE "undef"
00034 
00035 namespace TELEKYB_NAMESPACE
00036 {
00037 
00038 class OptionContainer {
00039 private:
00040         // Get next free OptionContainerName
00041         static std::string getNextOptionContainerNamespace(const std::string& basename);
00042 
00043 protected:
00044         // global ContainerMap map by name (Represents namespace must be unique)
00045         static std::map<std::string, OptionContainer*> globalContainerMap;
00046 
00047         // contains all options from all containers! <- With NameSpace(!)
00048         //static OptionsMap globalOptionsMap;
00049         // only contains Container Options <- Without Namespace(!)
00050         OptionsMap optionsMap;
00051         // namespace
00052         std::string optionContainerNamespace;
00053 
00054         // ROS OptionContainer
00055         ROSOptionContainer* rosOptionContainer;
00056 
00057         // name
00058         //std::string optionContainerName;
00059 
00060         virtual ~OptionContainer();
00061 
00062         // Notifiers
00063 //      template <class _T>
00064 //      void notifyDidCreate(const Option<_T>* option) const {
00065 //              BOOST_FOREACH(OptionListener<_T>* listener, OptionListener<_T>::getGlobalListenerSet()) {
00066 //                      listener->optionDidCreate(option);
00067 //              }
00068 //      }
00069 public:
00070         // Constructor to set Namespace
00071         OptionContainer(const std::string& optionContainerNamespace_);
00072 
00073         std::string getOptionContainerNamespace() const;
00074 
00075         std::string getNSPrefixedName(const std::string& name_) const;
00076 
00077         template < class _T >
00078         Option<_T>* addOption(const std::string name_, const std::string description_, const _T& defaultValue_,
00079                         bool mandatory_ = false, bool readOnly_ = false)
00080         {
00081                 std::string nsName = getNSPrefixedName(name_);
00082                 Option<_T>* option = NULL;
00083                 if (optionsMap.count( name_ ) != 0) {
00084                         ROS_FATAL_STREAM("Trying to add a Option that already exists! Name: " << nsName);
00085                         //ROS_BREAK();
00086                         ros::shutdown(); // TODO: Rename?
00087                 } else {
00088                         option = new Option<_T>(this, name_, description_, defaultValue_, mandatory_, readOnly_);
00089                         optionsMap[name_] = option;
00090 
00091                         // print?
00092                         if (BaseOption::printOptions) {
00093                                 option->print();
00094                         }
00095 
00096                         // notify
00097                         //notifyDidCreate<_T>(option);
00098                 }
00099 
00100                 return option;
00101         }
00102 
00103         template < class _T, class Compare_ >
00104         BoundsOption<_T, Compare_>* addBoundsOption(const std::string name_, const std::string description_, const _T& defaultValue_,
00105                         const _T& lowerBound_, const _T& upperBound_,
00106                         bool mandatory_ = false, bool readOnly_ = false)
00107         {
00108                 std::string nsName = getNSPrefixedName(name_);
00109                 BoundsOption<_T, Compare_>* option = NULL;
00110                 if (optionsMap.count( name_ ) != 0) {
00111                         ROS_FATAL_STREAM("Trying to add a BoundsOption that already exists! Name: " << nsName);
00112                         //ROS_BREAK();
00113                         ros::shutdown(); // TODO: Rename?
00114                 } else {
00115                         option = new BoundsOption<_T, Compare_>(this, name_, description_, defaultValue_, lowerBound_, upperBound_, mandatory_, readOnly_);
00116                         //option->setParent(this);
00117 
00118                         optionsMap[name_] = option;
00119 
00120                         // print?
00121                         if (BaseOption::printOptions) {
00122                                 option->print();
00123                         }
00124 
00125                         // notify
00126                         //notifyDidCreate<_T>(option);
00127                 }
00128                 return option;
00129         }
00130 
00131         template < class _T >
00132         BoundsOption<_T>* addBoundsOption(const std::string name_, const std::string description_, const _T& defaultValue_,
00133                         const _T& lowerBound_, const _T& upperBound_,
00134                         bool mandatory_ = false, bool readOnly_ = false)
00135         {
00136                 return addBoundsOption< _T, std::less<_T> >(name_, description_, defaultValue_, lowerBound_, upperBound_, mandatory_, readOnly_);
00137         }
00138 
00139         // returns NULL if not found.
00140         template <class _T>
00141         Option<_T>* getOptionByName(const std::string& optionName)
00142         {
00143                 Option<_T>* option = NULL;
00144                 OptionsMap::iterator it = optionsMap.find(optionName);
00145 
00146                 if (it != optionsMap.end()) {
00147                         // This cast the baseOption to the desired Typed Option. Dynamic cast. NULL if invalid cast
00148                         option = dynamic_cast< Option<_T>* >(it->second);
00149                 }
00150 
00151                 return option;
00152         }
00153 
00154         // returns NULL if not found
00155         template <class _T>
00156         static Option<_T>* getGlobalOptionByName(const std::string& containerName, const std::string& optionName)
00157         {
00158                 Option<_T>* option = NULL;
00159 
00160                 //  Container exits?
00161                 if (globalContainerMap.count(containerName) == 0) {
00162                         return option; // NULL!
00163                 }
00164 
00165                 OptionContainer* container = globalContainerMap[containerName];
00166 
00167                 return container->getOptionByName<_T>(optionName);
00168         }
00169 
00170         // update from RawOptions
00171         void updateFromRawOptions(bool onlyUpdateIntial = false);
00172 
00173 
00174         void get(YAML::Node& node);
00175         bool set(const YAML::Node& node);
00176 
00177         // Options are never removed
00178         //bool removeOption(const BaseOption& option);
00179         //bool removeOption(const std::string& optionName);
00180 };
00181 
00182 }
00183 
00184 #endif /* OPTIONCONTAINER_H_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


telekyb_base
Author(s): Dr. Antonio Franchi and Martin Riedel
autogenerated on Mon Nov 11 2013 11:12:34