32 #include <boost/make_shared.hpp> 38 #include <opencv2/core/core.hpp> 39 #include <opencv2/highgui/highgui.hpp> 42 #include <sensor_msgs/Image.h> 64 std::string image_file;
65 swri::param(priv,
"image_file", image_file, image_file);
72 rate = std::max(0.1, rate);
82 cv_image.
image = cv::imread(image_file, CV_LOAD_IMAGE_GRAYSCALE);
void publish(const ros::TimerEvent &e)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getPrivateNodeHandle() const
void publish(const sensor_msgs::Image &message) const
static void param(const ros::NodeHandle &nh, const std::string &name, int &variable, const int default_value)
SWRI_NODELET_EXPORT_CLASS(swri_image_util, DrawPolygonNodelet)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
ros::NodeHandle & getNodeHandle() const
cv_bridge::CvImage cv_image
image_transport::Publisher image_pub_
ROSCPP_DECL void requestShutdown()
void initialize(const ros::TimerEvent &unused)
sensor_msgs::ImagePtr toImageMsg() const