35 #include <opencv2/highgui/highgui.hpp>
38 #include <sensor_msgs/Image.h>
40 #include <stereo_msgs/DisparityImage.h>
49 #include <boost/thread.hpp>
50 #include <boost/format.hpp>
321 using namespace stereo_msgs;
351 : filename_format_(
""), save_count_(0),
352 left_received_(0), right_received_(0), disp_received_(0), all_received_(0)
357 local_nh.
param(
"autosize", autosize,
true);
359 std::string format_string;
360 local_nh.
param(
"filename_format", format_string, std::string(
"%s%04i.jpg"));
361 filename_format_.parse(format_string);
364 int flags = autosize ? cv::WND_PROP_AUTOSIZE : 0;
365 cv::namedWindow(
"left", flags);
366 cv::namedWindow(
"right", flags);
367 cv::namedWindow(
"disparity", flags);
371 #if CV_MAJOR_VERSION == 2
372 cvStartWindowThread();
381 ROS_INFO(
"Subscribing to:\n\t* %s\n\t* %s\n\t* %s", left_topic.c_str(), right_topic.c_str(),
382 disparity_topic.c_str());
386 left_sub_.
subscribe(it, left_topic, 1, transport);
387 right_sub_.
subscribe(it, right_topic, 1, transport);
388 disparity_sub_.
subscribe(nh, disparity_topic, 1);
391 left_sub_.registerCallback(boost::bind(
increment, &left_received_));
392 right_sub_.registerCallback(boost::bind(
increment, &right_received_));
398 local_nh.
param(
"queue_size", queue_size_, 5);
400 local_nh.
param(
"approximate_sync", approx,
false);
404 left_sub_, right_sub_, disparity_sub_) );
405 approximate_sync_->registerCallback(boost::bind(&
StereoView::imageCb,
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
410 left_sub_, right_sub_, disparity_sub_) );
411 exact_sync_->registerCallback(boost::bind(&
StereoView::imageCb,
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
417 cv::destroyAllWindows();
420 void imageCb(
const ImageConstPtr& left,
const ImageConstPtr& right,
421 const DisparityImageConstPtr& disparity_msg)
428 if (left->encoding.find(
"bayer") != std::string::npos)
429 boost::const_pointer_cast<Image>(left)->encoding =
"mono8";
430 if (right->encoding.find(
"bayer") != std::string::npos)
431 boost::const_pointer_cast<Image>(right)->encoding =
"mono8";
434 last_left_msg_ = left;
435 last_right_msg_ = right;
441 ROS_ERROR(
"Unable to convert one of '%s' or '%s' to 'bgr8'",
442 left->encoding.c_str(), right->encoding.c_str());
446 float min_disparity = disparity_msg->min_disparity;
447 float max_disparity = disparity_msg->max_disparity;
448 float multiplier = 255.0f / (max_disparity - min_disparity);
450 assert(disparity_msg->image.encoding == enc::TYPE_32FC1);
451 const cv::Mat_<float> dmat(disparity_msg->image.height, disparity_msg->image.width,
452 (
float*)&disparity_msg->image.data[0], disparity_msg->image.step);
453 disparity_color_.create(disparity_msg->image.height, disparity_msg->image.width);
455 for (
int row = 0; row < disparity_color_.rows; ++row) {
456 const float*
d = dmat[row];
457 for (
int col = 0; col < disparity_color_.cols; ++col) {
458 int index = (
d[col] - min_disparity) * multiplier + 0.5;
459 index = std::min(255, std::max(0, index));
461 disparity_color_(row, col)[2] =
colormap[3*index + 0];
462 disparity_color_(row, col)[1] =
colormap[3*index + 1];
463 disparity_color_(row, col)[0] =
colormap[3*index + 2];
469 image_mutex_.unlock();
470 if (!last_left_image_.empty()) {
471 cv::imshow(
"left", last_left_image_);
474 if (!last_right_image_.empty()) {
475 cv::imshow(
"right", last_right_image_);
478 cv::imshow(
"disparity", disparity_color_);
482 void saveImage(
const char* prefix,
const cv::Mat& image)
484 if (!image.empty()) {
485 std::string
filename = (filename_format_ % prefix % save_count_).str();
489 ROS_WARN(
"Couldn't save %s image, no data!", prefix);
493 static void mouseCb(
int event,
int x,
int y,
int flags,
void* param)
495 if (event == cv::EVENT_LBUTTONDOWN)
497 ROS_WARN_ONCE(
"Left-clicking no longer saves images. Right-click instead.");
500 if (event != cv::EVENT_RBUTTONDOWN)
504 boost::lock_guard<boost::mutex> guard(sv->
image_mutex_);
514 int threshold = 3 * all_received_;
515 if (left_received_ >= threshold || right_received_ >= threshold || disp_received_ >= threshold) {
516 ROS_WARN(
"[stereo_view] Low number of synchronized left/right/disparity triplets received.\n"
517 "Left images received: %d (topic '%s')\n"
518 "Right images received: %d (topic '%s')\n"
519 "Disparity images received: %d (topic '%s')\n"
520 "Synchronized triplets: %d\n"
522 "\t* stereo_image_proc is not running.\n"
523 "\t Does `rosnode info %s` show any connections?\n"
524 "\t* The cameras are not synchronized.\n"
525 "\t Try restarting stereo_view with parameter _approximate_sync:=True\n"
526 "\t* The network is too slow. One or more images are dropped from each triplet.\n"
527 "\t Try restarting stereo_view, increasing parameter 'queue_size' (currently %d)",
528 left_received_, left_sub_.
getTopic().c_str(),
529 right_received_, right_sub_.
getTopic().c_str(),
530 disp_received_, disparity_sub_.
getTopic().c_str(),
536 int main(
int argc,
char **argv)
540 ROS_WARN(
"'stereo' has not been remapped! Example command-line usage:\n"
541 "\t$ rosrun image_view stereo_view stereo:=narrow_stereo image:=image_color");
544 ROS_WARN(
"There is a delay between when the camera drivers publish the raw images and "
545 "when stereo_image_proc publishes the computed point cloud. stereo_view "
546 "may fail to synchronize these topics without a large queue_size.");
549 std::string transport = argc > 1 ? argv[1] :
"raw";