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> 58 static void destroy(GtkWidget *widget, gpointer data)
362 : filename_format_(
""), save_count_(0),
363 left_received_(0), right_received_(0), disp_received_(0), all_received_(0)
368 local_nh.
param(
"autosize", autosize,
true);
370 std::string format_string;
371 local_nh.
param(
"filename_format", format_string, std::string(
"%s%04i.jpg"));
372 filename_format_.parse(format_string);
375 int flags = autosize ? cv::WND_PROP_AUTOSIZE : 0;
376 cv::namedWindow(
"left", flags);
377 cv::namedWindow(
"right", flags);
378 cv::namedWindow(
"disparity", flags);
382 #if CV_MAJOR_VERSION == 2 384 g_signal_connect(GTK_WIDGET( cvGetWindowHandle(
"left") ),
385 "destroy", G_CALLBACK(destroy), NULL);
386 g_signal_connect(GTK_WIDGET( cvGetWindowHandle(
"right") ),
387 "destroy", G_CALLBACK(destroy), NULL);
388 g_signal_connect(GTK_WIDGET( cvGetWindowHandle(
"disparity") ),
389 "destroy", G_CALLBACK(destroy), NULL);
391 cvStartWindowThread();
400 ROS_INFO(
"Subscribing to:\n\t* %s\n\t* %s\n\t* %s", left_topic.c_str(), right_topic.c_str(),
401 disparity_topic.c_str());
405 left_sub_.
subscribe(it, left_topic, 1, transport);
406 right_sub_.
subscribe(it, right_topic, 1, transport);
407 disparity_sub_.
subscribe(nh, disparity_topic, 1);
410 left_sub_.registerCallback(boost::bind(
increment, &left_received_));
411 right_sub_.registerCallback(boost::bind(
increment, &right_received_));
417 local_nh.
param(
"queue_size", queue_size_, 5);
419 local_nh.
param(
"approximate_sync", approx,
false);
422 approximate_sync_.reset(
new ApproximateSync(ApproximatePolicy(queue_size_),
423 left_sub_, right_sub_, disparity_sub_) );
428 exact_sync_.reset(
new ExactSync(ExactPolicy(queue_size_),
429 left_sub_, right_sub_, disparity_sub_) );
436 cv::destroyAllWindows();
439 void imageCb(
const ImageConstPtr& left,
const ImageConstPtr& right,
440 const DisparityImageConstPtr& disparity_msg)
447 if (left->encoding.find(
"bayer") != std::string::npos)
448 boost::const_pointer_cast<Image>(left)->encoding =
"mono8";
449 if (right->encoding.find(
"bayer") != std::string::npos)
450 boost::const_pointer_cast<Image>(right)->encoding =
"mono8";
453 last_left_msg_ = left;
454 last_right_msg_ = right;
460 ROS_ERROR(
"Unable to convert one of '%s' or '%s' to 'bgr8'",
461 left->encoding.c_str(), right->encoding.c_str());
465 float min_disparity = disparity_msg->min_disparity;
466 float max_disparity = disparity_msg->max_disparity;
467 float multiplier = 255.0f / (max_disparity - min_disparity);
469 assert(disparity_msg->image.encoding == enc::TYPE_32FC1);
470 const cv::Mat_<float> dmat(disparity_msg->image.height, disparity_msg->image.width,
471 (
float*)&disparity_msg->image.data[0], disparity_msg->image.step);
472 disparity_color_.create(disparity_msg->image.height, disparity_msg->image.width);
474 for (
int row = 0; row < disparity_color_.rows; ++row) {
475 const float* d = dmat[row];
476 for (
int col = 0; col < disparity_color_.cols; ++col) {
477 int index = (d[col] - min_disparity) * multiplier + 0.5;
478 index = std::min(255, std::max(0, index));
480 disparity_color_(row, col)[2] =
colormap[3*index + 0];
481 disparity_color_(row, col)[1] =
colormap[3*index + 1];
482 disparity_color_(row, col)[0] =
colormap[3*index + 2];
488 image_mutex_.unlock();
489 if (!last_left_image_.empty()) {
490 cv::imshow(
"left", last_left_image_);
493 if (!last_right_image_.empty()) {
494 cv::imshow(
"right", last_right_image_);
497 cv::imshow(
"disparity", disparity_color_);
501 void saveImage(
const char* prefix,
const cv::Mat& image)
503 if (!image.empty()) {
504 std::string
filename = (filename_format_ % prefix % save_count_).str();
505 cv::imwrite(filename, image);
506 ROS_INFO(
"Saved image %s", filename.c_str());
508 ROS_WARN(
"Couldn't save %s image, no data!", prefix);
512 static void mouseCb(
int event,
int x,
int y,
int flags,
void* param)
514 if (event == cv::EVENT_LBUTTONDOWN)
516 ROS_WARN_ONCE(
"Left-clicking no longer saves images. Right-click instead.");
519 if (event != cv::EVENT_RBUTTONDOWN)
523 boost::lock_guard<boost::mutex> guard(sv->
image_mutex_);
533 int threshold = 3 * all_received_;
534 if (left_received_ >= threshold || right_received_ >= threshold || disp_received_ >= threshold) {
535 ROS_WARN(
"[stereo_view] Low number of synchronized left/right/disparity triplets received.\n" 536 "Left images received: %d (topic '%s')\n" 537 "Right images received: %d (topic '%s')\n" 538 "Disparity images received: %d (topic '%s')\n" 539 "Synchronized triplets: %d\n" 541 "\t* stereo_image_proc is not running.\n" 542 "\t Does `rosnode info %s` show any connections?\n" 543 "\t* The cameras are not synchronized.\n" 544 "\t Try restarting stereo_view with parameter _approximate_sync:=True\n" 545 "\t* The network is too slow. One or more images are dropped from each triplet.\n" 546 "\t Try restarting stereo_view, increasing parameter 'queue_size' (currently %d)",
547 left_received_, left_sub_.
getTopic().c_str(),
548 right_received_, right_sub_.
getTopic().c_str(),
549 disp_received_, disparity_sub_.
getTopic().c_str(),
555 int main(
int argc,
char **argv)
559 ROS_WARN(
"'stereo' has not been remapped! Example command-line usage:\n" 560 "\t$ rosrun image_view stereo_view stereo:=narrow_stereo image:=image_color");
563 ROS_WARN(
"There is a delay between when the camera drivers publish the raw images and " 564 "when stereo_image_proc publishes the computed point cloud. stereo_view " 565 "may fail to synchronize these topics without a large queue_size.");
568 std::string transport = argc > 1 ? argv[1] :
"raw";
message_filters::Synchronizer< ExactPolicy > ExactSync
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
message_filters::Synchronizer< ApproximatePolicy > ApproximateSync
std::string getTopic() const
ros::WallTimer check_synced_timer_
boost::mutex image_mutex_
image_transport::SubscriberFilter right_sub_
std::string resolveName(const std::string &name, bool remap=true) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL const std::string & getName()
void imageCb(const ImageConstPtr &left, const ImageConstPtr &right, const DisparityImageConstPtr &disparity_msg)
ExactTime< Image, Image, DisparityImage > ExactPolicy
ROSCPP_DECL std::string clean(const std::string &name)
message_filters::Subscriber< DisparityImage > disparity_sub_
static unsigned char colormap[768]
ApproximateTime< Image, Image, DisparityImage > ApproximatePolicy
cv::Mat_< cv::Vec3b > disparity_color_
ROSCPP_DECL void spin(Spinner &spinner)
ROSCPP_DECL std::string remap(const std::string &name)
boost::shared_ptr< ExactSync > exact_sync_
cv::Mat last_right_image_
#define ROS_WARN_ONCE(...)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
StereoView(const std::string &transport)
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
boost::shared_ptr< ApproximateSync > approximate_sync_
void saveImage(const char *prefix, const cv::Mat &image)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
static void mouseCb(int event, int x, int y, int flags, void *param)
ROSCPP_DECL void shutdown()
boost::format filename_format_
int main(int argc, char **argv)
std::string getTopic() const
void increment(int *value)
ImageConstPtr last_right_msg_
Connection registerCallback(const C &callback)
void checkInputsSynchronized()