paramSub.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <ros/param.h>
3 #include <ros/console.h>
4 
5 #include <ros/xmlrpc_manager.h>
6 #include <std_msgs/String.h>
7 
8 void callback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result)
9 {
10  std::string resp = params.toXml();
11  ROS_ERROR_STREAM("Updated parameter: " << params[2]);
12  result[0] = 1;
13  result[1] = std::string("");
14  result[2] = 0;
15 
16  //ros::param::update((std::string)params[1], params[2]);
17 }
18 
19 int main(int argc, char **argv)
20 {
21  XmlRpc::XmlRpcValue params, result, payload;
22 
23  ros::init(argc, argv, "test_node");
24 
25  ros::NodeHandle nh("~");
26 
27  ros::XMLRPCManager::instance()->unbind("paramUpdate");
28  ros::XMLRPCManager::instance()->bind("paramUpdate", callback);
29 
30  ros::param::set("~test_param", true);
31 
32  ROS_INFO("Created new parameter through XmlRpc API call.");
33 
34  params[0] = ros::this_node::getName();
35  params[1] = ros::XMLRPCManager::instance()->getServerURI();
36  params[2] = ros::names::resolve(std::string("~test_param"));
37 
38  if (ros::master::execute("subscribeParam", params, result, payload, false)) {
39  ROS_INFO("Subscribed to parameter.");
40  }
41  else {
42  ROS_ERROR("Failed to subscribe to the parameter.");
43  }
44 
45  while (nh.ok()) {
46  ros::spinOnce();
47 
48  }
49  return 0;
50 }
int main(int argc, char **argv)
Definition: paramSub.cpp:19
void callback(XmlRpc::XmlRpcValue &params, XmlRpc::XmlRpcValue &result)
Definition: paramSub.cpp:8


vapor_master
Author(s): RosHub Inc.
autogenerated on Mon Feb 28 2022 23:59:43