stereo_view.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #include <opencv2/highgui/highgui.hpp>
36 
37 #include <ros/ros.h>
38 #include <sensor_msgs/Image.h>
40 #include <stereo_msgs/DisparityImage.h>
41 #include <cv_bridge/cv_bridge.h>
42 
48 
49 #include <boost/thread.hpp>
50 #include <boost/format.hpp>
51 
52 
54 
55 // colormap for disparities, RGB
56 static unsigned char colormap[768] =
57  { 150, 150, 150,
58  107, 0, 12,
59  106, 0, 18,
60  105, 0, 24,
61  103, 0, 30,
62  102, 0, 36,
63  101, 0, 42,
64  99, 0, 48,
65  98, 0, 54,
66  97, 0, 60,
67  96, 0, 66,
68  94, 0, 72,
69  93, 0, 78,
70  92, 0, 84,
71  91, 0, 90,
72  89, 0, 96,
73  88, 0, 102,
74  87, 0, 108,
75  85, 0, 114,
76  84, 0, 120,
77  83, 0, 126,
78  82, 0, 131,
79  80, 0, 137,
80  79, 0, 143,
81  78, 0, 149,
82  77, 0, 155,
83  75, 0, 161,
84  74, 0, 167,
85  73, 0, 173,
86  71, 0, 179,
87  70, 0, 185,
88  69, 0, 191,
89  68, 0, 197,
90  66, 0, 203,
91  65, 0, 209,
92  64, 0, 215,
93  62, 0, 221,
94  61, 0, 227,
95  60, 0, 233,
96  59, 0, 239,
97  57, 0, 245,
98  56, 0, 251,
99  55, 0, 255,
100  54, 0, 255,
101  52, 0, 255,
102  51, 0, 255,
103  50, 0, 255,
104  48, 0, 255,
105  47, 0, 255,
106  46, 0, 255,
107  45, 0, 255,
108  43, 0, 255,
109  42, 0, 255,
110  41, 0, 255,
111  40, 0, 255,
112  38, 0, 255,
113  37, 0, 255,
114  36, 0, 255,
115  34, 0, 255,
116  33, 0, 255,
117  32, 0, 255,
118  31, 0, 255,
119  29, 0, 255,
120  28, 0, 255,
121  27, 0, 255,
122  26, 0, 255,
123  24, 0, 255,
124  23, 0, 255,
125  22, 0, 255,
126  20, 0, 255,
127  19, 0, 255,
128  18, 0, 255,
129  17, 0, 255,
130  15, 0, 255,
131  14, 0, 255,
132  13, 0, 255,
133  11, 0, 255,
134  10, 0, 255,
135  9, 0, 255,
136  8, 0, 255,
137  6, 0, 255,
138  5, 0, 255,
139  4, 0, 255,
140  3, 0, 255,
141  1, 0, 255,
142  0, 4, 255,
143  0, 10, 255,
144  0, 16, 255,
145  0, 22, 255,
146  0, 28, 255,
147  0, 34, 255,
148  0, 40, 255,
149  0, 46, 255,
150  0, 52, 255,
151  0, 58, 255,
152  0, 64, 255,
153  0, 70, 255,
154  0, 76, 255,
155  0, 82, 255,
156  0, 88, 255,
157  0, 94, 255,
158  0, 100, 255,
159  0, 106, 255,
160  0, 112, 255,
161  0, 118, 255,
162  0, 124, 255,
163  0, 129, 255,
164  0, 135, 255,
165  0, 141, 255,
166  0, 147, 255,
167  0, 153, 255,
168  0, 159, 255,
169  0, 165, 255,
170  0, 171, 255,
171  0, 177, 255,
172  0, 183, 255,
173  0, 189, 255,
174  0, 195, 255,
175  0, 201, 255,
176  0, 207, 255,
177  0, 213, 255,
178  0, 219, 255,
179  0, 225, 255,
180  0, 231, 255,
181  0, 237, 255,
182  0, 243, 255,
183  0, 249, 255,
184  0, 255, 255,
185  0, 255, 249,
186  0, 255, 243,
187  0, 255, 237,
188  0, 255, 231,
189  0, 255, 225,
190  0, 255, 219,
191  0, 255, 213,
192  0, 255, 207,
193  0, 255, 201,
194  0, 255, 195,
195  0, 255, 189,
196  0, 255, 183,
197  0, 255, 177,
198  0, 255, 171,
199  0, 255, 165,
200  0, 255, 159,
201  0, 255, 153,
202  0, 255, 147,
203  0, 255, 141,
204  0, 255, 135,
205  0, 255, 129,
206  0, 255, 124,
207  0, 255, 118,
208  0, 255, 112,
209  0, 255, 106,
210  0, 255, 100,
211  0, 255, 94,
212  0, 255, 88,
213  0, 255, 82,
214  0, 255, 76,
215  0, 255, 70,
216  0, 255, 64,
217  0, 255, 58,
218  0, 255, 52,
219  0, 255, 46,
220  0, 255, 40,
221  0, 255, 34,
222  0, 255, 28,
223  0, 255, 22,
224  0, 255, 16,
225  0, 255, 10,
226  0, 255, 4,
227  2, 255, 0,
228  8, 255, 0,
229  14, 255, 0,
230  20, 255, 0,
231  26, 255, 0,
232  32, 255, 0,
233  38, 255, 0,
234  44, 255, 0,
235  50, 255, 0,
236  56, 255, 0,
237  62, 255, 0,
238  68, 255, 0,
239  74, 255, 0,
240  80, 255, 0,
241  86, 255, 0,
242  92, 255, 0,
243  98, 255, 0,
244  104, 255, 0,
245  110, 255, 0,
246  116, 255, 0,
247  122, 255, 0,
248  128, 255, 0,
249  133, 255, 0,
250  139, 255, 0,
251  145, 255, 0,
252  151, 255, 0,
253  157, 255, 0,
254  163, 255, 0,
255  169, 255, 0,
256  175, 255, 0,
257  181, 255, 0,
258  187, 255, 0,
259  193, 255, 0,
260  199, 255, 0,
261  205, 255, 0,
262  211, 255, 0,
263  217, 255, 0,
264  223, 255, 0,
265  229, 255, 0,
266  235, 255, 0,
267  241, 255, 0,
268  247, 255, 0,
269  253, 255, 0,
270  255, 251, 0,
271  255, 245, 0,
272  255, 239, 0,
273  255, 233, 0,
274  255, 227, 0,
275  255, 221, 0,
276  255, 215, 0,
277  255, 209, 0,
278  255, 203, 0,
279  255, 197, 0,
280  255, 191, 0,
281  255, 185, 0,
282  255, 179, 0,
283  255, 173, 0,
284  255, 167, 0,
285  255, 161, 0,
286  255, 155, 0,
287  255, 149, 0,
288  255, 143, 0,
289  255, 137, 0,
290  255, 131, 0,
291  255, 126, 0,
292  255, 120, 0,
293  255, 114, 0,
294  255, 108, 0,
295  255, 102, 0,
296  255, 96, 0,
297  255, 90, 0,
298  255, 84, 0,
299  255, 78, 0,
300  255, 72, 0,
301  255, 66, 0,
302  255, 60, 0,
303  255, 54, 0,
304  255, 48, 0,
305  255, 42, 0,
306  255, 36, 0,
307  255, 30, 0,
308  255, 24, 0,
309  255, 18, 0,
310  255, 12, 0,
311  255, 6, 0,
312  255, 0, 0,
313  };
314 
315 inline void increment(int* value)
316 {
317  ++(*value);
318 }
319 
320 using namespace sensor_msgs;
321 using namespace stereo_msgs;
322 using namespace message_filters::sync_policies;
323 
324 // Note: StereoView is NOT nodelet-based, as it synchronizes the three streams.
326 {
327 private:
337 
338  ImageConstPtr last_left_msg_, last_right_msg_;
339  cv::Mat last_left_image_, last_right_image_;
340  cv::Mat_<cv::Vec3b> disparity_color_;
341  boost::mutex image_mutex_;
342 
343  boost::format filename_format_;
345 
347  int left_received_, right_received_, disp_received_, all_received_;
348 
349 public:
350  StereoView(const std::string& transport)
351  : filename_format_(""), save_count_(0),
352  left_received_(0), right_received_(0), disp_received_(0), all_received_(0)
353  {
354  // Read local parameters
355  ros::NodeHandle local_nh("~");
356  bool autosize;
357  local_nh.param("autosize", autosize, true);
358 
359  std::string format_string;
360  local_nh.param("filename_format", format_string, std::string("%s%04i.jpg"));
361  filename_format_.parse(format_string);
362 
363  // Do GUI window setup
364  int flags = autosize ? cv::WND_PROP_AUTOSIZE : 0;
365  cv::namedWindow("left", flags);
366  cv::namedWindow("right", flags);
367  cv::namedWindow("disparity", flags);
368  cv::setMouseCallback("left", &StereoView::mouseCb, this);
369  cv::setMouseCallback("right", &StereoView::mouseCb, this);
370  cv::setMouseCallback("disparity", &StereoView::mouseCb, this);
371 #if CV_MAJOR_VERSION == 2
372  cvStartWindowThread();
373 #endif
374 
375  // Resolve topic names
376  ros::NodeHandle nh;
377  std::string stereo_ns = nh.resolveName("stereo");
378  std::string left_topic = ros::names::clean(stereo_ns + "/left/" + nh.resolveName("image"));
379  std::string right_topic = ros::names::clean(stereo_ns + "/right/" + nh.resolveName("image"));
380  std::string disparity_topic = ros::names::clean(stereo_ns + "/disparity");
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());
383 
384  // Subscribe to three input topics.
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);
389 
390  // Complain every 30s if the topics appear unsynchronized
391  left_sub_.registerCallback(boost::bind(increment, &left_received_));
392  right_sub_.registerCallback(boost::bind(increment, &right_received_));
393  disparity_sub_.registerCallback(boost::bind(increment, &disp_received_));
394  check_synced_timer_ = nh.createWallTimer(ros::WallDuration(15.0),
395  boost::bind(&StereoView::checkInputsSynchronized, this));
396 
397  // Synchronize input topics. Optionally do approximate synchronization.
398  local_nh.param("queue_size", queue_size_, 5);
399  bool approx;
400  local_nh.param("approximate_sync", approx, false);
401  if (approx)
402  {
403  approximate_sync_.reset( new ApproximateSync(ApproximatePolicy(queue_size_),
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));
406  }
407  else
408  {
409  exact_sync_.reset( new ExactSync(ExactPolicy(queue_size_),
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));
412  }
413  }
414 
416  {
417  cv::destroyAllWindows();
418  }
419 
420  void imageCb(const ImageConstPtr& left, const ImageConstPtr& right,
421  const DisparityImageConstPtr& disparity_msg)
422  {
423  ++all_received_; // For error checking
424 
425  image_mutex_.lock();
426 
427  // May want to view raw bayer data
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";
432 
433  // Hang on to image data for sake of mouseCb
434  last_left_msg_ = left;
435  last_right_msg_ = right;
436  try {
437  last_left_image_ = cv_bridge::toCvShare(left, "bgr8")->image;
438  last_right_image_ = cv_bridge::toCvShare(right, "bgr8")->image;
439  }
440  catch (cv_bridge::Exception& e) {
441  ROS_ERROR("Unable to convert one of '%s' or '%s' to 'bgr8'",
442  left->encoding.c_str(), right->encoding.c_str());
443  }
444 
445  // Colormap and display the disparity image
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);
449 
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);
454 
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));
460  // Fill as BGR
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];
464  }
465  }
466 
467  // Must release the mutex before calling cv::imshow, or can deadlock against
468  // OpenCV's window mutex.
469  image_mutex_.unlock();
470  if (!last_left_image_.empty()) {
471  cv::imshow("left", last_left_image_);
472  cv::waitKey(1);
473  }
474  if (!last_right_image_.empty()) {
475  cv::imshow("right", last_right_image_);
476  cv::waitKey(1);
477  }
478  cv::imshow("disparity", disparity_color_);
479  cv::waitKey(1);
480  }
481 
482  void saveImage(const char* prefix, const cv::Mat& image)
483  {
484  if (!image.empty()) {
485  std::string filename = (filename_format_ % prefix % save_count_).str();
486  cv::imwrite(filename, image);
487  ROS_INFO("Saved image %s", filename.c_str());
488  } else {
489  ROS_WARN("Couldn't save %s image, no data!", prefix);
490  }
491  }
492 
493  static void mouseCb(int event, int x, int y, int flags, void* param)
494  {
495  if (event == cv::EVENT_LBUTTONDOWN)
496  {
497  ROS_WARN_ONCE("Left-clicking no longer saves images. Right-click instead.");
498  return;
499  }
500  if (event != cv::EVENT_RBUTTONDOWN)
501  return;
502 
503  StereoView *sv = (StereoView*)param;
504  boost::lock_guard<boost::mutex> guard(sv->image_mutex_);
505 
506  sv->saveImage("left", sv->last_left_image_);
507  sv->saveImage("right", sv->last_right_image_);
508  sv->saveImage("disp", sv->disparity_color_);
509  sv->save_count_++;
510  }
511 
513  {
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"
521  "Possible issues:\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(),
531  all_received_, ros::this_node::getName().c_str(), queue_size_);
532  }
533  }
534 };
535 
536 int main(int argc, char **argv)
537 {
538  ros::init(argc, argv, "stereo_view", ros::init_options::AnonymousName);
539  if (ros::names::remap("stereo") == "stereo") {
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");
542  }
543  if (ros::names::remap("image") == "/image_raw") {
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.");
547  }
548 
549  std::string transport = argc > 1 ? argv[1] : "raw";
550  StereoView view(transport);
551 
552  ros::spin();
553  return 0;
554 }
StereoView::right_received_
int right_received_
Definition: stereo_view.cpp:347
ros::init_options::AnonymousName
AnonymousName
image_transport::SubscriberFilter
sensor_msgs::image_encodings
StereoView::exact_sync_
boost::shared_ptr< ExactSync > exact_sync_
Definition: stereo_view.cpp:334
image_encodings.h
image_transport::ImageTransport
message_filters::Synchronizer
boost::shared_ptr
StereoView::ExactPolicy
ExactTime< Image, Image, DisparityImage > ExactPolicy
Definition: stereo_view.cpp:330
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
colormap
static unsigned char colormap[768]
Definition: stereo_view.cpp:56
ros::WallTimer
ros::names::clean
ROSCPP_DECL std::string clean(const std::string &name)
image_transport::SubscriberFilter::subscribe
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
StereoView::image_mutex_
boost::mutex image_mutex_
Definition: stereo_view.cpp:341
StereoView::mouseCb
static void mouseCb(int event, int x, int y, int flags, void *param)
Definition: stereo_view.cpp:493
StereoView::right_sub_
image_transport::SubscriberFilter right_sub_
Definition: stereo_view.cpp:328
ROS_WARN_ONCE
#define ROS_WARN_ONCE(...)
cv_bridge::Exception
StereoView::last_right_image_
cv::Mat last_right_image_
Definition: stereo_view.cpp:339
image_transport::SubscriberFilter::getTopic
std::string getTopic() const
main
int main(int argc, char **argv)
Definition: stereo_view.cpp:536
StereoView::checkInputsSynchronized
void checkInputsSynchronized()
Definition: stereo_view.cpp:512
message_filters::Subscriber::getTopic
std::string getTopic() const
message_filters::Subscriber< DisparityImage >
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
StereoView::check_synced_timer_
ros::WallTimer check_synced_timer_
Definition: stereo_view.cpp:346
message_filters::sync_policies::ApproximateTime
StereoView::approximate_sync_
boost::shared_ptr< ApproximateSync > approximate_sync_
Definition: stereo_view.cpp:335
subscriber_filter.h
filename
std::string filename
Definition: video_recorder.cpp:37
subscriber.h
StereoView
Definition: stereo_view.cpp:325
d
d
ROS_WARN
#define ROS_WARN(...)
StereoView::filename_format_
boost::format filename_format_
Definition: stereo_view.cpp:343
message_filters::SimpleFilter::registerCallback
Connection registerCallback(const boost::function< void(P)> &callback)
ros::names::remap
ROSCPP_DECL std::string remap(const std::string &name)
StereoView::ApproximateSync
message_filters::Synchronizer< ApproximatePolicy > ApproximateSync
Definition: stereo_view.cpp:333
exact_time.h
message_filters::Subscriber::subscribe
void subscribe()
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
StereoView::queue_size_
int queue_size_
Definition: stereo_view.cpp:336
message_filters::sync_policies
StereoView::last_right_msg_
ImageConstPtr last_right_msg_
Definition: stereo_view.cpp:338
StereoView::imageCb
void imageCb(const ImageConstPtr &left, const ImageConstPtr &right, const DisparityImageConstPtr &disparity_msg)
Definition: stereo_view.cpp:420
increment
void increment(int *value)
Definition: stereo_view.cpp:315
StereoView::save_count_
int save_count_
Definition: stereo_view.cpp:344
StereoView::ExactSync
message_filters::Synchronizer< ExactPolicy > ExactSync
Definition: stereo_view.cpp:332
cv_bridge.h
StereoView::StereoView
StereoView(const std::string &transport)
Definition: stereo_view.cpp:350
ROS_ERROR
#define ROS_ERROR(...)
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
synchronizer.h
param
T param(const std::string &param_name, const T &default_val)
approximate_time.h
StereoView::disparity_sub_
message_filters::Subscriber< DisparityImage > disparity_sub_
Definition: stereo_view.cpp:329
ros::spin
ROSCPP_DECL void spin()
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
StereoView::ApproximatePolicy
ApproximateTime< Image, Image, DisparityImage > ApproximatePolicy
Definition: stereo_view.cpp:331
ros::WallDuration
message_filters::sync_policies::ExactTime
ROS_INFO
#define ROS_INFO(...)
StereoView::saveImage
void saveImage(const char *prefix, const cv::Mat &image)
Definition: stereo_view.cpp:482
sensor_msgs
ros::NodeHandle::createWallTimer
WallTimer createWallTimer(WallDuration period, const WallTimerCallback &callback, bool oneshot=false, bool autostart=true) const
StereoView::last_left_image_
cv::Mat last_left_image_
Definition: stereo_view.cpp:339
StereoView::~StereoView
~StereoView()
Definition: stereo_view.cpp:415
ros::NodeHandle
StereoView::disparity_color_
cv::Mat_< cv::Vec3b > disparity_color_
Definition: stereo_view.cpp:340


image_view
Author(s): Patrick Mihelich
autogenerated on Wed Jan 24 2024 03:57:22