Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025 #ifndef _object_detection_alg_node_h_
00026 #define _object_detection_alg_node_h_
00027
00028
00029 #include <iri_base_algorithm/iri_base_algorithm.h>
00030 #include "object_detection_alg.h"
00031
00032
00033 #include "object_detection.h"
00034 #include "detection_functions.h"
00035
00036
00037
00038 #include <image_transport/image_transport.h>
00039 #include <cv_bridge/cv_bridge.h>
00040 #include <sensor_msgs/image_encodings.h>
00041 #include <opencv2/imgproc/imgproc.hpp>
00042 #include <opencv2/highgui/highgui.hpp>
00043
00044
00045 #include <geometry_msgs/PoseStamped.h>
00046
00047
00048
00049
00050 #include <iri_common_drivers_msgs/ttsAction.h>
00051 #include <tibi_dabo_msgs/sequenceAction.h>
00052 #include <actionlib/client/simple_action_client.h>
00053 #include <actionlib/client/terminal_state.h>
00054 #include <iri_nav_msgs/followTargetAction.h>
00055
00060 class ObjectDetectionAlgNode : public algorithm_base::IriBaseAlgorithm<ObjectDetectionAlgorithm>
00061 {
00062 private:
00063
00064 image_transport::ImageTransport it_;
00065
00066
00067 ros::Publisher target_pos_publisher_;
00068 geometry_msgs::PoseStamped PoseStamped_msg_;
00069 image_transport::Publisher image_pub_;
00070
00071
00072 image_transport::Subscriber image_sub_;
00073 void image_callback(const sensor_msgs::ImageConstPtr& msg);
00074 CMutex image_mutex_;
00075
00076
00077
00078
00079
00080
00081
00082
00083 actionlib::SimpleActionClient<iri_common_drivers_msgs::ttsAction> loquendo_client_;
00084 iri_common_drivers_msgs::ttsGoal loquendo_goal_;
00085 void loquendoMakeActionRequest(const std::string & msg);
00086 void loquendoDone(const actionlib::SimpleClientGoalState& state, const iri_common_drivers_msgs::ttsResultConstPtr& result);
00087 void loquendoActive();
00088 void loquendoFeedback(const iri_common_drivers_msgs::ttsFeedbackConstPtr& feedback);
00089
00090 actionlib::SimpleActionClient<tibi_dabo_msgs::sequenceAction> hri_client_;
00091 void hriMakeActionRequest(const std::vector<std::string> & xml_files);
00092 void hriDone(const actionlib::SimpleClientGoalState& state, const tibi_dabo_msgs::sequenceResultConstPtr& result);
00093 void hriActive();
00094 void hriFeedback(const tibi_dabo_msgs::sequenceFeedbackConstPtr& feedback);
00095
00096 actionlib::SimpleActionClient<iri_nav_msgs::followTargetAction> follow_target_client_;
00097 iri_nav_msgs::followTargetGoal follow_target_goal_;
00098 void follow_targetMakeActionRequest();
00099 void follow_targetDone(const actionlib::SimpleClientGoalState& state, const iri_nav_msgs::followTargetResultConstPtr& result);
00100 void follow_targetActive();
00101 void follow_targetFeedback(const iri_nav_msgs::followTargetFeedbackConstPtr& feedback);
00102
00103
00104
00105 bool cv_ptr_init;
00106 bool hri_busy;
00107 bool head_busy;
00108 cv_bridge::CvImagePtr cv_ptr;
00109 IplImage* ipl_scaledImage;
00110 clsParameters parameters;
00111
00112 typedef enum {HOME_STATE, LOOK_STATE, DETECTION_STATE, HRI_STATE} states;
00113 states current_state_;
00114
00115 typedef enum {TTS_=0,LEDS_=1,HEAD_=2,LEFT_ARM_=3,RIGHT_ARM_=4} clients;
00116 static const unsigned int NUM_CLIENTS=RIGHT_ARM_-TTS_+1;
00117
00118 bool detectOject(std::string & obj_tag);
00119 public:
00126 ObjectDetectionAlgNode(void);
00127
00134 ~ObjectDetectionAlgNode(void);
00135
00136 protected:
00149 void mainNodeThread(void);
00150
00163 void node_config_update(Config &config, uint32_t level);
00164
00171 void addNodeDiagnostics(void);
00172
00173
00174
00175
00176 };
00177
00178 #endif