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 JSK Lab 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 #include "jsk_topic_tools/log_utils.h"
00038 
00039 namespace jsk_topic_tools
00040 {
00041   double getXMLDoubleValue(XmlRpc::XmlRpcValue val)
00042   {
00043     switch(val.getType())
00044     {
00045     case XmlRpc::XmlRpcValue::TypeInt:
00046     {
00047       return (double)((int)val);
00048     }
00049     case XmlRpc::XmlRpcValue::TypeDouble:
00050     {
00051       return (double)val;
00052     }
00053     default:
00054     {
00055       ROS_ERROR_STREAM("the value cannot be converted into double: " << val);
00056       throw std::runtime_error("the value cannot be converted into double");
00057     }
00058     }
00059   }
00060   
00061   bool readVectorParameter(ros::NodeHandle& nh,
00062                            const std::string& param_name,
00063                            std::vector<double>& result)
00064   {
00065     if (nh.hasParam(param_name)) {
00066       XmlRpc::XmlRpcValue v;
00067       nh.param(param_name, v, v);
00068       if (v.getType() == XmlRpc::XmlRpcValue::TypeArray) {
00069         result.resize(v.size());
00070         for (size_t i = 0; i < v.size(); i++) {
00071           result[i] = getXMLDoubleValue(v[i]);
00072         }
00073         return true;
00074       }
00075       else {
00076         return false;
00077       }
00078     }
00079     else {
00080       return false;
00081     }
00082   }
00083 
00084   bool readVectorParameter(ros::NodeHandle& nh,
00085                            const std::string& param_name,
00086                            std::vector<std::vector<double> >& result)
00087   {
00088     if (nh.hasParam(param_name)) {
00089       XmlRpc::XmlRpcValue v_toplevel;
00090       nh.param(param_name, v_toplevel, v_toplevel);
00091       if (v_toplevel.getType() == XmlRpc::XmlRpcValue::TypeArray) {
00092         result.resize(v_toplevel.size());
00093         for (size_t i = 0; i < v_toplevel.size(); i++) {
00094           // ensure v[i] is an array
00095           XmlRpc::XmlRpcValue nested_v = v_toplevel[i];
00096           if (nested_v.getType() == XmlRpc::XmlRpcValue::TypeArray) {
00097             std::vector<double> nested_std_vector(nested_v.size());
00098             for (size_t j = 0; j < nested_v.size(); j++) {
00099               nested_std_vector[j] = getXMLDoubleValue(nested_v[j]);
00100             }
00101             result[i] = nested_std_vector;
00102           }
00103           else {
00104             return false;
00105           }
00106         }
00107         return true;
00108       }
00109       else {
00110         return false;
00111       }
00112     }
00113     else {
00114       return false;
00115     }
00116   }
00117 
00118   bool readVectorParameter(ros::NodeHandle& nh,
00119                            const std::string& param_name,
00120                            std::vector<std::vector<std::string> >& result)
00121   {
00122     if (nh.hasParam(param_name)) {
00123       XmlRpc::XmlRpcValue v_toplevel;
00124       nh.param(param_name, v_toplevel, v_toplevel);
00125       if (v_toplevel.getType() == XmlRpc::XmlRpcValue::TypeArray) {
00126         result.resize(v_toplevel.size());
00127         for (size_t i = 0; i < v_toplevel.size(); i++) {
00128           // ensure v[i] is an array
00129           XmlRpc::XmlRpcValue nested_v = v_toplevel[i];
00130           if (nested_v.getType() == XmlRpc::XmlRpcValue::TypeArray) {
00131             std::vector<std::string> nested_std_vector(nested_v.size());
00132             for (size_t j = 0; j < nested_v.size(); j++) {
00133               if (nested_v[j].getType() == XmlRpc::XmlRpcValue::TypeString) {
00134                 nested_std_vector[j] = (std::string)nested_v[j];
00135               }
00136               else {
00137                 return false;
00138               }
00139             }
00140             result[i] = nested_std_vector;
00141           }
00142           else {
00143             return false;
00144           }
00145         }
00146         return true;
00147       }
00148       else {
00149         return false;
00150       }
00151     }
00152     else {
00153       return false;
00154     }
00155   }
00156   
00157   bool readVectorParameter(ros::NodeHandle& nh,
00158                            const std::string& param_name,
00159                            std::vector<std::string>& result)
00160   {
00161     if (nh.hasParam(param_name)) {
00162       XmlRpc::XmlRpcValue v;
00163       nh.param(param_name, v, v);
00164       if (v.getType() == XmlRpc::XmlRpcValue::TypeArray) {
00165         result.resize(v.size());
00166         for (size_t i = 0; i < result.size(); i++) {
00167           if (v[i].getType() == XmlRpc::XmlRpcValue::TypeString) {
00168             result[i] = (std::string)v[i];
00169           }
00170           else {
00171             throw std::runtime_error(
00172               "the value cannot be converted into std::string");
00173           }
00174         }
00175         return true;
00176       }
00177       else {
00178         return false;
00179       }
00180     }
00181     else {
00182       return false;
00183     }
00184   }
00185 
00186   
00187 }


jsk_topic_tools
Author(s): Kei Okada , Yusuke Furuta
autogenerated on Fri Sep 8 2017 03:38:56