3 #include <ros/console.h> 5 #include <ros/xmlrpc_manager.h> 6 #include <std_msgs/String.h> 8 void callback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result)
10 std::string resp = params.toXml();
11 ROS_ERROR_STREAM(
"Updated parameter: " << params[2]);
13 result[1] = std::string(
"");
19 int main(
int argc,
char **argv)
21 XmlRpc::XmlRpcValue params, result, payload;
23 ros::init(argc, argv,
"test_node");
25 ros::NodeHandle nh(
"~");
27 ros::XMLRPCManager::instance()->unbind(
"paramUpdate");
28 ros::XMLRPCManager::instance()->bind(
"paramUpdate",
callback);
30 ros::param::set(
"~test_param",
true);
32 ROS_INFO(
"Created new parameter through XmlRpc API call.");
34 params[0] = ros::this_node::getName();
35 params[1] = ros::XMLRPCManager::instance()->getServerURI();
36 params[2] = ros::names::resolve(std::string(
"~test_param"));
38 if (ros::master::execute(
"subscribeParam", params, result, payload,
false)) {
39 ROS_INFO(
"Subscribed to parameter.");
42 ROS_ERROR(
"Failed to subscribe to the parameter.");
int main(int argc, char **argv)
void callback(XmlRpc::XmlRpcValue ¶ms, XmlRpc::XmlRpcValue &result)