All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends
GenericParam.cpp
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2011, Willow Garage
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #include "ompl/base/GenericParam.h"
38 #include "ompl/util/Exception.h"
39 
40 bool ompl::base::ParamSet::setParam(const std::string &key, const std::string &value)
41 {
42  std::map<std::string, GenericParamPtr>::const_iterator it = params_.find(key);
43  if (it != params_.end())
44  return it->second->setValue(value);
45  else
46  {
47  OMPL_ERROR("Parameter '%s' was not found", key.c_str());
48  return false;
49  }
50 }
51 
52 bool ompl::base::ParamSet::setParams(const std::map<std::string, std::string> &kv, bool ignoreUnknown)
53 {
54  bool result = true;
55  for (std::map<std::string, std::string>::const_iterator it = kv.begin() ; it != kv.end() ; ++it)
56  {
57  if (ignoreUnknown)
58  if (!hasParam(it->first))
59  continue;
60  bool r = setParam(it->first, it->second);
61  result = result && r;
62  }
63  return result;
64 }
65 
66 bool ompl::base::ParamSet::getParam(const std::string &key, std::string &value) const
67 {
68  std::map<std::string, GenericParamPtr>::const_iterator it = params_.find(key);
69  if (it != params_.end())
70  {
71  value = it->second->getValue();
72  return true;
73  }
74  return false;
75 }
76 
77 void ompl::base::ParamSet::getParamNames(std::vector<std::string> &params) const
78 {
79  params.clear();
80  params.reserve(params_.size());
81  for (std::map<std::string, GenericParamPtr>::const_iterator it = params_.begin() ; it != params_.end() ; ++it)
82  params.push_back(it->first);
83 }
84 
85 void ompl::base::ParamSet::getParamValues(std::vector<std::string> &vals) const
86 {
87  std::vector<std::string> names;
88  getParamNames(names);
89  vals.resize(names.size());
90  for (std::size_t i = 0 ; i < names.size() ; ++i)
91  vals[i] = params_.find(names[i])->second->getValue();
92 }
93 
94 const std::map<std::string, ompl::base::GenericParamPtr>& ompl::base::ParamSet::getParams(void) const
95 {
96  return params_;
97 }
98 
99 const ompl::base::GenericParamPtr& ompl::base::ParamSet::getParam(const std::string &key) const
100 {
101  static GenericParamPtr empty;
102  std::map<std::string, GenericParamPtr>::const_iterator it = params_.find(key);
103  if (it != params_.end())
104  return it->second;
105  else
106  return empty;
107 }
108 
109 void ompl::base::ParamSet::getParams(std::map<std::string, std::string> &params) const
110 {
111  for (std::map<std::string, GenericParamPtr>::const_iterator it = params_.begin() ; it != params_.end() ; ++it)
112  params[it->first] = it->second->getValue();
113 }
114 
115 bool ompl::base::ParamSet::hasParam(const std::string &key) const
116 {
117  return params_.find(key) != params_.end();
118 }
119 
121 {
122  if (!hasParam(key))
123  throw Exception("Parameter '%s' is not defined", key.c_str());
124  return *getParam(key);
125 }
126 
127 void ompl::base::ParamSet::include(const ParamSet &other, const std::string &prefix)
128 {
129  const std::map<std::string, GenericParamPtr> &p = other.getParams();
130  if (prefix.empty())
131  for (std::map<std::string, GenericParamPtr>::const_iterator it = p.begin() ; it != p.end() ; ++it)
132  params_[it->first] = it->second;
133  else
134  for (std::map<std::string, GenericParamPtr>::const_iterator it = p.begin() ; it != p.end() ; ++it)
135  params_[prefix + "." + it->first] = it->second;
136 }
137 
138 void ompl::base::ParamSet::add(const GenericParamPtr &param)
139 {
140  params_[param->getName()] = param;
141 }
142 
143 void ompl::base::ParamSet::remove(const std::string &name)
144 {
145  params_.erase(name);
146 }
147 
149 {
150  params_.clear();
151 }
152 
153 void ompl::base::ParamSet::print(std::ostream &out) const
154 {
155  for (std::map<std::string, GenericParamPtr>::const_iterator it = params_.begin() ; it != params_.end() ; ++it)
156  out << it->first << " = " << it->second->getValue() << std::endl;
157 }
void print(std::ostream &out) const
Print the parameters to a stream.
bool hasParam(const std::string &key) const
Check whether this set of parameters includes the parameter named key.
void include(const ParamSet &other, const std::string &prefix="")
Include the params of a different ParamSet into this one. Optionally include a prefix for each of the...
Motion planning algorithms often employ parameters to guide their exploration process. (e.g., goal biasing). Motion planners (and some of their components) use this class to declare what the parameters are, in a generic way, so that they can be set externally.
Definition: GenericParam.h:64
void getParamNames(std::vector< std::string > &params) const
List the names of the known parameters.
bool setParams(const std::map< std::string, std::string > &kv, bool ignoreUnknown=false)
Set the values for a set of parameters. The parameter names are the keys in the map kv...
bool getParam(const std::string &key, std::string &value) const
Get the value of the parameter named key. Store the value as string in value and return true if the p...
Maintain a set of parameters.
Definition: GenericParam.h:216
void getParams(std::map< std::string, std::string > &params) const
Get the known parameter as a map from names to their values cast as string.
bool setParam(const std::string &key, const std::string &value)
Algorithms in OMPL often have parameters that can be set externally. While each algorithm will have t...
void remove(const std::string &name)
Remove a parameter from the set.
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition: Console.h:64
void getParamValues(std::vector< std::string > &vals) const
List the values of the known parameters, in the same order as getParamNames()
GenericParam & operator[](const std::string &key)
Access operator for parameters, by name. If the parameter is not defined, an exception is thrown...
The exception type for ompl.
Definition: Exception.h:47
const std::map< std::string, GenericParamPtr > & getParams(void) const
Get the map from parameter names to parameter descriptions.
void add(const GenericParamPtr &param)
Add a parameter to the set.
void clear(void)
Clear all the set parameters.