32 #include <opencv2/core/core.hpp> 33 #include <opencv2/imgproc/imgproc.hpp> 39 #include <sensor_msgs/Image.h> 83 cv::resize(cv_image->image, scaled, size);
86 cv_scaled->image = scaled;
87 cv_scaled->encoding = cv_image->encoding;
88 cv_scaled->header = cv_image->header;
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())
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
image_transport::Publisher image_pub_
ros::NodeHandle & getPrivateNodeHandle() const
double Round(double value)
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
image_transport::Subscriber image_sub_
ros::NodeHandle & getNodeHandle() const
void ImageCallback(const sensor_msgs::ImageConstPtr &image)