32 #include <opencv2/core/core.hpp> 38 #include <sensor_msgs/Image.h> 87 cv::transpose(cv_image->image, cv_image->image);
88 cv::flip(cv_image->image, cv_image->image,
flip_axis_);
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())
double ToNearest(double value, double multiple)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getPrivateNodeHandle() const
image_transport::Publisher image_pub_
void publish(const sensor_msgs::Image &message) const
image_transport::Subscriber image_sub_
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())
ros::NodeHandle & getNodeHandle() const