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 <cv_bridge/cv_bridge.h>
00033 #include <image_transport/image_transport.h>
00034 #include <nodelet/nodelet.h>
00035 #include <opencv2/core/core.hpp>
00036 #include <ros/ros.h>
00037 #include <sensor_msgs/image_encodings.h>
00038 #include <sensor_msgs/Image.h>
00039 #include <XmlRpcException.h>
00040
00041 namespace swri_image_util
00042 {
00043 class DrawPolygonNodelet : public nodelet::Nodelet
00044 {
00045 public:
00046 DrawPolygonNodelet() :
00047 thickness_(-1),
00048 r_(0),
00049 g_(0),
00050 b_(0)
00051 {
00052 }
00053
00054 void onInit()
00055 {
00056 ros::NodeHandle &node = getNodeHandle();
00057 ros::NodeHandle &priv = getPrivateNodeHandle();
00058
00059 priv.param("thickness", thickness_, thickness_);
00060 priv.param("r", r_, r_);
00061 priv.param("g", g_, g_);
00062 priv.param("b", b_, b_);
00063
00064 try
00065 {
00066 XmlRpc::XmlRpcValue polygon;
00067 priv.getParam("polygon", polygon);
00068 for (size_t i = 0; i < polygon.size(); i++)
00069 {
00070 const XmlRpc::XmlRpcValue& point = polygon[i];
00071 XmlRpc::XmlRpcValue x_param = point[0];
00072 XmlRpc::XmlRpcValue y_param = point[1];
00073 polygon_.push_back(cv::Point(
00074 static_cast<int>(x_param),
00075 static_cast<int>(y_param)));
00076 }
00077 }
00078 catch (XmlRpc::XmlRpcException& e)
00079 {
00080 ROS_ERROR("Failed to parse polygon: %s", e.getMessage().c_str());
00081 ros::requestShutdown();
00082 return;
00083 }
00084
00085
00086 image_transport::ImageTransport it(node);
00087 image_pub_ = it.advertise("image_out", 1);
00088 image_sub_ = it.subscribe("image_in", 1, &DrawPolygonNodelet::imageCallback, this);
00089 }
00090
00091 void imageCallback(const sensor_msgs::ImageConstPtr& image)
00092 {
00093 cv_bridge::CvImagePtr cv_image = cv_bridge::toCvCopy(image);
00094
00095 const cv::Point* points[1] = { &polygon_[0] };
00096 int count = polygon_.size();
00097
00098 if (thickness_ < 1)
00099 {
00100 cv::fillPoly(cv_image->image, points, &count, 1, cv::Scalar(b_, g_, r_));
00101 }
00102 else
00103 {
00104 cv::polylines(cv_image->image, points, &count, 1, true, cv::Scalar(b_, g_, r_), thickness_);
00105 }
00106
00107 image_pub_.publish(cv_image->toImageMsg());
00108 }
00109
00110 private:
00111 int thickness_;
00112 int r_;
00113 int g_;
00114 int b_;
00115
00116 std::vector<cv::Point> polygon_;
00117
00118 image_transport::Subscriber image_sub_;
00119 image_transport::Publisher image_pub_;
00120 };
00121 }
00122
00123
00124 #include <swri_nodelet/class_list_macros.h>
00125 SWRI_NODELET_EXPORT_CLASS(swri_image_util, DrawPolygonNodelet);