52 #include "opencv2/imgproc/imgproc.hpp" 53 #include "opencv2/highgui/highgui.hpp" 54 #include "opencv2/features2d/features2d.hpp" 56 #include <dynamic_reconfigure/server.h> 57 #include "opencv_apps/SmoothingConfig.h" 73 typedef opencv_apps::SmoothingConfig
Config;
90 kernel_size_ = (config_.kernel_size / 2) * 2 + 1;
93 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
102 doWork(msg, cam_info->header.frame_id);
107 doWork(msg, msg->header.frame_id);
112 need_config_update_ =
true;
115 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
126 char kernel_label[] =
"Kernel Size : ";
128 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
130 if (need_config_update_)
132 kernel_size_ = (kernel_size_ / 2) * 2 + 1;
134 reconfigure_server_->updateConfig(config_);
135 need_config_update_ =
false;
139 cv::Mat out_image = in_image.clone();
141 switch (config_.filter_type)
143 case opencv_apps::Smoothing_Homogeneous_Blur:
147 cv::blur(in_image, out_image, cv::Size(i, i), cv::Point(-1, -1));
150 case opencv_apps::Smoothing_Gaussian_Blur:
154 cv::GaussianBlur(in_image, out_image, cv::Size(i, i), 0, 0);
157 case opencv_apps::Smoothing_Median_Blur:
161 cv::medianBlur(in_image, out_image, i);
164 case opencv_apps::Smoothing_Bilateral_Filter:
168 cv::bilateralFilter(in_image, out_image, i, i * 2, i / 2);
176 cv::imshow(window_name_, out_image);
177 int c = cv::waitKey(1);
184 catch (cv::Exception& e)
186 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
189 prev_stamp_ = msg->header.stamp;
195 if (config_.use_camera_info)
214 pnh_->param(
"queue_size", queue_size_, 3);
215 pnh_->param(
"debug_view", debug_view_,
false);
222 window_name_ =
"Smoothing Demo";
225 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
226 dynamic_reconfigure::Server<Config>::CallbackType
f =
228 reconfigure_server_->setCallback(f);
245 ROS_WARN(
"DeprecationWarning: Nodelet smoothing/smoothing is deprecated, " 246 "and renamed to opencv_apps/smoothing.");
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
int MAX_KERNEL_LENGTH
Global Variables.
#define NODELET_ERROR(...)
static void trackbarCallback(int, void *)
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
dynamic_reconfigure::Server< Config > ReconfigureServer
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
void reconfigureCallback(Config &new_config, uint32_t level)
Demo code to calculate moments.
PLUGINLIB_EXPORT_CLASS(opencv_apps::SmoothingNodelet, nodelet::Nodelet)
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
opencv_apps::SmoothingConfig Config
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
void publish(const sensor_msgs::Image &message) const
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
image_transport::Publisher img_pub_
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
image_transport::CameraSubscriber cam_sub_
#define ROS_DEBUG_STREAM(args)
static bool need_config_update_
image_transport::Subscriber img_sub_
boost::shared_ptr< image_transport::ImageTransport > it_
image_transport::Publisher advertiseImage(ros::NodeHandle &nh, const std::string &topic, int queue_size)
Advertise an image topic and watch the publisher. Publishers which are created by this method...
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const
boost::shared_ptr< ReconfigureServer > reconfigure_server_