main_window.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, 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: Mario Prats, Ioan Sucan */
00036 
00037 #include <main_window.h>
00038 #include <ui_utils.h>
00039 
00040 #include <QShortcut>
00041 #include <QFileDialog>
00042 #include <QMessageBox>
00043 
00044 #include <assert.h>
00045 #include <string>
00046 #include <rviz/tool_manager.h>
00047 #include <rviz/frame_manager.h>
00048 #include <rviz/display_factory.h>
00049 #include <rviz/selection/selection_manager.h>
00050 
00051 namespace benchmark_tool
00052 {
00053 
00054 const char * MainWindow::ROBOT_DESCRIPTION_PARAM = "robot_description";
00055 const char * MainWindow::ROBOT_DESCRIPTION_SEMANTIC_PARAM = "robot_description_semantic";
00056 const unsigned int MainWindow::DEFAULT_WAREHOUSE_PORT = 33830;
00057 
00058 MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
00059     QMainWindow(parent),
00060     goal_pose_dragging_(false)
00061 {
00062   QMessageBox::warning(this, "Development", "This GUI is under development and has many issues. Use at your own risk.");
00063 
00064   setWindowTitle("Benchmark Tool");
00065 
00066   goal_offset_.setIdentity();
00067 
00068   ui_.setupUi(this);
00069   settings_.reset(new QSettings("WillowGarage", "Benchmark Tool"));
00070   QVariant previous_database_names = settings_->value("database_name", QStringList());
00071   ui_.db_combo->addItems(previous_database_names.toStringList());
00072 
00073   robot_loader_dialog_ = new QDialog(0,0);
00074   load_robot_ui_.setupUi(robot_loader_dialog_);
00075 
00076   run_benchmark_dialog_ = new QDialog(0,0);
00077   run_benchmark_ui_.setupUi(run_benchmark_dialog_);
00078 
00079   bbox_dialog_ = new QDialog(0,0);
00080   bbox_dialog_ui_.setupUi(bbox_dialog_);
00081 
00082   //Rviz render panel
00083   render_panel_ = new rviz::RenderPanel();
00084   ui_.render_widget->addWidget(render_panel_);
00085   ui_.splitter->setStretchFactor(1, 4);
00086 
00087   visualization_manager_ = new rviz::VisualizationManager(render_panel_);
00088   render_panel_->initialize(visualization_manager_->getSceneManager(), visualization_manager_);
00089 
00090   visualization_manager_->initialize();
00091   visualization_manager_->startUpdate();
00092 
00093   //Grid display
00094   visualization_manager_->createDisplay("rviz/Grid", "Grid", true);
00095 
00096   //Planning scene display
00097   scene_display_ = new moveit_rviz_plugin::PlanningSceneDisplay();
00098   scene_display_->setName("Planning Scene");
00099   scene_display_->subProp("Robot Description")->setValue(ROBOT_DESCRIPTION_PARAM);
00100   scene_display_->subProp("Scene Geometry")->subProp("Scene Alpha")->setValue(1.0);
00101   visualization_manager_->addDisplay( scene_display_, true );
00102 
00103   //Interactive Marker display
00104   int_marker_display_ = visualization_manager_->getDisplayFactory()->make("rviz/InteractiveMarkers");
00105   int_marker_display_->initialize(visualization_manager_);
00106   int_marker_display_->setEnabled(true);
00107   int_marker_display_->subProp("Update Topic")->setValue(QString::fromStdString(robot_interaction::RobotInteraction::INTERACTIVE_MARKER_TOPIC + "/update"));
00108 
00109   if ( scene_display_ )
00110   {
00111     if (waitForPlanningSceneMonitor(scene_display_))
00112     {
00113       configure();
00114     }
00115     else
00116     {
00117       ROS_INFO("Couldn't find a valid robot description in the parameter server. Please load a robot on the GUI.");
00118     }
00119 
00120     if (ui_.planning_group_combo->count() > 0)
00121     {
00122       planningGroupChanged(ui_.planning_group_combo->currentText());
00123     }
00124 
00125     rviz::Tool * interact_tool = visualization_manager_->getToolManager()->addTool("rviz/Interact");
00126     if (interact_tool)
00127     {
00128       visualization_manager_->getToolManager()->setCurrentTool(interact_tool);
00129       interact_tool->activate();
00130     }
00131     visualization_manager_->getSelectionManager()->enableInteraction(true);
00132 
00133     //Setup ui: colors and icons
00134     ui_.db_connect_button->setStyleSheet("QPushButton { color : green }");
00135 
00136     ui_.goal_poses_open_button->setIcon(QIcon::fromTheme("document-open", QApplication::style()->standardIcon(QStyle::SP_DirOpenIcon)));
00137     ui_.goal_poses_add_button->setIcon(QIcon::fromTheme("list-add", QApplication::style()->standardIcon(QStyle::SP_FileDialogNewFolder)));
00138     ui_.goal_poses_remove_button->setIcon(QIcon::fromTheme("list-remove", QApplication::style()->standardIcon(QStyle::SP_DialogDiscardButton)));
00139     ui_.goal_poses_save_button->setIcon(QIcon::fromTheme("document-save", QApplication::style()->standardIcon(QStyle::SP_DriveFDIcon)));
00140     ui_.goal_switch_visibility_button->setIcon(QApplication::style()->standardIcon(QStyle::SP_DialogDiscardButton));
00141 
00142     ui_.start_states_open_button->setIcon(QIcon::fromTheme("document-open", QApplication::style()->standardIcon(QStyle::SP_DirOpenIcon)));
00143     ui_.start_states_add_button->setIcon(QIcon::fromTheme("list-add", QApplication::style()->standardIcon(QStyle::SP_FileDialogNewFolder)));
00144     ui_.start_states_remove_button->setIcon(QIcon::fromTheme("list-remove", QApplication::style()->standardIcon(QStyle::SP_DialogDiscardButton)));
00145     ui_.start_states_save_button->setIcon(QIcon::fromTheme("document-save", QApplication::style()->standardIcon(QStyle::SP_DriveFDIcon)));
00146 
00147     ui_.trajectory_open_button->setIcon(QIcon::fromTheme("document-open", QApplication::style()->standardIcon(QStyle::SP_DirOpenIcon)));
00148     ui_.trajectory_add_button->setIcon(QIcon::fromTheme("list-add", QApplication::style()->standardIcon(QStyle::SP_FileDialogNewFolder)));
00149     ui_.trajectory_remove_button->setIcon(QIcon::fromTheme("list-remove", QApplication::style()->standardIcon(QStyle::SP_DialogDiscardButton)));
00150     ui_.trajectory_save_button->setIcon(QIcon::fromTheme("document-save", QApplication::style()->standardIcon(QStyle::SP_DriveFDIcon)));
00151 
00152     //Connect signals and slots
00153     connect(ui_.actionExit, SIGNAL( triggered(bool) ), this, SLOT( exitActionTriggered(bool) ));
00154     connect(ui_.actionOpen, SIGNAL( triggered(bool) ), this, SLOT( openActionTriggered(bool) ));
00155     connect(ui_.planning_group_combo, SIGNAL( currentIndexChanged ( const QString & ) ), this, SLOT( planningGroupChanged( const QString & ) ));
00156     connect(ui_.db_connect_button, SIGNAL( clicked() ), this, SLOT( dbConnectButtonClicked() ));
00157     connect(ui_.load_scene_button, SIGNAL( clicked() ), this, SLOT( loadSceneButtonClicked() ));
00158     connect(ui_.planning_scene_list, SIGNAL( itemDoubleClicked (QListWidgetItem *) ), this, SLOT( loadSceneButtonClicked(QListWidgetItem *) ));
00159     connect(ui_.robot_interaction_button, SIGNAL( clicked() ), this, SLOT( robotInteractionButtonClicked() ));
00160 
00161     run_benchmark_ui_.benchmark_select_folder_button->setIcon(QIcon::fromTheme("document-open", QApplication::style()->standardIcon(QStyle::SP_DirOpenIcon)));
00162     connect( run_benchmark_ui_.run_benchmark_button, SIGNAL( clicked( ) ), this, SLOT( runBenchmarkButtonClicked(  ) ));
00163     connect( run_benchmark_ui_.save_config_button, SIGNAL( clicked( ) ), this, SLOT( saveBenchmarkConfigButtonClicked( ) ));
00164     connect( run_benchmark_ui_.cancel_button, SIGNAL( clicked( ) ), this, SLOT( cancelBenchmarkButtonClicked( ) ));
00165     connect( run_benchmark_ui_.benchmark_select_folder_button, SIGNAL( clicked( ) ), this, SLOT( benchmarkFolderButtonClicked( ) ));
00166     connect(run_benchmark_ui_.benchmark_include_planners_checkbox, SIGNAL(clicked(bool)), run_benchmark_ui_.planning_interfaces_text,  SLOT(setEnabled(bool)));
00167     connect(run_benchmark_ui_.benchmark_include_planners_checkbox, SIGNAL(clicked(bool)), run_benchmark_ui_.planning_interfaces_label,  SLOT(setEnabled(bool)));
00168     connect(run_benchmark_ui_.benchmark_include_planners_checkbox, SIGNAL(clicked(bool)), run_benchmark_ui_.planning_algorithms_text,  SLOT(setEnabled(bool)));
00169     connect(run_benchmark_ui_.benchmark_include_planners_checkbox, SIGNAL(clicked(bool)), run_benchmark_ui_.planning_algorithms_label,  SLOT(setEnabled(bool)));
00170 
00171     //Goal poses
00172     QMenu *add_button_menu = new QMenu(ui_.goal_poses_add_button);
00173     QAction *add_single_goal_action = new QAction("Single goal", add_button_menu);
00174     QAction *bbox_goals_action = new QAction("Goals in a bounding box", add_button_menu);
00175     add_button_menu->addAction(add_single_goal_action);
00176     add_button_menu->addAction(bbox_goals_action);
00177     ui_.goal_poses_add_button->setMenu(add_button_menu);
00178     connect( add_single_goal_action, SIGNAL( triggered() ), this, SLOT( createGoalPoseButtonClicked() ));
00179     connect( bbox_goals_action, SIGNAL( triggered() ), this, SLOT( showBBoxGoalsDialog() ));
00180     connect( bbox_dialog_ui_.ok_button, SIGNAL(clicked()), this, SLOT(createBBoxGoalsButtonClicked()));
00181     connect( bbox_dialog_ui_.cancel_button, SIGNAL(clicked()), bbox_dialog_, SLOT(hide()));
00182     connect( ui_.goal_poses_remove_button, SIGNAL( clicked() ), this, SLOT( deleteGoalsOnDBButtonClicked() ));
00183     connect( ui_.load_poses_filter_text, SIGNAL( returnPressed() ), this, SLOT( loadGoalsFromDBButtonClicked() ));
00184     connect( ui_.goal_poses_open_button, SIGNAL( clicked() ), this, SLOT( loadGoalsFromDBButtonClicked() ));
00185     connect( ui_.goal_poses_save_button, SIGNAL( clicked() ), this, SLOT( saveGoalsOnDBButtonClicked() ));
00186     connect( ui_.goal_switch_visibility_button, SIGNAL( clicked() ), this, SLOT( switchGoalVisibilityButtonClicked() ));
00187     connect( ui_.goal_poses_list, SIGNAL( itemSelectionChanged() ), this, SLOT( goalPoseSelectionChanged() ));
00188     connect( ui_.goal_poses_list, SIGNAL( itemDoubleClicked(QListWidgetItem *) ), this, SLOT( goalPoseDoubleClicked(QListWidgetItem *) ));
00189     connect( ui_.show_x_checkbox, SIGNAL( stateChanged( int ) ), this, SLOT( visibleAxisChanged( int ) ));
00190     connect( ui_.show_y_checkbox, SIGNAL( stateChanged( int ) ), this, SLOT( visibleAxisChanged( int ) ));
00191     connect( ui_.show_z_checkbox, SIGNAL( stateChanged( int ) ), this, SLOT( visibleAxisChanged( int ) ));
00192     connect( ui_.goal_offset_roll, SIGNAL( editingFinished ( )), this, SLOT( goalOffsetChanged( ) ));
00193     connect( ui_.goal_offset_pitch, SIGNAL( editingFinished ( )), this, SLOT( goalOffsetChanged( ) ));
00194     connect( ui_.goal_offset_yaw, SIGNAL( editingFinished ( )), this, SLOT( goalOffsetChanged( ) ));
00195 
00196     connect( ui_.check_goal_collisions_button, SIGNAL( clicked( ) ), this, SLOT( checkGoalsInCollision( ) ));
00197     connect( ui_.check_goal_reachability_button, SIGNAL( clicked( ) ), this, SLOT( checkGoalsReachable( ) ));
00198     connect( ui_.run_benchmark_button, SIGNAL( clicked( ) ), this, SLOT( runBenchmark( ) ));
00199     connect( ui_.load_results_button, SIGNAL( clicked( ) ), this, SLOT( loadBenchmarkResults( ) ));
00200 
00201     connect( ui_.start_states_add_button, SIGNAL( clicked() ), this, SLOT( saveStartStateButtonClicked() ));
00202     connect( ui_.start_states_remove_button, SIGNAL( clicked() ), this, SLOT( deleteStatesOnDBButtonClicked() ));
00203     connect( ui_.load_states_filter_text, SIGNAL( returnPressed() ), this, SLOT( loadStatesFromDBButtonClicked() ));
00204     connect( ui_.start_states_open_button, SIGNAL( clicked() ), this, SLOT( loadStatesFromDBButtonClicked() ));
00205     connect( ui_.start_states_save_button, SIGNAL( clicked() ), this, SLOT( saveStatesOnDBButtonClicked() ));
00206     connect( ui_.start_states_list, SIGNAL( itemDoubleClicked(QListWidgetItem*) ), this, SLOT( startStateItemDoubleClicked(QListWidgetItem*) ));
00207 
00208     QShortcut *copy_goals_shortcut = new QShortcut(QKeySequence(Qt::CTRL + Qt::Key_D), ui_.goal_poses_list);
00209     connect(copy_goals_shortcut, SIGNAL( activated() ), this, SLOT( copySelectedGoalPoses() ) );
00210 
00211     //Trajectories
00212     connect( ui_.trajectory_add_button, SIGNAL( clicked() ), this, SLOT( createTrajectoryButtonClicked() ));
00213     connect( ui_.trajectory_remove_button, SIGNAL( clicked() ), this, SLOT( removeTrajectoryButtonClicked() ));
00214     connect( ui_.trajectory_open_button, SIGNAL( clicked() ), this, SLOT( loadTrajectoriesFromDBButtonClicked() ));
00215     connect( ui_.trajectory_save_button, SIGNAL( clicked() ), this, SLOT( saveTrajectoriesOnDBButtonClicked() ));
00216     connect( ui_.trajectory_list, SIGNAL( itemSelectionChanged() ), this, SLOT( trajectorySelectionChanged() ));
00217     connect( ui_.trajectory_nwaypoints_spin, SIGNAL( valueChanged ( int )), this, SLOT( trajectoryNWaypointsChanged( int ) ));
00218     connect( ui_.trajectory_execute_button, SIGNAL( clicked() ), this, SLOT( trajectoryExecuteButtonClicked() ));
00219 
00220     //Start a QTimer for handling main loop jobs
00221     main_loop_jobs_timer_.reset(new QTimer(this));
00222     connect(main_loop_jobs_timer_.get(), SIGNAL( timeout() ), this, SLOT( MainLoop() ));
00223     main_loop_jobs_timer_->start(1000 / MAIN_LOOP_RATE);
00224   }
00225   else
00226   {
00227     ROS_ERROR("Cannot load robot. Is the robot_description parameter set?");
00228     exit(0);
00229   }
00230 }
00231 
00232 MainWindow::~MainWindow()
00233 {
00234 }
00235 
00236 bool MainWindow::waitForPlanningSceneMonitor(moveit_rviz_plugin::PlanningSceneDisplay *scene_display)
00237 {
00238   //Wait until the planning scene monitor is up
00239   ros::Time tstart = ros::Time::now();
00240   static const double psm_waiting_timeout = 10.0;
00241   while (! scene_display->getPlanningSceneMonitor() && (ros::Time::now() - tstart) < ros::Duration(psm_waiting_timeout))
00242   {
00243     ROS_INFO_ONCE("Waiting for the planning scene monitor...");
00244     scene_display->update(0.1, 0.1);
00245   }
00246 
00247   return scene_display->getPlanningSceneMonitor();
00248 }
00249 
00250 void MainWindow::exitActionTriggered(bool)
00251 {
00252   QApplication::quit();
00253 }
00254 
00255 void MainWindow::openActionTriggered(bool)
00256 {
00257   QString urdf_path = QFileDialog::getOpenFileName(this, tr("Select a robot description file"), tr(""), tr("URDF files (*.urdf)"));
00258 
00259   if (!urdf_path.isEmpty())
00260   {
00261     QString srdf_path = QFileDialog::getOpenFileName(this, tr("Select a semantic robot description file"), tr(""), tr("SRDF files (*.srdf)"));
00262 
00263     if (!srdf_path.isEmpty())
00264     {
00265       loadNewRobot(urdf_path.toStdString(), srdf_path.toStdString());
00266     }
00267   }
00268 }
00269 
00270 void MainWindow::loadNewRobot(const std::string &urdf_path, const std::string &srdf_path)
00271 {
00272   load_robot_ui_.status_label->setText("");
00273   load_robot_ui_.load_progress_bar->setValue(0);
00274 
00275   robot_loader_dialog_->show();
00276 
00277   QApplication::setOverrideCursor(QCursor(Qt::WaitCursor));
00278 
00279   //Load urdf
00280   boost::filesystem::path boost_urdf_path(urdf_path);
00281   load_robot_ui_.status_label->setText(QString::fromStdString("Loading urdf " + boost_urdf_path.string()));
00282   load_robot_ui_.load_progress_bar->setValue(10);
00283   if (boost::filesystem::exists(boost_urdf_path))
00284   {
00285     std::ifstream urdf_input_stream(boost_urdf_path.string().c_str());
00286     std::stringstream urdf_sstr;
00287     urdf_sstr << urdf_input_stream.rdbuf();
00288     ros::param::set(ROBOT_DESCRIPTION_PARAM, urdf_sstr.str());
00289   }
00290   else
00291   {
00292     ROS_ERROR("Cannot load URDF file");
00293   }
00294 
00295   //Load srdf
00296   boost::filesystem::path boost_srdf_path(srdf_path);
00297   load_robot_ui_.status_label->setText(QString::fromStdString("Loading srdf " + boost_srdf_path.string()));
00298   load_robot_ui_.load_progress_bar->setValue(20);
00299   if (boost::filesystem::exists(boost_srdf_path))
00300   {
00301     std::ifstream srdf_input_stream(boost_srdf_path.string().c_str());
00302     std::stringstream srdf_sstr;
00303     srdf_sstr << srdf_input_stream.rdbuf();
00304     ros::param::set(ROBOT_DESCRIPTION_SEMANTIC_PARAM, srdf_sstr.str());
00305   }
00306   else
00307   {
00308     ROS_ERROR("Cannot load SRDF file");
00309   }
00310 
00311   //Load kinematics.yaml, joint_limits.yaml and ompl_planning.yaml
00312   //TODO: Can we assume kinematics.yaml to be in the same folder as the srdf?
00313   boost::filesystem::path kinematics_file = boost::filesystem::operator/(boost_srdf_path.branch_path(), "kinematics.yaml");
00314   load_robot_ui_.status_label->setText(QString::fromStdString("Loading " + kinematics_file.string()));
00315   load_robot_ui_.load_progress_bar->setValue(30);
00316   if (boost::filesystem::exists( kinematics_file ) && boost::filesystem::is_regular_file( kinematics_file ))
00317   {
00318     if (system(("rosparam load " + kinematics_file.string()).c_str()) < 0)
00319     {
00320       ROS_ERROR("Couldn't load kinematics.yaml file");
00321     }
00322   }
00323 
00324   boost::filesystem::path joint_limits_file = boost::filesystem::operator/(boost_srdf_path.branch_path(), "joint_limits.yaml");
00325   load_robot_ui_.status_label->setText(QString::fromStdString("Loading " + joint_limits_file.string()));
00326   load_robot_ui_.load_progress_bar->setValue(40);
00327   if (boost::filesystem::exists( joint_limits_file ) && boost::filesystem::is_regular_file( joint_limits_file ))
00328   {
00329     if (system(("rosparam load " + joint_limits_file.string()).c_str()) < 0)
00330     {
00331       ROS_ERROR("Couldn't load joint_limits.yaml file");
00332     }
00333   }
00334 
00335   boost::filesystem::path ompl_planning_file = boost::filesystem::operator/(boost_srdf_path.branch_path(), "ompl_planning.yaml");
00336   load_robot_ui_.status_label->setText(QString::fromStdString("Loading " + ompl_planning_file.string()));
00337   load_robot_ui_.load_progress_bar->setValue(50);
00338   if (boost::filesystem::exists( ompl_planning_file ) && boost::filesystem::is_regular_file( ompl_planning_file ))
00339   {
00340     if (system(("rosparam load " + ompl_planning_file.string()).c_str()) < 0)
00341     {
00342       ROS_ERROR("Couldn't load ompl_planning.yaml file");
00343     }
00344   }
00345 
00346   load_robot_ui_.status_label->setText(QString("Resetting scene display... "));
00347   load_robot_ui_.load_progress_bar->setValue(60);
00348   std::string old_scene_name;
00349   if (scene_display_->getPlanningSceneRO())
00350     old_scene_name = scene_display_->getPlanningSceneRO()->getName();
00351   scene_display_->reset();
00352 
00353   if (waitForPlanningSceneMonitor(scene_display_))
00354   {
00355     if (configure())
00356     {
00357       //Reload the scene geometry if one scene was already loaded
00358       load_robot_ui_.status_label->setText(QString("Reloading scene... "));
00359       load_robot_ui_.load_progress_bar->setValue(90);
00360       QList<QListWidgetItem *> found_items = ui_.planning_scene_list->findItems(QString::fromStdString(old_scene_name), Qt::MatchExactly);
00361       if (found_items.size() > 0)
00362       {
00363         found_items[0]->setSelected(true);
00364         loadSceneButtonClicked();
00365       }
00366 
00367       //Reload the goals
00368       load_robot_ui_.status_label->setText(QString("Reloading goals... "));
00369       load_robot_ui_.load_progress_bar->setValue(95);
00370       if (ui_.goal_poses_list->count() > 0)
00371       {
00372         loadGoalsFromDBButtonClicked();
00373       }
00374       load_robot_ui_.status_label->setText(QString(""));
00375       load_robot_ui_.load_progress_bar->setValue(100);
00376     }
00377   }
00378   else
00379   {
00380     ROS_INFO("Couldn't find a valid robot description in the parameter server. Please load a robot on the GUI.");
00381   }
00382 
00383   robot_loader_dialog_->close();
00384   load_robot_ui_.load_progress_bar->setValue(0);
00385   QApplication::restoreOverrideCursor();
00386 }
00387 
00388 bool MainWindow::configure()
00389 {
00390   if ( ! scene_display_->getPlanningSceneMonitor() || ! scene_display_->getPlanningSceneMonitor()->getRobotModel() )
00391   {
00392     ROS_ERROR("Cannot load robot");
00393     ui_.robot_interaction_button->setEnabled(false);
00394     ui_.load_scene_button->setEnabled(false);
00395     ui_.load_results_button->setEnabled(false);
00396     ui_.check_goal_collisions_button->setEnabled(false);
00397     ui_.check_goal_reachability_button->setEnabled(false);
00398     ui_.db_connect_button->setEnabled(false);
00399     ui_.goal_poses_add_button->setEnabled(false);
00400     ui_.goal_poses_remove_button->setEnabled(false);
00401     ui_.load_poses_filter_text->setEnabled(false);
00402     ui_.goal_poses_open_button->setEnabled(false);
00403     ui_.goal_poses_save_button->setEnabled(false);
00404     ui_.goal_switch_visibility_button->setEnabled(false);
00405     ui_.show_x_checkbox->setEnabled(false);
00406     ui_.show_y_checkbox->setEnabled(false);
00407     ui_.show_z_checkbox->setEnabled(false);
00408     ui_.goal_offset_roll->setEnabled(false);
00409     ui_.goal_offset_pitch->setEnabled(false);
00410     ui_.goal_offset_yaw->setEnabled(false);
00411     ui_.start_states_add_button->setEnabled(false);
00412     ui_.start_states_remove_button->setEnabled(false);
00413     ui_.start_states_open_button->setEnabled(false);
00414     ui_.start_states_save_button->setEnabled(false);
00415     ui_.run_benchmark_button->setEnabled(false);
00416 
00417     ui_.trajectory_nwaypoints_spin->setEnabled(false);
00418     ui_.trajectories_filter_text->setEnabled(false);
00419     ui_.trajectory_add_button->setEnabled(false);
00420     ui_.trajectory_remove_button->setEnabled(false);
00421     ui_.trajectory_save_button->setEnabled(false);
00422     ui_.trajectory_open_button->setEnabled(false);
00423     ui_.trajectory_execute_button->setEnabled(false);
00424     return false;
00425   }
00426 
00427   ui_.robot_interaction_button->setEnabled(true);
00428   ui_.load_scene_button->setEnabled(true);
00429   ui_.load_results_button->setEnabled(true);
00430   ui_.check_goal_collisions_button->setEnabled(true);
00431   ui_.check_goal_reachability_button->setEnabled(true);
00432   ui_.db_connect_button->setEnabled(true);
00433   ui_.goal_poses_add_button->setEnabled(true);
00434   ui_.goal_poses_remove_button->setEnabled(true);
00435   ui_.load_poses_filter_text->setEnabled(true);
00436   ui_.goal_poses_open_button->setEnabled(true);
00437   ui_.goal_poses_save_button->setEnabled(true);
00438   ui_.goal_switch_visibility_button->setEnabled(true);
00439   ui_.show_x_checkbox->setEnabled(true);
00440   ui_.show_y_checkbox->setEnabled(true);
00441   ui_.show_z_checkbox->setEnabled(true);
00442   ui_.goal_offset_roll->setEnabled(true);
00443   ui_.goal_offset_pitch->setEnabled(true);
00444   ui_.goal_offset_yaw->setEnabled(true);
00445   ui_.start_states_add_button->setEnabled(true);
00446   ui_.start_states_remove_button->setEnabled(true);
00447   ui_.start_states_open_button->setEnabled(true);
00448   ui_.start_states_save_button->setEnabled(true);
00449 
00450   ui_.trajectory_nwaypoints_spin->setEnabled(true);
00451   ui_.trajectories_filter_text->setEnabled(true);
00452   ui_.trajectory_add_button->setEnabled(true);
00453   ui_.trajectory_remove_button->setEnabled(true);
00454   ui_.trajectory_save_button->setEnabled(true);
00455   ui_.trajectory_open_button->setEnabled(true);
00456   ui_.trajectory_execute_button->setEnabled(true);
00457 
00458   //Set the fixed frame to the model frame
00459   load_robot_ui_.status_label->setText(QString("Setting fixed frame..."));
00460   load_robot_ui_.load_progress_bar->setValue(65);
00461   visualization_manager_->setFixedFrame(QString(scene_display_->getPlanningSceneMonitor()->getRobotModel()->getModelFrame().c_str()));
00462   int_marker_display_->setFixedFrame(QString::fromStdString(scene_display_->getPlanningSceneMonitor()->getRobotModel()->getModelFrame()));
00463 
00464   //robot interaction
00465   load_robot_ui_.status_label->setText(QString("Resetting robot interaction..."));
00466   load_robot_ui_.load_progress_bar->setValue(75);
00467   robot_interaction_.reset(new robot_interaction::RobotInteraction(scene_display_->getPlanningSceneMonitor()->getRobotModel()));
00468 
00469   //Configure robot-dependent ui elements
00470   ui_.load_states_filter_text->setText(QString::fromStdString(scene_display_->getPlanningSceneMonitor()->getRobotModel()->getName() + ".*"));
00471 
00472   //Get the list of planning groups and fill in the combo box
00473   load_robot_ui_.status_label->setText(QString("Updating planning groups..."));
00474   load_robot_ui_.load_progress_bar->setValue(85);
00475   std::vector<std::string> group_names = scene_display_->getPlanningSceneMonitor()->getRobotModel()->getJointModelGroupNames();
00476   ui_.planning_group_combo->clear();
00477   for (std::size_t i = 0; i < group_names.size(); i++)
00478   {
00479     ui_.planning_group_combo->addItem(QString(group_names[i].c_str()));
00480   }
00481 
00482   if (group_names.size() > 0)
00483     planningGroupChanged(QString(group_names[0].c_str()));
00484 
00485   return true;
00486 }
00487 
00488 void MainWindow::planningGroupChanged(const QString &text)
00489 {
00490   if (robot_interaction_ && ! text.isEmpty())
00491   {
00492     robot_interaction_->decideActiveComponents(text.toStdString());
00493     if (robot_interaction_->getActiveEndEffectors().size() == 0)
00494       ROS_WARN_STREAM("No end-effectors defined for robot " << scene_display_->getPlanningSceneMonitor()->getRobotModel()->getName() << " and group " << text.toStdString());
00495     else
00496     {
00497       //Update the kinematic state associated to the goals
00498       for (GoalPoseMap::iterator it = goal_poses_.begin(); it != goal_poses_.end(); ++it)
00499       {
00500         it->second->setRobotState(scene_display_->getPlanningSceneRO()->getCurrentState());
00501         it->second->setEndEffector(robot_interaction_->getActiveEndEffectors()[0]);
00502 
00503         if (query_goal_state_)
00504         {
00505           robotInteractionButtonClicked();
00506           robotInteractionButtonClicked();
00507         }
00508       }
00509     }
00510   }
00511 }
00512 
00513 void MainWindow::robotInteractionButtonClicked()
00514 {
00515   if (query_goal_state_ && robot_interaction_)
00516   {
00517     robot_interaction_->clearInteractiveMarkers();
00518     query_goal_state_.reset();
00519   }
00520   else if (robot_interaction_ && scene_display_)
00521   {
00522     query_goal_state_.reset(new robot_interaction::RobotInteraction::InteractionHandler("goal", scene_display_->getPlanningSceneRO()->getCurrentState(), scene_display_->getPlanningSceneMonitor()->getTFClient()));
00523     query_goal_state_->setUpdateCallback(boost::bind(&MainWindow::scheduleStateUpdate, this));
00524     query_goal_state_->setGroupStateValidityCallback(boost::bind(&MainWindow::isIKSolutionCollisionFree, this, _1, _2, _3));
00525     robot_interaction_->addInteractiveMarkers(query_goal_state_);
00526   }
00527   else
00528   {
00529     ROS_WARN("robot interaction not initialized");
00530   }
00531   robot_interaction_->publishInteractiveMarkers();
00532 }
00533 
00534 bool MainWindow::isIKSolutionCollisionFree(robot_state::RobotState *state, const robot_model::JointModelGroup *group, const double *ik_solution)
00535 {
00536   if (scene_display_)
00537   {
00538     state->setJointGroupPositions(group, ik_solution);
00539     state->update();
00540     return !scene_display_->getPlanningSceneRO()->isStateColliding(*state, group->getName());
00541   }
00542   else
00543     return true;
00544 }
00545 
00546 void MainWindow::scheduleStateUpdate()
00547 {
00548   JobProcessing::addBackgroundJob(boost::bind(&MainWindow::scheduleStateUpdateBackgroundJob, this));
00549 }
00550 
00551 void MainWindow::scheduleStateUpdateBackgroundJob()
00552 {
00553   scene_display_->getPlanningSceneRW()->setCurrentState(*query_goal_state_->getState());
00554   scene_display_->queueRenderSceneGeometry();
00555 }
00556 
00557 void MainWindow::dbConnectButtonClicked()
00558 {
00559   JobProcessing::addBackgroundJob(boost::bind(&MainWindow::dbConnectButtonClickedBackgroundJob, this));
00560 }
00561 
00562 void MainWindow::dbConnectButtonClickedBackgroundJob()
00563 {
00564   if (planning_scene_storage_)
00565   {
00566     planning_scene_storage_.reset();
00567     robot_state_storage_.reset();
00568     constraints_storage_.reset();
00569     trajectory_constraints_storage_.reset();
00570     ui_.planning_scene_list->clear();
00571 
00572     JobProcessing::addMainLoopJob(boost::bind(&setButtonState, ui_.db_connect_button, false, "Disconnected", "QPushButton { color : red }"));
00573   }
00574   else
00575   {
00576     int port = -1;
00577     QStringList host_port;
00578 
00579     host_port = ui_.db_combo->currentText().split(":");
00580     if (host_port.size() > 1)
00581     {
00582       try
00583       {
00584         port = boost::lexical_cast<int>(host_port[1].toStdString());
00585       }
00586       catch (...)
00587       {
00588       }
00589     }
00590     else
00591       port = DEFAULT_WAREHOUSE_PORT;
00592 
00593     if (port > 0 && ! host_port[0].isEmpty())
00594     {
00595       database_host_ = host_port[0].toStdString();
00596       database_port_ = port;
00597 
00598       //Store into settings
00599       QVariant previous_database_names = settings_->value("database_name", QStringList());
00600       QStringList name_list = previous_database_names.toStringList();
00601       name_list.removeAll(ui_.db_combo->currentText());
00602       name_list.push_front(ui_.db_combo->currentText());
00603       static const short db_names_history_size = 5;
00604       if (name_list.size() > db_names_history_size)
00605         name_list.pop_back();
00606       settings_->setValue("database_name", name_list);
00607       ui_.db_combo->clear();
00608       ui_.db_combo->addItems(name_list);
00609 
00610       //Connect
00611       JobProcessing::addMainLoopJob(boost::bind(&setButtonState, ui_.db_connect_button, true, "Connecting...", "QPushButton { color : green }"));
00612       try
00613       {
00614         planning_scene_storage_.reset(new moveit_warehouse::PlanningSceneStorage(database_host_,
00615                                                                                  database_port_, 5.0));
00616         robot_state_storage_.reset(new moveit_warehouse::RobotStateStorage(database_host_,
00617                                                                            database_port_, 5.0));
00618         constraints_storage_.reset(new moveit_warehouse::ConstraintsStorage(database_host_,
00619                                                                             database_port_, 5.0));
00620         trajectory_constraints_storage_.reset(new moveit_warehouse::TrajectoryConstraintsStorage(database_host_,
00621                                                                                                  database_port_, 5.0));
00622         JobProcessing::addMainLoopJob(boost::bind(&setButtonState, ui_.db_connect_button, true, "Getting data...", "QPushButton { color : yellow }"));
00623 
00624         //Get all the scenes
00625         populatePlanningSceneList();
00626 
00627         JobProcessing::addMainLoopJob(boost::bind(&setButtonState, ui_.db_connect_button, true, "Disconnect", "QPushButton { color : blue }"));
00628       }
00629       catch(std::runtime_error &ex)
00630       {
00631         ROS_ERROR("%s", ex.what());
00632         JobProcessing::addMainLoopJob(boost::bind(&setButtonState, ui_.db_connect_button, false, "Connect", "QPushButton { color : green }"));
00633         JobProcessing::addMainLoopJob(boost::bind(&showCriticalMessage, this, "Error", ex.what()));
00634         return;
00635       }
00636     }
00637     else
00638     {
00639       ROS_ERROR("Warehouse server must be introduced as host:port (eg. server.domain.com:33830)");
00640       JobProcessing::addMainLoopJob(boost::bind(&setButtonState, ui_.db_connect_button, false, "Disconnected", "QPushButton { color : red }"));
00641       JobProcessing::addMainLoopJob(boost::bind(&showCriticalMessage, this, "Error", "Warehouse server must be introduced as host:port (eg. server.domain.com:33830)"));
00642     }
00643   }
00644 }
00645 
00646 void MainWindow::populatePlanningSceneList(void)
00647 {
00648   ui_.planning_scene_list->setUpdatesEnabled(false);
00649 
00650   ui_.planning_scene_list->clear();
00651   ui_.planning_scene_list->setSortingEnabled(true);
00652   ui_.planning_scene_list->sortItems(Qt::AscendingOrder);
00653 
00654   std::vector<std::string> names;
00655   planning_scene_storage_->getPlanningSceneNames(names);
00656   for (std::size_t i = 0; i < names.size(); ++i)
00657   {
00658     ui_.planning_scene_list->addItem(names[i].c_str());
00659   }
00660 
00661   ui_.planning_scene_list->setUpdatesEnabled(true);
00662 }
00663 
00664 void MainWindow::loadSceneButtonClicked(QListWidgetItem *item)
00665 {
00666   loadSceneButtonClicked();
00667 }
00668 
00669 void MainWindow::loadSceneButtonClicked(void)
00670 {
00671   if (ui_.planning_scene_list->currentItem() && ui_.planning_scene_list->currentItem()->text().toStdString() != scene_display_->getPlanningSceneRO()->getName())
00672   {
00673     ui_.goal_poses_list->clear();
00674     ui_.trajectory_list->clear();
00675     goal_poses_.clear();
00676     trajectories_.clear();
00677     JobProcessing::addBackgroundJob(boost::bind(&MainWindow::loadSceneButtonClickedBackgroundJob, this));
00678   }
00679 }
00680 
00681 void MainWindow::loadSceneButtonClickedBackgroundJob(void)
00682 {
00683   if (planning_scene_storage_)
00684   {
00685     QList<QListWidgetItem *> sel = ui_.planning_scene_list->selectedItems();
00686     if ( ! sel.empty())
00687     {
00688       QListWidgetItem *s = sel.front();
00689       std::string scene = s->text().toStdString();
00690 
00691       setStatusFromBackground(STATUS_INFO, QString::fromStdString("Attempting to load scene" + scene + "..."));
00692 
00693       moveit_warehouse::PlanningSceneWithMetadata scene_m;
00694       moveit_msgs::PlanningScene scene_msg;
00695       bool got_ps = false;
00696       try
00697       {
00698         got_ps = planning_scene_storage_->getPlanningScene(scene_m, scene);
00699       }
00700       catch (std::runtime_error &ex)
00701       {
00702         ROS_ERROR("%s", ex.what());
00703       }
00704 
00705       if (got_ps)
00706       {
00707         ROS_DEBUG("Loaded scene '%s'", scene.c_str());
00708         setStatusFromBackground(STATUS_INFO, QString::fromStdString("Rendering Scene..."));
00709 
00710         //Update the planning scene
00711         planning_scene_monitor::LockedPlanningSceneRW ps = scene_display_->getPlanningSceneRW();
00712         if (ps)
00713         {
00714           scene_msg = *scene_m;
00715           ps->getWorldNonConst()->clearObjects();
00716           for (std::size_t i = 0 ; i < scene_msg.object_colors.size() ; ++i)
00717             ps->setObjectColor(scene_msg.object_colors[i].id, scene_msg.object_colors[i].color);
00718           ps->processPlanningSceneWorldMsg(scene_msg.world);
00719           ps->setName(scene_msg.name);
00720           scene_display_->queueRenderSceneGeometry();
00721         }
00722 
00723         //Configure ui elements
00724         ui_.load_poses_filter_text->setText(QString::fromStdString(scene + ".*"));
00725         ui_.trajectories_filter_text->setText(QString::fromStdString(scene + ".*"));
00726         setStatusFromBackground(STATUS_INFO, QString::fromStdString(""));
00727       }
00728       else
00729       {
00730         ROS_WARN("Failed to load scene '%s'. Has the message format changed since the scene was saved?", scene.c_str());
00731       }
00732     }
00733   }
00734 }
00735 
00736 
00737 void MainWindow::updateGoalPoseMarkers(float wall_dt, float ros_dt)
00738 {
00739   if (goal_pose_dragging_) {
00740     for (GoalPoseMap::iterator it = goal_poses_.begin(); it != goal_poses_.end() ; ++it)
00741       if (it->second->isVisible())
00742         it->second->imarker->update(wall_dt);
00743   }
00744 
00745   for (TrajectoryMap::iterator it = trajectories_.begin(); it != trajectories_.end() ; ++it)
00746     if (it->second->control_marker->isVisible())
00747     {
00748       it->second->control_marker->imarker->update(wall_dt);
00749       if (it->second->start_marker)
00750         it->second->start_marker->imarker->update(wall_dt);
00751       if (it->second->end_marker)
00752         it->second->end_marker->imarker->update(wall_dt);
00753     }
00754 }
00755 
00756 void MainWindow::MainLoop()
00757 {
00758   int_marker_display_->update(1.0 / MAIN_LOOP_RATE, 1.0 / MAIN_LOOP_RATE);
00759   updateGoalPoseMarkers(1.0 / MAIN_LOOP_RATE, 1.0 / MAIN_LOOP_RATE);
00760 
00761   JobProcessing::executeMainLoopJobs();
00762 }
00763 
00764 void MainWindow::selectItemJob(QListWidgetItem *item, bool flag)
00765 {
00766   item->setSelected(flag);
00767 }
00768 
00769 void MainWindow::setItemSelectionInList(const std::string &item_name, bool selection, QListWidget *list)
00770 {
00771   QList<QListWidgetItem*> found_items = list->findItems(QString(item_name.c_str()), Qt::MatchExactly);
00772   for (std::size_t i = 0 ; i < found_items.size(); ++i)
00773     found_items[i]->setSelected(selection);
00774 }
00775 
00776 }


benchmarks_gui
Author(s): Mario Prats
autogenerated on Wed Aug 26 2015 12:44:27