00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #include <ros/ros.h>
00035 #include <nodelet/nodelet.h>
00036 #include <image_transport/image_transport.h>
00037
00038 #include <cv_bridge/cv_bridge.h>
00039 #include <opencv2/highgui/highgui.hpp>
00040 #include "window_thread.h"
00041
00042 #include <boost/thread.hpp>
00043 #include <boost/format.hpp>
00044
00045 #ifdef HAVE_GTK
00046 #include <gtk/gtk.h>
00047
00048
00049
00050
00051 static void destroyNode(GtkWidget *widget, gpointer data)
00052 {
00054
00055 exit(0);
00056 }
00057
00058 static void destroyNodelet(GtkWidget *widget, gpointer data)
00059 {
00060
00061
00062 reinterpret_cast<image_transport::Subscriber*>(data)->shutdown();
00063 }
00064 #endif
00065
00066
00067 namespace image_view {
00068
00069 class ImageNodelet : public nodelet::Nodelet
00070 {
00071 image_transport::Subscriber sub_;
00072
00073 boost::mutex image_mutex_;
00074 cv::Mat last_image_;
00075
00076 std::string window_name_;
00077 bool autosize_;
00078 boost::format filename_format_;
00079 int count_;
00080 bool initialized_;
00081
00082 virtual void onInit();
00083
00084 void imageCb(const sensor_msgs::ImageConstPtr& msg);
00085
00086 static void mouseCb(int event, int x, int y, int flags, void* param);
00087
00088 public:
00089 ImageNodelet();
00090
00091 ~ImageNodelet();
00092 };
00093
00094 ImageNodelet::ImageNodelet()
00095 : filename_format_(""), count_(0), initialized_(false)
00096 {
00097 }
00098
00099 ImageNodelet::~ImageNodelet()
00100 {
00101 cv::destroyWindow(window_name_);
00102 }
00103
00104 void ImageNodelet::onInit()
00105 {
00106 ros::NodeHandle nh = getNodeHandle();
00107 ros::NodeHandle local_nh = getPrivateNodeHandle();
00108
00109
00110 const std::vector<std::string>& argv = getMyArgv();
00111
00112 std::string transport;
00113 local_nh.param("image_transport", transport, std::string("raw"));
00114 for (int i = 0; i < (int)argv.size(); ++i)
00115 {
00116 if (argv[i][0] != '-')
00117 {
00118 transport = argv[i];
00119 break;
00120 }
00121 }
00122 NODELET_INFO_STREAM("Using transport \"" << transport << "\"");
00123
00124 bool shutdown_on_close = std::find(argv.begin(), argv.end(),
00125 "--shutdown-on-close") != argv.end();
00126
00127
00128 std::string topic = nh.resolveName("image");
00129 local_nh.param("window_name", window_name_, topic);
00130
00131 local_nh.param("autosize", autosize_, false);
00132
00133 std::string format_string;
00134 local_nh.param("filename_format", format_string, std::string("frame%04i.jpg"));
00135 filename_format_.parse(format_string);
00136
00137 #ifdef HAVE_GTK
00138
00139 GtkWidget *widget = GTK_WIDGET( cvGetWindowHandle(window_name_.c_str()) );
00140 if (shutdown_on_close)
00141 g_signal_connect(widget, "destroy", G_CALLBACK(destroyNode), NULL);
00142 else
00143 g_signal_connect(widget, "destroy", G_CALLBACK(destroyNodelet), &sub_);
00144 #endif
00145
00146
00147 startWindowThread();
00148
00149 image_transport::ImageTransport it(nh);
00150 image_transport::TransportHints hints(transport, ros::TransportHints(), getPrivateNodeHandle());
00151 sub_ = it.subscribe(topic, 1, &ImageNodelet::imageCb, this, hints);
00152 }
00153
00154 void ImageNodelet::imageCb(const sensor_msgs::ImageConstPtr& msg)
00155 {
00156 if ( ! initialized_ ) {
00157 cv::namedWindow(window_name_, autosize_ ? cv::WND_PROP_AUTOSIZE : 0);
00158 cv::setMouseCallback(window_name_, &ImageNodelet::mouseCb, this);
00159 initialized_ = true;
00160 }
00161
00162 image_mutex_.lock();
00163
00164
00165 bool do_dynamic_scaling = (msg->encoding.find("F") != std::string::npos);
00166
00167
00168 try {
00169 cv_bridge::CvtColorForDisplayOptions options;
00170 options.do_dynamic_scaling = do_dynamic_scaling;
00171 last_image_ = cvtColorForDisplay(cv_bridge::toCvShare(msg), "", options)->image;
00172 }
00173 catch (cv_bridge::Exception& e) {
00174 NODELET_ERROR_THROTTLE(30, "Unable to convert '%s' image for display: '%s'",
00175 msg->encoding.c_str(), e.what());
00176 }
00177
00178
00179
00180 image_mutex_.unlock();
00181 if (!last_image_.empty()) {
00182 cv::imshow(window_name_, last_image_);
00183 cv::waitKey(1);
00184 }
00185 }
00186
00187 void ImageNodelet::mouseCb(int event, int x, int y, int flags, void* param)
00188 {
00189 ImageNodelet *this_ = reinterpret_cast<ImageNodelet*>(param);
00190
00191 boost::function<const std::string&()> getName =
00192 boost::bind(&ImageNodelet::getName, this_);
00193
00194 if (event == cv::EVENT_LBUTTONDOWN)
00195 {
00196 NODELET_WARN_ONCE("Left-clicking no longer saves images. Right-click instead.");
00197 return;
00198 }
00199 if (event != cv::EVENT_RBUTTONDOWN)
00200 return;
00201
00202 boost::lock_guard<boost::mutex> guard(this_->image_mutex_);
00203
00204 const cv::Mat &image = this_->last_image_;
00205 if (image.empty())
00206 {
00207 NODELET_WARN("Couldn't save image, no data!");
00208 return;
00209 }
00210
00211 std::string filename = (this_->filename_format_ % this_->count_).str();
00212 if (cv::imwrite(filename, image))
00213 {
00214 NODELET_INFO("Saved image %s", filename.c_str());
00215 this_->count_++;
00216 }
00217 else
00218 {
00220 NODELET_ERROR("Failed to save image.");
00221 }
00222 }
00223
00224 }
00225
00226
00227 #include <pluginlib/class_list_macros.h>
00228 PLUGINLIB_EXPORT_CLASS( image_view::ImageNodelet, nodelet::Nodelet)