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 #include <string>
00031
00032 #include <opencv2/core/core.hpp>
00033 #include <opencv2/highgui/highgui.hpp>
00034 #include <opencv2/imgproc/imgproc.hpp>
00035
00036 #include <ros/ros.h>
00037 #include <nodelet/nodelet.h>
00038 #include <image_transport/image_transport.h>
00039 #include <sensor_msgs/image_encodings.h>
00040 #include <sensor_msgs/Image.h>
00041 #include <cv_bridge/cv_bridge.h>
00042
00043 namespace swri_image_util
00044 {
00045 class CrosshairsNodelet : public nodelet::Nodelet
00046 {
00047 public:
00048 CrosshairsNodelet()
00049 {
00050 }
00051
00052 ~CrosshairsNodelet()
00053 {
00054 }
00055
00056 void onInit()
00057 {
00058 ros::NodeHandle &node = getNodeHandle();
00059 ros::NodeHandle &priv = getPrivateNodeHandle();
00060
00061 image_transport::ImageTransport it(node);
00062 image_pub_ = it.advertise("crosshairs_image", 1);
00063 image_sub_ = it.subscribe("image", 1, &CrosshairsNodelet::ImageCallback, this);
00064 }
00065
00066 void ImageCallback(const sensor_msgs::ImageConstPtr& image)
00067 {
00068 cv_bridge::CvImagePtr cv_image = cv_bridge::toCvCopy(image);
00069
00070 const int h = cv_image->image.rows;
00071 const int w = cv_image->image.cols;
00072
00073 const cv::Scalar black(0, 0, 0);
00074 const int thickness = 3;
00075 const int line_type = 8;
00076
00077 cv::line(cv_image->image, cv::Point(0, w/2), cv::Point(h-1, w/2), black, thickness, line_type);
00078
00079 cv::line(cv_image->image, cv::Point(h/2, 0), cv::Point(h/2, w-1), black, thickness, line_type);
00080
00081 image_pub_.publish(cv_image->toImageMsg());
00082 }
00083
00084 private:
00085 image_transport::Subscriber image_sub_;
00086 image_transport::Publisher image_pub_;
00087 };
00088 }
00089
00090
00091 #include <swri_nodelet/class_list_macros.h>
00092 SWRI_NODELET_EXPORT_CLASS(swri_image_util, CrosshairsNodelet)