Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00039 #include <ros/ros.h>
00040 #include <sensor_msgs/image_encodings.h>
00041 #include <nodelet/nodelet.h>
00042 #include <image_transport/image_transport.h>
00043 #include <cv_bridge/cv_bridge.h>
00044
00045 #include <opencv2/highgui/highgui.hpp>
00046 #include <opencv2/imgproc/imgproc.hpp>
00047
00048
00049 #include <dynamic_reconfigure/server.h>
00050
00051
00052 namespace simple_example {
00053
00054 static const std::string OPENCV_WINDOW = "Image window";
00055
00056 class ImageConverter
00057 {
00058 ros::NodeHandle nh_;
00059 image_transport::ImageTransport it_;
00060 image_transport::Subscriber image_sub_;
00061 image_transport::Publisher image_pub_;
00062 bool debug_view_;
00063
00064 public:
00065 ImageConverter()
00066 : it_(nh_)
00067 {
00068
00069 image_sub_ = it_.subscribe("image", 1,
00070 &ImageConverter::imageCb, this);
00071 image_pub_ = it_.advertise("/image_converter/output_video/raw", 1);
00072
00073 ros::NodeHandle pnh_("~");
00074 pnh_.param("debug_view", debug_view_, false);
00075 if( debug_view_) {
00076 cv::namedWindow(OPENCV_WINDOW);
00077 }
00078 }
00079
00080 ~ImageConverter()
00081 {
00082 if( debug_view_) {
00083 cv::destroyWindow(OPENCV_WINDOW);
00084 }
00085 }
00086
00087 void imageCb(const sensor_msgs::ImageConstPtr& msg)
00088 {
00089 cv_bridge::CvImagePtr cv_ptr;
00090 try
00091 {
00092 cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
00093 }
00094 catch (cv_bridge::Exception& e)
00095 {
00096 ROS_ERROR("cv_bridge exception: %s", e.what());
00097 return;
00098 }
00099
00100
00101 if (cv_ptr->image.rows > 110 && cv_ptr->image.cols > 110)
00102 cv::circle(cv_ptr->image, cv::Point(cv_ptr->image.cols/2, cv_ptr->image.rows/2), 100, CV_RGB(255,0,0));
00103
00104 if( debug_view_) {
00105
00106 cv::imshow(OPENCV_WINDOW, cv_ptr->image);
00107 cv::waitKey(3);
00108 }
00109
00110
00111 image_pub_.publish(cv_ptr->toImageMsg());
00112 }
00113 };
00114
00115
00116 class SimpleExampleNodelet : public nodelet::Nodelet
00117 {
00118
00119
00120 public:
00121 virtual void onInit()
00122 {
00123 simple_example::ImageConverter ic;
00124 ros::spin();
00125 }
00126 };
00127
00128 }
00129
00130 #include <pluginlib/class_list_macros.h>
00131 PLUGINLIB_EXPORT_CLASS(simple_example::SimpleExampleNodelet, nodelet::Nodelet);