param.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2009, 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 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/param.h"
00029 #include "ros/master.h"
00030 #include "ros/xmlrpc_manager.h"
00031 #include "ros/this_node.h"
00032 #include "ros/names.h"
00033 
00034 #include <ros/console.h>
00035 
00036 #include <boost/thread/mutex.hpp>
00037 #include <boost/lexical_cast.hpp>
00038 
00039 #include <vector>
00040 #include <map>
00041 
00042 namespace ros
00043 {
00044 
00045 namespace param
00046 {
00047 
00048 typedef std::map<std::string, XmlRpc::XmlRpcValue> M_Param;
00049 M_Param g_params;
00050 boost::mutex g_params_mutex;
00051 S_string g_subscribed_params;
00052 
00053 void invalidateParentParams(const std::string& key)
00054 {
00055   std::string ns_key = names::parentNamespace(key);
00056   while (ns_key != "" && ns_key != "/")
00057   {
00058     if (g_subscribed_params.find(ns_key) != g_subscribed_params.end())
00059     {
00060       // by erasing the key the parameter will be re-queried
00061       g_params.erase(ns_key);
00062     }
00063     ns_key = names::parentNamespace(ns_key);
00064   }
00065 }
00066 
00067 void set(const std::string& key, const XmlRpc::XmlRpcValue& v)
00068 {
00069   std::string mapped_key = ros::names::resolve(key);
00070 
00071   XmlRpc::XmlRpcValue params, result, payload;
00072   params[0] = this_node::getName();
00073   params[1] = mapped_key;
00074   params[2] = v;
00075 
00076   {
00077     // Lock around the execute to the master in case we get a parameter update on this value between
00078     // executing on the master and setting the parameter in the g_params list.
00079     boost::mutex::scoped_lock lock(g_params_mutex);
00080 
00081     if (master::execute("setParam", params, result, payload, true))
00082     {
00083       // Update our cached params list now so that if get() is called immediately after param::set()
00084       // we already have the cached state and our value will be correct
00085       if (g_subscribed_params.find(mapped_key) != g_subscribed_params.end())
00086       {
00087         g_params[mapped_key] = v;
00088       }
00089       invalidateParentParams(mapped_key);
00090     }
00091   }
00092 }
00093 
00094 void set(const std::string& key, const std::string& s)
00095 {
00096   // construct xmlrpc_c::value object of the std::string and
00097   // call param::set(key, xmlvalue);
00098   XmlRpc::XmlRpcValue v(s);
00099   ros::param::set(key, v);
00100 }
00101 
00102 void set(const std::string& key, const char* s)
00103 {
00104   // construct xmlrpc_c::value object of the std::string and
00105   // call param::set(key, xmlvalue);
00106   std::string sxx = std::string(s);
00107   XmlRpc::XmlRpcValue v(sxx);
00108   ros::param::set(key, v);
00109 }
00110 
00111 void set(const std::string& key, double d)
00112 {
00113   XmlRpc::XmlRpcValue v(d);
00114   ros::param::set(key, v);
00115 }
00116 
00117 void set(const std::string& key, int i)
00118 {
00119   XmlRpc::XmlRpcValue v(i);
00120   ros::param::set(key, v);
00121 }
00122 
00123 void set(const std::string& key, bool b)
00124 {
00125   XmlRpc::XmlRpcValue v(b);
00126   ros::param::set(key, v);
00127 }
00128 
00129 template <class T>
00130   void setImpl(const std::string& key, const std::vector<T>& vec)
00131 {
00132   // Note: the XmlRpcValue starts off as "invalid" and assertArray turns it
00133   // into an array type with the given size
00134   XmlRpc::XmlRpcValue xml_vec;
00135   xml_vec.setSize(vec.size());
00136 
00137   // Copy the contents into the XmlRpcValue
00138   for(size_t i=0; i < vec.size(); i++) {
00139     xml_vec[i] = vec.at(i);
00140   }
00141 
00142   ros::param::set(key, xml_vec);
00143 }
00144 
00145 void set(const std::string& key, const std::vector<std::string>& vec)
00146 {
00147   setImpl(key, vec);
00148 }
00149 
00150 void set(const std::string& key, const std::vector<double>& vec)
00151 {
00152   setImpl(key, vec);
00153 }
00154 
00155 void set(const std::string& key, const std::vector<float>& vec)
00156 {
00157   setImpl(key, vec);
00158 }
00159 
00160 void set(const std::string& key, const std::vector<int>& vec)
00161 {
00162   setImpl(key, vec);
00163 }
00164 
00165 void set(const std::string& key, const std::vector<bool>& vec)
00166 {
00167   setImpl(key, vec);
00168 }
00169 
00170 template <class T>
00171   void setImpl(const std::string& key, const std::map<std::string, T>& map)
00172 {
00173   // Note: the XmlRpcValue starts off as "invalid" and assertArray turns it
00174   // into an array type with the given size
00175   XmlRpc::XmlRpcValue xml_value;
00176   const XmlRpc::XmlRpcValue::ValueStruct& xml_map = (const XmlRpc::XmlRpcValue::ValueStruct &)(xml_value);
00177   (void)xml_map;
00178 
00179   // Copy the contents into the XmlRpcValue
00180   for(typename std::map<std::string, T>::const_iterator it = map.begin(); it != map.end(); ++it) {
00181     xml_value[it->first] = it->second;
00182   }
00183 
00184   ros::param::set(key, xml_value);
00185 }
00186 
00187 void set(const std::string& key, const std::map<std::string, std::string>& map)
00188 {
00189   setImpl(key, map);
00190 }
00191 
00192 void set(const std::string& key, const std::map<std::string, double>& map)
00193 {
00194   setImpl(key, map);
00195 }
00196 
00197 void set(const std::string& key, const std::map<std::string, float>& map)
00198 {
00199   setImpl(key, map);
00200 }
00201 
00202 void set(const std::string& key, const std::map<std::string, int>& map)
00203 {
00204   setImpl(key, map);
00205 }
00206 
00207 void set(const std::string& key, const std::map<std::string, bool>& map)
00208 {
00209   setImpl(key, map);
00210 }
00211 
00212 bool has(const std::string& key)
00213 {
00214   XmlRpc::XmlRpcValue params, result, payload;
00215   params[0] = this_node::getName();
00216   params[1] = ros::names::resolve(key);
00217   //params[1] = key;
00218   // We don't loop here, because validateXmlrpcResponse() returns false
00219   // both when we can't contact the master and when the master says, "I
00220   // don't have that param."
00221   if (!master::execute("hasParam", params, result, payload, false))
00222   {
00223     return false;
00224   }
00225 
00226   return payload;
00227 }
00228 
00229 bool del(const std::string& key)
00230 {
00231   std::string mapped_key = ros::names::resolve(key);
00232 
00233   {
00234     boost::mutex::scoped_lock lock(g_params_mutex);
00235 
00236     g_subscribed_params.erase(mapped_key);
00237     g_params.erase(mapped_key);
00238   }
00239 
00240   XmlRpc::XmlRpcValue params, result, payload;
00241   params[0] = this_node::getName();
00242   params[1] = mapped_key;
00243   // We don't loop here, because validateXmlrpcResponse() returns false
00244   // both when we can't contact the master and when the master says, "I
00245   // don't have that param."
00246   if (!master::execute("deleteParam", params, result, payload, false))
00247   {
00248     return false;
00249   }
00250 
00251   return true;
00252 }
00253 
00254 bool getImpl(const std::string& key, XmlRpc::XmlRpcValue& v, bool use_cache)
00255 {
00256   std::string mapped_key = ros::names::resolve(key);
00257   if (mapped_key.empty()) mapped_key = "/";
00258 
00259   if (use_cache)
00260   {
00261     boost::mutex::scoped_lock lock(g_params_mutex);
00262 
00263     if (g_subscribed_params.find(mapped_key) != g_subscribed_params.end())
00264     {
00265       M_Param::iterator it = g_params.find(mapped_key);
00266       if (it != g_params.end())
00267       {
00268         if (it->second.valid())
00269         {
00270           ROS_DEBUG_NAMED("cached_parameters", "Using cached parameter value for key [%s]", mapped_key.c_str());
00271 
00272           v = it->second;
00273           return true;
00274         }
00275         else
00276         {
00277           ROS_DEBUG_NAMED("cached_parameters", "Cached parameter is invalid for key [%s]", mapped_key.c_str());
00278           return false;
00279         }
00280       }
00281     }
00282     else
00283     {
00284       // parameter we've never seen before, register for update from the master
00285       if (g_subscribed_params.insert(mapped_key).second)
00286       {
00287         XmlRpc::XmlRpcValue params, result, payload;
00288         params[0] = this_node::getName();
00289         params[1] = XMLRPCManager::instance()->getServerURI();
00290         params[2] = mapped_key;
00291 
00292         if (!master::execute("subscribeParam", params, result, payload, false))
00293         {
00294           ROS_DEBUG_NAMED("cached_parameters", "Subscribe to parameter [%s]: call to the master failed", mapped_key.c_str());
00295           g_subscribed_params.erase(mapped_key);
00296           use_cache = false;
00297         }
00298         else
00299         {
00300           ROS_DEBUG_NAMED("cached_parameters", "Subscribed to parameter [%s]", mapped_key.c_str());
00301         }
00302       }
00303     }
00304   }
00305 
00306   XmlRpc::XmlRpcValue params, result;
00307   params[0] = this_node::getName();
00308   params[1] = mapped_key;
00309 
00310   // We don't loop here, because validateXmlrpcResponse() returns false
00311   // both when we can't contact the master and when the master says, "I
00312   // don't have that param."
00313   bool ret = master::execute("getParam", params, result, v, false);
00314 
00315   if (use_cache)
00316   {
00317     boost::mutex::scoped_lock lock(g_params_mutex);
00318 
00319     ROS_DEBUG_NAMED("cached_parameters", "Caching parameter [%s] with value type [%d]", mapped_key.c_str(), v.getType());
00320     g_params[mapped_key] = v;
00321   }
00322 
00323   return ret;
00324 }
00325 
00326 bool getImpl(const std::string& key, std::string& s, bool use_cache)
00327 {
00328   XmlRpc::XmlRpcValue v;
00329   if (!getImpl(key, v, use_cache))
00330     return false;
00331   if (v.getType() != XmlRpc::XmlRpcValue::TypeString)
00332     return false;
00333   s = std::string(v);
00334   return true;
00335 }
00336 
00337 bool getImpl(const std::string& key, double& d, bool use_cache)
00338 {
00339   XmlRpc::XmlRpcValue v;
00340   if (!getImpl(key, v, use_cache))
00341   {
00342     return false;
00343   }
00344 
00345   if (v.getType() == XmlRpc::XmlRpcValue::TypeInt)
00346   {
00347     d = (int)v;
00348   }
00349   else if (v.getType() != XmlRpc::XmlRpcValue::TypeDouble)
00350   {
00351     return false;
00352   }
00353   else
00354   {
00355     d = v;
00356   }
00357 
00358   return true;
00359 }
00360 
00361 bool getImpl(const std::string& key, float& f, bool use_cache)
00362 {
00363   double d = static_cast<double>(f);
00364   bool result = getImpl(key, d, use_cache);
00365   if (result)
00366     f = static_cast<float>(d);
00367   return result;
00368 }
00369 
00370 bool getImpl(const std::string& key, int& i, bool use_cache)
00371 {
00372   XmlRpc::XmlRpcValue v;
00373   if (!getImpl(key, v, use_cache))
00374   {
00375     return false;
00376   }
00377 
00378   if (v.getType() == XmlRpc::XmlRpcValue::TypeDouble)
00379   {
00380     double d = v;
00381 
00382     if (fmod(d, 1.0) < 0.5)
00383     {
00384       d = floor(d);
00385     }
00386     else
00387     {
00388       d = ceil(d);
00389     }
00390 
00391     i = d;
00392   }
00393   else if (v.getType() != XmlRpc::XmlRpcValue::TypeInt)
00394   {
00395     return false;
00396   }
00397   else
00398   {
00399     i = v;
00400   }
00401 
00402   return true;
00403 }
00404 
00405 bool getImpl(const std::string& key, bool& b, bool use_cache)
00406 {
00407   XmlRpc::XmlRpcValue v;
00408   if (!getImpl(key, v, use_cache))
00409     return false;
00410   if (v.getType() != XmlRpc::XmlRpcValue::TypeBoolean)
00411     return false;
00412   b = v;
00413   return true;
00414 }
00415 
00416 bool get(const std::string& key, std::string& s)
00417 {
00418         return getImpl(key, s, false);
00419 }
00420 
00421 bool get(const std::string& key, double& d)
00422 {
00423         return getImpl(key, d, false);
00424 }
00425 
00426 bool get(const std::string& key, float& f)
00427 {
00428         return getImpl(key, f, false);
00429 }
00430 
00431 bool get(const std::string& key, int& i)
00432 {
00433         return getImpl(key, i, false);
00434 }
00435 
00436 bool get(const std::string& key, bool& b)
00437 {
00438         return getImpl(key, b, false);
00439 }
00440 
00441 bool get(const std::string& key, XmlRpc::XmlRpcValue& v)
00442 {
00443         return getImpl(key, v, false);
00444 }
00445 
00446 bool getCached(const std::string& key, std::string& s)
00447 {
00448         return getImpl(key, s, true);
00449 }
00450 
00451 bool getCached(const std::string& key, double& d)
00452 {
00453         return getImpl(key, d, true);
00454 }
00455 
00456 bool getCached(const std::string& key, float& f)
00457 {
00458         return getImpl(key, f, true);
00459 }
00460 
00461 bool getCached(const std::string& key, int& i)
00462 {
00463         return getImpl(key, i, true);
00464 }
00465 
00466 bool getCached(const std::string& key, bool& b)
00467 {
00468         return getImpl(key, b, true);
00469 }
00470 
00471 bool getCached(const std::string& key, XmlRpc::XmlRpcValue& v)
00472 {
00473         return getImpl(key, v, true);
00474 }
00475 
00476 template <class T> T xml_cast(XmlRpc::XmlRpcValue xml_value) 
00477 {
00478   return static_cast<T>(xml_value);
00479 }
00480 
00481 template <class T> bool xml_castable(int XmlType) 
00482 {
00483   return false;
00484 }
00485 
00486 template<> bool xml_castable<std::string>(int XmlType)
00487 {
00488   return XmlType == XmlRpc::XmlRpcValue::TypeString;
00489 }
00490 
00491 template<> bool xml_castable<double>(int XmlType)
00492 {
00493   return ( 
00494       XmlType == XmlRpc::XmlRpcValue::TypeDouble ||
00495       XmlType == XmlRpc::XmlRpcValue::TypeInt ||
00496       XmlType == XmlRpc::XmlRpcValue::TypeBoolean );
00497 }
00498 
00499 template<> bool xml_castable<float>(int XmlType)
00500 {
00501   return ( 
00502       XmlType == XmlRpc::XmlRpcValue::TypeDouble ||
00503       XmlType == XmlRpc::XmlRpcValue::TypeInt ||
00504       XmlType == XmlRpc::XmlRpcValue::TypeBoolean );
00505 }
00506 
00507 template<> bool xml_castable<int>(int XmlType)
00508 {
00509   return ( 
00510       XmlType == XmlRpc::XmlRpcValue::TypeDouble ||
00511       XmlType == XmlRpc::XmlRpcValue::TypeInt ||
00512       XmlType == XmlRpc::XmlRpcValue::TypeBoolean );
00513 }
00514 
00515 template<> bool xml_castable<bool>(int XmlType)
00516 {
00517   return ( 
00518       XmlType == XmlRpc::XmlRpcValue::TypeDouble ||
00519       XmlType == XmlRpc::XmlRpcValue::TypeInt ||
00520       XmlType == XmlRpc::XmlRpcValue::TypeBoolean );
00521 }
00522 
00523 template<> double xml_cast(XmlRpc::XmlRpcValue xml_value)
00524 {
00525   using namespace XmlRpc;
00526   switch(xml_value.getType()) {
00527     case XmlRpcValue::TypeDouble:
00528       return static_cast<double>(xml_value);
00529     case XmlRpcValue::TypeInt:
00530       return static_cast<double>(static_cast<int>(xml_value));
00531     case XmlRpcValue::TypeBoolean:
00532       return static_cast<double>(static_cast<bool>(xml_value));
00533     default:
00534      return 0.0;
00535   };
00536 }
00537 
00538 template<> float xml_cast(XmlRpc::XmlRpcValue xml_value)
00539 {
00540   using namespace XmlRpc;
00541   switch(xml_value.getType()) {
00542     case XmlRpcValue::TypeDouble:
00543       return static_cast<float>(static_cast<double>(xml_value));
00544     case XmlRpcValue::TypeInt:
00545       return static_cast<float>(static_cast<int>(xml_value));
00546     case XmlRpcValue::TypeBoolean:
00547       return static_cast<float>(static_cast<bool>(xml_value));
00548     default:
00549       return 0.0f;
00550   };
00551 }
00552 
00553 template<> int xml_cast(XmlRpc::XmlRpcValue xml_value)
00554 {
00555   using namespace XmlRpc;
00556   switch(xml_value.getType()) {
00557     case XmlRpcValue::TypeDouble:
00558       return static_cast<int>(static_cast<double>(xml_value));
00559     case XmlRpcValue::TypeInt:
00560       return static_cast<int>(xml_value);
00561     case XmlRpcValue::TypeBoolean:
00562       return static_cast<int>(static_cast<bool>(xml_value));
00563     default:
00564       return 0;
00565   };
00566 }
00567 
00568 template<> bool xml_cast(XmlRpc::XmlRpcValue xml_value)
00569 {
00570   using namespace XmlRpc;
00571   switch(xml_value.getType()) {
00572     case XmlRpcValue::TypeDouble:
00573       return static_cast<bool>(static_cast<double>(xml_value));
00574     case XmlRpcValue::TypeInt:
00575       return static_cast<bool>(static_cast<int>(xml_value));
00576     case XmlRpcValue::TypeBoolean:
00577       return static_cast<bool>(xml_value);
00578     default:
00579       return false;
00580   };
00581 }
00582   
00583 template <class T>
00584   bool getImpl(const std::string& key, std::vector<T>& vec, bool cached)
00585 {
00586   XmlRpc::XmlRpcValue xml_array;
00587   if(!getImpl(key, xml_array, cached)) {
00588     return false;
00589   }
00590 
00591   // Make sure it's an array type
00592   if(xml_array.getType() != XmlRpc::XmlRpcValue::TypeArray) {
00593     return false;
00594   }
00595 
00596   // Resize the target vector (destructive)
00597   vec.resize(xml_array.size());
00598 
00599   // Fill the vector with stuff
00600   for (int i = 0; i < xml_array.size(); i++) {
00601     if(!xml_castable<T>(xml_array[i].getType())) {
00602       return false;
00603     }
00604 
00605     vec[i] = xml_cast<T>(xml_array[i]);
00606   }
00607 
00608   return true;
00609 }
00610 
00611 bool get(const std::string& key, std::vector<std::string>& vec)
00612 {
00613   return getImpl(key, vec, false);
00614 }
00615 bool get(const std::string& key, std::vector<double>& vec)
00616 {
00617   return getImpl(key, vec, false);
00618 }
00619 bool get(const std::string& key, std::vector<float>& vec)
00620 {
00621   return getImpl(key, vec, false);
00622 }
00623 bool get(const std::string& key, std::vector<int>& vec)
00624 {
00625   return getImpl(key, vec, false);
00626 }
00627 bool get(const std::string& key, std::vector<bool>& vec)
00628 {
00629   return getImpl(key, vec, false);
00630 }
00631 
00632 bool getCached(const std::string& key, std::vector<std::string>& vec)
00633 {
00634   return getImpl(key, vec, true);
00635 }
00636 bool getCached(const std::string& key, std::vector<double>& vec)
00637 {
00638   return getImpl(key, vec, true);
00639 }
00640 bool getCached(const std::string& key, std::vector<float>& vec)
00641 {
00642   return getImpl(key, vec, true);
00643 }
00644 bool getCached(const std::string& key, std::vector<int>& vec)
00645 {
00646   return getImpl(key, vec, true);
00647 }
00648 bool getCached(const std::string& key, std::vector<bool>& vec)
00649 {
00650   return getImpl(key, vec, true);
00651 }
00652 
00653 template <class T>
00654   bool getImpl(const std::string& key, std::map<std::string, T>& map, bool cached)
00655 {
00656   XmlRpc::XmlRpcValue xml_value;
00657   if(!getImpl(key, xml_value, cached)) {
00658     return false;
00659   }
00660 
00661   // Make sure it's a struct type
00662   if(xml_value.getType() != XmlRpc::XmlRpcValue::TypeStruct) {
00663     return false;
00664   }
00665 
00666   // Fill the map with stuff
00667   for (XmlRpc::XmlRpcValue::ValueStruct::const_iterator it = xml_value.begin();
00668       it != xml_value.end();
00669       ++it)
00670   {
00671     // Make sure this element is the right type
00672     if(!xml_castable<T>(it->second.getType())) {
00673       return false;
00674     }
00675     // Store the element
00676     map[it->first] = xml_cast<T>(it->second);
00677   }
00678 
00679   return true;
00680 }
00681 
00682 bool get(const std::string& key, std::map<std::string, std::string>& map)
00683 {
00684   return getImpl(key, map, false);
00685 }
00686 bool get(const std::string& key, std::map<std::string, double>& map)
00687 {
00688   return getImpl(key, map, false);
00689 }
00690 bool get(const std::string& key, std::map<std::string, float>& map)
00691 {
00692   return getImpl(key, map, false);
00693 }
00694 bool get(const std::string& key, std::map<std::string, int>& map)
00695 {
00696   return getImpl(key, map, false);
00697 }
00698 bool get(const std::string& key, std::map<std::string, bool>& map)
00699 {
00700   return getImpl(key, map, false);
00701 }
00702 
00703 bool getCached(const std::string& key, std::map<std::string, std::string>& map)
00704 {
00705   return getImpl(key, map, true);
00706 }
00707 bool getCached(const std::string& key, std::map<std::string, double>& map)
00708 {
00709   return getImpl(key, map, true);
00710 }
00711 bool getCached(const std::string& key, std::map<std::string, float>& map)
00712 {
00713   return getImpl(key, map, true);
00714 }
00715 bool getCached(const std::string& key, std::map<std::string, int>& map)
00716 {
00717   return getImpl(key, map, true);
00718 }
00719 bool getCached(const std::string& key, std::map<std::string, bool>& map)
00720 {
00721   return getImpl(key, map, true);
00722 }
00723 
00724 bool getParamNames(std::vector<std::string>& keys)
00725 {
00726   XmlRpc::XmlRpcValue params, result, payload;
00727   params[0] = this_node::getName();
00728   if (!master::execute("getParamNames", params, result, payload, false)) {
00729     return false;
00730   }
00731   // Make sure it's an array type
00732   if (result.getType() != XmlRpc::XmlRpcValue::TypeArray) {
00733     return false;
00734   }
00735   // Make sure it returned 3 elements
00736   if (result.size() != 3) {
00737     return false;
00738   }
00739   // Get the actual parameter keys
00740   XmlRpc::XmlRpcValue parameters = result[2];
00741   // Resize the output
00742   keys.resize(parameters.size());
00743 
00744   // Fill the output vector with the answer
00745   for (int i = 0; i < parameters.size(); ++i) {
00746     if (parameters[i].getType() != XmlRpc::XmlRpcValue::TypeString) {
00747       return false;
00748     }
00749     keys[i] = std::string(parameters[i]);
00750   }
00751   return true;
00752 }
00753 
00754 bool search(const std::string& key, std::string& result_out)
00755 {
00756   return search(this_node::getName(), key, result_out);
00757 }
00758 
00759 bool search(const std::string& ns, const std::string& key, std::string& result_out)
00760 {
00761   XmlRpc::XmlRpcValue params, result, payload;
00762   params[0] = ns;
00763 
00764   // searchParam needs a separate form of remapping -- remapping on the unresolved name, rather than the
00765   // resolved one.
00766 
00767   std::string remapped = key;
00768   M_string::const_iterator it = names::getUnresolvedRemappings().find(key);
00769   if (it != names::getUnresolvedRemappings().end())
00770   {
00771     remapped = it->second;
00772   }
00773 
00774   params[1] = remapped;
00775   // We don't loop here, because validateXmlrpcResponse() returns false
00776   // both when we can't contact the master and when the master says, "I
00777   // don't have that param."
00778   if (!master::execute("searchParam", params, result, payload, false))
00779   {
00780     return false;
00781   }
00782 
00783   result_out = (std::string)payload;
00784 
00785   return true;
00786 }
00787 
00788 void update(const std::string& key, const XmlRpc::XmlRpcValue& v)
00789 {
00790   std::string clean_key = names::clean(key);
00791   ROS_DEBUG_NAMED("cached_parameters", "Received parameter update for key [%s]", clean_key.c_str());
00792 
00793   boost::mutex::scoped_lock lock(g_params_mutex);
00794 
00795   if (g_subscribed_params.find(clean_key) != g_subscribed_params.end())
00796   {
00797     g_params[clean_key] = v;
00798   }
00799   invalidateParentParams(clean_key);
00800 }
00801 
00802 void paramUpdateCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result)
00803 {
00804   result[0] = 1;
00805   result[1] = std::string("");
00806   result[2] = 0;
00807 
00808   ros::param::update((std::string)params[1], params[2]);
00809 }
00810 
00811 void init(const M_string& remappings)
00812 {
00813   M_string::const_iterator it = remappings.begin();
00814   M_string::const_iterator end = remappings.end();
00815   for (; it != end; ++it)
00816   {
00817     const std::string& name = it->first;
00818     const std::string& param = it->second;
00819 
00820     if (name.size() < 2)
00821     {
00822       continue;
00823     }
00824 
00825     if (name[0] == '_' && name[1] != '_')
00826     {
00827       std::string local_name = "~" + name.substr(1);
00828 
00829       bool success = false;
00830 
00831       try
00832       {
00833         int32_t i = boost::lexical_cast<int32_t>(param);
00834         ros::param::set(names::resolve(local_name), i);
00835         success = true;
00836       }
00837       catch (boost::bad_lexical_cast&)
00838       {
00839 
00840       }
00841 
00842       if (success)
00843       {
00844         continue;
00845       }
00846 
00847       try
00848       {
00849         double d = boost::lexical_cast<double>(param);
00850         ros::param::set(names::resolve(local_name), d);
00851         success = true;
00852       }
00853       catch (boost::bad_lexical_cast&)
00854       {
00855 
00856       }
00857 
00858       if (success)
00859       {
00860         continue;
00861       }
00862 
00863       if (param == "true" || param == "True" || param == "TRUE")
00864       {
00865         ros::param::set(names::resolve(local_name), true);
00866       }
00867       else if (param == "false" || param == "False" || param == "FALSE")
00868       {
00869         ros::param::set(names::resolve(local_name), false);
00870       }
00871       else
00872       {
00873         ros::param::set(names::resolve(local_name), param);
00874       }
00875     }
00876   }
00877 
00878   XMLRPCManager::instance()->bind("paramUpdate", paramUpdateCallback);
00879 }
00880 
00881 } // namespace param
00882 
00883 } // namespace ros


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Tue Mar 7 2017 03:44:47