00001 /**************************************************************** 00002 * 00003 * Copyright (c) 2010 00004 * 00005 * Fraunhofer Institute for Manufacturing Engineering 00006 * and Automation (IPA) 00007 * 00008 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00009 * 00010 * Project name: care-o-bot 00011 * ROS stack name: cob_perception_common 00012 * ROS package name: cob_image_flip 00013 * 00014 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00015 * 00016 * Author: Richard Bormann, email:richard.bormann@ipa.fhg.de 00017 * Supervised by: Richard Bormann, email:richard.bormann@ipa.fhg.de 00018 * 00019 * Date of creation: May 2011 00020 * ToDo: 00021 * 00022 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00023 * 00024 * Redistribution and use in source and binary forms, with or without 00025 * modification, are permitted provided that the following conditions are met: 00026 * 00027 * * Redistributions of source code must retain the above copyright 00028 * notice, this list of conditions and the following disclaimer. 00029 * * Redistributions in binary form must reproduce the above copyright 00030 * notice, this list of conditions and the following disclaimer in the 00031 * documentation and/or other materials provided with the distribution. 00032 * * Neither the name of the Fraunhofer Institute for Manufacturing 00033 * Engineering and Automation (IPA) nor the names of its 00034 * contributors may be used to endorse or promote products derived from 00035 * this software without specific prior written permission. 00036 * 00037 * This program is free software: you can redistribute it and/or modify 00038 * it under the terms of the GNU Lesser General Public License LGPL as 00039 * published by the Free Software Foundation, either version 3 of the 00040 * License, or (at your option) any later version. 00041 * 00042 * This program is distributed in the hope that it will be useful, 00043 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00044 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00045 * GNU Lesser General Public License LGPL for more details. 00046 * 00047 * You should have received a copy of the GNU Lesser General Public 00048 * License LGPL along with this program. 00049 * If not, see <http://www.gnu.org/licenses/>. 00050 * 00051 ****************************************************************/ 00052 00053 //################## 00054 //#### includes #### 00055 00056 // ROS includes 00057 #include <ros/ros.h> 00058 00059 // ROS message includes 00060 #include <sensor_msgs/Image.h> 00061 #include <sensor_msgs/PointCloud2.h> 00062 #include <tf/transform_listener.h> 00063 00064 // topics 00065 //#include <message_filters/subscriber.h> 00066 //#include <message_filters/synchronizer.h> 00067 //#include <message_filters/sync_policies/approximate_time.h> 00068 #include <image_transport/image_transport.h> 00069 #include <image_transport/subscriber_filter.h> 00070 00071 // opencv 00072 #include <opencv/cv.h> 00073 #include <opencv/highgui.h> 00074 #include <cv_bridge/cv_bridge.h> 00075 #include <sensor_msgs/image_encodings.h> 00076 00077 // point cloud 00078 #include <pcl/point_types.h> 00079 #include <pcl_ros/point_cloud.h> 00080 #include <pcl_conversions/pcl_conversions.h> 00081 00082 // timer 00083 #include <cob_image_flip/timer.h> 00084 00085 // System 00086 #include <iostream> 00087 00088 #include <cob_vision_utils/GlobalDefines.h> 00089 00090 namespace cob_image_flip 00091 { 00092 class CobKinectImageFlip 00093 { 00094 protected: 00095 int cob3Number_; 00096 bool flip_color_image_; 00097 bool flip_pointcloud_; 00098 int rotation_; 00099 std::string pointcloud_data_format_; 00100 bool display_warnings_; 00101 bool display_timing_; 00102 00103 unsigned int img_sub_counter_; 00104 unsigned int pc_sub_counter_; 00105 00106 ros::Subscriber point_cloud_sub_; 00107 ros::Publisher point_cloud_pub_; 00108 //message_filters::Subscriber<sensor_msgs::PointCloud2> point_cloud_sub_; ///< Point cloud input topic 00109 image_transport::ImageTransport* it_; 00110 image_transport::SubscriberFilter color_camera_image_sub_; 00111 image_transport::Publisher color_camera_image_pub_; 00112 //message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::Image> >* sync_pointcloud_; ///< synchronizer for input data 00113 //message_filters::Connection sync_pointcloud_callback_connection_; 00114 00115 tf::TransformListener* transform_listener_; 00116 00117 ros::NodeHandle node_handle_; 00118 00119 public: 00120 00121 CobKinectImageFlip(ros::NodeHandle nh); 00122 00123 ~CobKinectImageFlip(); 00124 00125 unsigned long init(); 00126 00127 unsigned long convertColorImageMessageToMat(const sensor_msgs::Image::ConstPtr& color_image_msg, cv_bridge::CvImageConstPtr& color_image_ptr, cv::Mat& color_image); 00128 00129 template <typename T> 00130 void inputCallback(const sensor_msgs::PointCloud2::ConstPtr& point_cloud_msg); 00131 00132 void imageCallback(const sensor_msgs::ImageConstPtr& color_image_msg); 00133 00134 void imgConnectCB(const image_transport::SingleSubscriberPublisher& pub); 00135 00136 void imgDisconnectCB(const image_transport::SingleSubscriberPublisher& pub); 00137 00138 void pcConnectCB(const ros::SingleSubscriberPublisher& pub); 00139 00140 void pcDisconnectCB(const ros::SingleSubscriberPublisher& pub); 00141 }; 00142 00143 }