Go to the documentation of this file.
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());
ros::NodeHandle & getNodeHandle() const
SWRI_NODELET_EXPORT_CLASS(swri_image_util, DrawPolygonNodelet)
sensor_msgs::ImagePtr toImageMsg() const
image_transport::Subscriber image_sub_
~NormalizeResponseNodelet()
ros::NodeHandle & getPrivateNodeHandle() const
NormalizeResponseNodelet()
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
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())
void publish(const sensor_msgs::Image &message) const
void ImageCallback(const sensor_msgs::ImageConstPtr &image)
T param(const std::string ¶m_name, const T &default_val) const
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
void NormalizeResponse(const cv::Mat &src, cv::Mat &dst, int winsize, int ftzero, uchar *buf)
image_transport::Publisher image_pub_
swri_image_util
Author(s): Kris Kozak
autogenerated on Fri Aug 2 2024 08:39:19