Go to the documentation of this file.00001 #include <gazebo_test_tools/FakeObjectRecognizer.h>
00002 #include <ros/ros.h>
00003
00004 #define DEFAULT_RECOGNIZE_OBJECT_TOPIC "/gazebo/recognize_object"
00005
00006 int main(int argc, char** argv)
00007 {
00008 ros::init(argc, argv, "fake_object_recognizer_cmd");
00009
00010 if (argc != 3)
00011 {
00012 ROS_INFO_STREAM("usage: "<<argv[0]<<" <object-name> <republish-flag>");
00013 return 1;
00014 }
00015
00016 ros::NodeHandle n;
00017 std::string RECOGNIZE_OBJECT_TOPIC;
00018
00019 n.param<std::string>("gazebo_test_tools/recognize_object_service", RECOGNIZE_OBJECT_TOPIC, DEFAULT_RECOGNIZE_OBJECT_TOPIC);
00020 ROS_INFO("Got recognize object service topic name: <%s>", RECOGNIZE_OBJECT_TOPIC.c_str());
00021
00022 ros::ServiceClient client = n.serviceClient<gazebo_test_tools::RecognizeGazeboObject>(RECOGNIZE_OBJECT_TOPIC);
00023 gazebo_test_tools::RecognizeGazeboObject srv;
00024 srv.request.name = argv[1];
00025 srv.request.republish = atoi(argv[2]);
00026
00027 if (client.call(srv))
00028 {
00029 ROS_INFO("Result:");
00030 std::cout<<srv.response<<std::endl;
00031 }
00032 else
00033 {
00034 ROS_ERROR("Failed to call service %s",RECOGNIZE_OBJECT_TOPIC.c_str());
00035 return 1;
00036 }
00037
00038 return 0;
00039 }