45 #include <opencv2/highgui/highgui.hpp> 46 #include <opencv2/imgproc/imgproc.hpp> 48 #include <dynamic_reconfigure/server.h> 70 image_pub_ = it_.
advertise(
"/image_converter/output_video/raw", 1);
73 pnh.
param(
"queue_size", queue_size_, 1);
74 pnh.
param(
"debug_view", debug_view_,
false);
77 cv::namedWindow(OPENCV_WINDOW);
85 cv::destroyWindow(OPENCV_WINDOW);
89 void imageCb(
const sensor_msgs::ImageConstPtr& msg)
98 ROS_ERROR(
"cv_bridge exception: %s", e.what());
103 if (cv_ptr->image.rows > 110 && cv_ptr->image.cols > 110)
104 cv::circle(cv_ptr->image, cv::Point(cv_ptr->image.cols / 2, cv_ptr->image.rows / 2), 100, CV_RGB(255, 0, 0));
109 cv::imshow(OPENCV_WINDOW, cv_ptr->image);
114 image_pub_.
publish(cv_ptr->toImageMsg());
139 ROS_WARN(
"DeprecationWarning: Nodelet simple_example/simple_example is deprecated, " 140 "and renamed to opencv_apps/simple_example.");
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())
image_transport::ImageTransport it_
Demo code to calculate moments.
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
image_transport::Subscriber image_sub_
ROSCPP_DECL void spin(Spinner &spinner)
PLUGINLIB_EXPORT_CLASS(opencv_apps::SimpleExampleNodelet, nodelet::Nodelet)
static const std::string OPENCV_WINDOW
void imageCb(const sensor_msgs::ImageConstPtr &msg)
void publish(const sensor_msgs::Image &message) const
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())
image_transport::Publisher image_pub_