apply_tof_calibration_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 _apply_tof_calibration_alg_h_
00026 #define _apply_tof_calibration_alg_h_
00027 
00028 #include <iri_apply_tof_calibration/ApplyTofCalibrationConfig.h>
00029 #include "mutex.h"
00030 
00031 // [PCL_ROS]
00032 #include "pcl_ros/point_cloud.h"
00033 #include "pcl/point_types.h"
00034 #include "pcl/ros/register_point_struct.h"
00035 #include "TOFCameraModel.h"
00036 #include "sensor_msgs/PointCloud2.h"
00037 
00038 //include apply_tof_calibration_alg main library
00039 
00045 class ApplyTofCalibrationAlgorithm
00046 {
00047   private:
00048     //pcl::PointCloud<pcl::PointXYZRGB> calibrated_pcl_;
00049     sensor_msgs::PointCloud2 calibrated_pcl_;
00050     TOFCameraModel* tofCameraModel_;
00051   protected:
00058     CMutex alg_mutex_;
00059 
00060     // private attributes and methods
00061 
00062   public:
00069     typedef iri_apply_tof_calibration::ApplyTofCalibrationConfig Config;
00070 
00077     Config config_;
00078 
00087     ApplyTofCalibrationAlgorithm(void);
00088 
00094     void lock(void) { alg_mutex_.enter(); };
00095 
00101     void unlock(void) { alg_mutex_.exit(); };
00102 
00110     bool try_enter(void) { return alg_mutex_.try_enter(); };
00111 
00123     void config_update(Config& new_cfg, uint32_t level=0);
00124 
00125     // here define all apply_tof_calibration_alg interface methods to retrieve and set
00126     // the driver parameters
00127     bool apply_tof_calibration_to_pcl2(const sensor_msgs::PointCloud2::ConstPtr& msg);
00128     //pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr get_calibrated_pcl(void);
00129     sensor_msgs::PointCloud2* get_calibrated_pcl(void);
00130 
00137     ~ApplyTofCalibrationAlgorithm(void);
00138 };
00139 
00140 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


iri_apply_tof_calibration
Author(s): Sergi Foix
autogenerated on Wed Oct 9 2013 12:40:17