00001 /* 00002 * Copyright (C) 2010, Willow Garage, Inc. 00003 * 00004 * Redistribution and use in source and binary forms, with or without 00005 * modification, are permitted provided that the following conditions are met: 00006 * * Redistributions of source code must retain the above copyright notice, 00007 * this list of conditions and the following disclaimer. 00008 * * Redistributions in binary form must reproduce the above copyright 00009 * notice, this list of conditions and the following disclaimer in the 00010 * documentation and/or other materials provided with the distribution. 00011 * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its 00012 * contributors may be used to endorse or promote products derived from 00013 * this software without specific prior written permission. 00014 * 00015 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00016 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00017 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00018 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00019 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00020 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00021 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00022 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00023 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00024 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00025 * POSSIBILITY OF SUCH DAMAGE. 00026 */ 00027 00028 #include <ros/ros.h> 00029 00030 int main(int argc, char** argv) 00031 { 00032 ros::init(argc, argv, "parameters"); 00033 ros::NodeHandle n; 00034 00035 { 00036 // %Tag(NH_GETPARAM_SIMPLE)% 00037 std::string s; 00038 n.getParam("my_param", s); 00039 // %EndTag(NH_GETPARAM_SIMPLE)% 00040 } 00041 00042 { 00043 // %Tag(NH_GETPARAM_CHECK_RETURN)% 00044 std::string s; 00045 if (n.getParam("my_param", s)) 00046 { 00047 ROS_INFO("Got param: %s", s.c_str()); 00048 } 00049 else 00050 { 00051 ROS_ERROR("Failed to get param 'my_param'"); 00052 } 00053 // %EndTag(NH_GETPARAM_CHECK_RETURN)% 00054 } 00055 00056 // %Tag(NH_PARAM_INT)% 00057 int i; 00058 n.param("my_num", i, 42); 00059 // %EndTag(NH_PARAM_INT)% 00060 00061 // %Tag(NH_PARAM_STRING)% 00062 std::string s; 00063 n.param<std::string>("my_param", s, "default_value"); 00064 // %EndTag(NH_PARAM_STRING)% 00065 00066 // %Tag(NH_SETPARAM)% 00067 n.setParam("my_param", "hello there"); 00068 // %EndTag(NH_SETPARAM)% 00069 00070 // %Tag(NH_DELETEPARAM)% 00071 n.deleteParam("my_param"); 00072 // %EndTag(NH_DELETEPARAM)% 00073 00074 // %Tag(NH_HASPARAM)% 00075 if (!n.hasParam("my_param")) 00076 { 00077 ROS_INFO("No param named 'my_param'"); 00078 } 00079 // %EndTag(NH_HASPARAM)% 00080 00081 // %Tag(NH_SEARCHPARAM)% 00082 std::string param_name; 00083 if (n.searchParam("b", param_name)) 00084 { 00085 // Found parameter, can now query it using param_name 00086 int i = 0; 00087 n.getParam(param_name, i); 00088 } 00089 else 00090 { 00091 ROS_INFO("No param 'b' found in an upward search"); 00092 } 00093 // %EndTag(NH_SEARCHPARAM)% 00094 }