draw_polygon_nodelet.cpp
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
00004 // All rights reserved.
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions are met:
00008 //     * Redistributions of source code must retain the above copyright
00009 //       notice, this list of conditions and the following disclaimer.
00010 //     * Redistributions in binary form must reproduce the above copyright
00011 //       notice, this list of conditions and the following disclaimer in the
00012 //       documentation and/or other materials provided with the distribution.
00013 //     * Neither the name of Southwest Research Institute® (SwRI®) nor the
00014 //       names of its contributors may be used to endorse or promote products
00015 //       derived from this software without specific prior written permission.
00016 //
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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 // Register nodelet plugin
00124 #include <swri_nodelet/class_list_macros.h>
00125 SWRI_NODELET_EXPORT_CLASS(swri_image_util, DrawPolygonNodelet);


swri_image_util
Author(s): Kris Kozak
autogenerated on Thu Jun 6 2019 20:34:52