2 #include <jsk_topic_tools/log_utils.h>
3 #include <geometry_msgs/PolygonStamped.h>
4 #include <dynamic_reconfigure/server.h>
5 #include <jsk_perception/camshiftdemoConfig.h>
6 #include <jsk_recognition_msgs/RotatedRectStamped.h>
7 #include <sensor_msgs/SetCameraInfo.h>
11 #include <sensor_msgs/Image.h>
17 #include <opencv2/video/tracking.hpp>
18 #include <opencv2/imgproc/imgproc.hpp>
19 #include <opencv2/highgui/highgui.hpp>
24 #if ( CV_MAJOR_VERSION >= 4)
25 #include <opencv2/highgui/highgui_c.h>
44 typedef jsk_perception::camshiftdemoConfig
Config;
50 Mat hsv_, hue_,
mask_, histimg_, backproj_;
54 #if (CV_MAJOR_VERSION == 2 && CV_MINOR_VERSION < 2)
89 local_nh.
param(
"max_queue_size", max_queue_size_, 3);
90 local_nh.
param(
"debug", debug_,
true);
98 pub_result_ = nh.
advertise<jsk_recognition_msgs::RotatedRectStamped>(local_nh.
resolveName(
"result"), 1);
104 backprojMode_ =
false;
105 selectObject_ =
false;
108 vmin_ = 10; vmax_ = 256; smin_ = 30;
111 hranges_[0] = 0; hranges_[1] = 180;
112 phranges_ = hranges_;
115 config_.vmin = vmin_;
116 config_.vmax = vmax_;
117 config_.smin = smin_;
119 reconfigure_server_.setCallback(
f);
122 on_mouse_param_.
image = &image_;
126 on_mouse_param_.
origin = &origin_;
130 namedWindow(
"Histogram", 1 );
131 namedWindow(
"CamShift Demo", 1 );
133 setMouseCallback(
"CamShift Demo", onMouse, (
void *)&on_mouse_param_ );
134 createTrackbar(
"Vmin",
"CamShift Demo", &vmin_, 256, 0 );
135 createTrackbar(
"Vmax",
"CamShift Demo", &vmax_, 256, 0 );
136 createTrackbar(
"Smin",
"CamShift Demo", &smin_, 256, 0 );
138 histimg_ = Mat::zeros(200, 320, CV_8UC3);
152 sensor_msgs::SetCameraInfo::Response &res)
155 onMouse(CV_EVENT_LBUTTONDOWN,
156 req.camera_info.roi.x_offset,
157 req.camera_info.roi.y_offset,
160 onMouse(CV_EVENT_LBUTTONUP,
161 req.camera_info.roi.x_offset +
req.camera_info.roi.width,
162 req.camera_info.roi.y_offset +
req.camera_info.roi.height,
169 void imageCB(
const sensor_msgs::ImageConstPtr& msg_ptr)
177 frame = cv_ptr->image;
184 frame.copyTo(image_);
189 int _vmin = vmin_, _vmax = vmax_;
191 inRange(hsv_, Scalar(0, smin_,
MIN(_vmin,_vmax)),
192 Scalar(180, 256,
MAX(_vmin, _vmax)), mask_);
194 hue_.create(hsv_.size(), hsv_.depth());
195 mixChannels(&hsv_, 1, &hue_, 1,
ch, 1);
197 if( trackObject_ < 0 )
199 Mat roi(hue_, selection_), maskroi(mask_, selection_);
200 calcHist(&roi, 1, 0, maskroi, hist_, 1, &hsize_, &phranges_);
201 normalize(hist_, hist_, 0, 255, CV_MINMAX);
203 trackWindow_ = selection_;
206 histimg_ = Scalar::all(0);
207 int binW = histimg_.cols / hsize_;
208 Mat buf(1, hsize_, CV_8UC3);
209 for(
int i = 0;
i < hsize_;
i++ )
210 buf.at<Vec3b>(
i) = Vec3b(saturate_cast<uchar>(
i*180./hsize_), 255, 255);
213 for(
int i = 0;
i < hsize_;
i++ )
215 int val = saturate_cast<int>(hist_.at<
float>(
i)*histimg_.rows/255);
216 rectangle( histimg_,
Point(
i*binW,histimg_.rows),
217 Point((
i+1)*binW,histimg_.rows - val),
218 Scalar(buf.at<Vec3b>(
i)), -1, 8 );
223 calcBackProject(&hue_, 1, 0, hist_, backproj_, &phranges_);
225 trackBox_ = CamShift(backproj_, trackWindow_,
226 TermCriteria( CV_TERMCRIT_EPS | CV_TERMCRIT_ITER, 10, 1 ));
229 cvtColor( backproj_, image_, CV_GRAY2BGR );
230 ellipse( image_, trackBox_, Scalar(0,0,255), 3, CV_AA );
232 jsk_recognition_msgs::RotatedRectStamped result_msg;
233 result_msg.header = msg_ptr->header;
234 result_msg.rect.x = trackBox_.center.x;
235 result_msg.rect.y = trackBox_.center.y;
236 result_msg.rect.width = trackBox_.size.width;
237 result_msg.rect.height = trackBox_.size.height;
238 result_msg.rect.angle = trackBox_.angle;
239 pub_result_.
publish(result_msg);
242 ROS_WARN(
"illegal tracBox = x:%f y:%f width:%f height:%f angle:%f",
243 trackBox_.center.x, trackBox_.center.y,
244 trackBox_.size.width, trackBox_.size.height,
249 if( selectObject_ && selection_.width > 0 && selection_.height > 0 )
251 Mat roi(image_, selection_);
252 bitwise_not(roi, roi);
255 img_.header = msg_ptr->header;
256 fillImage(img_,
"bgr8", image_.rows, image_.cols, image_.step,
const_cast<uint8_t*
>(image_.data));
258 fillImage(img_,
"bgr8", histimg_.rows, histimg_.cols, histimg_.step,
const_cast<uint8_t*
>(histimg_.data));
263 imshow(
"CamShift Demo", image_ );
264 imshow(
"Histogram", histimg_ );
266 char c = (char)waitKey(10);
270 backprojMode_ = !backprojMode_;
274 histimg_ = Scalar::all(0);
277 showHist_ = !showHist_;
279 destroyWindow(
"Histogram" );
281 namedWindow(
"Histogram", 1 );
291 selection_.x = msg_ptr->polygon.points[0].x;
292 selection_.y = msg_ptr->polygon.points[0].y;
293 selection_.width = msg_ptr->polygon.points[1].x - msg_ptr->polygon.points[0].x;
294 selection_.height = msg_ptr->polygon.points[1].y - msg_ptr->polygon.points[0].y;
295 selection_ &= Rect(0, 0, image_.cols, image_.rows);
302 vmin_ = config_.vmin;
303 vmax_ = config_.vmax;
304 smin_ = config_.smin;
305 switch ( config_.display_mode )
307 case jsk_perception::camshiftdemo_RGB:
308 backprojMode_ =
false;
310 case jsk_perception::camshiftdemo_Backproject:
311 backprojMode_ =
true;
317 static void onMouse(
int event,
int x,
int y,
int flags,
void* param)
320 Mat* image = on_mouse_param->
image;
323 Rect *selection = on_mouse_param->
selection;
330 selection->width = std::abs(
x -
origin->x);
331 selection->height = std::abs(y -
origin->y);
333 *selection &= Rect(0, 0, image->cols, image->rows);
338 case CV_EVENT_LBUTTONDOWN:
340 *selection = Rect(
x,y,0,0);
341 *selectObject =
true;
343 case CV_EVENT_LBUTTONUP:
344 *selectObject =
false;
345 if( selection->width > 0 && selection->height > 0 )
354 int main(
int argc,
char** argv)
358 if (
n.resolveName(
"image") ==
"/image") {
359 ROS_WARN(
"%s: image has not been remapped! Typical command-line usage:\n"
360 "\t$ ./%s image:=<image topic>",
argv[0],
argv[0]);