pointcloud_to_eigenvectors_alg.h
Go to the documentation of this file.
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 _pointcloud_to_eigenvectors_alg_h_
00026 #define _pointcloud_to_eigenvectors_alg_h_
00027 
00028 #include <iri_pointcloud_to_eigenvectors/PointcloudToEigenvectorsConfig.h>
00029 #include "mutex.h"
00030 #include <sensor_msgs/PointCloud2.h>
00031 #include <visualization_msgs/Marker.h>
00032 #include <Eigen/Dense>
00033 #include <tf/transform_listener.h>
00034 #include <pcl/common/transforms.h>
00035 #include <pcl/filters/passthrough.h>
00036 
00037 //include pointcloud_to_eigenvectors_alg main library
00038 
00044 class PointcloudToEigenvectorsAlgorithm
00045 {
00046   protected:
00053     CMutex alg_mutex_;
00054 
00055     // private attributes and methods
00056     Eigen::Vector4f plane_centroid_;
00057     Eigen::Quaternionf plane_pose_;
00058     visualization_msgs::Marker Marker_msg_;
00059 
00060   public:
00067     typedef iri_pointcloud_to_eigenvectors::PointcloudToEigenvectorsConfig Config;
00068 
00075     Config config_;
00076 
00085     PointcloudToEigenvectorsAlgorithm(void);
00086 
00092     void lock(void) { alg_mutex_.enter(); };
00093 
00099     void unlock(void) { alg_mutex_.exit(); };
00100 
00108     bool try_enter(void) { return alg_mutex_.try_enter(); };
00109 
00121     void config_update(Config& new_cfg, uint32_t level=0);
00122 
00123     // here define all pointcloud_to_eigenvectors_alg interface methods to retrieve and set
00124     // the driver parameters
00125     bool get_eigenvectors(const sensor_msgs::PointCloud2::ConstPtr& msg);
00126     visualization_msgs::Marker getMarker();
00127     Eigen::Vector4f getPlaneCentroid();
00128     Eigen::Quaternionf getPlanePose();
00129 
00136     ~PointcloudToEigenvectorsAlgorithm(void);
00137 };
00138 
00139 #endif


iri_pointcloud_to_eigenvectors
Author(s): Sergi Foix
autogenerated on Fri Dec 6 2013 20:11:39