Go to the documentation of this file.
34 #include <opencv2/core/core.hpp>
37 #include <sensor_msgs/Image.h>
58 std::vector<double> transform;
68 NODELET_INFO(
"No ~width and ~height parameters given. Output images will be same size as input.");
70 priv.
param(
"transform", transform, transform);
71 if (transform.size() != 9)
73 NODELET_FATAL(
"~transform must be a 9-element list of doubles (3x3 matrix, row major)");
78 m_ = cv::Mat(transform,
true).reshape(0, 3);
95 cv::warpPerspective(cv_image->image, cv_warped->image,
m_,
output_size_, CV_INTER_LANCZOS4);
97 cv_warped->encoding = cv_image->encoding;
98 cv_warped->header = cv_image->header;
#define NODELET_FATAL(...)
ros::NodeHandle & getNodeHandle() const
SWRI_NODELET_EXPORT_CLASS(swri_image_util, DrawPolygonNodelet)
image_transport::Subscriber image_sub_
image_transport::Publisher image_pub_
void handleImage(sensor_msgs::ImageConstPtr const &image)
ros::NodeHandle & getPrivateNodeHandle() const
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
static bool getParam(const ros::NodeHandle &nh, const std::string &name, bool &variable)
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())
bool hasParam(const std::string &key) const
void publish(const sensor_msgs::Image &message) const
#define NODELET_INFO(...)
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())
#define NODELET_INFO_STREAM(...)
swri_image_util
Author(s): Kris Kozak
autogenerated on Fri Aug 2 2024 08:39:19