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);
96 if (config_.use_camera_info)
111 boost::mutex::scoped_lock lock(mutex_);
113 threshold_value_ = config.threshold;
114 threshold_type_ = config.threshold_type;
115 max_binary_value_ = config.max_binary;
116 apply_otsu_ = config.apply_otsu;
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;
130 threshold_type_ |= CV_THRESH_OTSU;
132 cv::threshold(gray_image, result_image, threshold_value_, max_binary_value_, threshold_type_);
136 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
137 cv::imshow(window_name_, 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);
155 pnh_->param(
"queue_size", queue_size_, 3);
156 pnh_->param(
"debug_view", debug_view_,
false);
164 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
165 dynamic_reconfigure::Server<Config>::CallbackType
f =
167 reconfigure_server_->setCallback(f);
182 ROS_WARN(
"DeprecationWarning: Nodelet threshold/threshold is deprecated, " 183 "and renamed to opencv_apps/threshold.");
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define NODELET_ERROR(...)
image_transport::CameraSubscriber cam_sub_
PLUGINLIB_EXPORT_CLASS(opencv_apps::ThresholdNodelet, nodelet::Nodelet)
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
image_transport::Publisher img_pub_
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Demo code to calculate moments.
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.
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
dynamic_reconfigure::Server< Config > ReconfigureServer
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
image_transport::Subscriber img_sub_
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
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
void doWork(const sensor_msgs::Image::ConstPtr &image_msg, const std::string &input_frame_from_msg)
void reconfigureCallback(Config &config, uint32_t level)
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...
boost::shared_ptr< image_transport::ImageTransport > it_
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
opencv_apps::ThresholdConfig Config
#define NODELET_DEBUG(...)
boost::shared_ptr< ReconfigureServer > reconfigure_server_
sensor_msgs::ImagePtr toImageMsg() const
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)