param_example.cpp
Go to the documentation of this file.
1 #include <string>
2 #include <ros/ros.h>
4 
5 int main(int argc, char **argv)
6 {
7  ros::init(argc, argv, "param_test");
8  ros::NodeHandle pnh("~");
9 
10  int int_var;
11  swri::getParam(pnh, "used_int_var_1", int_var);
12  swri::param(pnh, "used_int_var_2", int_var, 2);
13  swri::param(pnh, "unset_int_var", int_var, 2);
14 
15  std::string str_var;
16  swri::getParam(pnh, "used_str_var_1", str_var);
17  swri::param(pnh, "used_str_var_2", str_var, "foo");
18  swri::param(pnh, "unset_str_var", str_var, "foo");
19 
20  double dbl_var;
21  swri::getParam(pnh, "used_dbl_var_1", dbl_var);
22  swri::param(pnh, "used_dbl_var_2", dbl_var, 2.0);
23  swri::param(pnh, "unset_dbl_var", dbl_var, 2.0);
24 
25  bool bool_var;
26  swri::getParam(pnh, "used_bool_var_1", bool_var);
27  swri::param(pnh, "used_bool_var_2", bool_var, true);
28  swri::param(pnh, "unset_bool_var", bool_var, true);
29 
31 
32  return 0;
33 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
static void warnUnusedParams(ros::NodeHandle const &n)
Definition: parameters.h:267
static void param(const ros::NodeHandle &nh, const std::string &name, int &variable, const int default_value)
Definition: parameters.h:102
static bool getParam(const ros::NodeHandle &nh, const std::string &name, int &variable)
Definition: parameters.h:22


swri_roscpp
Author(s):
autogenerated on Fri Jun 7 2019 22:05:50