video_playback.cpp
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2013, Johannes Meyer, TU Darmstadt
00003 // All rights reserved.
00004 
00005 // Redistribution and use in source and binary forms, with or without
00006 // modification, are permitted provided that the following conditions are met:
00007 //     * Redistributions of source code must retain the above copyright
00008 //       notice, this list of conditions and the following disclaimer.
00009 //     * Redistributions in binary form must reproduce the above copyright
00010 //       notice, this list of conditions and the following disclaimer in the
00011 //       documentation and/or other materials provided with the distribution.
00012 //     * Neither the name of the Flight Systems and Automatic Control group,
00013 //       TU Darmstadt, nor the names of its contributors may be used to
00014 //       endorse or promote products derived from this software without
00015 //       specific prior written permission.
00016 
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //=================================================================================================
00028 
00029 #include <rqt_video_playback/video_playback.h>
00030 #include <pluginlib/class_list_macros.h>
00031 
00032 #include <QFileDialog>
00033 
00034 namespace rqt_video_playback {
00035 
00036 VideoPlayback::VideoPlayback()
00037   : rqt_gui_cpp::Plugin()
00038   , widget_(0)
00039   , step_time_(100)
00040   , time_tolerance_(100)
00041 {
00042   setObjectName("VideoPlayback");
00043 }
00044 
00045 VideoPlayback::~VideoPlayback()
00046 {
00047 }
00048 
00049 void VideoPlayback::initPlugin(qt_gui_cpp::PluginContext& context)
00050 {
00051   widget_ = new QWidget();
00052   ui_.setupUi(widget_);
00053 
00054   if (context.serialNumber() > 1)
00055   {
00056     widget_->setWindowTitle(widget_->windowTitle() + " (" + QString::number(context.serialNumber()) + ")");
00057   }
00058   context.addWidget(widget_);
00059 
00060   // connect UI elements
00061   connect(ui_.open, SIGNAL(clicked()), this, SLOT(openClicked()));
00062   connect(ui_.play, SIGNAL(clicked()), this, SLOT(playClicked()));
00063   connect(ui_.previous, SIGNAL(clicked()), this, SLOT(previousClicked()));
00064   connect(ui_.next, SIGNAL(clicked()), this, SLOT(nextClicked()));
00065   connect(ui_.slider, SIGNAL(valueChanged(int)), this, SLOT(sliderValueChanged(int)));
00066   connect(ui_.sync, SIGNAL(clicked()), this, SLOT(sync()));
00067 
00068   // configure video player
00069   mediaObject()->setTickInterval(100);
00070   connect(mediaObject(), SIGNAL(stateChanged(Phonon::State, Phonon::State)), this, SLOT(stateChanged(Phonon::State, Phonon::State)));
00071   connect(mediaObject(), SIGNAL(currentSourceChanged(Phonon::MediaSource)), this, SLOT(currentSourceChanged(Phonon::MediaSource)));
00072   connect(mediaObject(), SIGNAL(totalTimeChanged(qint64)), this, SLOT(totalTimeChanged(qint64)));
00073 
00074   // connect clock update
00075   connect(this, SIGNAL(clockUpdated()), this, SLOT(sync()));
00076   subscriber_ = getNodeHandle().subscribe<rosgraph_msgs::Clock>("/clock", 1, boost::bind(&VideoPlayback::callbackClock, this, _1));
00077 }
00078 
00079 bool VideoPlayback::eventFilter(QObject* watched, QEvent* event)
00080 {
00081 //  if (watched == ui_.image_frame && event->type() == QEvent::Paint)
00082 //  {
00083 //    QPainter painter(ui_.image_frame);
00084 //    if (!qimage_.isNull())
00085 //    {
00086 //      // TODO: check if full draw is really necessary
00087 //      //QPaintEvent* paint_event = dynamic_cast<QPaintEvent*>(event);
00088 //      //painter.drawImage(paint_event->rect(), qimage_);
00089 //      qimage_mutex_.lock();
00090 //      painter.drawImage(ui_.image_frame->contentsRect(), qimage_);
00091 //      qimage_mutex_.unlock();
00092 //    } else {
00093 //      // default image with gradient
00094 //      QLinearGradient gradient(0, 0, ui_.image_frame->frameRect().width(), ui_.image_frame->frameRect().height());
00095 //      gradient.setColorAt(0, Qt::white);
00096 //      gradient.setColorAt(1, Qt::black);
00097 //      painter.setBrush(gradient);
00098 //      painter.drawRect(0, 0, ui_.image_frame->frameRect().width() + 1, ui_.image_frame->frameRect().height() + 1);
00099 //    }
00100 //    return false;
00101 //  }
00102 
00103   return QObject::eventFilter(watched, event);
00104 }
00105 
00106 void VideoPlayback::shutdownPlugin()
00107 {
00108   subscriber_.shutdown();
00109   ui_.videoPlayer->stop();
00110   ui_.videoPlayer->close();
00111 }
00112 
00113 void VideoPlayback::saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const
00114 {
00115 //  QString topic = ui_.topics_combo_box->currentText();
00116 //  //qDebug("ImageView::saveSettings() topic '%s'", topic.toStdString().c_str());
00117 //  instance_settings.setValue("topic", topic);
00118 //  instance_settings.setValue("zoom1", ui_.zoom_1_push_button->isChecked());
00119 //  instance_settings.setValue("dynamic_range", ui_.dynamic_range_check_box->isChecked());
00120 //  instance_settings.setValue("max_range", ui_.max_range_double_spin_box->value());
00121 }
00122 
00123 void VideoPlayback::restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings)
00124 {
00125 //  bool zoom1_checked = instance_settings.value("zoom1", false).toBool();
00126 //  ui_.zoom_1_push_button->setChecked(zoom1_checked);
00127 
00128 //  bool dynamic_range_checked = instance_settings.value("dynamic_range", false).toBool();
00129 //  ui_.dynamic_range_check_box->setChecked(dynamic_range_checked);
00130 
00131 //  double max_range = instance_settings.value("max_range", ui_.max_range_double_spin_box->value()).toDouble();
00132 //  ui_.max_range_double_spin_box->setValue(max_range);
00133 
00134 //  QString topic = instance_settings.value("topic", "").toString();
00135 //  //qDebug("ImageView::restoreSettings() topic '%s'", topic.toStdString().c_str());
00136 //  selectTopic(topic);
00137 }
00138 
00139 void VideoPlayback::openClicked()
00140 {
00141   QString filter;
00142 
00143   QString fileName = QFileDialog::getOpenFileName(widget_, tr("Open Movie"),
00144           QDir::homePath(), filter);
00145 
00146   if (fileName.isEmpty()) return;
00147 
00148   ui_.videoPlayer->load(fileName);
00149   ui_.sync->setChecked(false);
00150   sync();
00151 }
00152 
00153 void VideoPlayback::playClicked()
00154 {
00155   switch(mediaObject()->state()) {
00156     case Phonon::StoppedState:
00157       ui_.videoPlayer->play();
00158       break;
00159     case Phonon::PausedState:
00160       ui_.videoPlayer->play();
00161       break;
00162     case Phonon::PlayingState:
00163       ui_.videoPlayer->pause();
00164       break;
00165     default:
00166       qDebug() << "Unhandled Phonon state: " << mediaObject()->state();
00167       break;
00168   }
00169 }
00170 
00171 //void VideoPlayer::movieStateChanged(QMovie::MovieState state)
00172 //{
00173 //    switch(state) {
00174 //    case QMovie::NotRunning:
00175 //    case QMovie::Paused:
00176 //        playButton->setIcon(style()->standardIcon(QStyle::SP_MediaPlay));
00177 //        break;
00178 //    case QMovie::Running:
00179 //        playButton->setIcon(style()->standardIcon(QStyle::SP_MediaPause));
00180 //        break;
00181 //    }
00182 //}
00183 
00184 //void VideoPlayer::frameChanged(int frame)
00185 //{
00186 //    if (!presentImage(movie.currentImage())) {
00187 //        movie.stop();
00188 //        playButton->setEnabled(false);
00189 //        positionSlider->setMaximum(0);
00190 //    } else {
00191 //        positionSlider->setValue(frame);
00192 //    }
00193 //}
00194 
00195 void VideoPlayback::previousClicked()
00196 {
00197   qint64 new_time = ui_.videoPlayer->currentTime() - step_time_;
00198   if (new_time > 0)
00199     ui_.videoPlayer->seek(new_time);
00200 }
00201 
00202 void VideoPlayback::nextClicked()
00203 {
00204   qint64 new_time = ui_.videoPlayer->currentTime() + step_time_;
00205   if (new_time < ui_.videoPlayer->totalTime())
00206     ui_.videoPlayer->seek(new_time);
00207 }
00208 
00209 void VideoPlayback::sliderValueChanged(int value)
00210 {
00211   if (ui_.videoPlayer->currentTime() != value)
00212     ui_.videoPlayer->seek(value);
00213 }
00214 
00215 ros::Duration VideoPlayback::toRos(qint64 time)
00216 {
00217   uint32_t sec, nsec;
00218   sec = time / 1000ll;
00219   nsec = (time - sec * 1000ll) * 1000000;
00220   return ros::Duration(sec, nsec);
00221 }
00222 
00223 qint64 VideoPlayback::fromRos(const ros::Duration& duration)
00224 {
00225   return (qint64(duration.sec) * 1000ll + qint64(duration.nsec) / 1000000ll);
00226 }
00227 
00228 void VideoPlayback::sync()
00229 {
00230   tick(ui_.videoPlayer->mediaObject()->currentTime());
00231 }
00232 
00233 void VideoPlayback::tick(qint64 tick)
00234 {
00235   ui_.slider->setSliderPosition(tick);
00236 
00237   qint64 currentVideo = tick;
00238   qint64 totalTime = ui_.videoPlayer->totalTime();
00239 
00240   // is a video source loaded?
00241   if (ui_.videoPlayer->mediaObject()->currentSource().type() == Phonon::MediaSource::Empty) {
00242     ui_.controls->setEnabled(false);
00243     return;
00244   }
00245 
00246   // adjust start time if Sync is not checked
00247   if (!ui_.sync->isChecked()) {
00248     ui_.controls->setEnabled(true);
00249 
00250     if (!clock_.isZero()) start_ = clock_ - toRos(currentVideo);
00251     return;
00252   }
00253 
00254   // sync video with ROS clock time
00255   ui_.controls->setEnabled(false);
00256 
00257   // wait until clock is available
00258   if (clock_.isZero()) {
00259     ui_.videoPlayer->pause();
00260     return;
00261   }
00262 
00263   qint64 currentRos = fromRos(clock_ - start_);
00264 
00265   std::cout << "video: " << currentVideo << "/" << totalTime << ", ROS: " << currentRos << " => diff: " << (currentVideo - currentRos) << std::endl;
00266 
00267   if (currentVideo < currentRos - time_tolerance_) {
00268     if (currentRos < totalTime) {
00269       ui_.videoPlayer->seek(currentRos);
00270       ui_.videoPlayer->play();
00271     } else {
00272       ui_.videoPlayer->pause();
00273     }
00274   }
00275 
00276   if (currentVideo > currentRos + time_tolerance_) {
00277     if (currentRos >= 0) {
00278       ui_.videoPlayer->seek(currentRos);
00279       ui_.videoPlayer->play();
00280     } else {
00281       ui_.videoPlayer->pause();
00282     }
00283   }
00284 }
00285 
00286 void VideoPlayback::stateChanged(Phonon::State newstate, Phonon::State oldstate)
00287 {
00288   switch(newstate) {
00289     case Phonon::PlayingState:
00290       ui_.play->setIcon(QIcon::fromTheme("media-playback-pause"));
00291       break;
00292 
00293     case Phonon::StoppedState:
00294       ui_.play->setIcon(QIcon::fromTheme("media-playback-start"));
00295       break;
00296 
00297     case Phonon::PausedState:
00298       ui_.play->setIcon(QIcon::fromTheme("media-playback-start"));
00299       break;
00300   }
00301 }
00302 
00303 void VideoPlayback::totalTimeChanged(qint64 total)
00304 {
00305   ui_.slider->setMaximum(total);
00306 }
00307 
00308 void VideoPlayback::currentSourceChanged(Phonon::MediaSource)
00309 {
00310   sync();
00311 }
00312 
00313 void VideoPlayback::callbackClock(const rosgraph_msgs::Clock::ConstPtr& clock)
00314 {
00315   clock_ = clock->clock;
00316   clockUpdated();
00317 }
00318 
00319 } // namespace rqt_video_playback
00320 
00321 PLUGINLIB_EXPORT_CLASS(rqt_video_playback::VideoPlayback, rqt_gui_cpp::Plugin)


rqt_video_playback
Author(s): Johannes Meyer
autogenerated on Mon Oct 6 2014 00:35:50