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 _pmdcamera_driver_node_h_ 00026 #define _pmdcamera_driver_node_h_ 00027 00028 #include <iri_base_driver/iri_base_driver_node.h> 00029 #include "pmdcamera_driver.h" 00030 00031 #include <ros/ros.h> 00032 #include <ros/package.h> 00033 // [publisher subscriber headers] 00034 #include <sensor_msgs/Image.h> 00035 #include <sensor_msgs/image_encodings.h> 00036 #include <sensor_msgs/PointCloud.h> 00037 #include <sensor_msgs/PointCloud2.h> 00038 #include <sensor_msgs/CameraInfo.h> 00039 #include <camera_info_manager/camera_info_manager.h> 00040 #include <image_transport/image_transport.h> 00041 // [service client headers] 00042 00043 // [action server client headers] 00044 00045 typedef union { 00046 struct /*anonymous*/ 00047 { 00048 unsigned char Blue; 00049 unsigned char Green; 00050 unsigned char Red; 00051 unsigned char Alpha; 00052 }; 00053 float float_value; 00054 long long_value; 00055 } RGBValue; 00056 00074 class PmdcameraDriverNode : public iri_base_driver::IriBaseNodeDriver<PmdcameraDriver> 00075 { 00076 private: 00077 int width_,real_width_; 00078 int height_,real_height_; 00079 float max_intensity_; 00080 float max_amplitude_; 00081 float max_depth_; 00084 image_transport::ImageTransport *it_; 00085 00087 // [publisher attributes] 00088 // image_transport::Publisher image_raw_publisher_; 00089 image_transport::CameraPublisher image_raw_publisher_; 00090 sensor_msgs::Image Image_int_msg_; 00091 00092 image_transport::CameraPublisher image_flags_publisher_; 00093 sensor_msgs::Image Image_flags_msg_; 00094 00095 image_transport::CameraPublisher image_amp_publisher_; 00096 sensor_msgs::Image Image_amp_msg_; 00097 00098 image_transport::CameraPublisher image_depth_publisher_; 00099 sensor_msgs::Image Image_depth_msg_; 00100 00101 ros::Publisher cloud_raw_publisher_; 00102 sensor_msgs::PointCloud PointCloud_msg_; 00103 00104 ros::Publisher pcl_int_raw_publisher_; 00105 ros::Publisher pcl_amp_raw_publisher_; 00106 ros::Publisher pcl_range_raw_publisher_; 00107 sensor_msgs::PointCloud2 pcl2_int_msg_; 00108 sensor_msgs::PointCloud2 pcl2_amp_msg_; 00109 sensor_msgs::PointCloud2 pcl2_range_msg_; 00110 // [subscriber attributes] 00111 00112 // [service attributes] 00113 00114 // [client attributes] 00115 00116 // [action server attributes] 00117 00118 // [action client attributes] 00119 00121 camera_info_manager::CameraInfoManager *camera_info_manager_; 00122 std::string camera_name_; 00123 std::string camera_info_url_; 00125 sensor_msgs::CameraInfo camera_info_; 00126 00132 void assemblePcl2Int(const float* const coord_3D, const float* const intensity); 00133 00134 void assemblePcl2Amp(const float* const coord_3D, const float* const amplitude); 00135 00136 void assemblePcl2RangeImage(const float* const coord_3D, const float* const range, const float* const amp); 00137 00141 void assembleFlagsImage(float* flags); 00142 00147 void assembleIntensityImage(float* intensity); 00148 00153 void assembleAmplitudeImage(float* amplitude); 00154 00159 void assembleDepthImage(float* distance); 00160 00165 void findMaxIntensity(const float* intensity); 00166 void findMaxAmplitude(const float* amplitude); 00167 void findMaxDepth(const float* distance); 00168 00176 void postNodeOpenHook(void); 00177 00178 public: 00196 PmdcameraDriverNode(ros::NodeHandle& nh); 00197 00204 ~PmdcameraDriverNode(); 00205 00206 protected: 00219 void mainNodeThread(void); 00220 00221 // [diagnostic functions] 00222 00233 void addNodeDiagnostics(void); 00234 00235 // [driver test functions] 00236 00246 void addNodeOpenedTests(void); 00247 00257 void addNodeStoppedTests(void); 00258 00268 void addNodeRunningTests(void); 00269 00277 void reconfigureNodeHook(int level); 00278 00279 }; 00280 00281 #endif