32 #include <opencv2/core/core.hpp> 33 #include <opencv2/highgui/highgui.hpp> 39 #include <sensor_msgs/Image.h> 68 buffer_.create(1, 10000000, CV_8U);
83 normalized_image.
header = image->header;
84 normalized_image.encoding = image->encoding;
90 ROS_WARN(
"Unsupported image encoding: %s", image->encoding.c_str());
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
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_
void ImageCallback(const sensor_msgs::ImageConstPtr &image)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
~NormalizeResponseNodelet()
ros::NodeHandle & getPrivateNodeHandle() const
NormalizeResponseNodelet()
void NormalizeResponse(const cv::Mat &src, cv::Mat &dst, int winsize, int ftzero, uchar *buf)
void publish(const sensor_msgs::Image &message) const
SWRI_NODELET_EXPORT_CLASS(swri_image_util, DrawPolygonNodelet)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::NodeHandle & getNodeHandle() const
image_transport::Subscriber image_sub_