param.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2009, Willow Garage, Inc.
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #ifndef ROSCPP_PARAM_H
29 #define ROSCPP_PARAM_H
30 
31 #include "forwards.h"
32 #include "common.h"
33 #include "xmlrpcpp/XmlRpcValue.h"
34 
35 #include <vector>
36 #include <map>
37 
38 namespace ros
39 {
40 
44 namespace param
45 {
46 
53 ROSCPP_DECL void set(const std::string& key, const XmlRpc::XmlRpcValue& v);
60 ROSCPP_DECL void set(const std::string& key, const std::string& s);
67 ROSCPP_DECL void set(const std::string& key, const char* s);
74 ROSCPP_DECL void set(const std::string& key, double d);
81 ROSCPP_DECL void set(const std::string& key, int i);
88 ROSCPP_DECL void set(const std::string& key, bool b);
89 
90 
97 ROSCPP_DECL void set(const std::string& key, const std::vector<std::string>& vec);
104 ROSCPP_DECL void set(const std::string& key, const std::vector<double>& vec);
111 ROSCPP_DECL void set(const std::string& key, const std::vector<float>& vec);
118 ROSCPP_DECL void set(const std::string& key, const std::vector<int>& vec);
125 ROSCPP_DECL void set(const std::string& key, const std::vector<bool>& vec);
126 
133 ROSCPP_DECL void set(const std::string& key, const std::map<std::string, std::string>& map);
140 ROSCPP_DECL void set(const std::string& key, const std::map<std::string, double>& map);
147 ROSCPP_DECL void set(const std::string& key, const std::map<std::string, float>& map);
154 ROSCPP_DECL void set(const std::string& key, const std::map<std::string, int>& map);
161 ROSCPP_DECL void set(const std::string& key, const std::map<std::string, bool>& map);
162 
163 
172 ROSCPP_DECL bool get(const std::string& key, std::string& s);
181 ROSCPP_DECL bool get(const std::string& key, double& d);
190 ROSCPP_DECL bool get(const std::string& key, float& f);
199 ROSCPP_DECL bool get(const std::string& key, int& i);
208 ROSCPP_DECL bool get(const std::string& key, bool& b);
217 ROSCPP_DECL bool get(const std::string& key, XmlRpc::XmlRpcValue& v);
218 
232 ROSCPP_DECL bool getCached(const std::string& key, std::string& s);
246 ROSCPP_DECL bool getCached(const std::string& key, double& d);
260 ROSCPP_DECL bool getCached(const std::string& key, float& f);
274 ROSCPP_DECL bool getCached(const std::string& key, int& i);
288 ROSCPP_DECL bool getCached(const std::string& key, bool& b);
302 ROSCPP_DECL bool getCached(const std::string& key, XmlRpc::XmlRpcValue& v);
303 
312 ROSCPP_DECL bool get(const std::string& key, std::vector<std::string>& vec);
321 ROSCPP_DECL bool get(const std::string& key, std::vector<double>& vec);
330 ROSCPP_DECL bool get(const std::string& key, std::vector<float>& vec);
339 ROSCPP_DECL bool get(const std::string& key, std::vector<int>& vec);
348 ROSCPP_DECL bool get(const std::string& key, std::vector<bool>& vec);
349 
363 ROSCPP_DECL bool getCached(const std::string& key, std::vector<std::string>& vec);
377 ROSCPP_DECL bool getCached(const std::string& key, std::vector<double>& vec);
391 ROSCPP_DECL bool getCached(const std::string& key, std::vector<float>& vec);
405 ROSCPP_DECL bool getCached(const std::string& key, std::vector<int>& vec);
419 ROSCPP_DECL bool getCached(const std::string& key, std::vector<bool>& vec);
420 
429 ROSCPP_DECL bool get(const std::string& key, std::map<std::string, std::string>& map);
438 ROSCPP_DECL bool get(const std::string& key, std::map<std::string, double>& map);
447 ROSCPP_DECL bool get(const std::string& key, std::map<std::string, float>& map);
456 ROSCPP_DECL bool get(const std::string& key, std::map<std::string, int>& map);
465 ROSCPP_DECL bool get(const std::string& key, std::map<std::string, bool>& map);
466 
480 ROSCPP_DECL bool getCached(const std::string& key, std::map<std::string, std::string>& map);
494 ROSCPP_DECL bool getCached(const std::string& key, std::map<std::string, double>& map);
508 ROSCPP_DECL bool getCached(const std::string& key, std::map<std::string, float>& map);
522 ROSCPP_DECL bool getCached(const std::string& key, std::map<std::string, int>& map);
536 ROSCPP_DECL bool getCached(const std::string& key, std::map<std::string, bool>& map);
537 
545 ROSCPP_DECL bool has(const std::string& key);
553 ROSCPP_DECL bool del(const std::string& key);
554 
569 ROSCPP_DECL bool search(const std::string& ns, const std::string& key, std::string& result);
570 
585 ROSCPP_DECL bool search(const std::string& key, std::string& result);
586 
592 ROSCPP_DECL bool getParamNames(std::vector<std::string>& keys);
593 
598 ROSCPP_DECL void unsubscribeCachedParam(const std::string& key);
599 
603 ROSCPP_DECL void unsubscribeCachedParam(void);
604 
618 template<typename T>
619 bool param(const std::string& param_name, T& param_val, const T& default_val)
620 {
621  if (has(param_name))
622  {
623  if (get(param_name, param_val))
624  {
625  return true;
626  }
627  }
628 
629  param_val = default_val;
630  return false;
631 }
632 
650 template<typename T>
651 T param(const std::string& param_name, const T& default_val)
652 {
653  T param_val;
654  param(param_name, param_val, default_val);
655  return param_val;
656 }
657 
658 } // namespace param
659 
660 } // namespace ros
661 
662 #endif // ROSCPP_PARAM_H
forwards.h
ros::param::param
bool param(const std::string &param_name, T &param_val, const T &default_val)
Assign value from parameter server, with default.
Definition: param.h:619
s
XmlRpcServer s
ros
ros::param::del
ROSCPP_DECL bool del(const std::string &key)
Delete a parameter from the parameter server.
Definition: param.cpp:228
f
f
ros::param::getCached
ROSCPP_DECL bool getCached(const std::string &key, std::string &s)
Get a string value from the parameter server, with local caching.
Definition: param.cpp:439
d
d
XmlRpcValue.h
ros::param::get
ROSCPP_DECL bool get(const std::string &key, std::string &s)
Get a string value from the parameter server.
Definition: param.cpp:409
ros::param::search
ROSCPP_DECL bool search(const std::string &ns, const std::string &key, std::string &result)
Search up the tree for a parameter with a given key.
Definition: param.cpp:752
ros::param::unsubscribeCachedParam
ROSCPP_DECL void unsubscribeCachedParam(const std::string &key)
Unsubscribe cached parameter from the master.
Definition: param.cpp:804
ros::param::getParamNames
ROSCPP_DECL bool getParamNames(std::vector< std::string > &keys)
Get the list of all the parameters in the server.
Definition: param.cpp:717
ros::param::param
T param(const std::string &param_name, const T &default_val)
Return value from parameter server, or default if unavailable.
Definition: param.h:651
ros::param::has
ROSCPP_DECL bool has(const std::string &key)
Check whether a parameter exists on the parameter server.
Definition: param.cpp:211
XmlRpc::XmlRpcValue
ros::param::set
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
Set an arbitrary XML/RPC value on the parameter server.
Definition: param.cpp:67


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Sat Sep 14 2024 02:59:35