Go to the documentation of this file.00001 #include <string>
00002 #include <ros/ros.h>
00003 #include <swri_roscpp/parameters.h>
00004
00005 int main(int argc, char **argv)
00006 {
00007 ros::init(argc, argv, "param_test");
00008 ros::NodeHandle pnh("~");
00009
00010 int int_var;
00011 swri::getParam(pnh, "used_int_var_1", int_var);
00012 swri::param(pnh, "used_int_var_2", int_var, 2);
00013 swri::param(pnh, "unset_int_var", int_var, 2);
00014
00015 std::string str_var;
00016 swri::getParam(pnh, "used_str_var_1", str_var);
00017 swri::param(pnh, "used_str_var_2", str_var, "foo");
00018 swri::param(pnh, "unset_str_var", str_var, "foo");
00019
00020 double dbl_var;
00021 swri::getParam(pnh, "used_dbl_var_1", dbl_var);
00022 swri::param(pnh, "used_dbl_var_2", dbl_var, 2.0);
00023 swri::param(pnh, "unset_dbl_var", dbl_var, 2.0);
00024
00025 bool bool_var;
00026 swri::getParam(pnh, "used_bool_var_1", bool_var);
00027 swri::param(pnh, "used_bool_var_2", bool_var, true);
00028 swri::param(pnh, "unset_bool_var", bool_var, true);
00029
00030 swri::warnUnusedParams(pnh);
00031
00032 return 0;
00033 }