2011/ros11: cv_draw_circle.cpp

File cv_draw_circle.cpp, 1.4 KB (added by cteo, 7 years ago)
Line 
1#include <ros/ros.h>
2#include <image_transport/image_transport.h>
3#include <cv_bridge/cv_bridge.h>
4#include <sensor_msgs/image_encodings.h>
5#include <opencv2/imgproc/imgproc.hpp>
6#include <opencv2/highgui/highgui.hpp>
7
8namespace enc = sensor_msgs::image_encodings;
9
10static const char WINDOW[] = "Image window";
11
12class ImageConverter
13{
14  ros::NodeHandle nh_;
15  image_transport::ImageTransport it_;
16  image_transport::Subscriber image_sub_;
17  image_transport::Publisher image_pub_;
18 
19public:
20  ImageConverter()
21    : it_(nh_)
22  {
23    image_pub_ = it_.advertise("/umd_image_proc/image_umd_cvDrawCircle", 1);
24    image_sub_ = it_.subscribe("/quad/right1/image_raw", 1, &ImageConverter::imageCb, this);
25
26    cv::namedWindow(WINDOW);
27  }
28
29  ~ImageConverter()
30  {
31    cv::destroyWindow(WINDOW);
32  }
33
34  void imageCb(const sensor_msgs::ImageConstPtr& msg)
35  {
36    cv_bridge::CvImagePtr cv_ptr;
37    try
38    {
39      cv_ptr = cv_bridge::toCvCopy(msg, enc::BGR8);
40    }
41    catch (cv_bridge::Exception& e)
42    {
43      ROS_ERROR("cv_bridge exception: %s", e.what());
44      return;
45    }
46
47    if (cv_ptr->image.rows > 60 && cv_ptr->image.cols > 60)
48      cv::circle(cv_ptr->image, cv::Point(50, 50), 10, CV_RGB(255,0,0));
49
50    cv::imshow(WINDOW, cv_ptr->image);
51    cv::waitKey(3);
52   
53    image_pub_.publish(cv_ptr->toImageMsg());
54  }
55};
56
57int main(int argc, char** argv)
58{
59  ros::init(argc, argv, "umd_cvDrawCircle");
60  ImageConverter ic;
61  ros::spin();
62  return 0;
63}