Option.hpp
Go to the documentation of this file.
00001 /*
00002  * Option.h
00003  *
00004  *  Created on: Oct 11, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef OPTION_HPP_
00009 #define OPTION_HPP_
00010 
00011 #include <telekyb_defines/telekyb_defines.hpp>
00012 
00013 #include <telekyb_base/Options/BaseOption.hpp>
00014 
00015 #include <telekyb_base/Options/RawOptionsContainer.hpp>
00016 #include <telekyb_base/Options/OptionListener.hpp>
00017 
00018 #include <telekyb_base/ROS/ROSOptionController.hpp>
00019 #include <telekyb_base/ROS/ROSOption.hpp>
00020 
00021 #include <telekyb_base/Tools/YamlConversion.hpp>
00022 
00023 // STL
00024 #include <set>
00025 
00026 // ROS
00027 #include <ros/ros.h>
00028 
00029 // Boost
00030 #include <boost/thread/mutex.hpp>
00031 #include <boost/foreach.hpp>
00032 
00033 
00034 
00035 
00036 namespace TELEKYB_NAMESPACE
00037 {
00038 
00039 
00040 template < class _T >
00041 class Option : public BaseOption
00042 {
00043 protected:
00044         _T value;
00045         mutable boost::mutex valueMutex;
00046         // 1:1 Mapping to ROS
00047         ROSOption<_T>* rosOption;
00048 
00049         // Listeners
00050         std::set<OptionListener<_T>*> listenerSet;
00051 
00052 
00053         void notifyDidChange() const {
00054                 BOOST_FOREACH(OptionListener<_T>* listener, listenerSet) {
00055                         listener->optionDidChange(this);
00056                 }
00057         }
00058 
00059         void notifyShouldDelete() const {
00060                 BOOST_FOREACH(OptionListener<_T>* listener, listenerSet) {
00061                         listener->optionShouldDelete(this);
00062                 }
00063         }
00064 
00065         // Constructor is Protected
00066         Option(OptionContainer* parent_, const std::string name_, const std::string description_, const _T& defaultValue_, bool mandatory_ = false, bool readOnly_ = false)
00067                 : BaseOption(parent_, name_, description_, mandatory_, readOnly_), value(defaultValue_), rosOption(NULL) {
00068 
00069                 if( RawOptionsContainer::getOptionValue( getNSName(), value) || RawOptionsContainer::getOptionValue( name, value) ) {
00070                         initialValue = false;
00071                 } else {
00072                         // not updated
00073                         if (mandatory_) {
00074                                 ROS_FATAL_STREAM("Mandatory Option " << getNSName() << " not specified.");
00075                                 //ROS_BREAK();
00076                                 ros::shutdown();
00077                         }
00078                 }
00079 
00080                 //map to ROSOption
00081                 rosOption = new ROSOption<_T>(this);
00082                 //add to Container
00083                 ROSOptionController::addROSOption(rosOption);
00084                 //add as Listener
00085                 registerOptionListener(rosOption);
00086 
00087         }
00088 
00089         // OptionContainer && Telekyb
00090         friend class OptionContainer;
00091 
00092 public:
00093         virtual ~Option() {
00094                 notifyShouldDelete();
00095 
00096                 //remove as Listener
00097                 unRegisterOptionListener(rosOption);
00098                 // remove from Container
00099                 ROSOptionController::removeROSOption(rosOption);
00100                 delete rosOption;
00101         }
00102 
00103         // check's if value can be set
00104         virtual bool setValueCheck(const _T& value_) {
00105                 if (readOnly) {
00106                         ROS_WARN_STREAM("Trying to write read-only Option " << getNSName());
00107                         return false;
00108                 }
00109 
00110                 return true;
00111         }
00112 
00113         void setValue(const _T& value_) {
00114                 // setValue will be efficient without checks. this will propably be removed.
00115                 if ( ! setValueCheck(value_) ) {
00116                         return;
00117                 }
00118 
00119                 boost::mutex::scoped_lock lock(valueMutex);
00120                 value = value_;
00121                 lock.unlock();
00122 
00123                 notifyDidChange();
00124         }
00125 
00126         _T getValue() const {
00127                 boost::mutex::scoped_lock lock(valueMutex);
00128                 return value;
00129         }
00130 
00131         bool updateFromRawOptions(bool onlyUpdateIntial) {
00132                 // still initial?
00133                 if (onlyUpdateIntial && !initialValue) {
00134                         return false;
00135                 }
00136 
00137 
00138                 boost::mutex::scoped_lock lock(valueMutex);
00139                 return RawOptionsContainer::getOptionValue( getNSName(), value);
00140         }
00141 
00142         virtual void get(YAML::Node& node) {
00143                 node = getValue();
00144         }
00145 
00146         virtual bool set(const YAML::Node& node) {
00147                 _T tempValue;
00148                 bool success = YamlHelper::parseNodeToValue(node, tempValue);
00149                 if (success) {
00150                         ROS_INFO_STREAM("SYNC: Updating Option " << getNSName() << " to " << YamlHelper::parseValueToString(tempValue));
00151                         setValue(tempValue);
00152                 }
00153 
00154                 return success;
00155         }
00156 
00157         virtual void print() const {
00158                 std::cout << "--" << getNSName() << " (";
00159                 std::cout << YamlHelper::parseValueToString( getValue() ) << ", ";
00160                 std::cout << "man: " << YamlHelper::parseValueToString( mandatory ) << ", ";
00161                 std::cout << "r-o: " << YamlHelper::parseValueToString( readOnly );
00162                 std::cout << "): " << getDescription() << std::endl;
00163         }
00164 
00165         virtual bool hasBounds() const {
00166                 return false;
00167         }
00168 
00169         virtual bool isWithinBounds(const _T& value_) const {
00170                 return true;
00171         }
00172 
00173         // OptionListener
00174         void registerOptionListener(OptionListener<_T>* optionListener) {
00175                 listenerSet.insert(optionListener);
00176         }
00177 
00178         void unRegisterOptionListener(OptionListener<_T>* optionListener) {
00179                 listenerSet.erase(optionListener);
00180         }
00181 
00182         // protect with mutex?
00183         std::set<OptionListener<_T>*>& getListenerSet() {
00184                 return listenerSet;
00185         }
00186 };
00187 
00188 } // namespace
00189 
00190 #endif /* OPTION_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