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     useStartStateButtonClicked();
00179 }
00180 
00181 void MotionPlanningFrame::useStartStateButtonClicked()
00182 {
00183   // use background job: fetching the current state might take up to a second
00184   planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::useStartStateButtonExec, this),  //
00185                                       "update start state");
00186 }
00187 
00188 void MotionPlanningFrame::useStartStateButtonExec()
00189 {
00190   robot_state::RobotState start = *planning_display_->getQueryStartState();
00191   updateQueryStateHelper(start, ui_->start_state_selection->currentText().toStdString());
00192   planning_display_->setQueryStartState(start);
00193 }
00194 
00195 void MotionPlanningFrame::useGoalStateButtonClicked()
00196 {
00197   // use background job: fetching the current state might take up to a second
00198   planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::useGoalStateButtonExec, this),  //
00199                                       "update goal state");
00200 }
00201 
00202 void MotionPlanningFrame::useGoalStateButtonExec()
00203 {
00204   robot_state::RobotState goal = *planning_display_->getQueryGoalState();
00205   updateQueryStateHelper(goal, ui_->goal_state_selection->currentText().toStdString());
00206   planning_display_->setQueryGoalState(goal);
00207 }
00208 
00209 void MotionPlanningFrame::updateQueryStateHelper(robot_state::RobotState& state, const std::string& v)
00210 {
00211   if (v == "<random>")
00212   {
00213     configureWorkspace();
00214     if (const robot_model::JointModelGroup* jmg =
00215             state.getJointModelGroup(planning_display_->getCurrentPlanningGroup()))
00216       state.setToRandomPositions(jmg);
00217     return;
00218   }
00219 
00220   if (v == "<random valid>")
00221   {
00222     configureWorkspace();
00223 
00224     if (const robot_model::JointModelGroup* jmg =
00225             state.getJointModelGroup(planning_display_->getCurrentPlanningGroup()))
00226     {
00227       // Loop until a collision free state is found
00228       static const int MAX_ATTEMPTS = 100;
00229       int attempt_count = 0;  // prevent loop for going forever
00230       while (attempt_count < MAX_ATTEMPTS)
00231       {
00232         // Generate random state
00233         state.setToRandomPositions(jmg);
00234 
00235         state.update();  // prevent dirty transforms
00236 
00237         // Test for collision
00238         if (planning_display_->getPlanningSceneRO()->isStateValid(state, "", false))
00239           break;
00240 
00241         attempt_count++;
00242       }
00243       // Explain if no valid rand state found
00244       if (attempt_count >= MAX_ATTEMPTS)
00245         ROS_WARN("Unable to find a random collision free configuration after %d attempts", MAX_ATTEMPTS);
00246     }
00247     else
00248     {
00249       ROS_WARN_STREAM("Unable to get joint model group " << planning_display_->getCurrentPlanningGroup());
00250     }
00251     return;
00252   }
00253 
00254   if (v == "<current>")
00255   {
00256     planning_display_->waitForCurrentRobotState();
00257     const planning_scene_monitor::LockedPlanningSceneRO& ps = planning_display_->getPlanningSceneRO();
00258     if (ps)
00259       state = ps->getCurrentState();
00260     return;
00261   }
00262 
00263   if (v == "<same as goal>")
00264   {
00265     state = *planning_display_->getQueryGoalState();
00266     return;
00267   }
00268 
00269   if (v == "<same as start>")
00270   {
00271     state = *planning_display_->getQueryStartState();
00272     return;
00273   }
00274 
00275   // maybe it is a named state
00276   if (const robot_model::JointModelGroup* jmg = state.getJointModelGroup(planning_display_->getCurrentPlanningGroup()))
00277     state.setToDefaultValues(jmg, v);
00278 }
00279 
00280 void MotionPlanningFrame::populatePlannersList(const moveit_msgs::PlannerInterfaceDescription& desc)
00281 {
00282   std::string group = planning_display_->getCurrentPlanningGroup();
00283   ui_->planning_algorithm_combo_box->clear();
00284 
00285   // set the label for the planning library
00286   ui_->library_label->setText(QString::fromStdString(desc.name));
00287   ui_->library_label->setStyleSheet("QLabel { color : green; font: bold }");
00288 
00289   bool found_group = false;
00290   // the name of a planner is either "GROUP[planner_id]" or "planner_id"
00291   if (!group.empty())
00292     for (std::size_t i = 0; i < desc.planner_ids.size(); ++i)
00293       if (desc.planner_ids[i] == group)
00294         found_group = true;
00295       else if (desc.planner_ids[i].substr(0, group.length()) == group)
00296       {
00297         if (desc.planner_ids[i].size() > group.length() && desc.planner_ids[i][group.length()] == '[')
00298         {
00299           std::string id = desc.planner_ids[i].substr(group.length());
00300           if (id.size() > 2)
00301           {
00302             id.resize(id.length() - 1);
00303             ui_->planning_algorithm_combo_box->addItem(QString::fromStdString(id.substr(1)));
00304           }
00305         }
00306       }
00307   if (ui_->planning_algorithm_combo_box->count() == 0 && !found_group)
00308     for (std::size_t i = 0; i < desc.planner_ids.size(); ++i)
00309       ui_->planning_algorithm_combo_box->addItem(QString::fromStdString(desc.planner_ids[i]));
00310   ui_->planning_algorithm_combo_box->insertItem(0, "<unspecified>");
00311 
00312   // retrieve default planner config from parameter server
00313   const std::string& default_planner_config = move_group_->getDefaultPlannerId(found_group ? group : std::string());
00314   int defaultIndex = ui_->planning_algorithm_combo_box->findText(QString::fromStdString(default_planner_config));
00315   if (defaultIndex < 0)
00316     defaultIndex = 0;  // 0 is <unspecified> fallback
00317   ui_->planning_algorithm_combo_box->setCurrentIndex(defaultIndex);
00318 }
00319 
00320 void MotionPlanningFrame::populateConstraintsList()
00321 {
00322   if (move_group_)
00323     planning_display_->addMainLoopJob(
00324         boost::bind(&MotionPlanningFrame::populateConstraintsList, this, move_group_->getKnownConstraints()));
00325 }
00326 
00327 void MotionPlanningFrame::populateConstraintsList(const std::vector<std::string>& constr)
00328 {
00329   ui_->path_constraints_combo_box->clear();
00330   ui_->path_constraints_combo_box->addItem("None");
00331   for (std::size_t i = 0; i < constr.size(); ++i)
00332     ui_->path_constraints_combo_box->addItem(QString::fromStdString(constr[i]));
00333 }
00334 
00335 void MotionPlanningFrame::constructPlanningRequest(moveit_msgs::MotionPlanRequest& mreq)
00336 {
00337   mreq.group_name = planning_display_->getCurrentPlanningGroup();
00338   mreq.num_planning_attempts = ui_->planning_attempts->value();
00339   mreq.allowed_planning_time = ui_->planning_time->value();
00340   mreq.max_velocity_scaling_factor = ui_->velocity_scaling_factor->value();
00341   mreq.max_acceleration_scaling_factor = ui_->acceleration_scaling_factor->value();
00342   robot_state::robotStateToRobotStateMsg(*planning_display_->getQueryStartState(), mreq.start_state);
00343   mreq.workspace_parameters.min_corner.x = ui_->wcenter_x->value() - ui_->wsize_x->value() / 2.0;
00344   mreq.workspace_parameters.min_corner.y = ui_->wcenter_y->value() - ui_->wsize_y->value() / 2.0;
00345   mreq.workspace_parameters.min_corner.z = ui_->wcenter_z->value() - ui_->wsize_z->value() / 2.0;
00346   mreq.workspace_parameters.max_corner.x = ui_->wcenter_x->value() + ui_->wsize_x->value() / 2.0;
00347   mreq.workspace_parameters.max_corner.y = ui_->wcenter_y->value() + ui_->wsize_y->value() / 2.0;
00348   mreq.workspace_parameters.max_corner.z = ui_->wcenter_z->value() + ui_->wsize_z->value() / 2.0;
00349   robot_state::RobotStateConstPtr s = planning_display_->getQueryGoalState();
00350   const robot_state::JointModelGroup* jmg = s->getJointModelGroup(mreq.group_name);
00351   if (jmg)
00352   {
00353     mreq.goal_constraints.resize(1);
00354     mreq.goal_constraints[0] = kinematic_constraints::constructGoalConstraints(*s, jmg);
00355   }
00356 }
00357 
00358 void MotionPlanningFrame::configureWorkspace()
00359 {
00360   robot_model::VariableBounds bx, by, bz;
00361   bx.position_bounded_ = by.position_bounded_ = bz.position_bounded_ = true;
00362 
00363   robot_model::JointModel::Bounds b(3);
00364   bx.min_position_ = ui_->wcenter_x->value() - ui_->wsize_x->value() / 2.0;
00365   bx.max_position_ = ui_->wcenter_x->value() + ui_->wsize_x->value() / 2.0;
00366   by.min_position_ = ui_->wcenter_y->value() - ui_->wsize_y->value() / 2.0;
00367   by.max_position_ = ui_->wcenter_y->value() + ui_->wsize_y->value() / 2.0;
00368   bz.min_position_ = ui_->wcenter_z->value() - ui_->wsize_z->value() / 2.0;
00369   bz.max_position_ = ui_->wcenter_z->value() + ui_->wsize_z->value() / 2.0;
00370 
00371   if (move_group_)
00372     move_group_->setWorkspace(bx.min_position_, by.min_position_, bz.min_position_, bx.max_position_, by.max_position_,
00373                               bz.max_position_);
00374   planning_scene_monitor::PlanningSceneMonitorPtr psm = planning_display_->getPlanningSceneMonitor();
00375   // get non-const access to the kmodel and update planar & floating joints as indicated by the workspace settings
00376   if (psm && psm->getRobotModelLoader() && psm->getRobotModelLoader()->getModel())
00377   {
00378     const robot_model::RobotModelPtr& kmodel = psm->getRobotModelLoader()->getModel();
00379     const std::vector<robot_model::JointModel*>& jm = kmodel->getJointModels();
00380     for (std::size_t i = 0; i < jm.size(); ++i)
00381       if (jm[i]->getType() == robot_model::JointModel::PLANAR)
00382       {
00383         jm[i]->setVariableBounds(jm[i]->getName() + "/" + jm[i]->getLocalVariableNames()[0], bx);
00384         jm[i]->setVariableBounds(jm[i]->getName() + "/" + jm[i]->getLocalVariableNames()[1], by);
00385       }
00386       else if (jm[i]->getType() == robot_model::JointModel::FLOATING)
00387       {
00388         jm[i]->setVariableBounds(jm[i]->getName() + "/" + jm[i]->getLocalVariableNames()[0], bx);
00389         jm[i]->setVariableBounds(jm[i]->getName() + "/" + jm[i]->getLocalVariableNames()[1], by);
00390         jm[i]->setVariableBounds(jm[i]->getName() + "/" + jm[i]->getLocalVariableNames()[2], bz);
00391       }
00392   }
00393 }
00394 
00395 void MotionPlanningFrame::configureForPlanning()
00396 {
00397   move_group_->setStartState(*planning_display_->getQueryStartState());
00398   move_group_->setJointValueTarget(*planning_display_->getQueryGoalState());
00399   move_group_->setPlanningTime(ui_->planning_time->value());
00400   move_group_->setNumPlanningAttempts(ui_->planning_attempts->value());
00401   move_group_->setMaxVelocityScalingFactor(ui_->velocity_scaling_factor->value());
00402   move_group_->setMaxAccelerationScalingFactor(ui_->acceleration_scaling_factor->value());
00403   configureWorkspace();
00404   if (static_cast<bool>(planning_display_))
00405     planning_display_->dropVisualizedTrajectory();
00406 }
00407 
00408 void MotionPlanningFrame::remotePlanCallback(const std_msgs::EmptyConstPtr& msg)
00409 {
00410   planButtonClicked();
00411 }
00412 
00413 void MotionPlanningFrame::remoteExecuteCallback(const std_msgs::EmptyConstPtr& msg)
00414 {
00415   executeButtonClicked();
00416 }
00417 
00418 void MotionPlanningFrame::remoteUpdateStartStateCallback(const std_msgs::EmptyConstPtr& msg)
00419 {
00420   if (move_group_ && planning_display_)
00421   {
00422     planning_display_->waitForCurrentRobotState();
00423     const planning_scene_monitor::LockedPlanningSceneRO& ps = planning_display_->getPlanningSceneRO();
00424     if (ps)
00425     {
00426       robot_state::RobotState state = ps->getCurrentState();
00427       planning_display_->setQueryStartState(state);
00428     }
00429   }
00430 }
00431 
00432 void MotionPlanningFrame::remoteUpdateGoalStateCallback(const std_msgs::EmptyConstPtr& msg)
00433 {
00434   if (move_group_ && planning_display_)
00435   {
00436     planning_display_->waitForCurrentRobotState();
00437     const planning_scene_monitor::LockedPlanningSceneRO& ps = planning_display_->getPlanningSceneRO();
00438     if (ps)
00439     {
00440       robot_state::RobotState state = ps->getCurrentState();
00441       planning_display_->setQueryGoalState(state);
00442     }
00443   }
00444 }
00445 }


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