41 #include <opencv2/highgui/highgui.hpp> 42 #include <opencv2/imgproc/imgproc.hpp> 44 #include <dynamic_reconfigure/server.h> 45 #include "opencv_apps/CornerHarrisConfig.h" 65 typedef opencv_apps::CornerHarrisConfig
Config;
81 threshold_ = config_.threshold;
84 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
91 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
93 doWork(msg, cam_info->header.frame_id);
98 doWork(msg, msg->header.frame_id);
103 need_config_update_ =
true;
106 void doWork(
const sensor_msgs::ImageConstPtr& image_msg,
const std::string& input_frame_from_msg)
115 cv::Mat dst, dst_norm, dst_norm_scaled;
116 dst = cv::Mat::zeros(frame.size(), CV_32FC1);
120 if (frame.channels() > 1)
122 cv::cvtColor(frame, src_gray, cv::COLOR_BGR2GRAY);
127 cv::cvtColor(src_gray, frame, cv::COLOR_GRAY2BGR);
132 int aperture_size = 3;
136 cv::cornerHarris(src_gray, dst, block_size, aperture_size, k, cv::BORDER_DEFAULT);
139 cv::normalize(dst, dst_norm, 0, 255, cv::NORM_MINMAX, CV_32FC1, cv::Mat());
140 cv::convertScaleAbs(dst_norm, dst_norm_scaled);
143 for (
int j = 0; j < dst_norm.rows; j++)
145 for (
int i = 0; i < dst_norm.cols; i++)
147 if ((
int)dst_norm.at<
float>(j, i) > threshold_)
149 cv::circle(frame, cv::Point(i, j), 5, cv::Scalar(0), 2, 8, 0);
157 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
158 const int max_threshold = 255;
159 if (need_config_update_)
162 reconfigure_server_->updateConfig(config_);
163 need_config_update_ =
false;
165 cv::createTrackbar(
"Threshold:", window_name_, &threshold_, max_threshold,
trackbarCallback);
170 cv::imshow(window_name_, frame);
171 int c = cv::waitKey(1);
175 sensor_msgs::Image::Ptr out_img =
179 catch (cv::Exception& e)
181 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
188 if (config_.use_camera_info)
207 pnh_->param(
"queue_size", queue_size_, 3);
208 pnh_->param(
"debug_view", debug_view_,
false);
215 window_name_ =
"CornerHarris Demo";
217 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
218 dynamic_reconfigure::Server<Config>::CallbackType
f =
220 reconfigure_server_->setCallback(f);
237 ROS_WARN(
"DeprecationWarning: Nodelet corner_harris/corner_harris is deprecated, " 238 "and renamed to opencv_apps/corner_harris.");
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, 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...
#define NODELET_ERROR(...)
void doWork(const sensor_msgs::ImageConstPtr &image_msg, const std::string &input_frame_from_msg)
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
static bool need_config_update_
Demo code to calculate moments.
boost::shared_ptr< ReconfigureServer > reconfigure_server_
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
image_transport::CameraSubscriber cam_sub_
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
opencv_apps::CornerHarrisConfig Config
image_transport::Publisher img_pub_
image_transport::Subscriber img_sub_
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
static void trackbarCallback(int, void *)
dynamic_reconfigure::Server< Config > ReconfigureServer
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
void reconfigureCallback(Config &new_config, uint32_t level)
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
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...
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
boost::shared_ptr< image_transport::ImageTransport > it_
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
PLUGINLIB_EXPORT_CLASS(opencv_apps::CornerHarrisNodelet, nodelet::Nodelet)