param.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2009, Willow Garage, Inc.
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #include "ros/param.h"
29 #include "ros/master.h"
30 #include "ros/xmlrpc_manager.h"
31 #include "ros/this_node.h"
32 #include "ros/names.h"
33 
34 #include <ros/console.h>
35 
36 #include <boost/thread/mutex.hpp>
37 #include <boost/lexical_cast.hpp>
38 
39 #include <vector>
40 #include <map>
41 
42 namespace ros
43 {
44 
45 namespace param
46 {
47 
48 typedef std::map<std::string, XmlRpc::XmlRpcValue> M_Param;
49 M_Param g_params;
50 boost::mutex g_params_mutex;
52 
53 void invalidateParentParams(const std::string& key)
54 {
55  std::string ns_key = names::parentNamespace(key);
56  while (ns_key != "" && ns_key != "/")
57  {
58  if (g_subscribed_params.find(ns_key) != g_subscribed_params.end())
59  {
60  // by erasing the key the parameter will be re-queried
61  g_params.erase(ns_key);
62  }
63  ns_key = names::parentNamespace(ns_key);
64  }
65 }
66 
67 void set(const std::string& key, const XmlRpc::XmlRpcValue& v)
68 {
69  std::string mapped_key = ros::names::resolve(key);
70 
71  XmlRpc::XmlRpcValue params, result, payload;
72  params[0] = this_node::getName();
73  params[1] = mapped_key;
74  params[2] = v;
75 
76  {
77  // Lock around the execute to the master in case we get a parameter update on this value between
78  // executing on the master and setting the parameter in the g_params list.
79  boost::mutex::scoped_lock lock(g_params_mutex);
80 
81  if (master::execute("setParam", params, result, payload, true))
82  {
83  // Update our cached params list now so that if get() is called immediately after param::set()
84  // we already have the cached state and our value will be correct
85  if (g_subscribed_params.find(mapped_key) != g_subscribed_params.end())
86  {
87  g_params[mapped_key] = v;
88  }
89  invalidateParentParams(mapped_key);
90  }
91  }
92 }
93 
94 void set(const std::string& key, const std::string& s)
95 {
96  // construct xmlrpc_c::value object of the std::string and
97  // call param::set(key, xmlvalue);
99  ros::param::set(key, v);
100 }
101 
102 void set(const std::string& key, const char* s)
103 {
104  // construct xmlrpc_c::value object of the std::string and
105  // call param::set(key, xmlvalue);
106  std::string sxx = std::string(s);
107  XmlRpc::XmlRpcValue v(sxx);
108  ros::param::set(key, v);
109 }
110 
111 void set(const std::string& key, double d)
112 {
114  ros::param::set(key, v);
115 }
116 
117 void set(const std::string& key, int i)
118 {
119  XmlRpc::XmlRpcValue v(i);
120  ros::param::set(key, v);
121 }
122 
123 void set(const std::string& key, bool b)
124 {
125  XmlRpc::XmlRpcValue v(b);
126  ros::param::set(key, v);
127 }
128 
129 template <class T>
130  void setImpl(const std::string& key, const std::vector<T>& vec)
131 {
132  // Note: the XmlRpcValue starts off as "invalid" and assertArray turns it
133  // into an array type with the given size
134  XmlRpc::XmlRpcValue xml_vec;
135  xml_vec.setSize(vec.size());
136 
137  // Copy the contents into the XmlRpcValue
138  for(size_t i=0; i < vec.size(); i++) {
139  xml_vec[i] = vec.at(i);
140  }
141 
142  ros::param::set(key, xml_vec);
143 }
144 
145 void set(const std::string& key, const std::vector<std::string>& vec)
146 {
147  setImpl(key, vec);
148 }
149 
150 void set(const std::string& key, const std::vector<double>& vec)
151 {
152  setImpl(key, vec);
153 }
154 
155 void set(const std::string& key, const std::vector<float>& vec)
156 {
157  setImpl(key, vec);
158 }
159 
160 void set(const std::string& key, const std::vector<int>& vec)
161 {
162  setImpl(key, vec);
163 }
164 
165 void set(const std::string& key, const std::vector<bool>& vec)
166 {
167  setImpl(key, vec);
168 }
169 
170 template <class T>
171  void setImpl(const std::string& key, const std::map<std::string, T>& map)
172 {
173  // Note: the XmlRpcValue starts off as "invalid" and assertStruct turns it
174  // into a struct type
175  XmlRpc::XmlRpcValue xml_value;
176  xml_value.begin();
177 
178  // Copy the contents into the XmlRpcValue
179  for(typename std::map<std::string, T>::const_iterator it = map.begin(); it != map.end(); ++it) {
180  xml_value[it->first] = it->second;
181  }
182 
183  ros::param::set(key, xml_value);
184 }
185 
186 void set(const std::string& key, const std::map<std::string, std::string>& map)
187 {
188  setImpl(key, map);
189 }
190 
191 void set(const std::string& key, const std::map<std::string, double>& map)
192 {
193  setImpl(key, map);
194 }
195 
196 void set(const std::string& key, const std::map<std::string, float>& map)
197 {
198  setImpl(key, map);
199 }
200 
201 void set(const std::string& key, const std::map<std::string, int>& map)
202 {
203  setImpl(key, map);
204 }
205 
206 void set(const std::string& key, const std::map<std::string, bool>& map)
207 {
208  setImpl(key, map);
209 }
210 
211 bool has(const std::string& key)
212 {
213  XmlRpc::XmlRpcValue params, result, payload;
214  params[0] = this_node::getName();
215  params[1] = ros::names::resolve(key);
216  //params[1] = key;
217  // We don't loop here, because validateXmlrpcResponse() returns false
218  // both when we can't contact the master and when the master says, "I
219  // don't have that param."
220  if (!master::execute("hasParam", params, result, payload, false))
221  {
222  return false;
223  }
224 
225  return payload;
226 }
227 
228 bool del(const std::string& key)
229 {
230  std::string mapped_key = ros::names::resolve(key);
231 
232  {
233  boost::mutex::scoped_lock lock(g_params_mutex);
234 
235  g_subscribed_params.erase(mapped_key);
236  g_params.erase(mapped_key);
237  }
238 
239  XmlRpc::XmlRpcValue params, result, payload;
240  params[0] = this_node::getName();
241  params[1] = mapped_key;
242  // We don't loop here, because validateXmlrpcResponse() returns false
243  // both when we can't contact the master and when the master says, "I
244  // don't have that param."
245  if (!master::execute("deleteParam", params, result, payload, false))
246  {
247  return false;
248  }
249 
250  return true;
251 }
252 
253 bool getImpl(const std::string& key, XmlRpc::XmlRpcValue& v, bool use_cache)
254 {
255  std::string mapped_key = ros::names::resolve(key);
256  if (mapped_key.empty()) mapped_key = "/";
257 
258  if (use_cache)
259  {
260  boost::mutex::scoped_lock lock(g_params_mutex);
261 
262  if (g_subscribed_params.find(mapped_key) != g_subscribed_params.end())
263  {
264  M_Param::iterator it = g_params.find(mapped_key);
265  if (it != g_params.end())
266  {
267  if (it->second.valid())
268  {
269  ROS_DEBUG_NAMED("cached_parameters", "Using cached parameter value for key [%s]", mapped_key.c_str());
270 
271  v = it->second;
272  return true;
273  }
274  else
275  {
276  ROS_DEBUG_NAMED("cached_parameters", "Cached parameter is invalid for key [%s]", mapped_key.c_str());
277  return false;
278  }
279  }
280  }
281  else
282  {
283  // parameter we've never seen before, register for update from the master
284  if (g_subscribed_params.insert(mapped_key).second)
285  {
286  XmlRpc::XmlRpcValue params, result, payload;
287  params[0] = this_node::getName();
288  params[1] = XMLRPCManager::instance()->getServerURI();
289  params[2] = mapped_key;
290 
291  if (!master::execute("subscribeParam", params, result, payload, false))
292  {
293  ROS_DEBUG_NAMED("cached_parameters", "Subscribe to parameter [%s]: call to the master failed", mapped_key.c_str());
294  g_subscribed_params.erase(mapped_key);
295  use_cache = false;
296  }
297  else
298  {
299  ROS_DEBUG_NAMED("cached_parameters", "Subscribed to parameter [%s]", mapped_key.c_str());
300  }
301  }
302  }
303  }
304 
305  XmlRpc::XmlRpcValue params, result;
306  params[0] = this_node::getName();
307  params[1] = mapped_key;
308 
309  // We don't loop here, because validateXmlrpcResponse() returns false
310  // both when we can't contact the master and when the master says, "I
311  // don't have that param."
312  bool ret = master::execute("getParam", params, result, v, false);
313 
314  if (use_cache)
315  {
316  boost::mutex::scoped_lock lock(g_params_mutex);
317 
318  ROS_DEBUG_NAMED("cached_parameters", "Caching parameter [%s] with value type [%d]", mapped_key.c_str(), v.getType());
319  g_params[mapped_key] = v;
320  }
321 
322  return ret;
323 }
324 
325 bool getImpl(const std::string& key, std::string& s, bool use_cache)
326 {
328  if (!getImpl(key, v, use_cache))
329  return false;
331  return false;
332  s = std::string(v);
333  return true;
334 }
335 
336 bool getImpl(const std::string& key, double& d, bool use_cache)
337 {
339  if (!getImpl(key, v, use_cache))
340  {
341  return false;
342  }
343 
345  {
346  d = (int)v;
347  }
349  {
350  return false;
351  }
352  else
353  {
354  d = v;
355  }
356 
357  return true;
358 }
359 
360 bool getImpl(const std::string& key, float& f, bool use_cache)
361 {
362  double d = static_cast<double>(f);
363  bool result = getImpl(key, d, use_cache);
364  if (result)
365  f = static_cast<float>(d);
366  return result;
367 }
368 
369 bool getImpl(const std::string& key, int& i, bool use_cache)
370 {
372  if (!getImpl(key, v, use_cache))
373  {
374  return false;
375  }
376 
378  {
379  double d = v;
380 
381  if (fmod(d, 1.0) < 0.5)
382  {
383  d = floor(d);
384  }
385  else
386  {
387  d = ceil(d);
388  }
389 
390  i = d;
391  }
392  else if (v.getType() != XmlRpc::XmlRpcValue::TypeInt)
393  {
394  return false;
395  }
396  else
397  {
398  i = v;
399  }
400 
401  return true;
402 }
403 
404 bool getImpl(const std::string& key, bool& b, bool use_cache)
405 {
407  if (!getImpl(key, v, use_cache))
408  return false;
410  return false;
411  b = v;
412  return true;
413 }
414 
415 bool get(const std::string& key, std::string& s)
416 {
417  return getImpl(key, s, false);
418 }
419 
420 bool get(const std::string& key, double& d)
421 {
422  return getImpl(key, d, false);
423 }
424 
425 bool get(const std::string& key, float& f)
426 {
427  return getImpl(key, f, false);
428 }
429 
430 bool get(const std::string& key, int& i)
431 {
432  return getImpl(key, i, false);
433 }
434 
435 bool get(const std::string& key, bool& b)
436 {
437  return getImpl(key, b, false);
438 }
439 
440 bool get(const std::string& key, XmlRpc::XmlRpcValue& v)
441 {
442  return getImpl(key, v, false);
443 }
444 
445 bool getCached(const std::string& key, std::string& s)
446 {
447  return getImpl(key, s, true);
448 }
449 
450 bool getCached(const std::string& key, double& d)
451 {
452  return getImpl(key, d, true);
453 }
454 
455 bool getCached(const std::string& key, float& f)
456 {
457  return getImpl(key, f, true);
458 }
459 
460 bool getCached(const std::string& key, int& i)
461 {
462  return getImpl(key, i, true);
463 }
464 
465 bool getCached(const std::string& key, bool& b)
466 {
467  return getImpl(key, b, true);
468 }
469 
470 bool getCached(const std::string& key, XmlRpc::XmlRpcValue& v)
471 {
472  return getImpl(key, v, true);
473 }
474 
475 template <class T> T xml_cast(XmlRpc::XmlRpcValue xml_value)
476 {
477  return static_cast<T>(xml_value);
478 }
479 
480 template <class T> bool xml_castable(int XmlType)
481 {
482  return false;
483 }
484 
485 template<> bool xml_castable<std::string>(int XmlType)
486 {
487  return XmlType == XmlRpc::XmlRpcValue::TypeString;
488 }
489 
490 template<> bool xml_castable<double>(int XmlType)
491 {
492  return (
493  XmlType == XmlRpc::XmlRpcValue::TypeDouble ||
494  XmlType == XmlRpc::XmlRpcValue::TypeInt ||
496 }
497 
498 template<> bool xml_castable<float>(int XmlType)
499 {
500  return (
501  XmlType == XmlRpc::XmlRpcValue::TypeDouble ||
502  XmlType == XmlRpc::XmlRpcValue::TypeInt ||
504 }
505 
506 template<> bool xml_castable<int>(int XmlType)
507 {
508  return (
509  XmlType == XmlRpc::XmlRpcValue::TypeDouble ||
510  XmlType == XmlRpc::XmlRpcValue::TypeInt ||
512 }
513 
514 template<> bool xml_castable<bool>(int XmlType)
515 {
516  return (
517  XmlType == XmlRpc::XmlRpcValue::TypeDouble ||
518  XmlType == XmlRpc::XmlRpcValue::TypeInt ||
520 }
521 
522 template<> double xml_cast(XmlRpc::XmlRpcValue xml_value)
523 {
524  using namespace XmlRpc;
525  switch(xml_value.getType()) {
526  case XmlRpcValue::TypeDouble:
527  return static_cast<double>(xml_value);
528  case XmlRpcValue::TypeInt:
529  return static_cast<double>(static_cast<int>(xml_value));
530  case XmlRpcValue::TypeBoolean:
531  return static_cast<double>(static_cast<bool>(xml_value));
532  default:
533  return 0.0;
534  };
535 }
536 
537 template<> float xml_cast(XmlRpc::XmlRpcValue xml_value)
538 {
539  using namespace XmlRpc;
540  switch(xml_value.getType()) {
541  case XmlRpcValue::TypeDouble:
542  return static_cast<float>(static_cast<double>(xml_value));
543  case XmlRpcValue::TypeInt:
544  return static_cast<float>(static_cast<int>(xml_value));
545  case XmlRpcValue::TypeBoolean:
546  return static_cast<float>(static_cast<bool>(xml_value));
547  default:
548  return 0.0f;
549  };
550 }
551 
552 template<> int xml_cast(XmlRpc::XmlRpcValue xml_value)
553 {
554  using namespace XmlRpc;
555  switch(xml_value.getType()) {
556  case XmlRpcValue::TypeDouble:
557  return static_cast<int>(static_cast<double>(xml_value));
558  case XmlRpcValue::TypeInt:
559  return static_cast<int>(xml_value);
560  case XmlRpcValue::TypeBoolean:
561  return static_cast<int>(static_cast<bool>(xml_value));
562  default:
563  return 0;
564  };
565 }
566 
567 template<> bool xml_cast(XmlRpc::XmlRpcValue xml_value)
568 {
569  using namespace XmlRpc;
570  switch(xml_value.getType()) {
571  case XmlRpcValue::TypeDouble:
572  return static_cast<bool>(static_cast<double>(xml_value));
573  case XmlRpcValue::TypeInt:
574  return static_cast<bool>(static_cast<int>(xml_value));
575  case XmlRpcValue::TypeBoolean:
576  return static_cast<bool>(xml_value);
577  default:
578  return false;
579  };
580 }
581 
582 template <class T>
583  bool getImpl(const std::string& key, std::vector<T>& vec, bool cached)
584 {
585  XmlRpc::XmlRpcValue xml_array;
586  if(!getImpl(key, xml_array, cached)) {
587  return false;
588  }
589 
590  // Make sure it's an array type
591  if(xml_array.getType() != XmlRpc::XmlRpcValue::TypeArray) {
592  return false;
593  }
594 
595  // Resize the target vector (destructive)
596  vec.resize(xml_array.size());
597 
598  // Fill the vector with stuff
599  for (int i = 0; i < xml_array.size(); i++) {
600  if(!xml_castable<T>(xml_array[i].getType())) {
601  return false;
602  }
603 
604  vec[i] = xml_cast<T>(xml_array[i]);
605  }
606 
607  return true;
608 }
609 
610 bool get(const std::string& key, std::vector<std::string>& vec)
611 {
612  return getImpl(key, vec, false);
613 }
614 bool get(const std::string& key, std::vector<double>& vec)
615 {
616  return getImpl(key, vec, false);
617 }
618 bool get(const std::string& key, std::vector<float>& vec)
619 {
620  return getImpl(key, vec, false);
621 }
622 bool get(const std::string& key, std::vector<int>& vec)
623 {
624  return getImpl(key, vec, false);
625 }
626 bool get(const std::string& key, std::vector<bool>& vec)
627 {
628  return getImpl(key, vec, false);
629 }
630 
631 bool getCached(const std::string& key, std::vector<std::string>& vec)
632 {
633  return getImpl(key, vec, true);
634 }
635 bool getCached(const std::string& key, std::vector<double>& vec)
636 {
637  return getImpl(key, vec, true);
638 }
639 bool getCached(const std::string& key, std::vector<float>& vec)
640 {
641  return getImpl(key, vec, true);
642 }
643 bool getCached(const std::string& key, std::vector<int>& vec)
644 {
645  return getImpl(key, vec, true);
646 }
647 bool getCached(const std::string& key, std::vector<bool>& vec)
648 {
649  return getImpl(key, vec, true);
650 }
651 
652 template <class T>
653  bool getImpl(const std::string& key, std::map<std::string, T>& map, bool cached)
654 {
655  XmlRpc::XmlRpcValue xml_value;
656  if(!getImpl(key, xml_value, cached)) {
657  return false;
658  }
659 
660  // Make sure it's a struct type
661  if(xml_value.getType() != XmlRpc::XmlRpcValue::TypeStruct) {
662  return false;
663  }
664 
665  // Fill the map with stuff
666  for (XmlRpc::XmlRpcValue::ValueStruct::const_iterator it = xml_value.begin();
667  it != xml_value.end();
668  ++it)
669  {
670  // Make sure this element is the right type
671  if(!xml_castable<T>(it->second.getType())) {
672  return false;
673  }
674  // Store the element
675  map[it->first] = xml_cast<T>(it->second);
676  }
677 
678  return true;
679 }
680 
681 bool get(const std::string& key, std::map<std::string, std::string>& map)
682 {
683  return getImpl(key, map, false);
684 }
685 bool get(const std::string& key, std::map<std::string, double>& map)
686 {
687  return getImpl(key, map, false);
688 }
689 bool get(const std::string& key, std::map<std::string, float>& map)
690 {
691  return getImpl(key, map, false);
692 }
693 bool get(const std::string& key, std::map<std::string, int>& map)
694 {
695  return getImpl(key, map, false);
696 }
697 bool get(const std::string& key, std::map<std::string, bool>& map)
698 {
699  return getImpl(key, map, false);
700 }
701 
702 bool getCached(const std::string& key, std::map<std::string, std::string>& map)
703 {
704  return getImpl(key, map, true);
705 }
706 bool getCached(const std::string& key, std::map<std::string, double>& map)
707 {
708  return getImpl(key, map, true);
709 }
710 bool getCached(const std::string& key, std::map<std::string, float>& map)
711 {
712  return getImpl(key, map, true);
713 }
714 bool getCached(const std::string& key, std::map<std::string, int>& map)
715 {
716  return getImpl(key, map, true);
717 }
718 bool getCached(const std::string& key, std::map<std::string, bool>& map)
719 {
720  return getImpl(key, map, true);
721 }
722 
723 bool getParamNames(std::vector<std::string>& keys)
724 {
725  XmlRpc::XmlRpcValue params, result, payload;
726  params[0] = this_node::getName();
727  if (!master::execute("getParamNames", params, result, payload, false)) {
728  return false;
729  }
730  // Make sure it's an array type
731  if (result.getType() != XmlRpc::XmlRpcValue::TypeArray) {
732  return false;
733  }
734  // Make sure it returned 3 elements
735  if (result.size() != 3) {
736  return false;
737  }
738  // Get the actual parameter keys
739  XmlRpc::XmlRpcValue parameters = result[2];
740  // Resize the output
741  keys.resize(parameters.size());
742 
743  // Fill the output vector with the answer
744  for (int i = 0; i < parameters.size(); ++i) {
745  if (parameters[i].getType() != XmlRpc::XmlRpcValue::TypeString) {
746  return false;
747  }
748  keys[i] = std::string(parameters[i]);
749  }
750  return true;
751 }
752 
753 bool search(const std::string& key, std::string& result_out)
754 {
755  return search(this_node::getName(), key, result_out);
756 }
757 
758 bool search(const std::string& ns, const std::string& key, std::string& result_out)
759 {
760  XmlRpc::XmlRpcValue params, result, payload;
761  params[0] = ns;
762 
763  // searchParam needs a separate form of remapping -- remapping on the unresolved name, rather than the
764  // resolved one.
765 
766  std::string remapped = key;
767  M_string::const_iterator it = names::getUnresolvedRemappings().find(key);
768  if (it != names::getUnresolvedRemappings().end())
769  {
770  remapped = it->second;
771  }
772 
773  params[1] = remapped;
774  // We don't loop here, because validateXmlrpcResponse() returns false
775  // both when we can't contact the master and when the master says, "I
776  // don't have that param."
777  if (!master::execute("searchParam", params, result, payload, false))
778  {
779  return false;
780  }
781 
782  result_out = (std::string)payload;
783 
784  return true;
785 }
786 
787 void update(const std::string& key, const XmlRpc::XmlRpcValue& v)
788 {
789  std::string clean_key = names::clean(key);
790  ROS_DEBUG_NAMED("cached_parameters", "Received parameter update for key [%s]", clean_key.c_str());
791 
792  boost::mutex::scoped_lock lock(g_params_mutex);
793 
794  if (g_subscribed_params.find(clean_key) != g_subscribed_params.end())
795  {
796  g_params[clean_key] = v;
797  }
798  invalidateParentParams(clean_key);
799 }
800 
802 {
803  result[0] = 1;
804  result[1] = std::string("");
805  result[2] = 0;
806 
807  ros::param::update((std::string)params[1], params[2]);
808 }
809 
810 void init(const M_string& remappings)
811 {
812  M_string::const_iterator it = remappings.begin();
813  M_string::const_iterator end = remappings.end();
814  for (; it != end; ++it)
815  {
816  const std::string& name = it->first;
817  const std::string& param = it->second;
818 
819  if (name.size() < 2)
820  {
821  continue;
822  }
823 
824  if (name[0] == '_' && name[1] != '_')
825  {
826  std::string local_name = "~" + name.substr(1);
827 
828  bool success = false;
829 
830  try
831  {
832  int32_t i = boost::lexical_cast<int32_t>(param);
833  ros::param::set(names::resolve(local_name), i);
834  success = true;
835  }
836  catch (boost::bad_lexical_cast&)
837  {
838 
839  }
840 
841  if (success)
842  {
843  continue;
844  }
845 
846  try
847  {
848  double d = boost::lexical_cast<double>(param);
849  ros::param::set(names::resolve(local_name), d);
850  success = true;
851  }
852  catch (boost::bad_lexical_cast&)
853  {
854 
855  }
856 
857  if (success)
858  {
859  continue;
860  }
861 
862  if (param == "true" || param == "True" || param == "TRUE")
863  {
864  ros::param::set(names::resolve(local_name), true);
865  }
866  else if (param == "false" || param == "False" || param == "FALSE")
867  {
868  ros::param::set(names::resolve(local_name), false);
869  }
870  else
871  {
872  ros::param::set(names::resolve(local_name), param);
873  }
874  }
875  }
876 
877  XMLRPCManager::instance()->bind("paramUpdate", paramUpdateCallback);
878 }
879 
880 } // namespace param
881 
882 } // namespace ros
d
ROSCPP_DECL bool getParamNames(std::vector< std::string > &keys)
Get the list of all the parameters in the server.
Definition: param.cpp:723
std::map< std::string, XmlRpc::XmlRpcValue > M_Param
Definition: param.cpp:48
bool xml_castable(int XmlType)
Definition: param.cpp:480
bool param(const std::string &param_name, T &param_val, const T &default_val)
Assign value from parameter server, with default.
Definition: param.h:608
std::set< std::string > S_string
boost::mutex g_params_mutex
Definition: param.cpp:50
bool xml_castable< int >(int XmlType)
Definition: param.cpp:506
f
ROSCPP_DECL std::string parentNamespace(const std::string &name)
Get the parent namespace of a name.
Definition: names.cpp:206
int size() const
S_string g_subscribed_params
Definition: param.cpp:51
T xml_cast(XmlRpc::XmlRpcValue xml_value)
Definition: param.cpp:475
XmlRpcServer s
ROSCPP_DECL const std::string & getName()
Returns the name of the current node.
Definition: this_node.cpp:81
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
Resolve a graph resource name into a fully qualified graph resource name.
Definition: names.cpp:136
ROSCPP_DECL std::string clean(const std::string &name)
Cleans a graph resource name: removes double slashes, trailing slash.
Definition: names.cpp:99
Type const & getType() const
void setImpl(const std::string &key, const std::vector< T > &vec)
Definition: param.cpp:130
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
Definition: param.cpp:787
std::map< std::string, std::string > M_string
#define ROS_DEBUG_NAMED(name,...)
bool getImpl(const std::string &key, XmlRpc::XmlRpcValue &v, bool use_cache)
Definition: param.cpp:253
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
Set an arbitrary XML/RPC value on the parameter server.
Definition: param.cpp:67
void init(const M_string &remappings)
Definition: param.cpp:810
void invalidateParentParams(const std::string &key)
Definition: param.cpp:53
M_Param g_params
Definition: param.cpp:49
void setSize(int size)
ROSCPP_DECL bool execute(const std::string &method, const XmlRpc::XmlRpcValue &request, XmlRpc::XmlRpcValue &response, XmlRpc::XmlRpcValue &payload, bool wait_for_master)
Execute an XMLRPC call on the master.
Definition: master.cpp:179
ROSCPP_DECL const M_string & getUnresolvedRemappings()
Definition: names.cpp:51
ROSCPP_DECL bool has(const std::string &key)
Check whether a parameter exists on the parameter server.
Definition: param.cpp:211
ROSCPP_DECL bool getCached(const std::string &key, std::string &s)
Get a string value from the parameter server, with local caching.
Definition: param.cpp:445
ROSCPP_DECL bool del(const std::string &key)
Delete a parameter from the parameter server.
Definition: param.cpp:228
bool xml_castable< double >(int XmlType)
Definition: param.cpp:490
static const XMLRPCManagerPtr & instance()
bool xml_castable< float >(int XmlType)
Definition: param.cpp:498
ROSCPP_DECL bool search(const std::string &ns, const std::string &key, std::string &result)
Search up the tree for a parameter with a given key.
Definition: param.cpp:758
void paramUpdateCallback(XmlRpc::XmlRpcValue &params, XmlRpc::XmlRpcValue &result)
Definition: param.cpp:801
bool xml_castable< bool >(int XmlType)
Definition: param.cpp:514


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Sun Feb 3 2019 03:29:54