Go to the documentation of this file.
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;
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);
115 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
126 char kernel_label[] =
"Kernel Size : ";
139 cv::Mat out_image = in_image.clone();
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);
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);
226 dynamic_reconfigure::Server<Config>::CallbackType
f =
245 ROS_WARN(
"DeprecationWarning: Nodelet smoothing/smoothing is deprecated, "
246 "and renamed to opencv_apps/smoothing.");
252 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
#define NODELET_ERROR(...)
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
sensor_msgs::ImagePtr toImageMsg() const
image_transport::Publisher img_pub_
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics.
opencv_apps::SmoothingConfig Config
int MAX_KERNEL_LENGTH
Global Variables.
#define ROS_DEBUG_STREAM(args)
void reconfigureCallback(Config &new_config, uint32_t level)
boost::shared_ptr< ReconfigureServer > reconfigure_server_
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....
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
PLUGINLIB_EXPORT_CLASS(opencv_apps::SmoothingNodelet, nodelet::Nodelet)
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
void publish(const sensor_msgs::Image &message) const
Demo code to calculate moments.
boost::shared_ptr< image_transport::ImageTransport > it_
dynamic_reconfigure::Server< Config > ReconfigureServer
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
static void trackbarCallback(int, void *)
image_transport::CameraSubscriber cam_sub_
image_transport::Subscriber img_sub_
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
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.
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
static bool need_config_update_
#define NODELET_DEBUG(...)
opencv_apps
Author(s): Kei Okada
autogenerated on Fri May 23 2025 02:49:49