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 #include <opencv2/highgui/highgui.hpp>
00009
00010 namespace enc = sensor_msgs::image_encodings;
00011
00012 static const char WINDOW[] = "Image window";
00013
00014 class ImagePainter
00015 {
00016 ros::NodeHandle nh_;
00017 image_transport::ImageTransport it_;
00018 image_transport::Subscriber image_sub_;
00019 image_transport::Publisher image_pub_;
00020
00021 public:
00022 ImagePainter()
00023 : it_(nh_)
00024 {
00025 image_pub_ = it_.advertise("image_painted", 1);
00026 image_sub_ = it_.subscribe("image", 1, &ImagePainter::imageCb, this);
00027
00028 cv::namedWindow(WINDOW);
00029 }
00030
00031 ~ImagePainter()
00032 {
00033 cv::destroyWindow(WINDOW);
00034 }
00035
00036 void imageCb(const sensor_msgs::ImageConstPtr& msg)
00037 {
00038 cv_bridge::CvImagePtr cv_ptr;
00039 try
00040 {
00041 cv_ptr = cv_bridge::toCvCopy(msg, enc::BGR8);
00042 }
00043 catch (cv_bridge::Exception& e)
00044 {
00045 ROS_ERROR("cv_bridge exception: %s", e.what());
00046 return;
00047 }
00048
00049 if (cv_ptr->image.rows > 60 && cv_ptr->image.cols > 60)
00050 cv::circle(cv_ptr->image, cv::Point(30, 50), 10, CV_RGB(0,0,255));
00051
00052 cv::imshow(WINDOW, cv_ptr->image);
00053 cv::waitKey(3);
00054
00055 image_pub_.publish(cv_ptr->toImageMsg());
00056 }
00057 };
00058
00059 int main(int argc, char** argv)
00060 {
00061 ros::init(argc, argv, "image_painter");
00062 ImagePainter ic;
00063 ros::spin();
00064 return 0;
00065 }