tab_trajectories.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012, Willow Garage, Inc.
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  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  * Author: Mario Prats, Ioan Sucan
00030  */
00031 
00032 #include <main_window.h>
00033 #include <trajectory.h>
00034 #include <job_processing.h>
00035 #include <ui_utils.h>
00036 
00037 #include <eigen_conversions/eigen_msg.h>
00038 
00039 #include <QMessageBox>
00040 #include <QInputDialog>
00041 
00042 #include <boost/math/constants/constants.hpp>
00043 
00044 namespace benchmark_tool
00045 {
00046 
00047 void MainWindow::createTrajectoryButtonClicked(void)
00048 {
00049   std::stringstream ss;
00050 
00051   {
00052     const planning_scene_monitor::LockedPlanningSceneRO &ps = scene_display_->getPlanningSceneRO();
00053     if ( ! ps || robot_interaction_->getActiveEndEffectors().empty() )
00054     {
00055       if ( ! ps ) ROS_ERROR("Not planning scene");
00056       if ( robot_interaction_->getActiveEndEffectors().empty() ) ROS_ERROR("No end effector");
00057       return;
00058     }
00059     else
00060       ss << ps->getName().c_str() << "_trajectory_" << std::setfill('0') << std::setw(4) << trajectories_.size();
00061   }
00062 
00063   bool ok = false;
00064   QString text = QInputDialog::getText(this, tr("Choose a name"),
00065                                        tr("Trajectory name:"), QLineEdit::Normal,
00066                                        QString(ss.str().c_str()), &ok);
00067 
00068   std::string name;
00069   if (ok)
00070   {
00071     if ( ! text.isEmpty() )
00072     {
00073       name = text.toStdString();
00074       if (goal_poses_.find(name) != goal_poses_.end())
00075         QMessageBox::warning(this, "Name already exists", QString("The name '").append(name.c_str()).
00076                              append("' already exists. Not creating trajectory."));
00077       else
00078       {
00079         //Create the new trajectory starting point at the current eef pose, and attach an interactive marker to it
00080         Eigen::Affine3d tip_pose = scene_display_->getPlanningSceneRO()->getCurrentState().getLinkState(robot_interaction_->getActiveEndEffectors()[0].parent_link)->getGlobalLinkTransform();
00081         geometry_msgs::Pose marker_pose;
00082         tf::poseEigenToMsg(tip_pose, marker_pose);
00083         static const float marker_scale = 0.15;
00084 
00085         TrajectoryPtr trajectory_marker( new Trajectory(scene_display_->getPlanningSceneRO()->getCurrentState(), scene_display_->getSceneNode(), visualization_manager_,
00086                                                               name, scene_display_->getRobotModel()->getModelFrame(),
00087                                                               robot_interaction_->getActiveEndEffectors()[0], marker_pose, marker_scale, GripperMarker::NOT_TESTED,
00088                                                               ui_.trajectory_nwaypoints_spin->value()));
00089 
00090         trajectories_.insert(TrajectoryPair(name,  trajectory_marker));
00091       }
00092     }
00093     else
00094       QMessageBox::warning(this, "Goal not created", "Cannot use an empty name for a new goal pose.");
00095   }
00096 
00097   populateTrajectoriesList();
00098   selectLastItemInList(ui_.trajectory_list);
00099 }
00100 
00101 void MainWindow::populateTrajectoriesList(void)
00102 {
00103   bool old_signal_state = ui_.trajectory_list->blockSignals(true);
00104   ui_.trajectory_list->clear();
00105   for (TrajectoryMap::iterator it = trajectories_.begin(); it != trajectories_.end(); ++it)
00106   {
00107     QListWidgetItem *item = new QListWidgetItem(QString(it->first.c_str()));
00108     ui_.trajectory_list->addItem(item);
00109   }
00110   ui_.trajectory_list->blockSignals(old_signal_state);
00111 }
00112 
00113 void MainWindow::trajectorySelectionChanged(void)
00114 {
00115   for (unsigned int i = 0; i < ui_.trajectory_list->count() ; ++i)
00116   {
00117     QListWidgetItem *item = ui_.trajectory_list->item(i);
00118     std::string name = item->text().toStdString();
00119     if ( trajectories_.find(name) != trajectories_.end() && item->isSelected())
00120     {
00121       trajectories_[name]->show(scene_display_->getSceneNode(), visualization_manager_);
00122     }
00123     else
00124     {
00125       trajectories_[name]->hide();
00126     }
00127   }
00128 }
00129 
00130 void MainWindow::removeTrajectoryButtonClicked(void)
00131 {
00132   if (ui_.trajectory_list->currentItem())
00133   {
00134     //Warn the user
00135     QMessageBox msgBox;
00136     msgBox.setText("The selected trajectory will be removed from the database");
00137     msgBox.setInformativeText("Do you want to continue?");
00138     msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::No | QMessageBox::Cancel);
00139     msgBox.setDefaultButton(QMessageBox::No);
00140     int ret = msgBox.exec();
00141 
00142     switch (ret)
00143     {
00144       case QMessageBox::Yes:
00145       {
00146         //Go through the list of trajectories, and delete those selected
00147         QList<QListWidgetItem*> found_items = ui_.trajectory_list->selectedItems();
00148         for ( std::size_t i = 0 ; i < found_items.size() ; i++ )
00149         {
00150           try
00151           {
00152             trajectory_constraints_storage_->removeTrajectoryConstraints(found_items[i]->text().toStdString());
00153           }
00154           catch (std::runtime_error &ex)
00155           {
00156             ROS_ERROR("%s", ex.what());
00157           }
00158           trajectories_.erase(found_items[i]->text().toStdString());
00159         }
00160         populateTrajectoriesList();
00161       }
00162       break;
00163     }
00164   }
00165 }
00166 
00167 void MainWindow::loadTrajectoriesFromDBButtonClicked(void)
00168 {
00169   //Get all the trajectory constraints from the database
00170   if (trajectory_constraints_storage_ && !robot_interaction_->getActiveEndEffectors().empty())
00171   {
00172     //First clear the current list
00173     trajectories_.clear();
00174 
00175     std::vector<std::string> names;
00176     try
00177     {
00178       trajectory_constraints_storage_->getKnownTrajectoryConstraints(ui_.trajectories_filter_text->text().toStdString(), names);
00179     }
00180     catch (std::runtime_error &ex)
00181     {
00182       QMessageBox::warning(this, "Cannot query the database", QString("Wrongly formatted regular expression for trajectory contraints: ").append(ex.what()));
00183       return;
00184     }
00185 
00186     for (unsigned int i = 0 ; i < names.size() ; i++)
00187     {
00188       //Create a trajectory constraint
00189       moveit_warehouse::TrajectoryConstraintsWithMetadata tc;
00190       bool got_constraint = false;
00191       try
00192       {
00193         got_constraint = trajectory_constraints_storage_->getTrajectoryConstraints(tc, names[i]);
00194       }
00195       catch (std::runtime_error &ex)
00196       {
00197         ROS_ERROR("%s", ex.what());
00198       }
00199       if (!got_constraint)
00200         continue;
00201 
00202       if (tc->constraints.size() > 0 && tc->constraints[0].position_constraints[0].constraint_region.primitive_poses.size() > 0 && tc->constraints[0].orientation_constraints.size() > 0)
00203       {
00204         geometry_msgs::Pose shape_pose;
00205         shape_pose.position = tc->constraints[0].position_constraints[0].constraint_region.primitive_poses[0].position;
00206         shape_pose.orientation = tc->constraints[0].orientation_constraints[0].orientation;
00207         static const float marker_scale = 0.15;
00208         TrajectoryPtr trajectory_marker( new Trajectory(scene_display_->getPlanningSceneRO()->getCurrentState(), scene_display_->getSceneNode(), visualization_manager_,
00209                                                         names[i], scene_display_->getRobotModel()->getModelFrame(),
00210                                                         robot_interaction_->getActiveEndEffectors()[0], shape_pose, marker_scale, GripperMarker::NOT_TESTED,
00211                                                         ui_.trajectory_nwaypoints_spin->value()));
00212 
00213         if ( trajectories_.find(names[i]) != trajectories_.end() )
00214         {
00215           trajectories_.erase(names[i]);
00216         }
00217         trajectories_.insert(TrajectoryPair(names[i], trajectory_marker));
00218 
00219         for (std::size_t c = 0; c < tc->constraints.size(); ++c)
00220         {
00221           if (tc->constraints[c].position_constraints.size() > 0 && tc->constraints[c].position_constraints[0].constraint_region.primitive_poses.size() > 0 && tc->constraints[c].orientation_constraints.size() > 0 )
00222           {
00223             shape_pose.position = tc->constraints[c].position_constraints[0].constraint_region.primitive_poses[0].position;
00224             shape_pose.orientation = tc->constraints[c].orientation_constraints[0].orientation;
00225 
00226             static const float marker_scale = 0.15;
00227             GripperMarkerPtr waypoint_marker( new GripperMarker(scene_display_->getPlanningSceneRO()->getCurrentState(), scene_display_->getSceneNode(), visualization_manager_,
00228                                                                 names[i], scene_display_->getRobotModel()->getModelFrame(),
00229                                                                 robot_interaction_->getActiveEndEffectors()[0], shape_pose, marker_scale, GripperMarker::NOT_TESTED));
00230             waypoint_marker->unselect(true);
00231             waypoint_marker->setColor(0.0, 0.9, 0.0, 1 - (double)c / (double)tc->constraints.size());
00232             trajectory_marker->waypoint_markers.push_back(waypoint_marker);
00233           }
00234         }
00235 
00236         if (trajectory_marker->waypoint_markers.size() > 0)
00237         {
00238           trajectory_marker->start_marker = GripperMarkerPtr(new GripperMarker(*trajectory_marker->waypoint_markers.front()));
00239           trajectory_marker->end_marker = GripperMarkerPtr(new GripperMarker(*trajectory_marker->waypoint_markers.back()));
00240           trajectory_marker->waypoint_markers.front()->getPose(trajectory_marker->control_marker_start_pose);
00241           trajectory_marker->waypoint_markers.back()->getPose(trajectory_marker->control_marker_end_pose);
00242         }
00243         populateTrajectoriesList();
00244         selectFirstItemInList(ui_.trajectory_list);
00245       }
00246     }
00247    }
00248   else
00249   {
00250     if (!trajectory_constraints_storage_)
00251       QMessageBox::warning(this, "Warning", "Not connected to a database.");
00252   }
00253 }
00254 
00255 void MainWindow::saveTrajectoriesOnDBButtonClicked(void)
00256 {
00257   if (trajectory_constraints_storage_)
00258   {
00259     //Convert all goal trajectory markers into constraints and store them
00260     for (TrajectoryMap::iterator it = trajectories_.begin(); it != trajectories_.end(); ++it)
00261     {
00262       moveit_msgs::TrajectoryConstraints tc;
00263 
00264       for (std::size_t w = 0; w < it->second->waypoint_markers.size(); ++w)
00265       {
00266         moveit_msgs::Constraints c;
00267         c.name = it->second->waypoint_markers[w]->getName();
00268 
00269         shape_msgs::SolidPrimitive sp;
00270         sp.type = sp.BOX;
00271         sp.dimensions.resize(3, std::numeric_limits<float>::epsilon() * 10.0);
00272 
00273         moveit_msgs::PositionConstraint pc;
00274         pc.constraint_region.primitives.push_back(sp);
00275         geometry_msgs::Pose posemsg;
00276         it->second->waypoint_markers[w]->getPosition(posemsg.position);
00277         posemsg.orientation.x = 0.0;
00278         posemsg.orientation.y = 0.0;
00279         posemsg.orientation.z = 0.0;
00280         posemsg.orientation.w = 1.0;
00281         pc.constraint_region.primitive_poses.push_back(posemsg);
00282         pc.weight = 1.0;
00283         c.position_constraints.push_back(pc);
00284 
00285         moveit_msgs::OrientationConstraint oc;
00286         it->second->waypoint_markers[w]->getOrientation(oc.orientation);
00287         oc.absolute_x_axis_tolerance = oc.absolute_y_axis_tolerance =
00288             oc.absolute_z_axis_tolerance = std::numeric_limits<float>::epsilon() * 10.0;
00289         oc.weight = 1.0;
00290         c.orientation_constraints.push_back(oc);
00291         tc.constraints.push_back(c);
00292       }
00293 
00294       try
00295       {
00296         trajectory_constraints_storage_->addTrajectoryConstraints(tc, it->first);
00297       }
00298       catch (std::runtime_error &ex)
00299       {
00300         ROS_ERROR("Cannot save trajectory constraint: %s", ex.what());
00301       }
00302     }
00303   }
00304   else
00305   {
00306     QMessageBox::warning(this, "Warning", "Not connected to a database.");
00307   }
00308 }
00309 
00310 void MainWindow::trajectoryNWaypointsChanged(int n)
00311 {
00312   if (ui_.trajectory_list->currentItem())
00313   {
00314     TrajectoryMap::iterator it = trajectories_.find(ui_.trajectory_list->currentItem()->text().toStdString());
00315     it->second->setNumberOfWaypoints(n);
00316   }
00317 }
00318 
00319 void MainWindow::trajectoryExecuteButtonClicked()
00320 {
00321   if (ui_.trajectory_list->currentItem())
00322   {
00323     TrajectoryMap::iterator it = trajectories_.find(ui_.trajectory_list->currentItem()->text().toStdString());
00324     EigenSTL::vector_Affine3d waypoint_poses;
00325     for (std::size_t w = 1; w < it->second->waypoint_markers.size(); ++w )
00326     {
00327       Eigen::Affine3d pose;
00328       it->second->waypoint_markers[w]->getPose(pose);
00329       waypoint_poses.push_back(pose);
00330     }
00331 
00332     if (waypoint_poses.size() > 0)
00333     {
00334       robot_state::JointStateGroup *jsg = scene_display_->getPlanningSceneRW()->getCurrentStateNonConst().getJointStateGroup(ui_.planning_group_combo->currentText().toStdString());
00335 
00336       std::vector<boost::shared_ptr<robot_state::RobotState> > traj;
00337       double completed = jsg->computeCartesianPath(traj, robot_interaction_->getActiveEndEffectors()[0].parent_link, waypoint_poses, true, 0.04, 0.0);
00338 
00339       ROS_INFO_STREAM("Trajectory completion percentage " << completed);
00340       JobProcessing::addBackgroundJob(boost::bind(&MainWindow::animateTrajectory, this, traj));
00341     }
00342   }
00343 }
00344 
00345 void MainWindow::animateTrajectory(const std::vector<boost::shared_ptr<robot_state::RobotState> > &traj)
00346 {
00347   for (std::size_t i = 0; i < traj.size(); ++i)
00348   {
00349     scene_display_->getPlanningSceneRW()->setCurrentState(*traj[i]);
00350     scene_display_->queueRenderSceneGeometry();
00351     usleep(100000);
00352   }
00353 }
00354 
00355 } // namespace


benchmarks_gui
Author(s): Mario Prats
autogenerated on Mon Oct 6 2014 02:34:25