motion_planning_frame_planning.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/motion_planning_rviz_plugin/motion_planning_frame.h>
00038 #include <moveit/motion_planning_rviz_plugin/motion_planning_display.h>
00039 
00040 #include <moveit/kinematic_constraints/utils.h>
00041 #include <moveit/robot_state/conversions.h>
00042 
00043 #include <std_srvs/Empty.h>
00044 
00045 #include "ui_motion_planning_rviz_plugin_frame.h"
00046 
00047 namespace moveit_rviz_plugin
00048 {
00049 void MotionPlanningFrame::planButtonClicked()
00050 {
00051   planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computePlanButtonClicked, this), "compute "
00052                                                                                                          "plan");
00053 }
00054 
00055 void MotionPlanningFrame::executeButtonClicked()
00056 {
00057   ui_->execute_button->setEnabled(false);
00058   // execution is done in a separate thread, to not block other background jobs by blocking for synchronous execution
00059   planning_display_->spawnBackgroundJob(boost::bind(&MotionPlanningFrame::computeExecuteButtonClicked, this));
00060 }
00061 
00062 void MotionPlanningFrame::planAndExecuteButtonClicked()
00063 {
00064   ui_->plan_and_execute_button->setEnabled(false);
00065   ui_->execute_button->setEnabled(false);
00066   // execution is done in a separate thread, to not block other background jobs by blocking for synchronous execution
00067   planning_display_->spawnBackgroundJob(boost::bind(&MotionPlanningFrame::computePlanAndExecuteButtonClicked, this));
00068 }
00069 
00070 void MotionPlanningFrame::stopButtonClicked()
00071 {
00072   ui_->stop_button->setEnabled(false);  // avoid clicking again
00073   planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computeStopButtonClicked, this), "stop");
00074 }
00075 
00076 void MotionPlanningFrame::allowReplanningToggled(bool checked)
00077 {
00078   if (move_group_)
00079     move_group_->allowReplanning(checked);
00080 }
00081 
00082 void MotionPlanningFrame::allowLookingToggled(bool checked)
00083 {
00084   if (move_group_)
00085     move_group_->allowLooking(checked);
00086 }
00087 
00088 void MotionPlanningFrame::pathConstraintsIndexChanged(int index)
00089 {
00090   if (move_group_)
00091   {
00092     if (index > 0)
00093     {
00094       std::string c = ui_->path_constraints_combo_box->itemText(index).toStdString();
00095       if (!move_group_->setPathConstraints(c))
00096         ROS_WARN_STREAM("Unable to set the path constraints: " << c);
00097     }
00098     else
00099       move_group_->clearPathConstraints();
00100   }
00101 }
00102 
00103 void MotionPlanningFrame::onClearOctomapClicked()
00104 {
00105   std_srvs::Empty srv;
00106   clear_octomap_service_client_.call(srv);
00107 }
00108 
00109 void MotionPlanningFrame::computePlanButtonClicked()
00110 {
00111   if (!move_group_)
00112     return;
00113 
00114   // Clear status
00115   ui_->result_label->setText("Planning...");
00116 
00117   configureForPlanning();
00118   current_plan_.reset(new moveit::planning_interface::MoveGroup::Plan());
00119   if (move_group_->plan(*current_plan_))
00120   {
00121     ui_->execute_button->setEnabled(true);
00122 
00123     // Success
00124     ui_->result_label->setText(QString("Time: ").append(QString::number(current_plan_->planning_time_, 'f', 3)));
00125   }
00126   else
00127   {
00128     current_plan_.reset();
00129 
00130     // Failure
00131     ui_->result_label->setText("Failed");
00132   }
00133   Q_EMIT planningFinished();
00134 }
00135 
00136 void MotionPlanningFrame::computeExecuteButtonClicked()
00137 {
00138   if (move_group_ && current_plan_)
00139   {
00140     ui_->stop_button->setEnabled(true);  // enable stopping
00141     bool success = move_group_->execute(*current_plan_);
00142     onFinishedExecution(success);
00143   }
00144 }
00145 
00146 void MotionPlanningFrame::computePlanAndExecuteButtonClicked()
00147 {
00148   if (!move_group_)
00149     return;
00150   configureForPlanning();
00151   // move_group::move() on the server side, will always start from the current state
00152   // to suppress a warning, we pass an empty state (which encodes "start from current state")
00153   move_group_->setStartStateToCurrentState();
00154   ui_->stop_button->setEnabled(true);
00155   bool success = move_group_->move();
00156   onFinishedExecution(success);
00157   ui_->plan_and_execute_button->setEnabled(true);
00158 }
00159 
00160 void MotionPlanningFrame::computeStopButtonClicked()
00161 {
00162   if (move_group_)
00163     move_group_->stop();
00164 }
00165 
00166 void MotionPlanningFrame::onFinishedExecution(bool success)
00167 {
00168   // visualize result of execution
00169   if (success)
00170     ui_->result_label->setText("Executed");
00171   else
00172     ui_->result_label->setText(!ui_->stop_button->isEnabled() ? "Stopped" : "Failed");
00173   // disable stop button
00174   ui_->stop_button->setEnabled(false);
00175 
00176   // update query start state to current if neccessary
00177   if (ui_->start_state_selection->currentText() == "<current>")
00178   {
00179     ros::Duration(1).sleep();
00180     useStartStateButtonClicked();
00181   }
00182 }
00183 
00184 void MotionPlanningFrame::useStartStateButtonClicked()
00185 {
00186   robot_state::RobotState start = *planning_display_->getQueryStartState();
00187   updateQueryStateHelper(start, ui_->start_state_selection->currentText().toStdString());
00188   planning_display_->setQueryStartState(start);
00189 }
00190 
00191 void MotionPlanningFrame::useGoalStateButtonClicked()
00192 {
00193   robot_state::RobotState goal = *planning_display_->getQueryGoalState();
00194   updateQueryStateHelper(goal, ui_->goal_state_selection->currentText().toStdString());
00195   planning_display_->setQueryGoalState(goal);
00196 }
00197 
00198 void MotionPlanningFrame::updateQueryStateHelper(robot_state::RobotState& state, const std::string& v)
00199 {
00200   if (v == "<random>")
00201   {
00202     configureWorkspace();
00203     if (const robot_model::JointModelGroup* jmg =
00204             state.getJointModelGroup(planning_display_->getCurrentPlanningGroup()))
00205       state.setToRandomPositions(jmg);
00206     return;
00207   }
00208 
00209   if (v == "<random valid>")
00210   {
00211     configureWorkspace();
00212 
00213     if (const robot_model::JointModelGroup* jmg =
00214             state.getJointModelGroup(planning_display_->getCurrentPlanningGroup()))
00215     {
00216       // Loop until a collision free state is found
00217       static const int MAX_ATTEMPTS = 100;
00218       int attempt_count = 0;  // prevent loop for going forever
00219       while (attempt_count < MAX_ATTEMPTS)
00220       {
00221         // Generate random state
00222         state.setToRandomPositions(jmg);
00223 
00224         state.update();  // prevent dirty transforms
00225 
00226         // Test for collision
00227         if (planning_display_->getPlanningSceneRO()->isStateValid(state, "", false))
00228           break;
00229 
00230         attempt_count++;
00231       }
00232       // Explain if no valid rand state found
00233       if (attempt_count >= MAX_ATTEMPTS)
00234         ROS_WARN("Unable to find a random collision free configuration after %d attempts", MAX_ATTEMPTS);
00235     }
00236     else
00237     {
00238       ROS_WARN_STREAM("Unable to get joint model group " << planning_display_->getCurrentPlanningGroup());
00239     }
00240     return;
00241   }
00242 
00243   if (v == "<current>")
00244   {
00245     const planning_scene_monitor::LockedPlanningSceneRO& ps = planning_display_->getPlanningSceneRO();
00246     if (ps)
00247       state = ps->getCurrentState();
00248     return;
00249   }
00250 
00251   if (v == "<same as goal>")
00252   {
00253     state = *planning_display_->getQueryGoalState();
00254     return;
00255   }
00256 
00257   if (v == "<same as start>")
00258   {
00259     state = *planning_display_->getQueryStartState();
00260     return;
00261   }
00262 
00263   // maybe it is a named state
00264   if (const robot_model::JointModelGroup* jmg = state.getJointModelGroup(planning_display_->getCurrentPlanningGroup()))
00265     state.setToDefaultValues(jmg, v);
00266 }
00267 
00268 void MotionPlanningFrame::populatePlannersList(const moveit_msgs::PlannerInterfaceDescription& desc)
00269 {
00270   std::string group = planning_display_->getCurrentPlanningGroup();
00271   ui_->planning_algorithm_combo_box->clear();
00272 
00273   // set the label for the planning library
00274   ui_->library_label->setText(QString::fromStdString(desc.name));
00275   ui_->library_label->setStyleSheet("QLabel { color : green; font: bold }");
00276 
00277   bool found_group = false;
00278   // the name of a planner is either "GROUP[planner_id]" or "planner_id"
00279   if (!group.empty())
00280     for (std::size_t i = 0; i < desc.planner_ids.size(); ++i)
00281       if (desc.planner_ids[i] == group)
00282         found_group = true;
00283       else if (desc.planner_ids[i].substr(0, group.length()) == group)
00284       {
00285         if (desc.planner_ids[i].size() > group.length() && desc.planner_ids[i][group.length()] == '[')
00286         {
00287           std::string id = desc.planner_ids[i].substr(group.length());
00288           if (id.size() > 2)
00289           {
00290             id.resize(id.length() - 1);
00291             ui_->planning_algorithm_combo_box->addItem(QString::fromStdString(id.substr(1)));
00292           }
00293         }
00294       }
00295   if (ui_->planning_algorithm_combo_box->count() == 0 && !found_group)
00296     for (std::size_t i = 0; i < desc.planner_ids.size(); ++i)
00297       ui_->planning_algorithm_combo_box->addItem(QString::fromStdString(desc.planner_ids[i]));
00298   ui_->planning_algorithm_combo_box->insertItem(0, "<unspecified>");
00299 
00300   // retrieve default planner config from parameter server
00301   const std::string& default_planner_config = move_group_->getDefaultPlannerId(found_group ? group : std::string());
00302   int defaultIndex = ui_->planning_algorithm_combo_box->findText(QString::fromStdString(default_planner_config));
00303   if (defaultIndex < 0)
00304     defaultIndex = 0;  // 0 is <unspecified> fallback
00305   ui_->planning_algorithm_combo_box->setCurrentIndex(defaultIndex);
00306 }
00307 
00308 void MotionPlanningFrame::populateConstraintsList()
00309 {
00310   if (move_group_)
00311     planning_display_->addMainLoopJob(
00312         boost::bind(&MotionPlanningFrame::populateConstraintsList, this, move_group_->getKnownConstraints()));
00313 }
00314 
00315 void MotionPlanningFrame::populateConstraintsList(const std::vector<std::string>& constr)
00316 {
00317   ui_->path_constraints_combo_box->clear();
00318   ui_->path_constraints_combo_box->addItem("None");
00319   for (std::size_t i = 0; i < constr.size(); ++i)
00320     ui_->path_constraints_combo_box->addItem(QString::fromStdString(constr[i]));
00321 }
00322 
00323 void MotionPlanningFrame::constructPlanningRequest(moveit_msgs::MotionPlanRequest& mreq)
00324 {
00325   mreq.group_name = planning_display_->getCurrentPlanningGroup();
00326   mreq.num_planning_attempts = ui_->planning_attempts->value();
00327   mreq.allowed_planning_time = ui_->planning_time->value();
00328   mreq.max_velocity_scaling_factor = ui_->velocity_scaling_factor->value();
00329   mreq.max_acceleration_scaling_factor = ui_->acceleration_scaling_factor->value();
00330   robot_state::robotStateToRobotStateMsg(*planning_display_->getQueryStartState(), mreq.start_state);
00331   mreq.workspace_parameters.min_corner.x = ui_->wcenter_x->value() - ui_->wsize_x->value() / 2.0;
00332   mreq.workspace_parameters.min_corner.y = ui_->wcenter_y->value() - ui_->wsize_y->value() / 2.0;
00333   mreq.workspace_parameters.min_corner.z = ui_->wcenter_z->value() - ui_->wsize_z->value() / 2.0;
00334   mreq.workspace_parameters.max_corner.x = ui_->wcenter_x->value() + ui_->wsize_x->value() / 2.0;
00335   mreq.workspace_parameters.max_corner.y = ui_->wcenter_y->value() + ui_->wsize_y->value() / 2.0;
00336   mreq.workspace_parameters.max_corner.z = ui_->wcenter_z->value() + ui_->wsize_z->value() / 2.0;
00337   robot_state::RobotStateConstPtr s = planning_display_->getQueryGoalState();
00338   const robot_state::JointModelGroup* jmg = s->getJointModelGroup(mreq.group_name);
00339   if (jmg)
00340   {
00341     mreq.goal_constraints.resize(1);
00342     mreq.goal_constraints[0] = kinematic_constraints::constructGoalConstraints(*s, jmg);
00343   }
00344 }
00345 
00346 void MotionPlanningFrame::configureWorkspace()
00347 {
00348   robot_model::VariableBounds bx, by, bz;
00349   bx.position_bounded_ = by.position_bounded_ = bz.position_bounded_ = true;
00350 
00351   robot_model::JointModel::Bounds b(3);
00352   bx.min_position_ = ui_->wcenter_x->value() - ui_->wsize_x->value() / 2.0;
00353   bx.max_position_ = ui_->wcenter_x->value() + ui_->wsize_x->value() / 2.0;
00354   by.min_position_ = ui_->wcenter_y->value() - ui_->wsize_y->value() / 2.0;
00355   by.max_position_ = ui_->wcenter_y->value() + ui_->wsize_y->value() / 2.0;
00356   bz.min_position_ = ui_->wcenter_z->value() - ui_->wsize_z->value() / 2.0;
00357   bz.max_position_ = ui_->wcenter_z->value() + ui_->wsize_z->value() / 2.0;
00358 
00359   if (move_group_)
00360     move_group_->setWorkspace(bx.min_position_, by.min_position_, bz.min_position_, bx.max_position_, by.max_position_,
00361                               bz.max_position_);
00362   planning_scene_monitor::PlanningSceneMonitorPtr psm = planning_display_->getPlanningSceneMonitor();
00363   // get non-const access to the kmodel and update planar & floating joints as indicated by the workspace settings
00364   if (psm && psm->getRobotModelLoader() && psm->getRobotModelLoader()->getModel())
00365   {
00366     const robot_model::RobotModelPtr& kmodel = psm->getRobotModelLoader()->getModel();
00367     const std::vector<robot_model::JointModel*>& jm = kmodel->getJointModels();
00368     for (std::size_t i = 0; i < jm.size(); ++i)
00369       if (jm[i]->getType() == robot_model::JointModel::PLANAR)
00370       {
00371         jm[i]->setVariableBounds(jm[i]->getName() + "/" + jm[i]->getLocalVariableNames()[0], bx);
00372         jm[i]->setVariableBounds(jm[i]->getName() + "/" + jm[i]->getLocalVariableNames()[1], by);
00373       }
00374       else if (jm[i]->getType() == robot_model::JointModel::FLOATING)
00375       {
00376         jm[i]->setVariableBounds(jm[i]->getName() + "/" + jm[i]->getLocalVariableNames()[0], bx);
00377         jm[i]->setVariableBounds(jm[i]->getName() + "/" + jm[i]->getLocalVariableNames()[1], by);
00378         jm[i]->setVariableBounds(jm[i]->getName() + "/" + jm[i]->getLocalVariableNames()[2], bz);
00379       }
00380   }
00381 }
00382 
00383 void MotionPlanningFrame::configureForPlanning()
00384 {
00385   move_group_->setStartState(*planning_display_->getQueryStartState());
00386   move_group_->setJointValueTarget(*planning_display_->getQueryGoalState());
00387   move_group_->setPlanningTime(ui_->planning_time->value());
00388   move_group_->setNumPlanningAttempts(ui_->planning_attempts->value());
00389   move_group_->setMaxVelocityScalingFactor(ui_->velocity_scaling_factor->value());
00390   move_group_->setMaxAccelerationScalingFactor(ui_->acceleration_scaling_factor->value());
00391   configureWorkspace();
00392   if (static_cast<bool>(planning_display_))
00393     planning_display_->dropVisualizedTrajectory();
00394 }
00395 
00396 void MotionPlanningFrame::remotePlanCallback(const std_msgs::EmptyConstPtr& msg)
00397 {
00398   planButtonClicked();
00399 }
00400 
00401 void MotionPlanningFrame::remoteExecuteCallback(const std_msgs::EmptyConstPtr& msg)
00402 {
00403   executeButtonClicked();
00404 }
00405 
00406 void MotionPlanningFrame::remoteUpdateStartStateCallback(const std_msgs::EmptyConstPtr& msg)
00407 {
00408   if (move_group_ && planning_display_)
00409   {
00410     robot_state::RobotState state = *planning_display_->getQueryStartState();
00411     const planning_scene_monitor::LockedPlanningSceneRO& ps = planning_display_->getPlanningSceneRO();
00412     if (ps)
00413     {
00414       state = ps->getCurrentState();
00415       planning_display_->setQueryStartState(state);
00416     }
00417   }
00418 }
00419 
00420 void MotionPlanningFrame::remoteUpdateGoalStateCallback(const std_msgs::EmptyConstPtr& msg)
00421 {
00422   if (move_group_ && planning_display_)
00423   {
00424     robot_state::RobotState state = *planning_display_->getQueryStartState();
00425     const planning_scene_monitor::LockedPlanningSceneRO& ps = planning_display_->getPlanningSceneRO();
00426     if (ps)
00427     {
00428       state = ps->getCurrentState();
00429       planning_display_->setQueryGoalState(state);
00430     }
00431   }
00432 }
00433 }


visualization
Author(s): Ioan Sucan , Dave Coleman , Sachin Chitta
autogenerated on Mon Jul 24 2017 02:22:13