Go to the documentation of this file.
46 #include <opencv2/highgui/highgui.hpp>
47 #include "opencv2/imgproc/imgproc.hpp"
50 #include "opencv_apps/ThresholdConfig.h"
52 #include <dynamic_reconfigure/server.h>
61 typedef opencv_apps::ThresholdConfig
Config;
83 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
85 doWork(msg, cam_info->header.frame_id);
90 doWork(msg, msg->header.frame_id);
111 boost::mutex::scoped_lock lock(
mutex_);
119 void doWork(
const sensor_msgs::Image::ConstPtr& image_msg,
const std::string& input_frame_from_msg)
125 cv::cvtColor(src_image, gray_image, cv::COLOR_BGR2GRAY);
126 cv::Mat result_image;
138 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);
165 dynamic_reconfigure::Server<Config>::CallbackType
f =
182 ROS_WARN(
"DeprecationWarning: Nodelet threshold/threshold is deprecated, "
183 "and renamed to opencv_apps/threshold.");
189 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H
#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::CameraSubscriber cam_sub_
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
opencv_apps::ThresholdConfig Config
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics.
dynamic_reconfigure::Server< Config > ReconfigureServer
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.
image_transport::Publisher img_pub_
void doWork(const sensor_msgs::Image::ConstPtr &image_msg, const std::string &input_frame_from_msg)
image_transport::Subscriber img_sub_
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....
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.
PLUGINLIB_EXPORT_CLASS(opencv_apps::ThresholdNodelet, nodelet::Nodelet)
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
void reconfigureCallback(Config &config, uint32_t level)
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
boost::shared_ptr< image_transport::ImageTransport > it_
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.
#define NODELET_DEBUG(...)
boost::shared_ptr< ReconfigureServer > reconfigure_server_
opencv_apps
Author(s): Kei Okada
autogenerated on Fri May 23 2025 02:49:49