FakeObjectRecognizer.h
Go to the documentation of this file.
00001 #ifndef GAZEBO_TEST_TOOLS_FAKEOBJECTRECOGNISER_H
00002 #define GAZEBO_TEST_TOOLS_FAKEOBJECTRECOGNISER_H
00003 
00004 #include <ros/ros.h>
00005 
00006 #include <object_msgs/Object.h>
00007 #include <object_msgs/ObjectInfo.h>
00008 #include <object_msgs/ObjectInfoRequest.h>
00009 #include <object_msgs/ObjectInfoResponse.h>
00010 
00011 #include <gazebo_test_tools/RecognizeGazeboObject.h>
00012 #include <gazebo_test_tools/RecognizeGazeboObjectRequest.h>
00013 #include <gazebo_test_tools/RecognizeGazeboObjectResponse.h>
00014 
00015 #include <geometry_msgs/Pose.h>
00016 #include <boost/thread/mutex.hpp>
00017 
00018 namespace gazebo_test_tools
00019 {
00020 
00041 class FakeObjectRecognizer {
00042 private:
00043 
00044     typedef object_msgs::Object ObjectMsg;
00045     typedef object_msgs::ObjectInfo ObjectInfoMsg;
00046 
00047 public:
00048 
00049     FakeObjectRecognizer();
00050     virtual ~FakeObjectRecognizer();
00051 
00052 private:
00053 
00054     bool recognizeObject(gazebo_test_tools::RecognizeGazeboObject::Request  &req, gazebo_test_tools::RecognizeGazeboObject::Response &res);
00055 
00056     void publishRecognitionEvent(const ros::TimerEvent& e); 
00057 
00062     bool waitForQueryObjectInfo(const std::string& name, object_msgs::Object& object,
00063         bool include_geometry,  float timeout, float checkStep, bool printErrors);
00064 
00068     bool queryObjectInfo(const std::string& name, object_msgs::Object& object,
00069         bool include_geometry, bool printErrors);
00070 
00071     std::string OBJECTS_TOPIC;
00072 
00073     // service name/topic to request information about
00074     // objects with object_msgs/ObjectInfo.srv
00075     std::string SERVICE_REQUEST_OBJECT_TOPIC;
00076 
00077     // service which will be offered to recognise
00078     // an object, of type gazebo_test_tools/TriggerRecognition.srv.
00079     std::string SERVICE_RECOGNISE_OBJECT_TOPIC;
00080 
00081     
00082     // service of under which a object_msgs_tools/RegisterObject can
00083     // be sent in order to start publishing /tf information about an
00084     // object.
00085     std::string SERVICE_REGISTER_OBJECT_TF_TOPIC;
00086 
00087     // Recognised objects which are to be continuously published
00088     // as recognised are published at this rate.
00089     float PUBLISH_RECOGNISED_OBJECT_RATE;
00090 
00091     ros::Publisher object_pub;
00092     ros::ServiceClient object_info_client;
00093     ros::ServiceClient register_object_tf_client;
00094     
00095     ros::ServiceServer recognize_object_srv;
00096 
00097     // all objects which were set to be continuously published
00098     std::set<std::string> addedObjects;
00099     
00100     // mutex for addedObjects
00101     boost::mutex addedObjectsMtx;
00102 
00103     ros::Timer publishTimer;
00104 
00105     ros::NodeHandle node;
00106 };
00107 
00108 }  // namespace gazebo_test_tools
00109 
00110 #endif  // GAZEBO_TEST_TOOLS_FAKEOBJECTRECOGNISER_H


gazebo_test_tools
Author(s): Jennifer Buehler
autogenerated on Tue May 7 2019 03:29:23