00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
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
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
00078
00079 boost::mutex::scoped_lock lock(g_params_mutex);
00080
00081 if (master::execute("setParam", params, result, payload, true))
00082 {
00083
00084
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
00097
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
00105
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
00133
00134 XmlRpc::XmlRpcValue xml_vec;
00135 xml_vec.setSize(vec.size());
00136
00137
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
00174
00175 XmlRpc::XmlRpcValue xml_value;
00176 const XmlRpc::XmlRpcValue::ValueStruct& xml_map = (const XmlRpc::XmlRpcValue::ValueStruct &)(xml_value);
00177
00178
00179 for(typename std::map<std::string, T>::const_iterator it = map.begin(); it != map.end(); ++it) {
00180 xml_value[it->first] = it->second;
00181 }
00182
00183 ros::param::set(key, xml_value);
00184 }
00185
00186 void set(const std::string& key, const std::map<std::string, std::string>& map)
00187 {
00188 setImpl(key, map);
00189 }
00190
00191 void set(const std::string& key, const std::map<std::string, double>& map)
00192 {
00193 setImpl(key, map);
00194 }
00195
00196 void set(const std::string& key, const std::map<std::string, float>& map)
00197 {
00198 setImpl(key, map);
00199 }
00200
00201 void set(const std::string& key, const std::map<std::string, int>& map)
00202 {
00203 setImpl(key, map);
00204 }
00205
00206 void set(const std::string& key, const std::map<std::string, bool>& map)
00207 {
00208 setImpl(key, map);
00209 }
00210
00211 bool has(const std::string& key)
00212 {
00213 XmlRpc::XmlRpcValue params, result, payload;
00214 params[0] = this_node::getName();
00215 params[1] = ros::names::resolve(key);
00216
00217
00218
00219
00220 if (!master::execute("hasParam", params, result, payload, false))
00221 {
00222 return false;
00223 }
00224
00225 return payload;
00226 }
00227
00228 bool del(const std::string& key)
00229 {
00230 std::string mapped_key = ros::names::resolve(key);
00231
00232 {
00233 boost::mutex::scoped_lock lock(g_params_mutex);
00234
00235 g_subscribed_params.erase(mapped_key);
00236 g_params.erase(mapped_key);
00237 }
00238
00239 XmlRpc::XmlRpcValue params, result, payload;
00240 params[0] = this_node::getName();
00241 params[1] = mapped_key;
00242
00243
00244
00245 if (!master::execute("deleteParam", params, result, payload, false))
00246 {
00247 return false;
00248 }
00249
00250 return true;
00251 }
00252
00253 bool getImpl(const std::string& key, XmlRpc::XmlRpcValue& v, bool use_cache)
00254 {
00255 std::string mapped_key = ros::names::resolve(key);
00256
00257 if (use_cache)
00258 {
00259 boost::mutex::scoped_lock lock(g_params_mutex);
00260
00261 if (g_subscribed_params.find(mapped_key) != g_subscribed_params.end())
00262 {
00263 M_Param::iterator it = g_params.find(mapped_key);
00264 if (it != g_params.end())
00265 {
00266 if (it->second.valid())
00267 {
00268 ROS_DEBUG_NAMED("cached_parameters", "Using cached parameter value for key [%s]", mapped_key.c_str());
00269
00270 v = it->second;
00271 return true;
00272 }
00273 else
00274 {
00275 ROS_DEBUG_NAMED("cached_parameters", "Cached parameter is invalid for key [%s]", mapped_key.c_str());
00276 return false;
00277 }
00278 }
00279 }
00280 else
00281 {
00282
00283 if (g_subscribed_params.insert(mapped_key).second)
00284 {
00285 XmlRpc::XmlRpcValue params, result, payload;
00286 params[0] = this_node::getName();
00287 params[1] = XMLRPCManager::instance()->getServerURI();
00288 params[2] = mapped_key;
00289
00290 if (!master::execute("subscribeParam", params, result, payload, false))
00291 {
00292 ROS_DEBUG_NAMED("cached_parameters", "Subscribe to parameter [%s]: call to the master failed", mapped_key.c_str());
00293 g_subscribed_params.erase(mapped_key);
00294 use_cache = false;
00295 }
00296 else
00297 {
00298 ROS_DEBUG_NAMED("cached_parameters", "Subscribed to parameter [%s]", mapped_key.c_str());
00299 }
00300 }
00301 }
00302 }
00303
00304 XmlRpc::XmlRpcValue params, result;
00305 params[0] = this_node::getName();
00306 params[1] = mapped_key;
00307
00308
00309
00310
00311 bool ret = master::execute("getParam", params, result, v, false);
00312
00313 if (use_cache)
00314 {
00315 boost::mutex::scoped_lock lock(g_params_mutex);
00316
00317 ROS_DEBUG_NAMED("cached_parameters", "Caching parameter [%s] with value type [%d]", mapped_key.c_str(), v.getType());
00318 g_params[mapped_key] = v;
00319 }
00320
00321 return ret;
00322 }
00323
00324 bool getImpl(const std::string& key, std::string& s, bool use_cache)
00325 {
00326 XmlRpc::XmlRpcValue v;
00327 if (!getImpl(key, v, use_cache))
00328 return false;
00329 if (v.getType() != XmlRpc::XmlRpcValue::TypeString)
00330 return false;
00331 s = std::string(v);
00332 return true;
00333 }
00334
00335 bool getImpl(const std::string& key, double& d, bool use_cache)
00336 {
00337 XmlRpc::XmlRpcValue v;
00338 if (!getImpl(key, v, use_cache))
00339 {
00340 return false;
00341 }
00342
00343 if (v.getType() == XmlRpc::XmlRpcValue::TypeInt)
00344 {
00345 d = (int)v;
00346 }
00347 else if (v.getType() != XmlRpc::XmlRpcValue::TypeDouble)
00348 {
00349 return false;
00350 }
00351 else
00352 {
00353 d = v;
00354 }
00355
00356 return true;
00357 }
00358
00359 bool getImpl(const std::string& key, float& f, bool use_cache)
00360 {
00361 double d = static_cast<double>(f);
00362 bool result = getImpl(key, d, use_cache);
00363 if (result)
00364 f = static_cast<float>(d);
00365 return result;
00366 }
00367
00368 bool getImpl(const std::string& key, int& i, bool use_cache)
00369 {
00370 XmlRpc::XmlRpcValue v;
00371 if (!getImpl(key, v, use_cache))
00372 {
00373 return false;
00374 }
00375
00376 if (v.getType() == XmlRpc::XmlRpcValue::TypeDouble)
00377 {
00378 double d = v;
00379
00380 if (fmod(d, 1.0) < 0.5)
00381 {
00382 d = floor(d);
00383 }
00384 else
00385 {
00386 d = ceil(d);
00387 }
00388
00389 i = d;
00390 }
00391 else if (v.getType() != XmlRpc::XmlRpcValue::TypeInt)
00392 {
00393 return false;
00394 }
00395 else
00396 {
00397 i = v;
00398 }
00399
00400 return true;
00401 }
00402
00403 bool getImpl(const std::string& key, bool& b, bool use_cache)
00404 {
00405 XmlRpc::XmlRpcValue v;
00406 if (!getImpl(key, v, use_cache))
00407 return false;
00408 if (v.getType() != XmlRpc::XmlRpcValue::TypeBoolean)
00409 return false;
00410 b = v;
00411 return true;
00412 }
00413
00414 bool get(const std::string& key, std::string& s)
00415 {
00416 return getImpl(key, s, false);
00417 }
00418
00419 bool get(const std::string& key, double& d)
00420 {
00421 return getImpl(key, d, false);
00422 }
00423
00424 bool get(const std::string& key, float& f)
00425 {
00426 return getImpl(key, f, false);
00427 }
00428
00429 bool get(const std::string& key, int& i)
00430 {
00431 return getImpl(key, i, false);
00432 }
00433
00434 bool get(const std::string& key, bool& b)
00435 {
00436 return getImpl(key, b, false);
00437 }
00438
00439 bool get(const std::string& key, XmlRpc::XmlRpcValue& v)
00440 {
00441 return getImpl(key, v, false);
00442 }
00443
00444 bool getCached(const std::string& key, std::string& s)
00445 {
00446 return getImpl(key, s, true);
00447 }
00448
00449 bool getCached(const std::string& key, double& d)
00450 {
00451 return getImpl(key, d, true);
00452 }
00453
00454 bool getCached(const std::string& key, float& f)
00455 {
00456 return getImpl(key, f, true);
00457 }
00458
00459 bool getCached(const std::string& key, int& i)
00460 {
00461 return getImpl(key, i, true);
00462 }
00463
00464 bool getCached(const std::string& key, bool& b)
00465 {
00466 return getImpl(key, b, true);
00467 }
00468
00469 bool getCached(const std::string& key, XmlRpc::XmlRpcValue& v)
00470 {
00471 return getImpl(key, v, true);
00472 }
00473
00474 template <class T> T xml_cast(XmlRpc::XmlRpcValue xml_value)
00475 {
00476 return static_cast<T>(xml_value);
00477 }
00478
00479 template <class T> bool xml_castable(int XmlType)
00480 {
00481 return false;
00482 }
00483
00484 template<> bool xml_castable<std::string>(int XmlType)
00485 {
00486 return XmlType == XmlRpc::XmlRpcValue::TypeString;
00487 }
00488
00489 template<> bool xml_castable<double>(int XmlType)
00490 {
00491 return (
00492 XmlType == XmlRpc::XmlRpcValue::TypeDouble ||
00493 XmlType == XmlRpc::XmlRpcValue::TypeInt ||
00494 XmlType == XmlRpc::XmlRpcValue::TypeBoolean );
00495 }
00496
00497 template<> bool xml_castable<float>(int XmlType)
00498 {
00499 return (
00500 XmlType == XmlRpc::XmlRpcValue::TypeDouble ||
00501 XmlType == XmlRpc::XmlRpcValue::TypeInt ||
00502 XmlType == XmlRpc::XmlRpcValue::TypeBoolean );
00503 }
00504
00505 template<> bool xml_castable<int>(int XmlType)
00506 {
00507 return (
00508 XmlType == XmlRpc::XmlRpcValue::TypeDouble ||
00509 XmlType == XmlRpc::XmlRpcValue::TypeInt ||
00510 XmlType == XmlRpc::XmlRpcValue::TypeBoolean );
00511 }
00512
00513 template<> bool xml_castable<bool>(int XmlType)
00514 {
00515 return (
00516 XmlType == XmlRpc::XmlRpcValue::TypeDouble ||
00517 XmlType == XmlRpc::XmlRpcValue::TypeInt ||
00518 XmlType == XmlRpc::XmlRpcValue::TypeBoolean );
00519 }
00520
00521 template<> double xml_cast(XmlRpc::XmlRpcValue xml_value)
00522 {
00523 using namespace XmlRpc;
00524 switch(xml_value.getType()) {
00525 case XmlRpcValue::TypeDouble:
00526 return static_cast<double>(xml_value);
00527 case XmlRpcValue::TypeInt:
00528 return static_cast<double>(static_cast<int>(xml_value));
00529 case XmlRpcValue::TypeBoolean:
00530 return static_cast<double>(static_cast<bool>(xml_value));
00531 default:
00532 return 0.0;
00533 };
00534 }
00535
00536 template<> float xml_cast(XmlRpc::XmlRpcValue xml_value)
00537 {
00538 using namespace XmlRpc;
00539 switch(xml_value.getType()) {
00540 case XmlRpcValue::TypeDouble:
00541 return static_cast<float>(static_cast<double>(xml_value));
00542 case XmlRpcValue::TypeInt:
00543 return static_cast<float>(static_cast<int>(xml_value));
00544 case XmlRpcValue::TypeBoolean:
00545 return static_cast<float>(static_cast<bool>(xml_value));
00546 default:
00547 return 0.0f;
00548 };
00549 }
00550
00551 template<> int xml_cast(XmlRpc::XmlRpcValue xml_value)
00552 {
00553 using namespace XmlRpc;
00554 switch(xml_value.getType()) {
00555 case XmlRpcValue::TypeDouble:
00556 return static_cast<int>(static_cast<double>(xml_value));
00557 case XmlRpcValue::TypeInt:
00558 return static_cast<int>(xml_value);
00559 case XmlRpcValue::TypeBoolean:
00560 return static_cast<int>(static_cast<bool>(xml_value));
00561 default:
00562 return 0;
00563 };
00564 }
00565
00566 template<> bool xml_cast(XmlRpc::XmlRpcValue xml_value)
00567 {
00568 using namespace XmlRpc;
00569 switch(xml_value.getType()) {
00570 case XmlRpcValue::TypeDouble:
00571 return static_cast<bool>(static_cast<double>(xml_value));
00572 case XmlRpcValue::TypeInt:
00573 return static_cast<bool>(static_cast<int>(xml_value));
00574 case XmlRpcValue::TypeBoolean:
00575 return static_cast<bool>(xml_value);
00576 default:
00577 return false;
00578 };
00579 }
00580
00581 template <class T>
00582 bool getImpl(const std::string& key, std::vector<T>& vec, bool cached)
00583 {
00584 XmlRpc::XmlRpcValue xml_array;
00585 if(!getImpl(key, xml_array, cached)) {
00586 return false;
00587 }
00588
00589
00590 if(xml_array.getType() != XmlRpc::XmlRpcValue::TypeArray) {
00591 return false;
00592 }
00593
00594
00595 vec.resize(xml_array.size());
00596
00597
00598 for (int i = 0; i < xml_array.size(); i++) {
00599 if(!xml_castable<T>(xml_array[i].getType())) {
00600 return false;
00601 }
00602
00603 vec[i] = xml_cast<T>(xml_array[i]);
00604 }
00605
00606 return true;
00607 }
00608
00609 bool get(const std::string& key, std::vector<std::string>& vec)
00610 {
00611 return getImpl(key, vec, false);
00612 }
00613 bool get(const std::string& key, std::vector<double>& vec)
00614 {
00615 return getImpl(key, vec, false);
00616 }
00617 bool get(const std::string& key, std::vector<float>& vec)
00618 {
00619 return getImpl(key, vec, false);
00620 }
00621 bool get(const std::string& key, std::vector<int>& vec)
00622 {
00623 return getImpl(key, vec, false);
00624 }
00625 bool get(const std::string& key, std::vector<bool>& vec)
00626 {
00627 return getImpl(key, vec, false);
00628 }
00629
00630 bool getCached(const std::string& key, std::vector<std::string>& vec)
00631 {
00632 return getImpl(key, vec, true);
00633 }
00634 bool getCached(const std::string& key, std::vector<double>& vec)
00635 {
00636 return getImpl(key, vec, true);
00637 }
00638 bool getCached(const std::string& key, std::vector<float>& vec)
00639 {
00640 return getImpl(key, vec, true);
00641 }
00642 bool getCached(const std::string& key, std::vector<int>& vec)
00643 {
00644 return getImpl(key, vec, true);
00645 }
00646 bool getCached(const std::string& key, std::vector<bool>& vec)
00647 {
00648 return getImpl(key, vec, true);
00649 }
00650
00651 template <class T>
00652 bool getImpl(const std::string& key, std::map<std::string, T>& map, bool cached)
00653 {
00654 XmlRpc::XmlRpcValue xml_value;
00655 if(!getImpl(key, xml_value, cached)) {
00656 return false;
00657 }
00658
00659
00660 if(xml_value.getType() != XmlRpc::XmlRpcValue::TypeStruct) {
00661 return false;
00662 }
00663
00664
00665 for (XmlRpc::XmlRpcValue::ValueStruct::const_iterator it = xml_value.begin();
00666 it != xml_value.end();
00667 ++it)
00668 {
00669
00670 if(!xml_castable<T>(it->second.getType())) {
00671 return false;
00672 }
00673
00674 map[it->first] = xml_cast<T>(it->second);
00675 }
00676
00677 return true;
00678 }
00679
00680 bool get(const std::string& key, std::map<std::string, std::string>& map)
00681 {
00682 return getImpl(key, map, false);
00683 }
00684 bool get(const std::string& key, std::map<std::string, double>& map)
00685 {
00686 return getImpl(key, map, false);
00687 }
00688 bool get(const std::string& key, std::map<std::string, float>& map)
00689 {
00690 return getImpl(key, map, false);
00691 }
00692 bool get(const std::string& key, std::map<std::string, int>& map)
00693 {
00694 return getImpl(key, map, false);
00695 }
00696 bool get(const std::string& key, std::map<std::string, bool>& map)
00697 {
00698 return getImpl(key, map, false);
00699 }
00700
00701 bool getCached(const std::string& key, std::map<std::string, std::string>& map)
00702 {
00703 return getImpl(key, map, true);
00704 }
00705 bool getCached(const std::string& key, std::map<std::string, double>& map)
00706 {
00707 return getImpl(key, map, true);
00708 }
00709 bool getCached(const std::string& key, std::map<std::string, float>& map)
00710 {
00711 return getImpl(key, map, true);
00712 }
00713 bool getCached(const std::string& key, std::map<std::string, int>& map)
00714 {
00715 return getImpl(key, map, true);
00716 }
00717 bool getCached(const std::string& key, std::map<std::string, bool>& map)
00718 {
00719 return getImpl(key, map, true);
00720 }
00721
00722
00723 bool search(const std::string& key, std::string& result_out)
00724 {
00725 return search(this_node::getName(), key, result_out);
00726 }
00727
00728 bool search(const std::string& ns, const std::string& key, std::string& result_out)
00729 {
00730 XmlRpc::XmlRpcValue params, result, payload;
00731 params[0] = ns;
00732
00733
00734
00735
00736 std::string remapped = key;
00737 M_string::const_iterator it = names::getUnresolvedRemappings().find(key);
00738 if (it != names::getUnresolvedRemappings().end())
00739 {
00740 remapped = it->second;
00741 }
00742
00743 params[1] = remapped;
00744
00745
00746
00747 if (!master::execute("searchParam", params, result, payload, false))
00748 {
00749 return false;
00750 }
00751
00752 result_out = (std::string)payload;
00753
00754 return true;
00755 }
00756
00757 void update(const std::string& key, const XmlRpc::XmlRpcValue& v)
00758 {
00759 std::string clean_key = names::clean(key);
00760 ROS_DEBUG_NAMED("cached_parameters", "Received parameter update for key [%s]", clean_key.c_str());
00761
00762 boost::mutex::scoped_lock lock(g_params_mutex);
00763
00764 if (g_subscribed_params.find(clean_key) != g_subscribed_params.end())
00765 {
00766 g_params[clean_key] = v;
00767 }
00768 invalidateParentParams(clean_key);
00769 }
00770
00771 void paramUpdateCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result)
00772 {
00773 result[0] = 1;
00774 result[1] = std::string("");
00775 result[2] = 0;
00776
00777 ros::param::update((std::string)params[1], params[2]);
00778 }
00779
00780 void init(const M_string& remappings)
00781 {
00782 M_string::const_iterator it = remappings.begin();
00783 M_string::const_iterator end = remappings.end();
00784 for (; it != end; ++it)
00785 {
00786 const std::string& name = it->first;
00787 const std::string& param = it->second;
00788
00789 if (name.size() < 2)
00790 {
00791 continue;
00792 }
00793
00794 if (name[0] == '_' && name[1] != '_')
00795 {
00796 std::string local_name = "~" + name.substr(1);
00797
00798 bool success = false;
00799
00800 try
00801 {
00802 int32_t i = boost::lexical_cast<int32_t>(param);
00803 ros::param::set(names::resolve(local_name), i);
00804 success = true;
00805 }
00806 catch (boost::bad_lexical_cast&)
00807 {
00808
00809 }
00810
00811 if (success)
00812 {
00813 continue;
00814 }
00815
00816 try
00817 {
00818 double d = boost::lexical_cast<double>(param);
00819 ros::param::set(names::resolve(local_name), d);
00820 success = true;
00821 }
00822 catch (boost::bad_lexical_cast&)
00823 {
00824
00825 }
00826
00827 if (success)
00828 {
00829 continue;
00830 }
00831
00832 if (param == "true" || param == "True" || param == "TRUE")
00833 {
00834 ros::param::set(names::resolve(local_name), true);
00835 }
00836 else if (param == "false" || param == "False" || param == "FALSE")
00837 {
00838 ros::param::set(names::resolve(local_name), false);
00839 }
00840 else
00841 {
00842 ros::param::set(names::resolve(local_name), param);
00843 }
00844 }
00845 }
00846
00847 XMLRPCManager::instance()->bind("paramUpdate", paramUpdateCallback);
00848 }
00849
00850 }
00851
00852 }