tablet_controller_panel.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 
00037 #include "tablet_controller_panel.h"
00038 #include <Eigen/Core>
00039 #include <Eigen/Geometry>
00040 namespace jsk_rviz_plugins
00041 {
00042   TabletCmdVelArea::TabletCmdVelArea(QWidget* parent, ros::Publisher& pub_cmd_vel):
00043     QWidget(parent), mouse_x_(-1), mouse_y_(-1), pub_cmd_vel_(pub_cmd_vel)
00044   {
00045     setBackgroundRole(QPalette::Base);
00046     setAutoFillBackground(true);
00047   }
00048 
00049   QSize TabletCmdVelArea::minimumSizeHint() const
00050   {
00051     return QSize(300, 300);
00052   }
00053 
00054   QSize TabletCmdVelArea::sizeHint() const
00055   {
00056     return QSize(300, 300);
00057   }
00058 
00059   void TabletCmdVelArea::mouseMoveEvent(QMouseEvent* event){
00060     mouse_x_ = event->x();
00061     mouse_y_ = event->y();
00062     repaint();
00063   }
00064   void TabletCmdVelArea::mousePressEvent(QMouseEvent* event){
00065     mouse_x_ = event->x();
00066     mouse_y_ = event->y();
00067     repaint();
00068   }
00069   void TabletCmdVelArea::mouseReleaseEvent(QMouseEvent* event){
00070     mouse_x_ = -1;
00071     mouse_y_ = -1;
00072     repaint();
00073     publishCmdVel(0, 0, 0);
00074   }
00075   
00076   void TabletCmdVelArea::paintEvent(QPaintEvent* event)
00077   {
00078     QSize widget_size = size();
00079     int line_width = 20;
00080     int width = widget_size.width() - line_width * 2;
00081     int height = widget_size.height() - line_width * 2;
00082     // out circle
00083     int radius = std::min(width, height) / 2;
00084     int center_x = width / 2 + line_width;
00085     int center_y = height / 2 + line_width;
00086     QPainter painter(this);
00087     painter.setRenderHint(QPainter::Antialiasing);
00088     QPen pen;
00089     pen.setColor(QColor(130, 177, 255));
00090     pen.setWidth(10);
00091     painter.setPen(pen);
00092     painter.drawArc(center_x - radius, center_y - radius,
00093                     radius * 2, radius * 2, 0, (360 + 1) * 16);
00094     // position of mouse
00095     QPen inner_pen;
00096     inner_pen.setColor(QColor(33, 150, 243));
00097     int inner_size = 40;
00098     inner_pen.setWidth(inner_size);
00099     painter.setPen(inner_pen);
00100     if (mouse_x_ == -1 && mouse_y_ == -1) {
00101       mouse_x_ = center_x;
00102       mouse_y_ = center_y;
00103     }
00104     else {
00105       publishVelocity(mouse_x_, mouse_y_, center_x, center_y);
00106     }
00107     painter.drawArc(mouse_x_ - inner_size / 2,
00108                     mouse_y_ - inner_size / 2, 
00109                     inner_size, inner_size, 0, (360 + 1) * 16);
00110   }
00111 
00112   void TabletCmdVelArea::publishVelocity(
00113     int mouse_x, int mouse_y, int cx, int cy)
00114   {
00115     double diff_x = mouse_x - cx;
00116     double diff_y = mouse_y - cy;
00117     Eigen::Vector3d ex(0, -1, 0);
00118     Eigen::Vector3d vel(diff_x / cx, diff_y / cy, 0);
00119     
00120     int sign = 1;
00121     if (ex.cross(vel).dot(Eigen::Vector3d(0, 0, -1)) < 0) {
00122       sign = -1;
00123     }
00124     double dot = ex.dot(vel) / ex.norm() / vel.norm();
00125     if (dot < -1) {
00126       dot = -1.0;
00127     }
00128     else if (dot > 1) {
00129       dot = 1.0;
00130     }
00131     double theta = sign * acos(dot);
00132     if (!std::isnan(theta)) {
00133       Eigen::Vector3d vel_refined(-vel[1], -vel[0], 0);
00134       
00135       publishCmdVel(vel_refined[0] * 0.2 , vel_refined[1] * 0.2, theta * 0.2);
00136     }
00137   }
00138 
00139   void TabletCmdVelArea::publishCmdVel(double x, double y, double theta)
00140   {
00141     ROS_INFO("(%f, %f)", x, y);
00142     ROS_INFO("theta: %f", theta);
00143     geometry_msgs::Twist twist;
00144     twist.linear.x = x;
00145     twist.linear.y = y;
00146     twist.angular.z = theta;
00147     pub_cmd_vel_.publish(twist);
00148   }
00149 
00150   QString TabletControllerPanel::defaultButtonStyleSheet()
00151   {
00152     return "QPushButton {background-color: #FF5252; color: white; font-size: 30pt;}";
00153   }
00154 
00155   QString TabletControllerPanel::executeButtonStyleSheet()
00156   {
00157     return "QPushButton {background-color: white; color: #424242; font-size: 30pt;}";
00158   }
00159 
00160   QString TabletControllerPanel::radioButtonStyleSheet()
00161   {
00162     return "QRadioButton {font-size: 20pt; color: #424242;}";
00163   }
00164   
00165   QString TabletControllerPanel::listStyleSheet()
00166   {
00167     return "QListWidget {font-size: 20pt; color: #424242;}";
00168   }
00169   
00170   TabletControllerPanel::TabletControllerPanel(QWidget* parent): rviz::Panel(parent)
00171   {
00172     ros::NodeHandle nh;
00173     pub_start_demo_ = nh.advertise<jsk_rviz_plugins::StringStamped>(
00174       "/Tablet/StartDemo", 1);
00175     pub_spot_ = nh.advertise<jsk_rviz_plugins::StringStamped>(
00176       "/Tablet/MoveToSpot", 1);
00177     sub_spots_ = nh.subscribe("/spots_marker_array",
00178                               1, &TabletControllerPanel::spotCallback, this);
00179     pub_cmd_vel_ = nh.advertise<geometry_msgs::Twist>(
00180       "/navigation/unsafe_vel", 1);
00181     layout_ = new QVBoxLayout();
00182     layout_->addStretch();
00183     task_button_ = new QPushButton("Task", this);
00184     task_button_->setMinimumHeight(100);
00185     task_button_->setStyleSheet(defaultButtonStyleSheet());
00186 
00187     connect(task_button_, SIGNAL(released()), this, SLOT(taskButtonClicked()));
00188     layout_->addWidget(task_button_);
00189     layout_->addSpacing(10);
00190     spot_button_ = new QPushButton("Move to spot", this);
00191     spot_button_->setMinimumHeight(100);
00192     spot_button_->setStyleSheet(defaultButtonStyleSheet());
00193     connect(spot_button_, SIGNAL(released()), this, SLOT(spotButtonClicked()));
00194     layout_->addWidget(spot_button_);
00195     layout_->addSpacing(10);
00196     cmd_vel_area_ = new TabletCmdVelArea(this, pub_cmd_vel_);
00197     layout_->addWidget(cmd_vel_area_);
00198     
00199     
00200     setLayout(layout_);
00201     setBackgroundRole(QPalette::Base);
00202     setAutoFillBackground(true);
00203   }
00204 
00205   TabletControllerPanel::~TabletControllerPanel()
00206   {
00207 
00208   }
00209 
00210   void TabletControllerPanel::load(const rviz::Config& config)
00211   {
00212     rviz::Panel::load(config);
00213   }
00214   
00215   void TabletControllerPanel::save(rviz::Config config) const
00216   {
00217     rviz::Panel::save(config);
00218   }
00219 
00221   // callbacks
00223   void TabletControllerPanel::spotCallback(
00224     const visualization_msgs::MarkerArray::ConstPtr& marker)
00225   {
00226     boost::mutex::scoped_lock lock(mutex_);
00227     spots_.clear();
00228     for (size_t i = 0; i < marker->markers.size(); i++) {
00229       std::string text = marker->markers[i].text;
00230       if (!text.empty()) {
00231         spots_.push_back(text);
00232       }
00233     }
00234   }
00235   
00236 
00237   
00238   void TabletControllerPanel::taskButtonClicked()
00239   {
00240     task_dialog_ = new QDialog();
00241     task_dialog_->setBackgroundRole(QPalette::Base);
00242     task_dialog_->setAutoFillBackground(true);
00243     task_dialog_layout_ = new QVBoxLayout();
00244     task_radio_buttons_.clear();
00245     std::vector<std::string> tasks;
00246     tasks.push_back("/Tablet/other/GetGeorgia");
00247     tasks.push_back("/Tablet/chen/GoToElevator");
00248     tasks.push_back("/Tablet/chen/Greeting1");
00249     tasks.push_back("/Tablet/chen/Greeting2");
00250     tasks.push_back("/Tablet/chen/Greeting3");
00251     tasks.push_back("/Tablet/chen/Greeting4");
00252     tasks.push_back("/Tablet/chen/Greeting5");
00253     tasks.push_back("/Tablet/chen/HandOver");
00254     for (size_t i = 0; i < tasks.size(); i++) {
00255       QRadioButton* task = new QRadioButton(QString::fromStdString(tasks[i]), this);
00256       task->setMinimumHeight(50);
00257       if (i == 0) {
00258         task->setChecked(true);
00259       }
00260       task->setStyleSheet(radioButtonStyleSheet());
00261       task_radio_buttons_.push_back(task);
00262     }
00263     
00264     for (size_t i = 0; i < task_radio_buttons_.size(); i++) {
00265       task_dialog_layout_->addWidget(task_radio_buttons_[i]);
00266     }
00267     task_dialog_button_layout_ = new QHBoxLayout();
00268     task_execute_button_ = new QPushButton("Execute", this);
00269     task_execute_button_->setStyleSheet(executeButtonStyleSheet());
00270     task_execute_button_->setMinimumHeight(100);
00271     task_execute_button_->setMinimumWidth(300);
00272     task_dialog_button_layout_->addWidget(task_execute_button_);
00273     connect(task_execute_button_, SIGNAL(released()), this, SLOT(taskExecuteClicked()));
00274     task_cancel_button_ = new QPushButton("Cancel", this);
00275     task_cancel_button_->setStyleSheet(defaultButtonStyleSheet());
00276     task_cancel_button_->setMinimumHeight(100);
00277     task_cancel_button_->setMinimumWidth(300);
00278     connect(task_cancel_button_, SIGNAL(released()), this, SLOT(taskCancelClicked()));
00279     task_dialog_button_layout_->addWidget(task_cancel_button_);
00280     task_dialog_layout_->addLayout(task_dialog_button_layout_);
00281     task_dialog_->setLayout(task_dialog_layout_);
00282     task_dialog_->show();
00283     
00284   }
00285 
00286   void TabletControllerPanel::taskCancelClicked()
00287   {
00288     task_dialog_->reject();
00289   }
00290 
00291   void TabletControllerPanel::taskExecuteClicked()
00292   {
00293     for (size_t i = 0; i < task_radio_buttons_.size(); i++) {
00294       QRadioButton* radio = task_radio_buttons_[i];
00295       if (radio->isChecked()) {
00296         std::string task = radio->text().toStdString();
00297         ROS_INFO("task: %s", task.c_str());
00298         task_dialog_->reject();
00299         jsk_rviz_plugins::StringStamped command;
00300         command.data = task;
00301         command.header.stamp = ros::Time::now();
00302         pub_start_demo_.publish(command);
00303         return;
00304       }
00305     }
00306   }
00307   
00308   void TabletControllerPanel::spotButtonClicked()
00309   {
00310     boost::mutex::scoped_lock lock(mutex_);
00311     spot_dialog_ = new QDialog();
00312     spot_dialog_->setBackgroundRole(QPalette::Base);
00313     spot_dialog_->setAutoFillBackground(true);
00314     spot_dialog_layout_ = new QVBoxLayout();
00315 
00316     spot_list_ = new QListWidget();
00317     spot_list_->setSortingEnabled(true);
00318     spot_list_->setStyleSheet(listStyleSheet());
00319     for (size_t i = 0; i < spots_.size(); i++) {
00320       QListWidgetItem* item = new QListWidgetItem(
00321         QString::fromStdString(spots_[i]));
00322       item->setSizeHint(QSize(item->sizeHint().width(), 30));
00323       spot_list_->addItem(item);
00324     }
00325     spot_dialog_layout_->addWidget(spot_list_);
00326     spot_dialog_button_layout_ = new QHBoxLayout();
00327     spot_go_button_ = new QPushButton("Go", this);
00328     spot_go_button_->setStyleSheet(executeButtonStyleSheet());
00329     spot_go_button_->setMinimumHeight(50);
00330     spot_go_button_->setMinimumWidth(300);
00331     connect(spot_go_button_, SIGNAL(released()),
00332             this, SLOT(spotGoClicked()));
00333     spot_dialog_button_layout_->addWidget(spot_go_button_);
00334     
00335     spot_cancel_button_ = new QPushButton("Cancel", this);
00336     spot_cancel_button_->setMinimumHeight(50);
00337     spot_cancel_button_->setMinimumWidth(300);
00338     spot_cancel_button_->setStyleSheet(defaultButtonStyleSheet());
00339     connect(spot_cancel_button_, SIGNAL(released()),
00340             this, SLOT(spotCancelClicked()));
00341     spot_dialog_button_layout_->addWidget(spot_cancel_button_);
00342     spot_dialog_layout_->addLayout(spot_dialog_button_layout_);
00343     spot_dialog_->setLayout(spot_dialog_layout_);
00344     spot_dialog_->show();
00345   }
00346 
00347   void TabletControllerPanel::spotCancelClicked()
00348   {
00349     spot_dialog_->reject();
00350   }
00351 
00352   void TabletControllerPanel::spotGoClicked()
00353   {
00354     QListWidgetItem* item = spot_list_->currentItem();
00355     if (item) {
00356       std::string spot = item->text().toStdString();
00357       jsk_rviz_plugins::StringStamped spot_command;
00358       spot_command.data = spot;
00359       spot_command.header.stamp = ros::Time::now();
00360       pub_spot_.publish(spot_command);
00361     }
00362     spot_dialog_->reject();
00363   }
00364 
00365 }
00366 
00367 #include <pluginlib/class_list_macros.h>
00368 PLUGINLIB_EXPORT_CLASS (jsk_rviz_plugins::TabletControllerPanel, rviz::Panel);


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Wed May 1 2019 02:40:22