draw_polygon_nodelet.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
30 #include <string>
31 
32 #include <cv_bridge/cv_bridge.h>
34 #include <nodelet/nodelet.h>
35 #include <opencv2/core/core.hpp>
36 #include <ros/ros.h>
38 #include <sensor_msgs/Image.h>
39 #include <XmlRpcException.h>
40 
41 namespace swri_image_util
42 {
44  {
45  public:
47  thickness_(-1),
48  r_(0),
49  g_(0),
50  b_(0)
51  {
52  }
53 
54  void onInit()
55  {
58 
59  priv.param("thickness", thickness_, thickness_);
60  priv.param("r", r_, r_);
61  priv.param("g", g_, g_);
62  priv.param("b", b_, b_);
63 
64  try
65  {
66  XmlRpc::XmlRpcValue polygon;
67  priv.getParam("polygon", polygon);
68  for (size_t i = 0; i < polygon.size(); i++)
69  {
70  const XmlRpc::XmlRpcValue& point = polygon[i];
71  XmlRpc::XmlRpcValue x_param = point[0];
72  XmlRpc::XmlRpcValue y_param = point[1];
73  polygon_.push_back(cv::Point(
74  static_cast<int>(x_param),
75  static_cast<int>(y_param)));
76  }
77  }
78  catch (XmlRpc::XmlRpcException& e)
79  {
80  ROS_ERROR("Failed to parse polygon: %s", e.getMessage().c_str());
82  return;
83  }
84 
85 
87  image_pub_ = it.advertise("image_out", 1);
88  image_sub_ = it.subscribe("image_in", 1, &DrawPolygonNodelet::imageCallback, this);
89  }
90 
91  void imageCallback(const sensor_msgs::ImageConstPtr& image)
92  {
94 
95  const cv::Point* points[1] = { &polygon_[0] };
96  int count = polygon_.size();
97 
98  if (thickness_ < 1)
99  {
100  cv::fillPoly(cv_image->image, points, &count, 1, cv::Scalar(b_, g_, r_));
101  }
102  else
103  {
104  cv::polylines(cv_image->image, points, &count, 1, true, cv::Scalar(b_, g_, r_), thickness_);
105  }
106 
107  image_pub_.publish(cv_image->toImageMsg());
108  }
109 
110  private:
112  int r_;
113  int g_;
114  int b_;
115 
116  std::vector<cv::Point> polygon_;
117 
120  };
121 }
122 
123 // Register nodelet plugin
125 SWRI_NODELET_EXPORT_CLASS(swri_image_util, DrawPolygonNodelet);
XmlRpc::XmlRpcValue::size
int size() const
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
image_encodings.h
SWRI_NODELET_EXPORT_CLASS
SWRI_NODELET_EXPORT_CLASS(swri_image_util, DrawPolygonNodelet)
image_transport::ImageTransport
boost::shared_ptr
XmlRpc::XmlRpcException::getMessage
const std::string & getMessage() const
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
swri_image_util::DrawPolygonNodelet::imageCallback
void imageCallback(const sensor_msgs::ImageConstPtr &image)
Definition: draw_polygon_nodelet.cpp:91
swri_image_util::DrawPolygonNodelet
Definition: draw_polygon_nodelet.cpp:43
swri_image_util::DrawPolygonNodelet::polygon_
std::vector< cv::Point > polygon_
Definition: draw_polygon_nodelet.cpp:116
swri_image_util::DrawPolygonNodelet::image_pub_
image_transport::Publisher image_pub_
Definition: draw_polygon_nodelet.cpp:119
swri_image_util
Definition: draw_util.h:37
swri_image_util::DrawPolygonNodelet::b_
int b_
Definition: draw_polygon_nodelet.cpp:114
swri_image_util::DrawPolygonNodelet::thickness_
int thickness_
Definition: draw_polygon_nodelet.cpp:111
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::requestShutdown
ROSCPP_DECL void requestShutdown()
image_transport::ImageTransport::advertise
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
image_transport::Subscriber
class_list_macros.h
swri_image_util::DrawPolygonNodelet::r_
int r_
Definition: draw_polygon_nodelet.cpp:112
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
image_transport::ImageTransport::subscribe
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
swri_image_util::DrawPolygonNodelet::g_
int g_
Definition: draw_polygon_nodelet.cpp:113
swri_image_util::DrawPolygonNodelet::image_sub_
image_transport::Subscriber image_sub_
Definition: draw_polygon_nodelet.cpp:118
swri_image_util::DrawPolygonNodelet::onInit
void onInit()
Definition: draw_polygon_nodelet.cpp:54
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
image_transport.h
XmlRpc::XmlRpcException
nodelet::Nodelet
nodelet.h
image_transport::Publisher
cv_bridge.h
ROS_ERROR
#define ROS_ERROR(...)
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
XmlRpcException.h
swri_image_util::DrawPolygonNodelet::DrawPolygonNodelet
DrawPolygonNodelet()
Definition: draw_polygon_nodelet.cpp:46
XmlRpc::XmlRpcValue
ros::NodeHandle


swri_image_util
Author(s): Kris Kozak
autogenerated on Fri Aug 2 2024 08:39:19