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
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include "ompl/base/GenericParam.h"
00038 #include "ompl/util/Exception.h"
00039
00040 bool ompl::base::ParamSet::setParam(const std::string &key, const std::string &value)
00041 {
00042 std::map<std::string, GenericParamPtr>::const_iterator it = params_.find(key);
00043 if (it != params_.end())
00044 return it->second->setValue(value);
00045 else
00046 {
00047 logError("Parameter '%s' was not found", key.c_str());
00048 return false;
00049 }
00050 }
00051
00052 bool ompl::base::ParamSet::setParams(const std::map<std::string, std::string> &kv, bool ignoreUnknown)
00053 {
00054 bool result = true;
00055 for (std::map<std::string, std::string>::const_iterator it = kv.begin() ; it != kv.end() ; ++it)
00056 {
00057 if (ignoreUnknown)
00058 if (!hasParam(it->first))
00059 continue;
00060 bool r = setParam(it->first, it->second);
00061 result = result && r;
00062 }
00063 return result;
00064 }
00065
00066 bool ompl::base::ParamSet::getParam(const std::string &key, std::string &value) const
00067 {
00068 std::map<std::string, GenericParamPtr>::const_iterator it = params_.find(key);
00069 if (it != params_.end())
00070 {
00071 value = it->second->getValue();
00072 return true;
00073 }
00074 return false;
00075 }
00076
00077 void ompl::base::ParamSet::getParamNames(std::vector<std::string> ¶ms) const
00078 {
00079 params.clear();
00080 params.reserve(params_.size());
00081 for (std::map<std::string, GenericParamPtr>::const_iterator it = params_.begin() ; it != params_.end() ; ++it)
00082 params.push_back(it->first);
00083 }
00084
00085 void ompl::base::ParamSet::getParamValues(std::vector<std::string> &vals) const
00086 {
00087 std::vector<std::string> names;
00088 getParamNames(names);
00089 vals.resize(names.size());
00090 for (std::size_t i = 0 ; i < names.size() ; ++i)
00091 vals[i] = params_.find(names[i])->second->getValue();
00092 }
00093
00094 const std::map<std::string, ompl::base::GenericParamPtr>& ompl::base::ParamSet::getParams(void) const
00095 {
00096 return params_;
00097 }
00098
00099 const ompl::base::GenericParamPtr& ompl::base::ParamSet::getParam(const std::string &key) const
00100 {
00101 static GenericParamPtr empty;
00102 std::map<std::string, GenericParamPtr>::const_iterator it = params_.find(key);
00103 if (it != params_.end())
00104 return it->second;
00105 else
00106 return empty;
00107 }
00108
00109 void ompl::base::ParamSet::getParams(std::map<std::string, std::string> ¶ms) const
00110 {
00111 for (std::map<std::string, GenericParamPtr>::const_iterator it = params_.begin() ; it != params_.end() ; ++it)
00112 params[it->first] = it->second->getValue();
00113 }
00114
00115 bool ompl::base::ParamSet::hasParam(const std::string &key) const
00116 {
00117 return params_.find(key) != params_.end();
00118 }
00119
00120 ompl::base::GenericParam& ompl::base::ParamSet::operator[](const std::string &key)
00121 {
00122 if (!hasParam(key))
00123 throw Exception("Parameter '%s' is not defined", key.c_str());
00124 return *getParam(key);
00125 }
00126
00127 void ompl::base::ParamSet::include(const ParamSet &other, const std::string &prefix)
00128 {
00129 const std::map<std::string, GenericParamPtr> &p = other.getParams();
00130 if (prefix.empty())
00131 for (std::map<std::string, GenericParamPtr>::const_iterator it = p.begin() ; it != p.end() ; ++it)
00132 params_[it->first] = it->second;
00133 else
00134 for (std::map<std::string, GenericParamPtr>::const_iterator it = p.begin() ; it != p.end() ; ++it)
00135 params_[prefix + "." + it->first] = it->second;
00136 }
00137
00138 void ompl::base::ParamSet::add(const GenericParamPtr ¶m)
00139 {
00140 params_[param->getName()] = param;
00141 }
00142
00143 void ompl::base::ParamSet::remove(const std::string &name)
00144 {
00145 params_.erase(name);
00146 }
00147
00148 void ompl::base::ParamSet::clear(void)
00149 {
00150 params_.clear();
00151 }
00152
00153 void ompl::base::ParamSet::print(std::ostream &out) const
00154 {
00155 for (std::map<std::string, GenericParamPtr>::const_iterator it = params_.begin() ; it != params_.end() ; ++it)
00156 out << it->first << " = " << it->second->getValue() << std::endl;
00157 }