parameters.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2010, 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 Stanford University or 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 #include <ros/ros.h>
29 
30 int main(int argc, char** argv)
31 {
32  ros::init(argc, argv, "parameters");
34 
35  {
36 // %Tag(NH_GETPARAM_SIMPLE)%
37  std::string s;
38  n.getParam("my_param", s);
39 // %EndTag(NH_GETPARAM_SIMPLE)%
40  }
41 
42  {
43 // %Tag(NH_GETPARAM_CHECK_RETURN)%
44  std::string s;
45  if (n.getParam("my_param", s))
46  {
47  ROS_INFO("Got param: %s", s.c_str());
48  }
49  else
50  {
51  ROS_ERROR("Failed to get param 'my_param'");
52  }
53 // %EndTag(NH_GETPARAM_CHECK_RETURN)%
54  }
55 
56 // %Tag(NH_PARAM_INT)%
57  int i;
58  n.param("my_num", i, 42);
59 // %EndTag(NH_PARAM_INT)%
60 
61 // %Tag(NH_PARAM_STRING)%
62  std::string s;
63  n.param<std::string>("my_param", s, "default_value");
64 // %EndTag(NH_PARAM_STRING)%
65 
66 // %Tag(NH_SETPARAM)%
67  n.setParam("my_param", "hello there");
68 // %EndTag(NH_SETPARAM)%
69 
70 // %Tag(NH_DELETEPARAM)%
71  n.deleteParam("my_param");
72 // %EndTag(NH_DELETEPARAM)%
73 
74 // %Tag(NH_HASPARAM)%
75  if (!n.hasParam("my_param"))
76  {
77  ROS_INFO("No param named 'my_param'");
78  }
79 // %EndTag(NH_HASPARAM)%
80 
81 // %Tag(NH_SEARCHPARAM)%
82  std::string param_name;
83  if (n.searchParam("b", param_name))
84  {
85  // Found parameter, can now query it using param_name
86  int i = 0;
87  n.getParam(param_name, i);
88  }
89  else
90  {
91  ROS_INFO("No param 'b' found in an upward search");
92  }
93 // %EndTag(NH_SEARCHPARAM)%
94 }
bool deleteParam(const std::string &key) const
XmlRpcServer s
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
Definition: parameters.cpp:30
#define ROS_INFO(...)
bool searchParam(const std::string &key, std::string &result) const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool getParam(const std::string &key, std::string &s) const
bool hasParam(const std::string &key) const
#define ROS_ERROR(...)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const


roscpp_tutorials
Author(s): Morgan Quigley, Dirk Thomas
autogenerated on Sun Oct 18 2020 13:09:42