00001 /* vim: set sw=4 sts=4 et foldmethod=syntax : */ 00002 00003 #ifndef IRI_DEFORMABLE_ANALYSIS_GUARD_IRI_DEFORMABLE_ANALYSIS_H 00004 #define IRI_DEFORMABLE_ANALYSIS_GUARD_IRI_DEFORMABLE_ANALYSIS_H 1 00005 00006 #include <iridrivers/event.h> 00007 #include <iridrivers/eventexceptions.h> 00008 00009 #include "ros/ros.h" 00010 #include "iri_deformable_analysis/DoDeformableAnalysis.h" 00011 #include <iri_deformable_analysis/ScoreMapMixResults.h> 00012 #include <geometry_msgs/Pose.h> 00013 00014 /* 00015 * \brief Deformable Analysis service provider 00016 * 00017 * This class implement the request to make a deformable analysis for 00018 * a given PCL. 00019 * 00020 */ 00021 class IRIDeformableAnalysis 00022 { 00023 00024 typedef double microseconds; 00025 00026 private: 00027 ros::NodeHandle nh_; 00028 /* 00029 * make deformable service handler 00030 */ 00031 ros::ServiceServer deformable_service_; 00032 /* 00033 * publish the PCL recieved so rest of nodes start to make 00034 * the job on PCL. 00035 */ 00036 ros::Publisher deformable_pcl_publisher_; 00037 /* 00038 * subscriber to recieve the best results corresponding to the 00039 * PCL published. 00040 */ 00041 ros::Subscriber score_results_subscriber_; 00042 static const microseconds timeout_for_score_results_; 00043 00044 /* 00045 * control when the results are recieved so we can free the 00046 * lock on dermable service callback 00047 */ 00048 CEvent score_results_recieved_event_; 00049 iri_deformable_analysis::ScoreMapMixResults last_score_results_; 00050 00051 bool 00052 deformable_analysis_callback(iri_deformable_analysis::DoDeformableAnalysis::Request & req, 00053 iri_deformable_analysis::DoDeformableAnalysis::Response & res); 00054 void 00055 score_results_callback(const iri_deformable_analysis::ScoreMapMixResults::ConstPtr & msg); 00056 00057 public: 00058 IRIDeformableAnalysis(); 00059 }; 00060 00061 00062 #endif