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 #ifndef RAWOPTIONSCONTAINER_HPP__
00028 #define RAWOPTIONSCONTAINER_HPP__
00029
00030 #include <telekyb_defines/telekyb_defines.hpp>
00031
00032 #include <telekyb_base/Tools/XmlRpcHelper.hpp>
00033
00034
00035 #include <map>
00036 #include <string>
00037 #include <iostream>
00038 #include <sstream>
00039
00040
00041 #include <yaml-cpp/yaml.h>
00042
00043 #include <telekyb_base/Tools/YamlHelper.hpp>
00044
00045
00046 #include <ros/ros.h>
00047
00048 namespace TELEKYB_NAMESPACE
00049 {
00050
00051 typedef std::map<std::string, std::string> StringMap;
00052
00053 class RawOptionsContainer {
00054 protected:
00055 static StringMap rawOptionsMap;
00056 static bool addUpdateDashOption(std::string dashkey, const std::string& value, bool overwrite, bool showDashError = false);
00057
00058 public:
00059
00060 static bool hasOption(const std::string& key);
00061
00062 static bool removeOption(const std::string& key);
00063 static bool getOption(const std::string& key, std::string& value);
00064
00065 static bool updateOption(const std::string& key, const std::string& value);
00066
00067 static bool addOption(const std::string& key, const std::string& value);
00068
00069 static void addUpdateOption(const std::string& key, const std::string& value);
00070
00071
00072 static bool parseCommandLine(int argc, char* const argv[], bool overwrite = false);
00073 static bool parseCommandLine(const std::vector<std::string>& commandLineArgs, bool overwrite = false);
00074
00075
00076 static bool parseFile(const std::string& fileName, bool overwrite = false);
00077
00078
00079 template < class _T >
00080 static bool getOptionValue(const std::string& name, _T& value) {
00081 bool success = false;
00082 std::string stringValue;
00083 if (getOption(name, stringValue)) {
00084 success = true;
00085 } else if (ros::param::has("~" + name)) {
00086
00087 XmlRpc::XmlRpcValue xmlValue;
00088 ros::param::get("~" + name, xmlValue);
00089 success = XmlRpcHelper::xmlRpcValuetoString(xmlValue, stringValue);
00090 } else {
00091
00092 }
00093
00094 if (success) {
00095
00096
00097
00098
00099 if (! YamlHelper::parseStringToValue(stringValue, value) ) {
00100 ROS_ERROR_STREAM("Option " << name << ". Unable to parse String!");
00101 success = false;
00102 }
00103
00104 }
00105
00106
00107
00108
00109 return success;
00110 }
00111
00112
00113
00114
00115
00116
00117
00118 static void clearOptions();
00119
00120 static void print();
00121 static std::string toString();
00122
00123
00124 static StringMap& getMap();
00125
00126 };
00127
00128 }
00129
00130 #endif