simple_example_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2015, Tal Regev.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Kei Okada nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 // http://wiki.ros.org/cv_bridge/Tutorials/UsingCvBridgeToConvertBetweenROSImagesAndOpenCVImages
39 #include <ros/ros.h>
41 #include <nodelet/nodelet.h>
43 #include <cv_bridge/cv_bridge.h>
44 
45 #include <opencv2/highgui/highgui.hpp>
46 #include <opencv2/imgproc/imgproc.hpp>
47 
48 #include <dynamic_reconfigure/server.h>
49 
50 namespace opencv_apps
51 {
52 namespace simple_example
53 {
54 static const std::string OPENCV_WINDOW = "Image window";
55 
57 {
64 
65 public:
66  ImageConverter() : it_(nh_)
67  {
68  // Subscrive to input video feed and publish output video feed
69  image_sub_ = it_.subscribe("image", queue_size_, &ImageConverter::imageCb, this);
70  image_pub_ = it_.advertise("/image_converter/output_video/raw", 1);
71 
72  ros::NodeHandle pnh("~");
73  pnh.param("queue_size", queue_size_, 1);
74  pnh.param("debug_view", debug_view_, false);
75  if (debug_view_)
76  {
77  cv::namedWindow(OPENCV_WINDOW);
78  }
79  }
80 
82  {
83  if (debug_view_)
84  {
85  cv::destroyWindow(OPENCV_WINDOW);
86  }
87  }
88 
89  void imageCb(const sensor_msgs::ImageConstPtr& msg)
90  {
91  cv_bridge::CvImagePtr cv_ptr;
92  try
93  {
95  }
96  catch (cv_bridge::Exception& e)
97  {
98  ROS_ERROR("cv_bridge exception: %s", e.what());
99  return;
100  }
101 
102  // Draw an example circle on the video stream
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));
105 
106  if (debug_view_)
107  {
108  // Update GUI Window
109  cv::imshow(OPENCV_WINDOW, cv_ptr->image);
110  cv::waitKey(3);
111  }
112 
113  // Output modified video stream
114  image_pub_.publish(cv_ptr->toImageMsg());
115  }
116 };
117 
118 } // namespace simple_example
119 
121 {
122 public:
123  virtual void onInit() // NOLINT(modernize-use-override)
124  {
126  ros::spin();
127  }
128 };
129 
130 } // namespace opencv_apps
131 
132 namespace simple_example
133 {
135 {
136 public:
137  virtual void onInit() // NOLINT(modernize-use-override)
138  {
139  ROS_WARN("DeprecationWarning: Nodelet simple_example/simple_example is deprecated, "
140  "and renamed to opencv_apps/simple_example.");
142  }
143 };
144 } // namespace simple_example
145 
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())
Demo code to calculate moments.
Definition: nodelet.h:48
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN(...)
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 &param_name, T &param_val, const T &default_val) const
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define ROS_ERROR(...)


opencv_apps
Author(s): Kei Okada
autogenerated on Sat Aug 22 2020 03:35:08