motion_planning_frame_context.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012, Willow Garage, Inc.
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: Ioan Sucan */
00036 
00037 #include <moveit/warehouse/planning_scene_storage.h>
00038 #include <moveit/warehouse/constraints_storage.h>
00039 #include <moveit/warehouse/state_storage.h>
00040 
00041 #include <moveit/motion_planning_rviz_plugin/motion_planning_frame.h>
00042 #include <moveit/motion_planning_rviz_plugin/motion_planning_display.h>
00043 
00044 #include <rviz/display_context.h>
00045 #include <rviz/window_manager_interface.h>
00046 
00047 #include <QMessageBox>
00048 #include <QInputDialog>
00049 
00050 #include "ui_motion_planning_rviz_plugin_frame.h"
00051 
00052 namespace moveit_rviz_plugin
00053 {
00054 void MotionPlanningFrame::databaseConnectButtonClicked()
00055 {
00056   planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computeDatabaseConnectButtonClicked, this),
00057                                       "connect to database");
00058 }
00059 
00060 void MotionPlanningFrame::publishSceneButtonClicked()
00061 {
00062   const planning_scene_monitor::LockedPlanningSceneRO& ps = planning_display_->getPlanningSceneRO();
00063   if (ps)
00064   {
00065     moveit_msgs::PlanningScene msg;
00066     ps->getPlanningSceneMsg(msg);
00067     planning_scene_publisher_.publish(msg);
00068   }
00069 }
00070 
00071 void MotionPlanningFrame::planningAlgorithmIndexChanged(int index)
00072 {
00073   if (move_group_)
00074   {
00075     if (index > 0)
00076       move_group_->setPlannerId(ui_->planning_algorithm_combo_box->itemText(index).toStdString());
00077     else
00078       move_group_->setPlannerId("");
00079   }
00080 }
00081 
00082 void MotionPlanningFrame::resetDbButtonClicked()
00083 {
00084   if (QMessageBox::warning(this, "Data about to be deleted", "The following dialog will allow you to drop a MoveIt "
00085                                                              "Warehouse database. Are you sure you want to continue?",
00086                            QMessageBox::Yes | QMessageBox::No) == QMessageBox::No)
00087     return;
00088 
00089   QStringList dbs;
00090   dbs.append("Planning Scenes");
00091   dbs.append("Constraints");
00092   dbs.append("Robot States");
00093 
00094   bool ok = false;
00095   QString response =
00096       QInputDialog::getItem(this, tr("Select Database"), tr("Choose the database to reset:"), dbs, 2, false, &ok);
00097   if (!ok)
00098     return;
00099 
00100   if (QMessageBox::critical(
00101           this, "Data about to be deleted",
00102           QString("All data in database '").append(response).append("'. Are you sure you want to continue?"),
00103           QMessageBox::Yes | QMessageBox::No) == QMessageBox::No)
00104     return;
00105 
00106   planning_display_->addBackgroundJob(
00107       boost::bind(&MotionPlanningFrame::computeResetDbButtonClicked, this, response.toStdString()), "reset database");
00108 }
00109 
00110 void MotionPlanningFrame::computeDatabaseConnectButtonClicked()
00111 {
00112   if (planning_scene_storage_)
00113   {
00114     planning_scene_storage_.reset();
00115     robot_state_storage_.reset();
00116     constraints_storage_.reset();
00117     planning_display_->addMainLoopJob(
00118         boost::bind(&MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper, this, 1));
00119   }
00120   else
00121   {
00122     planning_display_->addMainLoopJob(
00123         boost::bind(&MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper, this, 2));
00124     try
00125     {
00126       planning_scene_storage_.reset(new moveit_warehouse::PlanningSceneStorage(ui_->database_host->text().toStdString(),
00127                                                                                ui_->database_port->value(), 5.0));
00128       robot_state_storage_.reset(new moveit_warehouse::RobotStateStorage(ui_->database_host->text().toStdString(),
00129                                                                          ui_->database_port->value(), 5.0));
00130       constraints_storage_.reset(new moveit_warehouse::ConstraintsStorage(ui_->database_host->text().toStdString(),
00131                                                                           ui_->database_port->value(), 5.0));
00132     }
00133     catch (std::runtime_error& ex)
00134     {
00135       planning_display_->addMainLoopJob(
00136           boost::bind(&MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper, this, 3));
00137       ROS_ERROR("%s", ex.what());
00138       return;
00139     }
00140     planning_display_->addMainLoopJob(
00141         boost::bind(&MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper, this, 4));
00142   }
00143 }
00144 
00145 void MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper(int mode)
00146 {
00147   if (mode == 1)
00148   {
00149     ui_->planning_scene_tree->setUpdatesEnabled(false);
00150     ui_->planning_scene_tree->clear();
00151     ui_->planning_scene_tree->setUpdatesEnabled(true);
00152 
00153     ui_->database_connect_button->setUpdatesEnabled(false);
00154     ui_->database_connect_button->setText(QString::fromStdString("Connect"));
00155     ui_->database_connect_button->setStyleSheet("QPushButton { color : green }");
00156     ui_->database_connect_button->setUpdatesEnabled(true);
00157     ui_->reset_db_button->hide();
00158 
00159     ui_->load_scene_button->setEnabled(false);
00160     ui_->load_query_button->setEnabled(false);
00161     ui_->save_query_button->setEnabled(false);
00162     ui_->save_scene_button->setEnabled(false);
00163     ui_->delete_query_button->setEnabled(false);
00164     ui_->delete_scene_button->setEnabled(false);
00165     populateConstraintsList(std::vector<std::string>());
00166   }
00167   else if (mode == 2)
00168   {
00169     ui_->database_connect_button->setUpdatesEnabled(false);
00170     ui_->database_connect_button->setText(QString::fromStdString("Connecting ..."));
00171     ui_->database_connect_button->setUpdatesEnabled(true);
00172     populateConstraintsList(std::vector<std::string>());
00173   }
00174   else if (mode == 3)
00175   {
00176     ui_->database_connect_button->setUpdatesEnabled(false);
00177     ui_->database_connect_button->setText(QString::fromStdString("Connect"));
00178     ui_->database_connect_button->setStyleSheet("QPushButton { color : green }");
00179     ui_->database_connect_button->setUpdatesEnabled(true);
00180     ui_->reset_db_button->hide();
00181   }
00182   else if (mode == 4)
00183   {
00184     ui_->database_connect_button->setUpdatesEnabled(false);
00185     ui_->database_connect_button->setText(QString::fromStdString("Disconnect"));
00186     ui_->database_connect_button->setStyleSheet("QPushButton { color : darkBlue }");
00187     ui_->database_connect_button->setUpdatesEnabled(true);
00188     ui_->save_scene_button->setEnabled(true);
00189     ui_->reset_db_button->show();
00190     populatePlanningSceneTreeView();
00191     loadStoredStates(".*");  // automatically populate the 'Stored States' tab with all states
00192     if (move_group_)
00193     {
00194       move_group_->setConstraintsDatabase(ui_->database_host->text().toStdString(), ui_->database_port->value());
00195       planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::populateConstraintsList, this),
00196                                           "populateConstraintsList");
00197     }
00198   }
00199 }
00200 
00201 void MotionPlanningFrame::computeResetDbButtonClicked(const std::string& db)
00202 {
00203   if (db == "Constraints" && constraints_storage_)
00204     constraints_storage_->reset();
00205   else if (db == "Robot States" && robot_state_storage_)
00206     robot_state_storage_->reset();
00207   else if (db == "Planning Scenes")
00208     planning_scene_storage_->reset();
00209 }
00210 }


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