$search
00001 /****************************************************************************** 00002 * \file 00003 * 00004 * $Id:$ 00005 * 00006 * Copyright (C) Brno University of Technology 00007 * 00008 * This file is part of software developed by dcgm-robotics@FIT group. 00009 * 00010 * Author: Vit Stancl (stancl@fit.vutbr.cz) 00011 * Supervised by: Michal Spanel (spanel@fit.vutbr.cz) 00012 * Date: 25/1/2012 00013 * 00014 * This file is free software: you can redistribute it and/or modify 00015 * it under the terms of the GNU Lesser General Public License as published by 00016 * the Free Software Foundation, either version 3 of the License, or 00017 * (at your option) any later version. 00018 * 00019 * This file is distributed in the hope that it will be useful, 00020 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00021 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00022 * GNU Lesser General Public License for more details. 00023 * 00024 * You should have received a copy of the GNU Lesser General Public License 00025 * along with this file. If not, see <http://www.gnu.org/licenses/>. 00026 */ 00027 00028 #pragma once 00029 #ifndef CPCTOOCREGISTRATION_H_ 00030 #define CPCTOOCREGISTRATION_H_ 00031 00032 #include <sensor_msgs/CameraInfo.h> 00033 #include <ros/callback_queue.h> 00034 #include <tf/transform_listener.h> 00035 #include <LinearMath/btMatrix3x3.h> 00036 00037 #include <boost/scoped_ptr.hpp> 00038 #include <boost/thread/thread.hpp> 00039 #include <boost/thread/recursive_mutex.hpp> 00040 #include <image_geometry/pinhole_camera_model.h> 00041 #include <ros/node_handle.h> 00042 00043 #include <srs_env_model/but_server/server_tools.h> 00044 00045 #include "pcl_registration_module.h" 00046 00047 #include <pcl/filters/voxel_grid.h> 00048 00049 namespace srs_env_model 00050 { 00054 class COcPatchMaker 00055 { 00056 public: 00058 //typedef sensor_msgs::PointCloud2 tCloud; 00059 typedef tPointCloud tCloud; 00060 00061 public: 00063 COcPatchMaker(); 00064 00066 virtual void init(ros::NodeHandle & node_handle); 00067 00069 bool computeCloud( const SMapWithParameters & par, const ros::Time & time ); 00070 00072 tCloud & getCloud( ) { return m_cloud; } 00073 00075 void setCloudFrameId( const std::string & fid ){ m_pcFrameId = fid; } 00076 00077 protected: 00079 void onCameraChangedCB(const sensor_msgs::CameraInfo::ConstPtr &cam_info); 00080 00081 // main loop when spinning our own thread 00082 // - process callbacks in our callback queue 00083 // - process pending goals 00084 void spinThread(); 00085 00087 bool inSensorCone(const cv::Point2d& uv) const; 00088 00090 void publishInternal(const ros::Time & timestamp); 00091 00093 virtual void handleOccupiedNode(tButServerOcTree::iterator& it, const SMapWithParameters & mp); 00094 00095 protected: 00097 bool m_bTransformCamera; 00098 00100 std::string m_cameraFrameId; 00101 00103 std::string m_pcFrameId; 00104 00105 // Camera position topic name 00106 std::string m_cameraInfoTopic; 00107 00109 ros::Subscriber m_camPosSubscriber; 00110 00111 // Mutex used to lock camera position parameters 00112 boost::recursive_mutex m_camPosMutex; 00113 00115 bool m_bSpinThread; 00116 00117 // these are needed when spinning up a dedicated thread 00118 boost::scoped_ptr<boost::thread> spin_thread_; 00119 ros::NodeHandle node_handle_; 00120 ros::CallbackQueue callback_queue_; 00121 volatile bool need_to_terminate_; 00122 00124 bool m_bCamModelInitialized; 00125 00127 int m_camera_stereo_offset_left, m_camera_stereo_offset_right; 00128 00130 tCloud m_cloud; 00131 00133 bool m_bPublishCloud; 00134 00136 image_geometry::PinholeCameraModel m_camera_model, m_camera_model_buffer; 00137 00139 sensor_msgs::CameraInfo m_camera_info_buffer; 00140 00142 cv::Size m_camera_size, m_camera_size_buffer; 00143 00145 tf::TransformListener m_tfListener; 00146 00148 ros::Publisher m_pubConstrainedPC; 00149 00151 std::string m_ocFrameId; 00152 00154 ros::Time m_DataTimeStamp, m_time_stamp; 00155 00157 tf::Transform m_to_sensorTf; 00158 00160 double m_fracX; 00161 00163 double m_fracY; 00164 00166 btMatrix3x3 m_fracMatrix; 00167 00168 public: 00169 EIGEN_MAKE_ALIGNED_OPERATOR_NEW 00170 00171 }; // class COcToPcl 00172 00173 00177 class CPcToOcRegistration 00178 { 00179 public: 00181 typedef sensor_msgs::PointCloud2 tCloud; 00182 00184 typedef CPclRegistration< tPclPoint, tPclPoint> tRegistrator; 00185 00186 public: 00188 CPcToOcRegistration(); 00189 00191 virtual void init(ros::NodeHandle & node_handle); 00192 00194 bool registerCloud( tPointCloudPtr & cloud, const SMapWithParameters & map ); 00195 00197 Eigen::Matrix4f getTransform() { return m_registration.getTransform(); } 00198 00200 bool isRegistering(){ return m_registration.isRegistering(); } 00201 00202 protected: 00204 COcPatchMaker m_patchMaker; 00205 00207 tRegistrator m_registration; 00208 00210 pcl::VoxelGrid<tCloud> m_gridFilter; 00211 00213 tCloud::Ptr m_resampledCloud; 00214 00216 tf::TransformListener m_tfListener; 00217 00218 public: 00219 EIGEN_MAKE_ALIGNED_OPERATOR_NEW 00220 00221 }; // class CPcToOcRegistration 00222 00223 00224 } // namespace srs_env_model 00225 00226 #endif /* CPCTOOCREGISTRATION_H_ */