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
00035
00036 #include "video_capture_display.h"
00037 #include <rviz/display_context.h>
00038 #include <rviz/view_manager.h>
00039 #include <rviz/display_group.h>
00040 #include <rviz/display.h>
00041 #include <rviz/render_panel.h>
00042 #include <QImage>
00043 #if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0)
00044 #include <QScreen>
00045 #include <QGuiApplication>
00046 #endif
00047 #include <boost/filesystem.hpp>
00048
00049 namespace jsk_rviz_plugins
00050 {
00051 VideoCaptureDisplay::VideoCaptureDisplay():
00052 Display(), capturing_(false), first_time_(true)
00053 {
00054 start_capture_property_ = new rviz::BoolProperty(
00055 "start capture", false, "start capture",
00056 this, SLOT(updateStartCapture()));
00057 file_name_property_ = new rviz::StringProperty(
00058 "filename", "output.avi",
00059 "filename", this, SLOT(updateFileName()));
00060 fps_property_ = new rviz::FloatProperty(
00061 "fps", 30.0,
00062 "fps", this, SLOT(updateFps()));
00063 fps_property_->setMin(0.1);
00064 }
00065
00066 VideoCaptureDisplay::~VideoCaptureDisplay()
00067 {
00068 delete start_capture_property_;
00069 delete file_name_property_;
00070 }
00071
00072 void VideoCaptureDisplay::onInitialize()
00073 {
00074 updateFileName();
00075 updateFps();
00076
00077 start_capture_property_->setBool(false);
00078 context_->queueRender();
00079 }
00080
00081 void VideoCaptureDisplay::onEnable()
00082 {
00083 start_capture_property_->setBool(false);
00084 context_->queueRender();
00085 }
00086
00087 void VideoCaptureDisplay::updateFileName()
00088 {
00089 if (capturing_) {
00090 ROS_WARN("cannot change name wile recording");
00091 file_name_property_->setStdString(file_name_);
00092 }
00093 else {
00094 file_name_ = file_name_property_->getStdString();
00095 int exists_check = access(file_name_.c_str(), F_OK);
00096 if (exists_check == 0) {
00097 int access_result = access(file_name_.c_str(), W_OK);
00098 ROS_INFO("access_result to %s: %d", file_name_.c_str(), access_result);
00099 if (access_result != 0) {
00100 setStatus(rviz::StatusProperty::Error, "File", "NOT Writable");
00101 }
00102 else {
00103 setStatus(rviz::StatusProperty::Ok, "File", "Writable");
00104 }
00105 }
00106 else {
00107 ROS_INFO("%s do not exists", file_name_.c_str());
00108 boost::filesystem::path pathname(file_name_);
00109 std::string dirname = pathname.parent_path().string();
00110 if (dirname.length() == 0) {
00111 dirname = ".";
00112 }
00113 ROS_INFO("dirname: %s", dirname.c_str());
00114 int directory_access_result = access(dirname.c_str(), W_OK);
00115 if (directory_access_result != 0) {
00116 setStatus(rviz::StatusProperty::Error, "File", "NOT Writable (direcotry)");
00117 }
00118 else {
00119 setStatus(rviz::StatusProperty::Ok, "File", "Writable");
00120 }
00121 }
00122 }
00123 }
00124
00125 void VideoCaptureDisplay::updateStartCapture()
00126 {
00127 ROS_INFO("updateStartCapture");
00128 if (first_time_) {
00129 ROS_WARN("ignore first time capture enabling");
00130 }
00131 else {
00132
00133 if (start_capture_property_->getBool()) {
00134 capturing_ = true;
00135 startCapture();
00136 }
00137 else {
00138 capturing_ = false;
00139 stopCapture();
00140 }
00141 }
00142 }
00143
00144 void VideoCaptureDisplay::updateFps()
00145 {
00146 fps_ = fps_property_->getFloat();
00147 }
00148
00149 void VideoCaptureDisplay::startCapture()
00150 {
00151 ROS_INFO("start capturing");
00152 frame_counter_ = 0;
00153 rviz::RenderPanel* panel = context_->getViewManager()->getRenderPanel();
00154 int width = panel->width();
00155 int height = panel->height();
00156 writer_.open(file_name_, CV_FOURCC_DEFAULT, fps_, cv::Size(width, height));
00157 }
00158
00159 void VideoCaptureDisplay::stopCapture()
00160 {
00161 ROS_INFO("stop capturing");
00162 writer_.release();
00163 frame_counter_ = 0;
00164 }
00165
00166 void VideoCaptureDisplay::update(float wall_dt, float ros_dt)
00167 {
00168 if (first_time_) {
00169 ROS_WARN("force to disable capturing");
00170 start_capture_property_->setBool(false);
00171 first_time_ = false;
00172 return;
00173 }
00174 if (capturing_) {
00175 rviz::RenderPanel* panel = context_->getViewManager()->getRenderPanel();
00176 #if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0)
00177 QPixmap screenshot
00178 = QGuiApplication::primaryScreen()->grabWindow(context_->getViewManager()->getRenderPanel()->winId());
00179 #else
00180 QPixmap screenshot
00181 = QPixmap::grabWindow(context_->getViewManager()->getRenderPanel()->winId());
00182 #endif
00183 QImage src = screenshot.toImage().convertToFormat(QImage::Format_RGB888);
00184 cv::Mat image(src.height(), src.width(), CV_8UC3,
00185 (uchar*)src.bits(), src.bytesPerLine());
00186 cv::cvtColor(image, image, CV_RGB2BGR);
00187 writer_ << image;
00188 ++frame_counter_;
00189 if (frame_counter_ % 100 == 0) {
00190 ROS_INFO("taking %d frames as video", frame_counter_);
00191 }
00192 }
00193
00194 }
00195 }
00196
00197
00198 #include <pluginlib/class_list_macros.h>
00199 PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::VideoCaptureDisplay, rviz::Display)
00200