Go to the documentation of this file.00001 #include <ros/ros.h>
00002 #include <object_msgs/RegisterObject.h>
00003
00004 int main(int argc, char** argv)
00005 {
00006 ros::init(argc, argv, "register_object_client");
00007 ros::NodeHandle priv("~");
00008 ros::NodeHandle pub("");
00009
00010 if (!pub.hasParam("/object_tf_broadcaster/register_object_service"))
00011 {
00012 ROS_ERROR("Missing parameter register_object_service");
00013 return 0;
00014 }
00015 std::string REGISTER_OBJECT_SERVICE;
00016 priv.param<std::string>("/object_tf_broadcaster/register_object_service", REGISTER_OBJECT_SERVICE, REGISTER_OBJECT_SERVICE);
00017 ROS_INFO("Using register object service name: <%s>", REGISTER_OBJECT_SERVICE.c_str());
00018
00019 ros::ServiceClient client = pub.serviceClient<object_msgs::RegisterObject>(REGISTER_OBJECT_SERVICE);
00020 object_msgs::RegisterObject srv;
00021 srv.request.name = argv[1];
00022 if (client.call(srv))
00023 {
00024 ROS_INFO("Result:");
00025 std::cout<<srv.response<<std::endl;
00026 }
00027 else
00028 {
00029 ROS_ERROR("Failed to call service %s",REGISTER_OBJECT_SERVICE.c_str());
00030 }
00031 return 0;
00032 }