00001 // Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC. 00002 // Author 00003 // All rights reserved. 00004 // 00005 // This file is part of iri-ros-pkg 00006 // iri-ros-pkg is free software: you can redistribute it and/or modify 00007 // it under the terms of the GNU Lesser General Public License as published by 00008 // the Free Software Foundation, either version 3 of the License, or 00009 // at your option) any later version. 00010 // 00011 // This program is distributed in the hope that it will be useful, 00012 // but WITHOUT ANY WARRANTY; without even the implied warranty of 00013 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00014 // GNU Lesser General Public License for more details. 00015 // 00016 // You should have received a copy of the GNU Lesser General Public License 00017 // along with this program. If not, see <http://www.gnu.org/licenses/>. 00018 // 00019 // IMPORTANT NOTE: This code has been generated through a script from the 00020 // iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness 00021 // of the scripts. ROS topics can be easly add by using those scripts. Please 00022 // refer to the IRI wiki page for more information: 00023 // http://wikiri.upc.es/index.php/Robotics_Lab 00024 00025 #ifndef _zyonz_obtain_roi_jump_edge_based_alg_h_ 00026 #define _zyonz_obtain_roi_jump_edge_based_alg_h_ 00027 00028 #include <zyonz_obtain_roi_jump_edge_based/ZyonzObtainRoiJumpEdgeBasedConfig.h> 00029 #include "mutex.h" 00030 #include <opencv2/highgui/highgui.hpp> 00031 #include <opencv2/imgproc/imgproc.hpp> 00032 #include <cv_bridge/cv_bridge.h> 00033 #include "pcl_ros/point_cloud.h" 00034 #include "pcl/point_types.h" 00035 #include "pcl_ros/transforms.h" 00036 #include "sensor_msgs/image_encodings.h" 00037 #include "geometry_msgs/PoseStamped.h" 00038 #include "tf/transform_listener.h" 00039 #include "tf/transform_datatypes.h" 00040 00041 //include zyonz_obtain_roi_jump_edge_based_alg main library 00042 00048 class ZyonzObtainRoiJumpEdgeBasedAlgorithm 00049 { 00050 private: 00051 pcl::PointCloud<pcl::PointXYZ> roi_pc_; 00052 sensor_msgs::Image::Ptr roi_img_ptr_; 00053 geometry_msgs::PoseStamped::Ptr roi_pose_ptr_; 00054 geometry_msgs::PoseStamped::Ptr viewpoint_pose_ptr_; 00055 00056 protected: 00063 CMutex alg_mutex_; 00064 00065 // private attributes and methods 00066 00067 public: 00074 typedef zyonz_obtain_roi_jump_edge_based::ZyonzObtainRoiJumpEdgeBasedConfig Config; 00075 00082 Config config_; 00083 00092 ZyonzObtainRoiJumpEdgeBasedAlgorithm(void); 00093 00099 void lock(void) { alg_mutex_.enter(); }; 00100 00106 void unlock(void) { alg_mutex_.exit(); }; 00107 00115 bool try_enter(void) { return alg_mutex_.try_enter(); }; 00116 00128 void config_update(Config& new_cfg, uint32_t level=0); 00129 00130 bool principal_component_analysis(pcl::PointCloud<pcl::PointXYZ>::ConstPtr point_cloud, Eigen::Vector4f& centroid, Eigen::Quaternionf& orientation); 00131 bool isRunning(sensor_msgs::PointCloud2::ConstPtr& point_cloud_ConstPtr, sensor_msgs::Image::ConstPtr& cluster_a_img_ConstPtr, sensor_msgs::Image::ConstPtr& cluster_b_img_ConstPtr, sensor_msgs::Image::ConstPtr& residual_img_ConstPtr); 00132 00133 // here define all zyonz_obtain_roi_jump_edge_based_alg interface methods to retrieve and set 00134 // the driver parameters 00135 00136 pcl::PointCloud<pcl::PointXYZ>::ConstPtr get_roi_pc(void); 00137 sensor_msgs::Image::Ptr get_roi_img(void); 00138 geometry_msgs::PoseStamped::Ptr get_roi_pose(void); 00139 geometry_msgs::PoseStamped::Ptr get_viewpoint_pose(void); 00140 00147 ~ZyonzObtainRoiJumpEdgeBasedAlgorithm(void); 00148 }; 00149 00150 #endif