48 #include <opencv2/highgui/highgui.hpp> 49 #include <opencv2/imgproc/imgproc.hpp> 51 #include <dynamic_reconfigure/server.h> 52 #include "opencv_apps/GoodfeatureTrackConfig.h" 53 #include "opencv_apps/Point2D.h" 54 #include "opencv_apps/Point2DArrayStamped.h" 67 typedef opencv_apps::GoodfeatureTrackConfig
Config;
84 max_corners_ = config_.max_corners;
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);
106 need_config_update_ =
true;
109 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
118 opencv_apps::Point2DArrayStamped corners_msg;
119 corners_msg.header = msg->header;
123 int max_trackbar = 100;
125 if (frame.channels() > 1)
127 cv::cvtColor(frame, src_gray, cv::COLOR_BGR2GRAY);
132 cv::cvtColor(src_gray, frame, cv::COLOR_GRAY2BGR);
138 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
139 cv::createTrackbar(
"Max corners", window_name_, &max_corners_, max_trackbar,
trackbarCallback);
140 if (need_config_update_)
143 reconfigure_server_->updateConfig(config_);
144 need_config_update_ =
false;
149 if (max_corners_ < 1)
155 std::vector<cv::Point2f> corners;
156 double quality_level = 0.01;
157 double min_distance = 10;
159 bool use_harris_detector =
false;
165 cv::goodFeaturesToTrack(src_gray, corners, max_corners_, quality_level, min_distance, cv::Mat(), block_size,
166 use_harris_detector, k);
171 for (
const cv::Point2f& corner : corners)
173 cv::circle(frame, corner, r, cv::Scalar(rng.uniform(0, 255), rng.uniform(0, 255), rng.uniform(0, 255)), -1, 8,
180 cv::imshow(window_name_, frame);
181 int c = cv::waitKey(1);
185 for (
const cv::Point2f& i : corners)
187 opencv_apps::Point2D corner;
190 corners_msg.points.push_back(corner);
197 catch (cv::Exception& e)
199 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
202 prev_stamp_ = msg->header.stamp;
208 if (config_.use_camera_info)
227 pnh_->param(
"queue_size", queue_size_, 3);
228 pnh_->param(
"debug_view", debug_view_,
false);
235 window_name_ =
"Image";
238 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
239 dynamic_reconfigure::Server<Config>::CallbackType
f =
241 reconfigure_server_->setCallback(f);
244 msg_pub_ = advertise<opencv_apps::Point2DArrayStamped>(*
pnh_,
"corners", 1);
259 ROS_WARN(
"DeprecationWarning: Nodelet goodfeature_track/goodfeature_track is deprecated, " 260 "and renamed to opencv_apps/goodfeature_track.");
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define NODELET_INFO_STREAM(...)
#define NODELET_ERROR(...)
static bool need_config_update_
void publish(const boost::shared_ptr< M > &message) const
PLUGINLIB_EXPORT_CLASS(opencv_apps::GoodfeatureTrackNodelet, nodelet::Nodelet)
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Demo code to calculate moments.
image_transport::Publisher img_pub_
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
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...
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
image_transport::CameraSubscriber cam_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.
boost::shared_ptr< ReconfigureServer > reconfigure_server_
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
static void trackbarCallback(int, void *)
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...
dynamic_reconfigure::Server< Config > ReconfigureServer
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
opencv_apps::GoodfeatureTrackConfig Config
#define NODELET_DEBUG(...)
boost::shared_ptr< image_transport::ImageTransport > it_
sensor_msgs::ImagePtr toImageMsg() const
void imageCallback(const sensor_msgs::ImageConstPtr &msg)