image_flip.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016  
00017 
00018 //##################
00019 //#### includes ####
00020 
00021 // ROS includes
00022 #include <ros/ros.h>
00023 
00024 // ROS message includes
00025 #include <sensor_msgs/Image.h>
00026 #include <sensor_msgs/PointCloud2.h>
00027 #include <stereo_msgs/DisparityImage.h>
00028 #include <tf/transform_listener.h>
00029 #include <cob_perception_msgs/Float64ArrayStamped.h>
00030 
00031 // topics
00032 #include <image_transport/image_transport.h>
00033 #include <image_transport/subscriber_filter.h>
00034 
00035 // opencv
00036 #include <opencv2/opencv.hpp>
00037 #include <cv_bridge/cv_bridge.h>
00038 #include <sensor_msgs/image_encodings.h>
00039 
00040 // point cloud
00041 #include <pcl/point_types.h>
00042 #include <pcl_ros/point_cloud.h>
00043 #include <pcl_conversions/pcl_conversions.h>
00044 
00045 // System
00046 #include <iostream>
00047 
00048 namespace cob_image_flip
00049 {
00050 class ImageFlip
00051 {
00052 protected:
00053 
00054         // parameters
00055         int rotation_mode_;                             // rotation mode (0=fixed angle as defined  by rotation_angle, 1=automatic upright rotation against gravity using reference coordinate frame with upwards directed z-axis, 2=as 1 but image rotation only in 90deg steps -> faster)
00056         double rotation_angle_;                 // image rotation [in deg] (especially efficient with 0, 90, 180, 270 deg)
00057         std::string reference_frame_;   // reference world coordinate frame with z-axis pointing upwards (= against gravity direction)
00058 //      std::string camera_frame_;              // camera coordinate frame (image coordinate system with x-axis to the right, y-axis downwards, z-axis into viewing direction of the camera)
00059         bool flip_color_image_;                 // flip color image
00060         bool flip_pointcloud_;                  // flip point cloud (usually unnecessary because tf takes care of this with original point cloud)
00061         bool flip_disparity_image_;             // flip disparity image
00062         bool display_warnings_;                 // display warning if transformation not available
00063         bool display_timing_;                   // display timing information
00064 
00065         double last_rotation_angle_;
00066         double last_rotation_factor_;
00067 
00068         // subscriber counters
00069         unsigned int img_sub_counter_;
00070         unsigned int pc_sub_counter_;
00071         unsigned int disparity_sub_counter_;
00072 
00073         ros::Subscriber point_cloud_sub_;       
00074         ros::Publisher point_cloud_pub_;        
00075         ros::Publisher point_cloud_2d_transform_pub_;   
00076         image_transport::ImageTransport* it_;
00077         image_transport::SubscriberFilter color_camera_image_sub_;      
00078         image_transport::Publisher color_camera_image_pub_;                     
00079         ros::Publisher color_camera_image_2d_transform_pub_;    
00080         ros::Subscriber disparity_image_sub_;   
00081         ros::Publisher disparity_image_pub_;    
00082         ros::Publisher disparity_image_2d_transform_pub_;       
00083 
00084         tf::TransformListener transform_listener_;
00085 
00086         ros::NodeHandle node_handle_; 
00087 
00088 public:
00089 
00090         enum RotationMode { FIXED_ANGLE=0, AUTOMATIC_GRAVITY_DIRECTION=1, AUTOMATIC_GRAVITY_DIRECTION_90=2 };   // (0=fixed angle as defined  by rotation_angle, 1=automatic upright rotation against gravity using reference coordinate frame with upwards directed z-axis, 2=as 1 but image rotation only in 90deg steps -> faster)
00091 
00092         ImageFlip(ros::NodeHandle nh);
00093 
00094         ~ImageFlip();
00095 
00096         double determineRotationAngle(const std::string& camera_frame_id, const ros::Time& time);
00097 
00098         bool convertImageMessageToMat(const sensor_msgs::Image::ConstPtr& color_image_msg, cv_bridge::CvImageConstPtr& color_image_ptr, cv::Mat& color_image);//, const sensor_msgs::image_encodings image_encoding = sensor_msgs::image_encodings::TYPE_32FC1);
00099 
00100 
00101         void imageCallback(const sensor_msgs::ImageConstPtr& color_image_msg);
00102 
00103         void imgConnectCB(const image_transport::SingleSubscriberPublisher& pub);
00104 
00105         void imgDisconnectCB(const image_transport::SingleSubscriberPublisher& pub);
00106 
00107 
00108         void pcCallback(const sensor_msgs::PointCloud2::ConstPtr& point_cloud_msg);
00109 
00110         void pcConnectCB(const ros::SingleSubscriberPublisher& pub);
00111 
00112         void pcDisconnectCB(const ros::SingleSubscriberPublisher& pub);
00113 
00114 
00115         void disparityCallback(const stereo_msgs::DisparityImage::ConstPtr& disparity_image_msg);
00116 
00117         void disparityConnectCB(const ros::SingleSubscriberPublisher& pub);
00118 
00119         void disparityDisconnectCB(const ros::SingleSubscriberPublisher& pub);
00120 };
00121 
00122 }


cob_image_flip
Author(s): Richard Bormann
autogenerated on Fri Mar 15 2019 03:10:14