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* )
118 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
125 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
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;
194 case cv::EVENT_LBUTTONDOWN:
199 case cv::EVENT_LBUTTONUP:
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);
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);
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));
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;
290 bitwise_not(roi, roi);
298 char c = (char)cv::waitKey(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);
387 histimg = cv::Mat::zeros(200, 320, CV_8UC3);
390 dynamic_reconfigure::Server<Config>::CallbackType
f =
396 msg_pub_ = advertise<opencv_apps::RotatedRectStamped>(*
pnh_,
"track_box", 1);
401 NODELET_INFO(
"\tb - switch to/from backprojection view");
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)
411 for (
int i = 0; i <
hsize; i++)
413 hist.at<
float>(i) = hist_value[i];
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.");
456 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H