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


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Sat Aug 1 2020 05:36:29