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