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