51 #include <opencv2/video/tracking.hpp> 52 #include <opencv2/highgui/highgui.hpp> 53 #include <opencv2/imgproc/imgproc.hpp> 55 #include <dynamic_reconfigure/server.h> 56 #include "opencv_apps/CamShiftConfig.h" 57 #include "opencv_apps/RotatedRectStamped.h" 70 typedef opencv_apps::CamShiftConfig
Config;
102 static void onMouse(
int event,
int x,
int y,
int ,
void* )
104 on_mouse_update_ =
true;
105 on_mouse_event_ = event;
112 config_ = new_config;
113 vmin_ = config_.vmin;
114 vmax_ = config_.vmax;
115 smin_ = config_.smin;
118 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
127 doWork(msg, cam_info->header.frame_id);
132 doWork(msg, msg->header.frame_id);
137 need_config_update_ =
true;
140 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
150 opencv_apps::RotatedRectStamped rect_msg;
151 rect_msg.header = msg->header;
159 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
161 cv::setMouseCallback(window_name_,
onMouse,
nullptr);
166 if (need_config_update_)
168 config_.vmin =
vmin_;
169 config_.vmax =
vmax_;
170 config_.smin =
smin_;
171 reconfigure_server_->updateConfig(config_);
172 need_config_update_ =
false;
176 if (on_mouse_update_)
184 selection.x = MIN(x, origin.x);
185 selection.y = MIN(y, origin.y);
186 selection.width = std::abs(x - origin.x);
187 selection.height = std::abs(y - origin.y);
189 selection &= cv::Rect(0, 0, frame.cols, frame.rows);
194 case cv::EVENT_LBUTTONDOWN:
195 origin = cv::Point(x, y);
196 selection = cv::Rect(x, y, 0, 0);
199 case cv::EVENT_LBUTTONUP:
200 selectObject =
false;
201 if (selection.width > 0 && selection.height > 0)
205 on_mouse_update_ =
false;
210 cv::Mat hsv, hue, mask;
211 cv::cvtColor(frame, hsv, cv::COLOR_BGR2HSV);
217 cv::inRange(hsv, cv::Scalar(0, smin_, MIN(vmin, vmax)), cv::Scalar(180, 256, MAX(vmin, vmax)), mask);
219 hue.create(hsv.size(), hsv.depth());
220 cv::mixChannels(&hsv, 1, &hue, 1, ch, 1);
224 cv::Mat roi(hue, selection), maskroi(mask, selection);
225 cv::calcHist(&roi, 1,
nullptr, maskroi, hist, 1, &hsize, &phranges);
226 cv::normalize(hist, hist, 0, 255, cv::NORM_MINMAX);
227 std::vector<float> hist_value;
228 hist_value.resize(hsize);
229 for (
int i = 0; i <
hsize; i++)
231 hist_value[i] = hist.at<
float>(i);
233 pnh_->setParam(
"histogram", hist_value);
238 histimg = cv::Scalar::all(0);
239 int bin_w = histimg.cols /
hsize;
240 cv::Mat buf(1, hsize, CV_8UC3);
241 for (
int i = 0; i <
hsize; i++)
242 buf.at<cv::Vec3b>(i) = cv::Vec3b(cv::saturate_cast<uchar>(i * 180. / hsize), 255, 255);
243 cv::cvtColor(buf, buf, cv::COLOR_HSV2BGR);
245 for (
int i = 0; i <
hsize; i++)
247 int val = cv::saturate_cast<
int>(hist.at<
float>(i) * histimg.rows / 255);
248 cv::rectangle(histimg, cv::Point(i * bin_w, histimg.rows), cv::Point((i + 1) * bin_w, histimg.rows - val),
249 cv::Scalar(buf.at<cv::Vec3b>(i)), -1, 8);
253 cv::calcBackProject(&hue, 1,
nullptr, hist, backproj, &phranges);
255 cv::RotatedRect track_box = cv::CamShift(
256 backproj, trackWindow, cv::TermCriteria(cv::TermCriteria::EPS + cv::TermCriteria::MAX_ITER, 10, 1));
257 if (trackWindow.area() <= 1)
259 int cols = backproj.cols, rows = backproj.rows, r = (MIN(cols, rows) + 5) / 6;
262 trackWindow = cv::Rect(cols / 2 - r, rows / 2 - r, cols / 2 + r, rows / 2 + r) & cv::Rect(0, 0, cols, rows);
266 cv::cvtColor(backproj, frame, cv::COLOR_GRAY2BGR);
267 #ifndef CV_VERSION_EPOCH 268 cv::ellipse(frame, track_box, cv::Scalar(0, 0, 255), 3, cv::LINE_AA);
270 cv::ellipse(frame, track_box, cv::Scalar(0, 0, 255), 3, CV_AA);
273 rect_msg.rect.angle = track_box.angle;
274 opencv_apps::Point2D point_msg;
275 opencv_apps::Size size_msg;
276 point_msg.x = track_box.center.x;
277 point_msg.y = track_box.center.y;
278 size_msg.width = track_box.size.width;
279 size_msg.height = track_box.size.height;
280 rect_msg.rect.center = point_msg;
281 rect_msg.rect.size = size_msg;
284 else if (trackObject < 0)
287 if (selectObject && selection.width > 0 && selection.height > 0)
289 cv::Mat roi(frame, selection);
290 bitwise_not(roi, roi);
295 cv::imshow(window_name_, frame);
296 cv::imshow(histogram_name_, histimg);
298 char c = (char)cv::waitKey(1);
308 histimg = cv::Scalar::all(0);
313 cv::destroyWindow(histogram_name_);
315 cv::namedWindow(histogram_name_, 1);
326 sensor_msgs::Image::Ptr out_img2 =
333 catch (cv::Exception& e)
335 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
338 prev_stamp_ = msg->header.stamp;
344 if (config_.use_camera_info)
363 pnh_->param(
"queue_size", queue_size_, 3);
364 pnh_->param(
"debug_view", debug_view_,
false);
371 window_name_ =
"CamShift Demo";
372 histogram_name_ =
"Histogram";
377 backprojMode =
false;
378 selectObject =
false;
387 histimg = cv::Mat::zeros(200, 320, CV_8UC3);
389 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
390 dynamic_reconfigure::Server<Config>::CallbackType
f =
392 reconfigure_server_->setCallback(f);
396 msg_pub_ = advertise<opencv_apps::RotatedRectStamped>(*
pnh_,
"track_box", 1);
399 NODELET_INFO(
"\tESC - quit the program");
400 NODELET_INFO(
"\tc - stop the tracking");
401 NODELET_INFO(
"\tb - switch to/from backprojection view");
402 NODELET_INFO(
"\th - show/hide object histogram");
403 NODELET_INFO(
"\tp - pause video");
404 NODELET_INFO(
"To initialize tracking, select the object with mouse");
406 std::vector<float> hist_value;
407 pnh_->getParam(
"histogram", hist_value);
408 if (hist_value.size() ==
hsize)
410 hist.create(hsize, 1, CV_32F);
411 for (
int i = 0; i <
hsize; i++)
413 hist.at<
float>(i) = hist_value[i];
416 trackWindow = cv::Rect(0, 0, 640, 480);
418 histimg = cv::Scalar::all(0);
419 int bin_w = histimg.cols /
hsize;
420 cv::Mat buf(1, hsize, CV_8UC3);
421 for (
int i = 0; i <
hsize; i++)
422 buf.at<cv::Vec3b>(i) = cv::Vec3b(cv::saturate_cast<uchar>(i * 180. / hsize), 255, 255);
423 cv::cvtColor(buf, buf, cv::COLOR_HSV2BGR);
425 for (
int i = 0; i <
hsize; i++)
427 int val = cv::saturate_cast<
int>(hist.at<
float>(i) * histimg.rows / 255);
428 cv::rectangle(histimg, cv::Point(i * bin_w, histimg.rows), cv::Point((i + 1) * bin_w, histimg.rows - val),
429 cv::Scalar(buf.at<cv::Vec3b>(i)), -1, 8);
449 ROS_WARN(
"DeprecationWarning: Nodelet camshift/camshift is deprecated, " 450 "and renamed to opencv_apps/camshift.");
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
static int on_mouse_event_
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
static void onMouse(int event, int x, int y, int, void *)
image_transport::Subscriber img_sub_
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
Demo code to calculate moments.
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
boost::shared_ptr< ReconfigureServer > reconfigure_server_
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
dynamic_reconfigure::Server< Config > ReconfigureServer
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
static void trackbarCallback(int, void *)
opencv_apps::CamShiftConfig Config
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
void reconfigureCallback(Config &new_config, uint32_t level)
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...
PLUGINLIB_EXPORT_CLASS(opencv_apps::CamShiftNodelet, nodelet::Nodelet)
image_transport::Publisher img_pub_
void publish(const sensor_msgs::Image &message) const
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
boost::shared_ptr< image_transport::ImageTransport > it_
image_transport::Publisher bproj_pub_
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...
image_transport::CameraSubscriber cam_sub_
#define NODELET_INFO(...)
std::string histogram_name_
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
static bool need_config_update_
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
#define NODELET_DEBUG(...)
static bool on_mouse_update_
sensor_msgs::ImagePtr toImageMsg() const