32 #include <opencv2/core/core.hpp> 33 #include <opencv2/highgui/highgui.hpp> 34 #include <opencv2/imgproc/imgproc.hpp> 40 #include <sensor_msgs/Image.h> 70 const int h = cv_image->image.rows;
71 const int w = cv_image->image.cols;
73 const cv::Scalar black(0, 0, 0);
74 const int thickness = 3;
75 const int line_type = 8;
77 cv::line(cv_image->image, cv::Point(0, w/2), cv::Point(h-1, w/2), black, thickness, line_type);
79 cv::line(cv_image->image, cv::Point(h/2, 0), cv::Point(h/2, w-1), black, thickness, line_type);
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())
image_transport::Publisher image_pub_
ros::NodeHandle & getNodeHandle() const
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getPrivateNodeHandle() const
image_transport::Subscriber image_sub_
SWRI_NODELET_EXPORT_CLASS(swri_image_util, DrawPolygonNodelet)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void ImageCallback(const sensor_msgs::ImageConstPtr &image)
void publish(const sensor_msgs::Image &message) const