image_flip.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 //##################
19 //#### includes ####
20 
21 // ROS includes
22 #include <ros/ros.h>
23 
24 // ROS message includes
25 #include <sensor_msgs/Image.h>
26 #include <sensor_msgs/PointCloud2.h>
27 #include <stereo_msgs/DisparityImage.h>
28 #include <tf/transform_listener.h>
29 #include <cob_perception_msgs/Float64ArrayStamped.h>
30 
31 // topics
34 
35 // opencv
36 #include <opencv2/opencv.hpp>
37 #include <cv_bridge/cv_bridge.h>
39 
40 // point cloud
41 #include <pcl/point_types.h>
42 #include <pcl_ros/point_cloud.h>
44 
45 // System
46 #include <iostream>
47 
48 namespace cob_image_flip
49 {
50 class ImageFlip
51 {
52 protected:
53 
54  // parameters
55  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)
56  double rotation_angle_; // image rotation [in deg] (especially efficient with 0, 90, 180, 270 deg)
57  std::string reference_frame_; // reference world coordinate frame with z-axis pointing upwards (= against gravity direction)
58 // 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)
59  bool flip_color_image_; // flip color image
60  bool flip_pointcloud_; // flip point cloud (usually unnecessary because tf takes care of this with original point cloud)
61  bool flip_disparity_image_; // flip disparity image
62  bool display_warnings_; // display warning if transformation not available
63  bool display_timing_; // display timing information
64 
67 
68  // subscriber counters
69  unsigned int img_sub_counter_;
70  unsigned int pc_sub_counter_;
71  unsigned int disparity_sub_counter_;
72 
83 
85 
87 
88 public:
89 
90  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)
91 
93 
94  ~ImageFlip();
95 
96  double determineRotationAngle(const std::string& camera_frame_id, const ros::Time& time);
97 
98  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);
99 
100 
101  void imageCallback(const sensor_msgs::ImageConstPtr& color_image_msg);
102 
104 
106 
107 
108  void pcCallback(const sensor_msgs::PointCloud2::ConstPtr& point_cloud_msg);
109 
111 
113 
114 
115  void disparityCallback(const stereo_msgs::DisparityImage::ConstPtr& disparity_image_msg);
116 
118 
120 };
121 
122 }
ros::Publisher point_cloud_2d_transform_pub_
publisher for the transformation matrix for the in plane rotation and translation in the image plane...
Definition: image_flip.h:75
unsigned int pc_sub_counter_
Definition: image_flip.h:70
void imageCallback(const sensor_msgs::ImageConstPtr &color_image_msg)
Definition: image_flip.cpp:195
ros::Subscriber point_cloud_sub_
point cloud input topic
Definition: image_flip.h:73
ImageFlip(ros::NodeHandle nh)
Definition: image_flip.cpp:26
image_transport::Publisher color_camera_image_pub_
color camera image output topic
Definition: image_flip.h:78
ros::Publisher disparity_image_pub_
disparity image output topic
Definition: image_flip.h:81
void disparityConnectCB(const ros::SingleSubscriberPublisher &pub)
Definition: image_flip.cpp:715
image_transport::ImageTransport * it_
Definition: image_flip.h:76
ros::NodeHandle node_handle_
ROS node handle.
Definition: image_flip.h:86
unsigned int img_sub_counter_
Definition: image_flip.h:69
ros::Publisher color_camera_image_2d_transform_pub_
publisher for the transformation matrix for the in plane rotation and translation in the image plane...
Definition: image_flip.h:79
ros::Publisher point_cloud_pub_
point cloud output topic
Definition: image_flip.h:74
void imgDisconnectCB(const image_transport::SingleSubscriberPublisher &pub)
Definition: image_flip.cpp:335
void pcConnectCB(const ros::SingleSubscriberPublisher &pub)
Definition: image_flip.cpp:559
void pcDisconnectCB(const ros::SingleSubscriberPublisher &pub)
Definition: image_flip.cpp:569
void imgConnectCB(const image_transport::SingleSubscriberPublisher &pub)
Definition: image_flip.cpp:325
image_transport::SubscriberFilter color_camera_image_sub_
color camera image input topic
Definition: image_flip.h:77
void disparityCallback(const stereo_msgs::DisparityImage::ConstPtr &disparity_image_msg)
Definition: image_flip.cpp:584
void pcCallback(const sensor_msgs::PointCloud2::ConstPtr &point_cloud_msg)
Definition: image_flip.cpp:346
unsigned int disparity_sub_counter_
Definition: image_flip.h:71
ros::Subscriber disparity_image_sub_
disparity image input topic
Definition: image_flip.h:80
void disparityDisconnectCB(const ros::SingleSubscriberPublisher &pub)
Definition: image_flip.cpp:725
std::string reference_frame_
Definition: image_flip.h:57
tf::TransformListener transform_listener_
Definition: image_flip.h:84
ros::Publisher disparity_image_2d_transform_pub_
publisher for the transformation matrix for the in plane rotation and translation in the image plane...
Definition: image_flip.h:82
double determineRotationAngle(const std::string &camera_frame_id, const ros::Time &time)
Definition: image_flip.cpp:90
bool convertImageMessageToMat(const sensor_msgs::Image::ConstPtr &color_image_msg, cv_bridge::CvImageConstPtr &color_image_ptr, cv::Mat &color_image)
Definition: image_flip.cpp:178


cob_image_flip
Author(s): Richard Bormann
autogenerated on Sun Oct 18 2020 13:13:18