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: dd/mm/2011 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 but_depthtexture_H_included 00030 #define but_depthtexture_H_included 00031 00032 #include <ros/ros.h> 00033 #include <image_transport/image_transport.h> 00034 #include <sensor_msgs/image_encodings.h> 00035 #include <but_rostexture.h> 00036 #include <cv_bridge/cv_bridge.h> 00037 #include <OGRE/OgreMatrix4.h> 00038 #include <image_geometry/pinhole_camera_model.h> 00039 00040 namespace srs_ui_but 00041 { 00042 00043 namespace enc = sensor_msgs::image_encodings; 00044 00045 class CDepthImageConvertor 00046 { 00047 public: 00049 CDepthImageConvertor(const ros::NodeHandle& nh, const std::string & topic); 00050 00052 ~CDepthImageConvertor(); 00053 00055 sensor_msgs::ImagePtr & getSensorMsgsImage() { return m_depth_msg; } 00056 00058 boost::mutex & getMutexLock() { return m_mutex; } 00059 00061 bool hasData() { return m_counter > 0; } 00062 00064 void setTopic(const std::string& topic); 00065 00067 std::string getTopic() { return m_topic; } 00068 00070 void setMatrix( const Ogre::Matrix4 & m ) { m_projectionMatrix = m; } 00071 00073 void setCameraModel(const sensor_msgs::CameraInfo& msg); 00074 00075 protected: 00077 void depthCb(const sensor_msgs::ImageConstPtr& raw_msg); 00078 00080 virtual bool convertDepth(const sensor_msgs::ImageConstPtr& raw_msg); 00081 00083 virtual bool convertDepth16(const sensor_msgs::ImageConstPtr& raw_msg); 00084 00086 virtual bool convertDepth16UC1(const sensor_msgs::ImageConstPtr& raw_msg); 00087 00089 virtual bool convertDepth8(const sensor_msgs::ImageConstPtr& raw_msg); 00090 00092 bool toVisible(int coord = 2); 00093 00095 bool toFloat( int coord = 2); 00096 00097 protected: 00098 // Subscriptions 00099 boost::shared_ptr<image_transport::ImageTransport> m_it; 00100 image_transport::Subscriber m_sub_raw; 00101 00103 image_transport::Publisher m_pub_depth, m_pub_float; 00104 00106 sensor_msgs::ImagePtr m_depth_msg, m_visible_msg, m_float_msg; 00107 00109 Ogre::Vector4 m_min_range, m_max_range; 00110 00112 std::string m_msg_encoding; 00113 std::string m_visible_encoding; 00114 00116 boost::mutex m_mutex; 00117 00119 long m_counter; 00120 00122 std::string m_topic; 00123 00124 image_transport::TransportHints m_hints; 00125 00127 Ogre::Matrix4 m_projectionMatrix; 00128 00130 image_geometry::PinholeCameraModel m_camera_model; 00131 00133 bool m_bCamModelInitialized; 00134 00135 }; // class CDepthImageConvertor 00136 00137 00138 class CRosDepthTexture : public CDepthImageConvertor 00139 { 00140 public: 00142 CRosDepthTexture( const ros::NodeHandle& nh, const std::string & texture_name, const std::string& topic_name, const std::string & encoding, bool bStaticTexture = false ); 00143 00145 const Ogre::TexturePtr& getTexture() { return m_texture_converter.getOgreTexture(); } 00146 00148 void clear(); 00149 00150 protected: 00152 virtual bool convertDepth(const sensor_msgs::ImageConstPtr& raw_msg); 00153 00154 protected: 00156 CRosTextureConverter m_texture_converter; 00157 00158 00159 00160 }; // class CRosDepthTexture 00161 00162 } // namespace srs_ui_but 00163 00164 //but_depthtexture_H_included 00165 #endif 00166