trajectory_panel.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2017, Yannick Jonetzko
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Yannick Jonetzko */
00036 
00037 #include <moveit/rviz_plugin_render_tools/trajectory_panel.h>
00038 #include <QHBoxLayout>
00039 
00040 namespace moveit_rviz_plugin
00041 {
00042 TrajectoryPanel::TrajectoryPanel(QWidget* parent) : Panel(parent)
00043 {
00044 }
00045 
00046 TrajectoryPanel::~TrajectoryPanel()
00047 {
00048 }
00049 
00050 void TrajectoryPanel::onInitialize()
00051 {
00052   slider_ = new QSlider(Qt::Horizontal);
00053   slider_->setTickInterval(1);
00054   slider_->setMinimum(0);
00055   slider_->setMaximum(0);
00056   slider_->setTickPosition(QSlider::TicksBelow);
00057   slider_->setPageStep(1);
00058   slider_->setEnabled(false);
00059   connect(slider_, SIGNAL(valueChanged(int)), this, SLOT(sliderValueChanged(int)));
00060 
00061   maximum_label_ = new QLabel(QString::number(slider_->maximum()));
00062   minimum_label_ = new QLabel(QString::number(slider_->minimum()));
00063   minimum_label_->setFixedWidth(20);
00064 
00065   button_ = new QPushButton();
00066   button_->setText("Pause");
00067   button_->setEnabled(false);
00068   connect(button_, SIGNAL(clicked()), this, SLOT(buttonClicked()));
00069 
00070   QHBoxLayout* layout = new QHBoxLayout;
00071   layout->addWidget(new QLabel("Waypoint:"));
00072   layout->addWidget(minimum_label_);
00073   layout->addWidget(slider_);
00074   layout->addWidget(maximum_label_);
00075   layout->addWidget(button_);
00076   setLayout(layout);
00077 
00078   paused_ = false;
00079   parentWidget()->setVisible(false);
00080 }
00081 
00082 void TrajectoryPanel::onEnable()
00083 {
00084   show();
00085   parentWidget()->show();
00086 }
00087 
00088 void TrajectoryPanel::onDisable()
00089 {
00090   hide();
00091   paused_ = false;
00092   parentWidget()->hide();
00093 }
00094 
00095 void TrajectoryPanel::update(int way_point_count)
00096 {
00097   int max_way_point = std::max(0, way_point_count - 1);
00098 
00099   slider_->setEnabled(way_point_count != 0);
00100   button_->setEnabled(way_point_count != 0);
00101 
00102   last_way_point_ = max_way_point;
00103   paused_ = false;
00104   slider_->setSliderPosition(0);
00105   slider_->setMaximum(max_way_point);
00106   maximum_label_->setText(QString::number(max_way_point));
00107 }
00108 
00109 void TrajectoryPanel::pauseButton(bool pause)
00110 {
00111   if (pause)
00112   {
00113     button_->setText("Play");
00114     paused_ = true;
00115   }
00116   else
00117   {
00118     button_->setText("Pause");
00119     paused_ = false;
00120     if (slider_->sliderPosition() == last_way_point_)
00121       slider_->setSliderPosition(0);
00122   }
00123 }
00124 
00125 void TrajectoryPanel::setSliderPosition(int position)
00126 {
00127   slider_->setSliderPosition(position);
00128 }
00129 
00130 void TrajectoryPanel::sliderValueChanged(int value)
00131 {
00132   minimum_label_->setText(QString::number(value));
00133 }
00134 
00135 void TrajectoryPanel::buttonClicked()
00136 {
00137   if (paused_)
00138     pauseButton(false);
00139   else
00140     pauseButton(true);
00141 }
00142 
00143 }  // namespace moveit_rviz_plugin


visualization
Author(s): Ioan Sucan , Dave Coleman , Sachin Chitta
autogenerated on Wed Jun 19 2019 19:25:00