Go to the documentation of this file.
53 #include "opencv2/imgproc/imgproc.hpp"
54 #include "opencv2/highgui/highgui.hpp"
55 #include "opencv2/features2d/features2d.hpp"
57 #include <dynamic_reconfigure/server.h>
58 #include "opencv_apps/MorphologyConfig.h"
71 typedef opencv_apps::MorphologyConfig
Config;
87 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
94 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
96 doWork(msg, cam_info->header.frame_id);
101 doWork(msg, msg->header.frame_id);
104 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
117 cv::Mat out_image = in_image.clone();
119 int morph_operator =
config_.morph_operator;
120 int morph_element =
config_.morph_element;
121 int morph_size =
config_.morph_size;
123 ROS_DEBUG_STREAM(
"Applying morphology transforms with operator " << morph_operator <<
", element "
124 << morph_element <<
", and size " << morph_size);
126 cv::Mat element = cv::getStructuringElement(morph_element, cv::Size(2 * morph_size + 1, 2 * morph_size + 1),
127 cv::Point(morph_size, morph_size));
130 cv::morphologyEx(in_image, out_image, morph_operator + 2, element);
136 int c = cv::waitKey(1);
143 catch (cv::Exception& e)
145 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
183 dynamic_reconfigure::Server<Config>::CallbackType
f =
201 ROS_WARN(
"DeprecationWarning: Nodelet morphology/morphology is deprecated, "
202 "and renamed to opencv_apps/morphology.");
208 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H
void reconfigureCallback(Config &new_config, uint32_t level)
#define NODELET_ERROR(...)
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
boost::shared_ptr< ReconfigureServer > reconfigure_server_
sensor_msgs::ImagePtr toImageMsg() const
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics.
dynamic_reconfigure::Server< Config > ReconfigureServer
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
#define ROS_DEBUG_STREAM(args)
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)
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
opencv_apps::MorphologyConfig Config
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
image_transport::Publisher img_pub_
void publish(const sensor_msgs::Image &message) const
Demo code to calculate moments.
const ROSCPP_DECL std::string & getName()
image_transport::Subscriber img_sub_
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
boost::shared_ptr< image_transport::ImageTransport > it_
image_transport::CameraSubscriber cam_sub_
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
PLUGINLIB_EXPORT_CLASS(opencv_apps::MorphologyNodelet, nodelet::Nodelet)
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.
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.
#define NODELET_DEBUG(...)
opencv_apps
Author(s): Kei Okada
autogenerated on Fri May 23 2025 02:49:49