Go to the documentation of this file.00001
00002
00003 #include <ros/ros.h>
00004 #include <image_transport/image_transport.h>
00005 #include <cv_bridge/cv_bridge.h>
00006 #include <sensor_msgs/image_encodings.h>
00007 #include <opencv2/imgproc/imgproc.hpp>
00008
00009 namespace enc = sensor_msgs::image_encodings;
00010
00011 class ImageFlip
00012 {
00013 ros::NodeHandle nh_;
00014 image_transport::ImageTransport it_;
00015 image_transport::Subscriber image_sub_;
00016 image_transport::Publisher image_pub_;
00017
00018 public:
00019 ImageFlip()
00020 : it_(nh_)
00021 {
00022 image_pub_ = it_.advertise("image_rotated", 1);
00023 image_sub_ = it_.subscribe("image", 1, &ImageFlip::imageCb, this);
00024 }
00025
00026 ~ImageFlip()
00027 {
00028 }
00029
00030 void imageCb(const sensor_msgs::ImageConstPtr& msg)
00031 {
00032 cv_bridge::CvImagePtr cv_ptr;
00033 try
00034 {
00035 cv_ptr = cv_bridge::toCvCopy(msg, enc::BGR8);
00036 }
00037 catch (cv_bridge::Exception& e)
00038 {
00039 ROS_ERROR("cv_bridge exception: %s", e.what());
00040 return;
00041 }
00042 cv::Mat out = cv_ptr->image.clone();
00043
00046 cv::flip(cv_ptr->image, out, 0);
00049
00050
00051
00052 cv_bridge::CvImage out_msg;
00053 out_msg.header = msg->header;
00054 out_msg.encoding = sensor_msgs::image_encodings::RGB8;
00055 out_msg.image = out;
00056
00057 image_pub_.publish(out_msg.toImageMsg());
00058 }
00059 };
00060
00061 int main(int argc, char** argv)
00062 {
00063 ros::init(argc, argv, "image_converter");
00064 ImageFlip ic;
00065 ros::spin();
00066 return 0;
00067 }