35 #include <opencv2/core/core.hpp> 38 #include <sensor_msgs/Image.h> 68 for (
size_t i = 0; i < polygon.
size(); i++)
74 static_cast<int>(x_param),
75 static_cast<int>(y_param)));
95 const cv::Point* points[1] = { &
polygon_[0] };
100 cv::fillPoly(cv_image->image, points, &count, 1, cv::Scalar(
b_,
g_,
r_));
104 cv::polylines(cv_image->image, points, &count, 1,
true, cv::Scalar(
b_,
g_,
r_),
thickness_);
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())
const std::string & getMessage() const
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
image_transport::Publisher image_pub_
std::vector< cv::Point > polygon_
ros::NodeHandle & getPrivateNodeHandle() const
void publish(const sensor_msgs::Image &message) const
void imageCallback(const sensor_msgs::ImageConstPtr &image)
SWRI_NODELET_EXPORT_CLASS(swri_image_util, DrawPolygonNodelet)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
image_transport::Subscriber image_sub_
ros::NodeHandle & getNodeHandle() const
ROSCPP_DECL void requestShutdown()
bool getParam(const std::string &key, std::string &s) const