rosparam_utils.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Willow Garage nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include "jsk_topic_tools/rosparam_utils.h"
00037 
00038 namespace jsk_topic_tools
00039 {
00040   double getXMLDoubleValue(XmlRpc::XmlRpcValue val)
00041   {
00042     switch(val.getType())
00043     {
00044     case XmlRpc::XmlRpcValue::TypeInt:
00045     {
00046       return (double)((int)val);
00047     }
00048     case XmlRpc::XmlRpcValue::TypeDouble:
00049     {
00050       return (double)val;
00051     }
00052     default:
00053     {
00054       throw std::runtime_error("the value cannot be converted into double");
00055     }
00056     }
00057   }
00058   
00059   bool readVectorParameter(ros::NodeHandle& nh,
00060                            const std::string& param_name,
00061                            std::vector<double>& result)
00062   {
00063     if (nh.hasParam(param_name)) {
00064       XmlRpc::XmlRpcValue v;
00065       nh.param(param_name, v, v);
00066       if (v.getType() == XmlRpc::XmlRpcValue::TypeArray) {
00067         result.resize(v.size());
00068         for (size_t i = 0; i < v.size(); i++) {
00069           result[i] = getXMLDoubleValue(v[i]);
00070         }
00071         return true;
00072       }
00073       else {
00074         return false;
00075       }
00076     }
00077     else {
00078       return false;
00079     }
00080   }
00081 
00082   bool readVectorParameter(ros::NodeHandle& nh,
00083                            const std::string& param_name,
00084                            std::vector<std::vector<double> >& result)
00085   {
00086     if (nh.hasParam(param_name)) {
00087       XmlRpc::XmlRpcValue v_toplevel;
00088       nh.param(param_name, v_toplevel, v_toplevel);
00089       if (v_toplevel.getType() == XmlRpc::XmlRpcValue::TypeArray) {
00090         result.resize(v_toplevel.size());
00091         for (size_t i = 0; i < v_toplevel.size(); i++) {
00092           // ensure v[i] is an array
00093           XmlRpc::XmlRpcValue nested_v = v_toplevel[i];
00094           if (nested_v.getType() == XmlRpc::XmlRpcValue::TypeArray) {
00095             std::vector<double> nested_std_vector(nested_v.size());
00096             for (size_t j = 0; j < nested_v.size(); j++) {
00097               nested_std_vector[j] = getXMLDoubleValue(nested_v[j]);
00098             }
00099             result[i] = nested_std_vector;
00100           }
00101           else {
00102             return false;
00103           }
00104         }
00105         return true;
00106       }
00107       else {
00108         return false;
00109       }
00110     }
00111     else {
00112       return false;
00113     }
00114   }
00115 
00116   bool readVectorParameter(ros::NodeHandle& nh,
00117                            const std::string& param_name,
00118                            std::vector<std::vector<std::string> >& result)
00119   {
00120     if (nh.hasParam(param_name)) {
00121       XmlRpc::XmlRpcValue v_toplevel;
00122       nh.param(param_name, v_toplevel, v_toplevel);
00123       if (v_toplevel.getType() == XmlRpc::XmlRpcValue::TypeArray) {
00124         result.resize(v_toplevel.size());
00125         for (size_t i = 0; i < v_toplevel.size(); i++) {
00126           // ensure v[i] is an array
00127           XmlRpc::XmlRpcValue nested_v = v_toplevel[i];
00128           if (nested_v.getType() == XmlRpc::XmlRpcValue::TypeArray) {
00129             std::vector<std::string> nested_std_vector(nested_v.size());
00130             for (size_t j = 0; j < nested_v.size(); j++) {
00131               if (nested_v[j].getType() == XmlRpc::XmlRpcValue::TypeString) {
00132                 nested_std_vector[j] = (std::string)nested_v[j];
00133               }
00134               else {
00135                 return false;
00136               }
00137             }
00138             result[i] = nested_std_vector;
00139           }
00140           else {
00141             return false;
00142           }
00143         }
00144         return true;
00145       }
00146       else {
00147         return false;
00148       }
00149     }
00150     else {
00151       return false;
00152     }
00153   }
00154   
00155   bool readVectorParameter(ros::NodeHandle& nh,
00156                            const std::string& param_name,
00157                            std::vector<std::string>& result)
00158   {
00159     if (nh.hasParam(param_name)) {
00160       XmlRpc::XmlRpcValue v;
00161       nh.param(param_name, v, v);
00162       if (v.getType() == XmlRpc::XmlRpcValue::TypeArray) {
00163         result.resize(v.size());
00164         for (size_t i = 0; i < result.size(); i++) {
00165           if (v[i].getType() == XmlRpc::XmlRpcValue::TypeString) {
00166             result[i] = (std::string)v[i];
00167           }
00168           else {
00169             throw std::runtime_error(
00170               "the value cannot be converted into std::string");
00171           }
00172         }
00173         return true;
00174       }
00175       else {
00176         return false;
00177       }
00178     }
00179     else {
00180       return false;
00181     }
00182   }
00183 
00184   
00185 }


jsk_topic_tools
Author(s): Kei Okada , Yusuke Furuta
autogenerated on Sun Jan 25 2015 12:38:34