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 #include <dynamic_reconfigure/server.h>
00049
00050 namespace opencv_apps
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 int queue_size_;
00063 bool debug_view_;
00064
00065 public:
00066 ImageConverter() : it_(nh_)
00067 {
00068
00069 image_sub_ = it_.subscribe("image", queue_size_, &ImageConverter::imageCb, this);
00070 image_pub_ = it_.advertise("/image_converter/output_video/raw", 1);
00071
00072 ros::NodeHandle pnh("~");
00073 pnh.param("queue_size", queue_size_, 1);
00074 pnh.param("debug_view", debug_view_, false);
00075 if (debug_view_)
00076 {
00077 cv::namedWindow(OPENCV_WINDOW);
00078 }
00079 }
00080
00081 ~ImageConverter()
00082 {
00083 if (debug_view_)
00084 {
00085 cv::destroyWindow(OPENCV_WINDOW);
00086 }
00087 }
00088
00089 void imageCb(const sensor_msgs::ImageConstPtr& msg)
00090 {
00091 cv_bridge::CvImagePtr cv_ptr;
00092 try
00093 {
00094 cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
00095 }
00096 catch (cv_bridge::Exception& e)
00097 {
00098 ROS_ERROR("cv_bridge exception: %s", e.what());
00099 return;
00100 }
00101
00102
00103 if (cv_ptr->image.rows > 110 && cv_ptr->image.cols > 110)
00104 cv::circle(cv_ptr->image, cv::Point(cv_ptr->image.cols / 2, cv_ptr->image.rows / 2), 100, CV_RGB(255, 0, 0));
00105
00106 if (debug_view_)
00107 {
00108
00109 cv::imshow(OPENCV_WINDOW, cv_ptr->image);
00110 cv::waitKey(3);
00111 }
00112
00113
00114 image_pub_.publish(cv_ptr->toImageMsg());
00115 }
00116 };
00117
00118 }
00119
00120 class SimpleExampleNodelet : public nodelet::Nodelet
00121 {
00122 public:
00123 virtual void onInit()
00124 {
00125 simple_example::ImageConverter ic;
00126 ros::spin();
00127 }
00128 };
00129
00130 }
00131
00132 namespace simple_example
00133 {
00134 class SimpleExampleNodelet : public opencv_apps::SimpleExampleNodelet
00135 {
00136 public:
00137 virtual void onInit()
00138 {
00139 ROS_WARN("DeprecationWarning: Nodelet simple_example/simple_example is deprecated, "
00140 "and renamed to opencv_apps/simple_example.");
00141 opencv_apps::SimpleExampleNodelet::onInit();
00142 }
00143 };
00144 }
00145
00146 #include <pluginlib/class_list_macros.h>
00147 PLUGINLIB_EXPORT_CLASS(opencv_apps::SimpleExampleNodelet, nodelet::Nodelet);
00148 PLUGINLIB_EXPORT_CLASS(simple_example::SimpleExampleNodelet, nodelet::Nodelet);