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/recursive_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;
50 boost::recursive_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::recursive_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::recursive_mutex::scoped_lock lock(g_params_mutex);
234 
235  if (g_subscribed_params.find(mapped_key) != g_subscribed_params.end())
236  {
237  g_subscribed_params.erase(mapped_key);
238  unsubscribeCachedParam(mapped_key);
239  }
240  g_params.erase(mapped_key);
241  }
242 
243  XmlRpc::XmlRpcValue params, result, payload;
244  params[0] = this_node::getName();
245  params[1] = mapped_key;
246  // We don't loop here, because validateXmlrpcResponse() returns false
247  // both when we can't contact the master and when the master says, "I
248  // don't have that param."
249  if (!master::execute("deleteParam", params, result, payload, false))
250  {
251  return false;
252  }
253 
254  return true;
255 }
256 
257 bool getImpl(const std::string& key, XmlRpc::XmlRpcValue& v, bool use_cache)
258 {
259  std::string mapped_key = ros::names::resolve(key);
260  if (mapped_key.empty()) mapped_key = "/";
261 
262  if (use_cache)
263  {
264  boost::recursive_mutex::scoped_lock lock(g_params_mutex);
265 
266  if (g_subscribed_params.find(mapped_key) != g_subscribed_params.end())
267  {
268  M_Param::iterator it = g_params.find(mapped_key);
269  if (it != g_params.end())
270  {
271  if (it->second.valid())
272  {
273  v = it->second;
274  return true;
275  }
276  else
277  {
278  return false;
279  }
280  }
281  }
282  else
283  {
284  // parameter we've never seen before, register for update from the master
285  if (g_subscribed_params.insert(mapped_key).second)
286  {
287  XmlRpc::XmlRpcValue params, result, payload;
288  params[0] = this_node::getName();
289  params[1] = XMLRPCManager::instance()->getServerURI();
290  params[2] = mapped_key;
291 
292  if (!master::execute("subscribeParam", params, result, payload, false))
293  {
294  g_subscribed_params.erase(mapped_key);
295  use_cache = false;
296  }
297  }
298  }
299  }
300 
301  XmlRpc::XmlRpcValue params, result;
302  params[0] = this_node::getName();
303  params[1] = mapped_key;
304 
305  // We don't loop here, because validateXmlrpcResponse() returns false
306  // both when we can't contact the master and when the master says, "I
307  // don't have that param."
308  bool ret = master::execute("getParam", params, result, v, false);
309 
310  if (use_cache)
311  {
312  boost::recursive_mutex::scoped_lock lock(g_params_mutex);
313  g_params[mapped_key] = v;
314  }
315 
316  return ret;
317 }
318 
319 bool getImpl(const std::string& key, std::string& s, bool use_cache)
320 {
322  if (!getImpl(key, v, use_cache))
323  return false;
325  return false;
326  s = std::string(v);
327  return true;
328 }
329 
330 bool getImpl(const std::string& key, double& d, bool use_cache)
331 {
333  if (!getImpl(key, v, use_cache))
334  {
335  return false;
336  }
337 
339  {
340  d = (int)v;
341  }
343  {
344  return false;
345  }
346  else
347  {
348  d = v;
349  }
350 
351  return true;
352 }
353 
354 bool getImpl(const std::string& key, float& f, bool use_cache)
355 {
356  double d = static_cast<double>(f);
357  bool result = getImpl(key, d, use_cache);
358  if (result)
359  f = static_cast<float>(d);
360  return result;
361 }
362 
363 bool getImpl(const std::string& key, int& i, bool use_cache)
364 {
366  if (!getImpl(key, v, use_cache))
367  {
368  return false;
369  }
370 
372  {
373  double d = v;
374 
375  if (fmod(d, 1.0) < 0.5)
376  {
377  d = floor(d);
378  }
379  else
380  {
381  d = ceil(d);
382  }
383 
384  i = d;
385  }
386  else if (v.getType() != XmlRpc::XmlRpcValue::TypeInt)
387  {
388  return false;
389  }
390  else
391  {
392  i = v;
393  }
394 
395  return true;
396 }
397 
398 bool getImpl(const std::string& key, bool& b, bool use_cache)
399 {
401  if (!getImpl(key, v, use_cache))
402  return false;
404  return false;
405  b = v;
406  return true;
407 }
408 
409 bool get(const std::string& key, std::string& s)
410 {
411  return getImpl(key, s, false);
412 }
413 
414 bool get(const std::string& key, double& d)
415 {
416  return getImpl(key, d, false);
417 }
418 
419 bool get(const std::string& key, float& f)
420 {
421  return getImpl(key, f, false);
422 }
423 
424 bool get(const std::string& key, int& i)
425 {
426  return getImpl(key, i, false);
427 }
428 
429 bool get(const std::string& key, bool& b)
430 {
431  return getImpl(key, b, false);
432 }
433 
434 bool get(const std::string& key, XmlRpc::XmlRpcValue& v)
435 {
436  return getImpl(key, v, false);
437 }
438 
439 bool getCached(const std::string& key, std::string& s)
440 {
441  return getImpl(key, s, true);
442 }
443 
444 bool getCached(const std::string& key, double& d)
445 {
446  return getImpl(key, d, true);
447 }
448 
449 bool getCached(const std::string& key, float& f)
450 {
451  return getImpl(key, f, true);
452 }
453 
454 bool getCached(const std::string& key, int& i)
455 {
456  return getImpl(key, i, true);
457 }
458 
459 bool getCached(const std::string& key, bool& b)
460 {
461  return getImpl(key, b, true);
462 }
463 
464 bool getCached(const std::string& key, XmlRpc::XmlRpcValue& v)
465 {
466  return getImpl(key, v, true);
467 }
468 
469 template <class T> T xml_cast(XmlRpc::XmlRpcValue xml_value)
470 {
471  return static_cast<T>(xml_value);
472 }
473 
474 template <class T> bool xml_castable(int XmlType)
475 {
476  return false;
477 }
478 
479 template<> bool xml_castable<std::string>(int XmlType)
480 {
481  return XmlType == XmlRpc::XmlRpcValue::TypeString;
482 }
483 
484 template<> bool xml_castable<double>(int XmlType)
485 {
486  return (
487  XmlType == XmlRpc::XmlRpcValue::TypeDouble ||
488  XmlType == XmlRpc::XmlRpcValue::TypeInt ||
490 }
491 
492 template<> bool xml_castable<float>(int XmlType)
493 {
494  return (
495  XmlType == XmlRpc::XmlRpcValue::TypeDouble ||
496  XmlType == XmlRpc::XmlRpcValue::TypeInt ||
498 }
499 
500 template<> bool xml_castable<int>(int XmlType)
501 {
502  return (
503  XmlType == XmlRpc::XmlRpcValue::TypeDouble ||
504  XmlType == XmlRpc::XmlRpcValue::TypeInt ||
506 }
507 
508 template<> bool xml_castable<bool>(int XmlType)
509 {
510  return (
511  XmlType == XmlRpc::XmlRpcValue::TypeDouble ||
512  XmlType == XmlRpc::XmlRpcValue::TypeInt ||
514 }
515 
516 template<> double xml_cast(XmlRpc::XmlRpcValue xml_value)
517 {
518  using namespace XmlRpc;
519  switch(xml_value.getType()) {
520  case XmlRpcValue::TypeDouble:
521  return static_cast<double>(xml_value);
522  case XmlRpcValue::TypeInt:
523  return static_cast<double>(static_cast<int>(xml_value));
524  case XmlRpcValue::TypeBoolean:
525  return static_cast<double>(static_cast<bool>(xml_value));
526  default:
527  return 0.0;
528  };
529 }
530 
531 template<> float xml_cast(XmlRpc::XmlRpcValue xml_value)
532 {
533  using namespace XmlRpc;
534  switch(xml_value.getType()) {
535  case XmlRpcValue::TypeDouble:
536  return static_cast<float>(static_cast<double>(xml_value));
537  case XmlRpcValue::TypeInt:
538  return static_cast<float>(static_cast<int>(xml_value));
539  case XmlRpcValue::TypeBoolean:
540  return static_cast<float>(static_cast<bool>(xml_value));
541  default:
542  return 0.0f;
543  };
544 }
545 
546 template<> int xml_cast(XmlRpc::XmlRpcValue xml_value)
547 {
548  using namespace XmlRpc;
549  switch(xml_value.getType()) {
550  case XmlRpcValue::TypeDouble:
551  return static_cast<int>(static_cast<double>(xml_value));
552  case XmlRpcValue::TypeInt:
553  return static_cast<int>(xml_value);
554  case XmlRpcValue::TypeBoolean:
555  return static_cast<int>(static_cast<bool>(xml_value));
556  default:
557  return 0;
558  };
559 }
560 
561 template<> bool xml_cast(XmlRpc::XmlRpcValue xml_value)
562 {
563  using namespace XmlRpc;
564  switch(xml_value.getType()) {
565  case XmlRpcValue::TypeDouble:
566  return static_cast<bool>(static_cast<double>(xml_value));
567  case XmlRpcValue::TypeInt:
568  return static_cast<bool>(static_cast<int>(xml_value));
569  case XmlRpcValue::TypeBoolean:
570  return static_cast<bool>(xml_value);
571  default:
572  return false;
573  };
574 }
575 
576 template <class T>
577  bool getImpl(const std::string& key, std::vector<T>& vec, bool cached)
578 {
579  XmlRpc::XmlRpcValue xml_array;
580  if(!getImpl(key, xml_array, cached)) {
581  return false;
582  }
583 
584  // Make sure it's an array type
585  if(xml_array.getType() != XmlRpc::XmlRpcValue::TypeArray) {
586  return false;
587  }
588 
589  // Resize the target vector (destructive)
590  vec.resize(xml_array.size());
591 
592  // Fill the vector with stuff
593  for (int i = 0; i < xml_array.size(); i++) {
594  if(!xml_castable<T>(xml_array[i].getType())) {
595  return false;
596  }
597 
598  vec[i] = xml_cast<T>(xml_array[i]);
599  }
600 
601  return true;
602 }
603 
604 bool get(const std::string& key, std::vector<std::string>& vec)
605 {
606  return getImpl(key, vec, false);
607 }
608 bool get(const std::string& key, std::vector<double>& vec)
609 {
610  return getImpl(key, vec, false);
611 }
612 bool get(const std::string& key, std::vector<float>& vec)
613 {
614  return getImpl(key, vec, false);
615 }
616 bool get(const std::string& key, std::vector<int>& vec)
617 {
618  return getImpl(key, vec, false);
619 }
620 bool get(const std::string& key, std::vector<bool>& vec)
621 {
622  return getImpl(key, vec, false);
623 }
624 
625 bool getCached(const std::string& key, std::vector<std::string>& vec)
626 {
627  return getImpl(key, vec, true);
628 }
629 bool getCached(const std::string& key, std::vector<double>& vec)
630 {
631  return getImpl(key, vec, true);
632 }
633 bool getCached(const std::string& key, std::vector<float>& vec)
634 {
635  return getImpl(key, vec, true);
636 }
637 bool getCached(const std::string& key, std::vector<int>& vec)
638 {
639  return getImpl(key, vec, true);
640 }
641 bool getCached(const std::string& key, std::vector<bool>& vec)
642 {
643  return getImpl(key, vec, true);
644 }
645 
646 template <class T>
647  bool getImpl(const std::string& key, std::map<std::string, T>& map, bool cached)
648 {
649  XmlRpc::XmlRpcValue xml_value;
650  if(!getImpl(key, xml_value, cached)) {
651  return false;
652  }
653 
654  // Make sure it's a struct type
655  if(xml_value.getType() != XmlRpc::XmlRpcValue::TypeStruct) {
656  return false;
657  }
658 
659  // Fill the map with stuff
660  for (XmlRpc::XmlRpcValue::ValueStruct::const_iterator it = xml_value.begin();
661  it != xml_value.end();
662  ++it)
663  {
664  // Make sure this element is the right type
665  if(!xml_castable<T>(it->second.getType())) {
666  return false;
667  }
668  // Store the element
669  map[it->first] = xml_cast<T>(it->second);
670  }
671 
672  return true;
673 }
674 
675 bool get(const std::string& key, std::map<std::string, std::string>& map)
676 {
677  return getImpl(key, map, false);
678 }
679 bool get(const std::string& key, std::map<std::string, double>& map)
680 {
681  return getImpl(key, map, false);
682 }
683 bool get(const std::string& key, std::map<std::string, float>& map)
684 {
685  return getImpl(key, map, false);
686 }
687 bool get(const std::string& key, std::map<std::string, int>& map)
688 {
689  return getImpl(key, map, false);
690 }
691 bool get(const std::string& key, std::map<std::string, bool>& map)
692 {
693  return getImpl(key, map, false);
694 }
695 
696 bool getCached(const std::string& key, std::map<std::string, std::string>& map)
697 {
698  return getImpl(key, map, true);
699 }
700 bool getCached(const std::string& key, std::map<std::string, double>& map)
701 {
702  return getImpl(key, map, true);
703 }
704 bool getCached(const std::string& key, std::map<std::string, float>& map)
705 {
706  return getImpl(key, map, true);
707 }
708 bool getCached(const std::string& key, std::map<std::string, int>& map)
709 {
710  return getImpl(key, map, true);
711 }
712 bool getCached(const std::string& key, std::map<std::string, bool>& map)
713 {
714  return getImpl(key, map, true);
715 }
716 
717 bool getParamNames(std::vector<std::string>& keys)
718 {
719  XmlRpc::XmlRpcValue params, result, payload;
720  params[0] = this_node::getName();
721  if (!master::execute("getParamNames", params, result, payload, false)) {
722  return false;
723  }
724  // Make sure it's an array type
725  if (result.getType() != XmlRpc::XmlRpcValue::TypeArray) {
726  return false;
727  }
728  // Make sure it returned 3 elements
729  if (result.size() != 3) {
730  return false;
731  }
732  // Get the actual parameter keys
733  XmlRpc::XmlRpcValue parameters = result[2];
734  // Resize the output
735  keys.resize(parameters.size());
736 
737  // Fill the output vector with the answer
738  for (int i = 0; i < parameters.size(); ++i) {
739  if (parameters[i].getType() != XmlRpc::XmlRpcValue::TypeString) {
740  return false;
741  }
742  keys[i] = std::string(parameters[i]);
743  }
744  return true;
745 }
746 
747 bool search(const std::string& key, std::string& result_out)
748 {
749  return search(this_node::getName(), key, result_out);
750 }
751 
752 bool search(const std::string& ns, const std::string& key, std::string& result_out)
753 {
754  XmlRpc::XmlRpcValue params, result, payload;
755  params[0] = ns;
756 
757  // searchParam needs a separate form of remapping -- remapping on the unresolved name, rather than the
758  // resolved one.
759 
760  std::string remapped = key;
761  M_string::const_iterator it = names::getUnresolvedRemappings().find(key);
762  if (it != names::getUnresolvedRemappings().end())
763  {
764  remapped = it->second;
765  }
766 
767  params[1] = remapped;
768  // We don't loop here, because validateXmlrpcResponse() returns false
769  // both when we can't contact the master and when the master says, "I
770  // don't have that param."
771  if (!master::execute("searchParam", params, result, payload, false))
772  {
773  return false;
774  }
775 
776  result_out = (std::string)payload;
777 
778  return true;
779 }
780 
781 void update(const std::string& key, const XmlRpc::XmlRpcValue& v)
782 {
783  std::string clean_key = names::clean(key);
784  ROS_DEBUG_NAMED("cached_parameters", "Received parameter update for key [%s]", clean_key.c_str());
785 
786  boost::recursive_mutex::scoped_lock lock(g_params_mutex);
787 
788  if (g_subscribed_params.find(clean_key) != g_subscribed_params.end())
789  {
790  g_params[clean_key] = v;
791  }
792  invalidateParentParams(clean_key);
793 }
794 
796 {
797  result[0] = 1;
798  result[1] = std::string("");
799  result[2] = 0;
800 
801  ros::param::update((std::string)params[1], params[2]);
802 }
803 
804 void unsubscribeCachedParam(const std::string& key)
805 {
806  XmlRpc::XmlRpcValue params, result, payload;
807  params[0] = this_node::getName();
808  params[1] = XMLRPCManager::instance()->getServerURI();
809  params[2] = key;
810  master::execute("unsubscribeParam", params, result, payload, false);
811 }
812 
814 {
815  // lock required, all of the cached parameter will be unsubscribed.
816  boost::recursive_mutex::scoped_lock lock(g_params_mutex);
817 
818  for(S_string::iterator itr = g_subscribed_params.begin();
819  itr != g_subscribed_params.end(); ++itr)
820  {
821  const std::string mapped_key(*itr);
822  unsubscribeCachedParam(mapped_key);
823  }
824 }
825 
826 void init(const M_string& remappings)
827 {
828  M_string::const_iterator it = remappings.begin();
829  M_string::const_iterator end = remappings.end();
830  for (; it != end; ++it)
831  {
832  const std::string& name = it->first;
833  const std::string& param = it->second;
834 
835  if (name.size() < 2)
836  {
837  continue;
838  }
839 
840  if (name[0] == '_' && name[1] != '_')
841  {
842  std::string local_name = "~" + name.substr(1);
843 
844  bool success = false;
845 
846  try
847  {
848  int32_t i = boost::lexical_cast<int32_t>(param);
849  ros::param::set(names::resolve(local_name), i);
850  success = true;
851  }
852  catch (boost::bad_lexical_cast&)
853  {
854 
855  }
856 
857  if (success)
858  {
859  continue;
860  }
861 
862  try
863  {
864  double d = boost::lexical_cast<double>(param);
865  ros::param::set(names::resolve(local_name), d);
866  success = true;
867  }
868  catch (boost::bad_lexical_cast&)
869  {
870 
871  }
872 
873  if (success)
874  {
875  continue;
876  }
877 
878  if (param == "true" || param == "True" || param == "TRUE")
879  {
880  ros::param::set(names::resolve(local_name), true);
881  }
882  else if (param == "false" || param == "False" || param == "FALSE")
883  {
884  ros::param::set(names::resolve(local_name), false);
885  }
886  else
887  {
888  ros::param::set(names::resolve(local_name), param);
889  }
890  }
891  }
892 
893  XMLRPCManager::instance()->bind("paramUpdate", paramUpdateCallback);
894 }
895 
896 } // namespace param
897 
898 } // namespace ros
ros::param::setImpl
void setImpl(const std::string &key, const std::vector< T > &vec)
Definition: param.cpp:130
XmlRpc::XmlRpcValue::size
int size() const
this_node.h
ros::param::getImpl
bool getImpl(const std::string &key, XmlRpc::XmlRpcValue &v, bool use_cache)
Definition: param.cpp:257
ros::param::xml_castable< float >
bool xml_castable< float >(int XmlType)
Definition: param.cpp:492
ros::param::paramUpdateCallback
void paramUpdateCallback(XmlRpc::XmlRpcValue &params, XmlRpc::XmlRpcValue &result)
Definition: param.cpp:795
ros::param::xml_castable
bool xml_castable(int XmlType)
Definition: param.cpp:474
ros::param::param
bool param(const std::string &param_name, T &param_val, const T &default_val)
Assign value from parameter server, with default.
Definition: param.h:619
ros::param::xml_castable< bool >
bool xml_castable< bool >(int XmlType)
Definition: param.cpp:508
s
XmlRpcServer s
ros
ros::param::xml_castable< int >
bool xml_castable< int >(int XmlType)
Definition: param.cpp:500
ros::param::init
void init(const M_string &remappings)
Definition: param.cpp:826
ros::param::g_subscribed_params
S_string g_subscribed_params
Definition: param.cpp:51
XmlRpc::XmlRpcValue::TypeInt
TypeInt
ros::names::clean
ROSCPP_DECL std::string clean(const std::string &name)
Cleans a graph resource name: removes double slashes, trailing slash.
Definition: names.cpp:99
XmlRpc
ros::param::M_Param
std::map< std::string, XmlRpc::XmlRpcValue > M_Param
Definition: param.cpp:48
ros::param::g_params_mutex
boost::recursive_mutex g_params_mutex
Definition: param.cpp:50
ros::names::parentNamespace
ROSCPP_DECL std::string parentNamespace(const std::string &name)
Get the parent namespace of a name.
Definition: names.cpp:206
ros::param::del
ROSCPP_DECL bool del(const std::string &key)
Delete a parameter from the parameter server.
Definition: param.cpp:228
ros::names::resolve
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
XmlRpc::XmlRpcValue::TypeStruct
TypeStruct
f
f
console.h
ros::param::getCached
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:439
XmlRpc::XmlRpcValue::TypeDouble
TypeDouble
ros::param::update
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
Definition: param.cpp:781
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
XmlRpc::XmlRpcValue::TypeString
TypeString
param.h
d
d
ros::XMLRPCManager::instance
static const XMLRPCManagerPtr & instance()
Definition: xmlrpc_manager.cpp:98
xmlrpc_manager.h
XmlRpc::XmlRpcValue::end
iterator end()
XmlRpc::XmlRpcValue::getType
const Type & getType() const
ros::master::execute
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:175
XmlRpc::XmlRpcValue::TypeArray
TypeArray
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
Returns the name of the current node.
Definition: this_node.cpp:74
ros::param::g_params
M_Param g_params
Definition: param.cpp:49
master.h
ros::S_string
std::set< std::string > S_string
ros::names::getUnresolvedRemappings
const ROSCPP_DECL M_string & getUnresolvedRemappings()
Definition: names.cpp:51
ros::param::get
ROSCPP_DECL bool get(const std::string &key, std::string &s)
Get a string value from the parameter server.
Definition: param.cpp:409
ros::param::search
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:752
XmlRpc::XmlRpcValue::setSize
void setSize(int size)
ros::param::unsubscribeCachedParam
ROSCPP_DECL void unsubscribeCachedParam(const std::string &key)
Unsubscribe cached parameter from the master.
Definition: param.cpp:804
ros::param::getParamNames
ROSCPP_DECL bool getParamNames(std::vector< std::string > &keys)
Get the list of all the parameters in the server.
Definition: param.cpp:717
ros::param::has
ROSCPP_DECL bool has(const std::string &key)
Check whether a parameter exists on the parameter server.
Definition: param.cpp:211
XmlRpc::XmlRpcValue::begin
iterator begin()
XmlRpc::XmlRpcValue::TypeBoolean
TypeBoolean
names.h
ros::param::invalidateParentParams
void invalidateParentParams(const std::string &key)
Definition: param.cpp:53
ros::param::xml_cast
T xml_cast(XmlRpc::XmlRpcValue xml_value)
Definition: param.cpp:469
ros::param::xml_castable< double >
bool xml_castable< double >(int XmlType)
Definition: param.cpp:484
XmlRpc::XmlRpcValue
ros::M_string
std::map< std::string, std::string > M_string
ros::param::set
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


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Sat Sep 14 2024 02:59:35