motion_planning_display.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, 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, Dave Coleman, Adam Leeper, Sachin Chitta */
00036 
00037 #include <moveit/motion_planning_rviz_plugin/motion_planning_display.h>
00038 #include <moveit/rviz_plugin_render_tools/planning_link_updater.h>
00039 #include <moveit/rviz_plugin_render_tools/robot_state_visualization.h>
00040 #include <rviz/visualization_manager.h>
00041 #include <rviz/robot/robot.h>
00042 #include <rviz/robot/robot_link.h>
00043 
00044 #include <rviz/properties/property.h>
00045 #include <rviz/properties/string_property.h>
00046 #include <rviz/properties/bool_property.h>
00047 #include <rviz/properties/float_property.h>
00048 #include <rviz/properties/ros_topic_property.h>
00049 #include <rviz/properties/editable_enum_property.h>
00050 #include <rviz/properties/color_property.h>
00051 #include <rviz/display_context.h>
00052 #include <rviz/frame_manager.h>
00053 #include <rviz/panel_dock_widget.h>
00054 #include <rviz/window_manager_interface.h>
00055 #include <rviz/display_factory.h>
00056 #include <rviz/ogre_helpers/movable_text.h>
00057 
00058 #include <OgreSceneManager.h>
00059 #include <OgreSceneNode.h>
00060 #include <rviz/ogre_helpers/shape.h>
00061 
00062 #include <tf/transform_listener.h>
00063 
00064 #include <moveit/robot_state/conversions.h>
00065 #include <moveit/trajectory_processing/trajectory_tools.h>
00066 
00067 #include <boost/format.hpp>
00068 #include <boost/algorithm/string/replace.hpp>
00069 #include <boost/algorithm/string/trim.hpp>
00070 #include <boost/lexical_cast.hpp>
00071 
00072 #include <QShortcut>
00073 
00074 #include "ui_motion_planning_rviz_plugin_frame.h"
00075 
00076 namespace moveit_rviz_plugin
00077 {
00078 // ******************************************************************************************
00079 // Base class contructor
00080 // ******************************************************************************************
00081 MotionPlanningDisplay::MotionPlanningDisplay()
00082   : PlanningSceneDisplay()
00083   , text_to_display_(NULL)
00084   , private_handle_("~")
00085   , frame_(NULL)
00086   , menu_handler_start_(new interactive_markers::MenuHandler)
00087   , menu_handler_goal_(new interactive_markers::MenuHandler)
00088   , int_marker_display_(NULL)
00089 {
00090   // Category Groups
00091   plan_category_ = new rviz::Property("Planning Request", QVariant(), "", this);
00092   metrics_category_ = new rviz::Property("Planning Metrics", QVariant(), "", this);
00093   path_category_ = new rviz::Property("Planned Path", QVariant(), "", this);
00094 
00095   // Metrics category -----------------------------------------------------------------------------------------
00096   compute_weight_limit_property_ = new rviz::BoolProperty(
00097       "Show Weight Limit", false, "Shows the weight limit at a particular pose for an end-effector", metrics_category_,
00098       SLOT(changedShowWeightLimit()), this);
00099 
00100   show_manipulability_index_property_ =
00101       new rviz::BoolProperty("Show Manipulability Index", false, "Shows the manipulability index for an end-effector",
00102                              metrics_category_, SLOT(changedShowManipulabilityIndex()), this);
00103 
00104   show_manipulability_property_ =
00105       new rviz::BoolProperty("Show Manipulability", false, "Shows the manipulability for an end-effector",
00106                              metrics_category_, SLOT(changedShowManipulability()), this);
00107 
00108   show_joint_torques_property_ = new rviz::BoolProperty("Show Joint Torques", false,
00109                                                         "Shows the joint torques for a given configuration and payload",
00110                                                         metrics_category_, SLOT(changedShowJointTorques()), this);
00111 
00112   metrics_set_payload_property_ =
00113       new rviz::FloatProperty("Payload", 1.0f, "Specify the payload at the end effector (kg)", metrics_category_,
00114                               SLOT(changedMetricsSetPayload()), this);
00115   metrics_set_payload_property_->setMin(0.0);
00116 
00117   metrics_text_height_property_ = new rviz::FloatProperty("TextHeight", 0.08f, "Text height", metrics_category_,
00118                                                           SLOT(changedMetricsTextHeight()), this);
00119   metrics_text_height_property_->setMin(0.001);
00120 
00121   // Planning request category -----------------------------------------------------------------------------------------
00122 
00123   planning_group_property_ = new rviz::EditableEnumProperty(
00124       "Planning Group", "", "The name of the group of links to plan for (from the ones defined in the SRDF)",
00125       plan_category_, SLOT(changedPlanningGroup()), this);
00126   show_workspace_property_ = new rviz::BoolProperty("Show Workspace", false, "Shows the axis-aligned bounding box for "
00127                                                                              "the workspace allowed for planning",
00128                                                     plan_category_, SLOT(changedWorkspace()), this);
00129   query_start_state_property_ =
00130       new rviz::BoolProperty("Query Start State", false, "Set a custom start state for the motion planning query",
00131                              plan_category_, SLOT(changedQueryStartState()), this);
00132   query_goal_state_property_ =
00133       new rviz::BoolProperty("Query Goal State", true, "Shows the goal state for the motion planning query",
00134                              plan_category_, SLOT(changedQueryGoalState()), this);
00135   query_marker_scale_property_ = new rviz::FloatProperty(
00136       "Interactive Marker Size", 0.0f, "Specifies scale of the interactive marker overlayed on the robot",
00137       plan_category_, SLOT(changedQueryMarkerScale()), this);
00138   query_marker_scale_property_->setMin(0.0f);
00139 
00140   query_start_color_property_ =
00141       new rviz::ColorProperty("Start State Color", QColor(0, 255, 0), "The highlight color for the start state",
00142                               plan_category_, SLOT(changedQueryStartColor()), this);
00143   query_start_alpha_property_ =
00144       new rviz::FloatProperty("Start State Alpha", 1.0f, "Specifies the alpha for the robot links", plan_category_,
00145                               SLOT(changedQueryStartAlpha()), this);
00146   query_start_alpha_property_->setMin(0.0);
00147   query_start_alpha_property_->setMax(1.0);
00148 
00149   query_goal_color_property_ =
00150       new rviz::ColorProperty("Goal State Color", QColor(250, 128, 0), "The highlight color for the goal state",
00151                               plan_category_, SLOT(changedQueryGoalColor()), this);
00152 
00153   query_goal_alpha_property_ =
00154       new rviz::FloatProperty("Goal State Alpha", 1.0f, "Specifies the alpha for the robot links", plan_category_,
00155                               SLOT(changedQueryGoalAlpha()), this);
00156   query_goal_alpha_property_->setMin(0.0);
00157   query_goal_alpha_property_->setMax(1.0);
00158 
00159   query_colliding_link_color_property_ =
00160       new rviz::ColorProperty("Colliding Link Color", QColor(255, 0, 0), "The highlight color for colliding links",
00161                               plan_category_, SLOT(changedQueryCollidingLinkColor()), this);
00162 
00163   query_outside_joint_limits_link_color_property_ =
00164       new rviz::ColorProperty("Joint Violation Color", QColor(255, 0, 255),
00165                               "The highlight color for child links of joints that are outside bounds", plan_category_,
00166                               SLOT(changedQueryJointViolationColor()), this);
00167 
00168   // Trajectory playback / planned path category ---------------------------------------------
00169   trajectory_visual_.reset(new TrajectoryVisualization(path_category_, this));
00170 
00171   // Start background jobs
00172   background_process_.setJobUpdateEvent(boost::bind(&MotionPlanningDisplay::backgroundJobUpdate, this, _1, _2));
00173 }
00174 
00175 // ******************************************************************************************
00176 // Deconstructor
00177 // ******************************************************************************************
00178 MotionPlanningDisplay::~MotionPlanningDisplay()
00179 {
00180   background_process_.clearJobUpdateEvent();
00181   clearJobs();
00182 
00183   query_robot_start_.reset();
00184   query_robot_goal_.reset();
00185 
00186   delete text_to_display_;
00187   delete int_marker_display_;
00188   if (frame_dock_)
00189     delete frame_dock_;
00190 }
00191 
00192 void MotionPlanningDisplay::onInitialize()
00193 {
00194   PlanningSceneDisplay::onInitialize();
00195 
00196   // Planned Path Display
00197   trajectory_visual_->onInitialize(planning_scene_node_, context_, update_nh_);
00198 
00199   query_robot_start_.reset(new RobotStateVisualization(planning_scene_node_, context_, "Planning Request Start", NULL));
00200   query_robot_start_->setCollisionVisible(false);
00201   query_robot_start_->setVisualVisible(true);
00202   query_robot_start_->setVisible(query_start_state_property_->getBool());
00203   std_msgs::ColorRGBA color;
00204   QColor qcolor = query_start_color_property_->getColor();
00205   color.r = qcolor.redF();
00206   color.g = qcolor.greenF();
00207   color.b = qcolor.blueF();
00208   color.a = 1.0f;
00209   query_robot_start_->setDefaultAttachedObjectColor(color);
00210 
00211   query_robot_goal_.reset(new RobotStateVisualization(planning_scene_node_, context_, "Planning Request Goal", NULL));
00212   query_robot_goal_->setCollisionVisible(false);
00213   query_robot_goal_->setVisualVisible(true);
00214   query_robot_goal_->setVisible(query_goal_state_property_->getBool());
00215   qcolor = query_goal_color_property_->getColor();
00216   color.r = qcolor.redF();
00217   color.g = qcolor.greenF();
00218   color.b = qcolor.blueF();
00219   query_robot_goal_->setDefaultAttachedObjectColor(color);
00220 
00221   rviz::WindowManagerInterface* window_context = context_->getWindowManager();
00222   frame_ = new MotionPlanningFrame(this, context_, window_context ? window_context->getParentWindow() : NULL);
00223   resetStatusTextColor();
00224   addStatusText("Initialized.");
00225 
00226   // immediately switch to next trajectory display after planning
00227   connect(frame_, SIGNAL(planningFinished()), trajectory_visual_.get(), SLOT(interruptCurrentDisplay()));
00228 
00229   if (window_context)
00230   {
00231     frame_dock_ = window_context->addPane(getName(), frame_);
00232     connect(frame_dock_, SIGNAL(visibilityChanged(bool)), this, SLOT(motionPanelVisibilityChange(bool)));
00233     frame_dock_->setIcon(getIcon());
00234   }
00235 
00236   int_marker_display_ = context_->getDisplayFactory()->make("rviz/InteractiveMarkers");
00237   int_marker_display_->initialize(context_);
00238 
00239   text_display_scene_node_ = planning_scene_node_->createChildSceneNode();
00240   text_to_display_ = new rviz::MovableText("EMPTY");
00241   text_to_display_->setTextAlignment(rviz::MovableText::H_CENTER, rviz::MovableText::V_CENTER);
00242   text_to_display_->setCharacterHeight(metrics_text_height_property_->getFloat());
00243   text_to_display_->showOnTop();
00244   text_to_display_->setVisible(false);
00245   text_display_for_start_ = false;
00246   text_display_scene_node_->attachObject(text_to_display_);
00247 
00248   if (context_ && context_->getWindowManager() && context_->getWindowManager()->getParentWindow())
00249   {
00250     QShortcut* im_reset_shortcut =
00251         new QShortcut(QKeySequence(Qt::CTRL + Qt::Key_R), context_->getWindowManager()->getParentWindow());
00252     connect(im_reset_shortcut, SIGNAL(activated()), this, SLOT(resetInteractiveMarkers()));
00253   }
00254 }
00255 
00256 void MotionPlanningDisplay::motionPanelVisibilityChange(bool enable)
00257 {
00258   if (enable)
00259     setEnabled(true);
00260 }
00261 
00262 void MotionPlanningDisplay::toggleSelectPlanningGroupSubscription(bool enable)
00263 {
00264   if (enable)
00265   {
00266     planning_group_sub_ = node_handle_.subscribe("/rviz/moveit/select_planning_group", 1,
00267                                                  &MotionPlanningDisplay::selectPlanningGroupCallback, this);
00268   }
00269   else
00270   {
00271     planning_group_sub_.shutdown();
00272   }
00273 }
00274 
00275 void MotionPlanningDisplay::selectPlanningGroupCallback(const std_msgs::StringConstPtr& msg)
00276 {
00277   if (!getRobotModel() || !robot_interaction_)
00278     return;
00279   if (getRobotModel()->hasJointModelGroup(msg->data))
00280   {
00281     planning_group_property_->setStdString(msg->data);
00282     changedPlanningGroup();
00283   }
00284   else
00285   {
00286     ROS_ERROR("Group [%s] not found in the robot model.", msg->data.c_str());
00287   }
00288 }
00289 void MotionPlanningDisplay::reset()
00290 {
00291   text_to_display_->setVisible(false);
00292 
00293   query_robot_start_->clear();
00294   query_robot_goal_->clear();
00295 
00296   PlanningSceneDisplay::reset();
00297 
00298   // Planned Path Display
00299   trajectory_visual_->reset();
00300 
00301   frame_->disable();
00302   frame_->enable();
00303 
00304   query_robot_start_->setVisible(query_start_state_property_->getBool());
00305   query_robot_goal_->setVisible(query_goal_state_property_->getBool());
00306 }
00307 
00308 void MotionPlanningDisplay::setName(const QString& name)
00309 {
00310   BoolProperty::setName(name);
00311   if (frame_dock_)
00312   {
00313     frame_dock_->setWindowTitle(name);
00314     frame_dock_->setObjectName(name);
00315   }
00316   trajectory_visual_->setName(name);
00317 }
00318 
00319 void MotionPlanningDisplay::backgroundJobUpdate(moveit::tools::BackgroundProcessing::JobEvent, const std::string&)
00320 {
00321   addMainLoopJob(boost::bind(&MotionPlanningDisplay::updateBackgroundJobProgressBar, this));
00322 }
00323 
00324 void MotionPlanningDisplay::updateBackgroundJobProgressBar()
00325 {
00326   if (!frame_)
00327     return;
00328   QProgressBar* p = frame_->ui_->background_job_progress;
00329   std::size_t n = background_process_.getJobCount();
00330 
00331   if (n == 0)
00332   {
00333     p->setValue(p->maximum());
00334     p->update();
00335     p->hide();
00336     p->setMaximum(0);
00337   }
00338   else
00339   {
00340     if (n == 1)
00341     {
00342       if (p->maximum() == 0)
00343         p->setValue(0);
00344       else
00345         p->setValue(p->maximum() - 1);
00346     }
00347     else
00348     {
00349       if (p->maximum() < n)
00350         p->setMaximum(n);
00351       else
00352         p->setValue(p->maximum() - n);
00353     }
00354     p->show();
00355     p->update();
00356   }
00357 }
00358 
00359 void MotionPlanningDisplay::changedShowWeightLimit()
00360 {
00361   if (text_display_for_start_)
00362   {
00363     if (query_start_state_property_->getBool())
00364       displayMetrics(true);
00365   }
00366   else
00367   {
00368     if (query_goal_state_property_->getBool())
00369       displayMetrics(false);
00370   }
00371 }
00372 
00373 void MotionPlanningDisplay::changedShowManipulabilityIndex()
00374 {
00375   if (text_display_for_start_)
00376   {
00377     if (query_start_state_property_->getBool())
00378       displayMetrics(true);
00379   }
00380   else
00381   {
00382     if (query_goal_state_property_->getBool())
00383       displayMetrics(false);
00384   }
00385 }
00386 
00387 void MotionPlanningDisplay::changedShowManipulability()
00388 {
00389   if (text_display_for_start_)
00390   {
00391     if (query_start_state_property_->getBool())
00392       displayMetrics(true);
00393   }
00394   else
00395   {
00396     if (query_goal_state_property_->getBool())
00397       displayMetrics(false);
00398   }
00399 }
00400 
00401 void MotionPlanningDisplay::changedShowJointTorques()
00402 {
00403   if (text_display_for_start_)
00404   {
00405     if (query_start_state_property_->getBool())
00406       displayMetrics(true);
00407   }
00408   else
00409   {
00410     if (query_goal_state_property_->getBool())
00411       displayMetrics(false);
00412   }
00413 }
00414 
00415 void MotionPlanningDisplay::changedMetricsSetPayload()
00416 {
00417   if (text_display_for_start_)
00418   {
00419     if (query_start_state_property_->getBool())
00420       displayMetrics(true);
00421   }
00422   else
00423   {
00424     if (query_goal_state_property_->getBool())
00425       displayMetrics(false);
00426   }
00427 }
00428 
00429 void MotionPlanningDisplay::changedMetricsTextHeight()
00430 {
00431   text_to_display_->setCharacterHeight(metrics_text_height_property_->getFloat());
00432 }
00433 
00434 void MotionPlanningDisplay::displayTable(const std::map<std::string, double>& values, const Ogre::ColourValue& color,
00435                                          const Ogre::Vector3& pos, const Ogre::Quaternion& orient)
00436 {
00437   // the line we want to render
00438   std::stringstream ss;
00439   for (std::map<std::string, double>::const_iterator it = values.begin(); it != values.end(); ++it)
00440     ss << boost::format("%-10s %-4.2f") % it->first % it->second << std::endl;
00441 
00442   if (ss.str().empty())
00443   {
00444     text_to_display_->setVisible(false);
00445     return;
00446   }
00447 
00448   text_to_display_->setCaption(ss.str());
00449   text_to_display_->setColor(color);
00450   text_display_scene_node_->setPosition(pos);
00451   text_display_scene_node_->setOrientation(orient);
00452 
00453   // make sure the node is visible
00454   text_to_display_->setVisible(true);
00455 }
00456 
00457 void MotionPlanningDisplay::renderWorkspaceBox()
00458 {
00459   if (!frame_ || !show_workspace_property_->getBool())
00460   {
00461     if (workspace_box_)
00462       workspace_box_.reset();
00463     return;
00464   }
00465 
00466   if (!workspace_box_)
00467   {
00468     workspace_box_.reset(new rviz::Shape(rviz::Shape::Cube, context_->getSceneManager(), planning_scene_node_));
00469     workspace_box_->setColor(0.0f, 0.0f, 0.6f, 0.3f);
00470   }
00471 
00472   Ogre::Vector3 center(frame_->ui_->wcenter_x->value(), frame_->ui_->wcenter_y->value(),
00473                        frame_->ui_->wcenter_z->value());
00474   Ogre::Vector3 extents(frame_->ui_->wsize_x->value(), frame_->ui_->wsize_y->value(), frame_->ui_->wsize_z->value());
00475   workspace_box_->setScale(extents);
00476   workspace_box_->setPosition(center);
00477 }
00478 
00479 void MotionPlanningDisplay::computeMetrics(bool start, const std::string& group, double payload)
00480 {
00481   if (!robot_interaction_)
00482     return;
00483   const std::vector<robot_interaction::RobotInteraction::EndEffector>& eef =
00484       robot_interaction_->getActiveEndEffectors();
00485   if (eef.empty())
00486     return;
00487   boost::mutex::scoped_lock slock(update_metrics_lock_);
00488 
00489   robot_state::RobotStateConstPtr state = start ? getQueryStartState() : getQueryGoalState();
00490   for (std::size_t i = 0; i < eef.size(); ++i)
00491     if (eef[i].parent_group == group)
00492       computeMetricsInternal(computed_metrics_[std::make_pair(start, group)], eef[i], *state, payload);
00493 }
00494 
00495 void MotionPlanningDisplay::computeMetricsInternal(std::map<std::string, double>& metrics,
00496                                                    const robot_interaction::RobotInteraction::EndEffector& ee,
00497                                                    const robot_state::RobotState& state, double payload)
00498 {
00499   metrics.clear();
00500   dynamics_solver::DynamicsSolverPtr ds;
00501   std::map<std::string, dynamics_solver::DynamicsSolverPtr>::const_iterator it = dynamics_solver_.find(ee.parent_group);
00502   if (it != dynamics_solver_.end())
00503     ds = it->second;
00504 
00505   // Max payload
00506   if (ds)
00507   {
00508     double max_payload;
00509     unsigned int saturated_joint;
00510     std::vector<double> joint_values;
00511     state.copyJointGroupPositions(ee.parent_group, joint_values);
00512     if (ds->getMaxPayload(joint_values, max_payload, saturated_joint))
00513     {
00514       metrics["max_payload"] = max_payload;
00515       metrics["saturated_joint"] = saturated_joint;
00516     }
00517     std::vector<double> joint_torques;
00518     joint_torques.resize(joint_values.size());
00519     if (ds->getPayloadTorques(joint_values, payload, joint_torques))
00520     {
00521       for (std::size_t i = 0; i < joint_torques.size(); ++i)
00522       {
00523         std::stringstream stream;
00524         stream << "torque[" << i << "]";
00525         metrics[stream.str()] = joint_torques[i];
00526       }
00527     }
00528   }
00529 
00530   if (kinematics_metrics_)
00531   {
00532     if (position_only_ik_.find(ee.parent_group) == position_only_ik_.end())
00533       private_handle_.param(ee.parent_group + "/position_only_ik", position_only_ik_[ee.parent_group], false);
00534 
00535     double manipulability_index, manipulability;
00536     bool position_ik = position_only_ik_[ee.parent_group];
00537     if (kinematics_metrics_->getManipulabilityIndex(state, ee.parent_group, manipulability_index, position_ik))
00538       metrics["manipulability_index"] = manipulability_index;
00539     if (kinematics_metrics_->getManipulability(state, ee.parent_group, manipulability))
00540       metrics["manipulability"] = manipulability;
00541   }
00542 }
00543 
00544 namespace
00545 {
00546 inline void copyItemIfExists(const std::map<std::string, double>& source, std::map<std::string, double>& dest,
00547                              const std::string& key)
00548 {
00549   std::map<std::string, double>::const_iterator it = source.find(key);
00550   if (it != source.end())
00551     dest[key] = it->second;
00552 }
00553 }
00554 
00555 void MotionPlanningDisplay::displayMetrics(bool start)
00556 {
00557   if (!robot_interaction_ || !planning_scene_monitor_)
00558     return;
00559 
00560   static const Ogre::Quaternion orientation(1.0, 0.0, 0.0, 0.0);
00561   const std::vector<robot_interaction::RobotInteraction::EndEffector>& eef =
00562       robot_interaction_->getActiveEndEffectors();
00563   if (eef.empty())
00564     return;
00565 
00566   robot_state::RobotStateConstPtr state = start ? getQueryStartState() : getQueryGoalState();
00567 
00568   for (std::size_t i = 0; i < eef.size(); ++i)
00569   {
00570     Ogre::Vector3 position(0.0, 0.0, 0.0);
00571     std::map<std::string, double> text_table;
00572     const std::map<std::string, double>& metrics_table = computed_metrics_[std::make_pair(start, eef[i].parent_group)];
00573     if (compute_weight_limit_property_->getBool())
00574     {
00575       copyItemIfExists(metrics_table, text_table, "max_payload");
00576       copyItemIfExists(metrics_table, text_table, "saturated_joint");
00577     }
00578     if (show_manipulability_index_property_->getBool())
00579       copyItemIfExists(metrics_table, text_table, "manipulability_index");
00580     if (show_manipulability_property_->getBool())
00581       copyItemIfExists(metrics_table, text_table, "manipulability");
00582     if (show_joint_torques_property_->getBool())
00583     {
00584       std::size_t nj = getRobotModel()->getJointModelGroup(eef[i].parent_group)->getJointModelNames().size();
00585       for (size_t j = 0; j < nj; ++j)
00586       {
00587         std::stringstream stream;
00588         stream << "torque[" << j << "]";
00589         copyItemIfExists(metrics_table, text_table, stream.str());
00590       }
00591     }
00592 
00593     const robot_state::LinkModel* lm = NULL;
00594     const robot_model::JointModelGroup* jmg = getRobotModel()->getJointModelGroup(eef[i].parent_group);
00595     if (jmg)
00596       if (!jmg->getLinkModelNames().empty())
00597         lm = state->getLinkModel(jmg->getLinkModelNames().back());
00598     if (lm)
00599     {
00600       const Eigen::Vector3d& t = state->getGlobalLinkTransform(lm).translation();
00601       position[0] = t.x();
00602       position[1] = t.y();
00603       position[2] = t.z() + 0.2;  // \todo this should be a param
00604     }
00605     if (start)
00606       displayTable(text_table, query_start_color_property_->getOgreColor(), position, orientation);
00607     else
00608       displayTable(text_table, query_goal_color_property_->getOgreColor(), position, orientation);
00609     text_display_for_start_ = start;
00610   }
00611 }
00612 
00613 void MotionPlanningDisplay::drawQueryStartState()
00614 {
00615   if (!planning_scene_monitor_)
00616     return;
00617 
00618   if (query_start_state_property_->getBool())
00619   {
00620     if (isEnabled())
00621     {
00622       robot_state::RobotStateConstPtr state = getQueryStartState();
00623 
00624       // update link poses
00625       query_robot_start_->update(state);
00626       query_robot_start_->setVisible(true);
00627 
00628       // update link colors
00629       std::vector<std::string> collision_links;
00630       getPlanningSceneRO()->getCollidingLinks(collision_links, *state);
00631       status_links_start_.clear();
00632       for (std::size_t i = 0; i < collision_links.size(); ++i)
00633         status_links_start_[collision_links[i]] = COLLISION_LINK;
00634       if (!collision_links.empty())
00635       {
00636         collision_detection::CollisionResult::ContactMap pairs;
00637         getPlanningSceneRO()->getCollidingPairs(pairs, *state);
00638         setStatusTextColor(query_start_color_property_->getColor());
00639         addStatusText("Start state colliding links:");
00640         for (collision_detection::CollisionResult::ContactMap::const_iterator it = pairs.begin(); it != pairs.end();
00641              ++it)
00642           addStatusText(it->first.first + " - " + it->first.second);
00643         addStatusText(".");
00644       }
00645       if (!getCurrentPlanningGroup().empty())
00646       {
00647         const robot_model::JointModelGroup* jmg = state->getJointModelGroup(getCurrentPlanningGroup());
00648         if (jmg)
00649         {
00650           std::vector<std::string> outside_bounds;
00651           const std::vector<const robot_model::JointModel*>& jmodels = jmg->getActiveJointModels();
00652           for (std::size_t i = 0; i < jmodels.size(); ++i)
00653             if (!state->satisfiesBounds(jmodels[i], jmodels[i]->getMaximumExtent() * 1e-2))
00654             {
00655               outside_bounds.push_back(jmodels[i]->getChildLinkModel()->getName());
00656               status_links_start_[outside_bounds.back()] = OUTSIDE_BOUNDS_LINK;
00657             }
00658           if (!outside_bounds.empty())
00659           {
00660             setStatusTextColor(query_start_color_property_->getColor());
00661             addStatusText("Links descending from joints that are outside bounds in start state:");
00662             addStatusText(outside_bounds);
00663           }
00664         }
00665       }
00666       updateLinkColors();
00667       // update metrics text
00668       displayMetrics(true);
00669     }
00670   }
00671   else
00672     query_robot_start_->setVisible(false);
00673   context_->queueRender();
00674 }
00675 
00676 void MotionPlanningDisplay::resetStatusTextColor()
00677 {
00678   setStatusTextColor(Qt::darkGray);
00679 }
00680 
00681 void MotionPlanningDisplay::setStatusTextColor(const QColor& color)
00682 {
00683   if (frame_)
00684     frame_->ui_->status_text->setTextColor(color);
00685 }
00686 
00687 void MotionPlanningDisplay::addStatusText(const std::string& text)
00688 {
00689   if (frame_)
00690     frame_->ui_->status_text->append(QString::fromStdString(text));
00691 }
00692 
00693 void MotionPlanningDisplay::addStatusText(const std::vector<std::string>& text)
00694 {
00695   for (std::size_t i = 0; i < text.size(); ++i)
00696     addStatusText(text[i]);
00697 }
00698 
00699 void MotionPlanningDisplay::recomputeQueryStartStateMetrics()
00700 {
00701   std::string group = planning_group_property_->getStdString();
00702   if (!group.empty())
00703     computeMetrics(true, group, metrics_set_payload_property_->getFloat());
00704 }
00705 
00706 void MotionPlanningDisplay::recomputeQueryGoalStateMetrics()
00707 {
00708   std::string group = planning_group_property_->getStdString();
00709   if (!group.empty())
00710     computeMetrics(false, group, metrics_set_payload_property_->getFloat());
00711 }
00712 
00713 void MotionPlanningDisplay::changedQueryStartState()
00714 {
00715   if (!planning_scene_monitor_)
00716     return;
00717   setStatusTextColor(query_start_color_property_->getColor());
00718   addStatusText("Changed start state");
00719   drawQueryStartState();
00720   addBackgroundJob(boost::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, true), "publishInteractiveMarke"
00721                                                                                                "rs");
00722 }
00723 
00724 void MotionPlanningDisplay::changedQueryGoalState()
00725 {
00726   if (!planning_scene_monitor_)
00727     return;
00728   setStatusTextColor(query_goal_color_property_->getColor());
00729   addStatusText("Changed goal state");
00730   drawQueryGoalState();
00731   addBackgroundJob(boost::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, true), "publishInteractiveMarke"
00732                                                                                                "rs");
00733 }
00734 
00735 void MotionPlanningDisplay::drawQueryGoalState()
00736 {
00737   if (!planning_scene_monitor_)
00738     return;
00739   if (query_goal_state_property_->getBool())
00740   {
00741     if (isEnabled())
00742     {
00743       robot_state::RobotStateConstPtr state = getQueryGoalState();
00744 
00745       // update link poses
00746       query_robot_goal_->update(state);
00747       query_robot_goal_->setVisible(true);
00748 
00749       // update link colors
00750       std::vector<std::string> collision_links;
00751       getPlanningSceneRO()->getCollidingLinks(collision_links, *state);
00752       status_links_goal_.clear();
00753       for (std::size_t i = 0; i < collision_links.size(); ++i)
00754         status_links_goal_[collision_links[i]] = COLLISION_LINK;
00755       if (!collision_links.empty())
00756       {
00757         collision_detection::CollisionResult::ContactMap pairs;
00758         getPlanningSceneRO()->getCollidingPairs(pairs, *state);
00759         setStatusTextColor(query_goal_color_property_->getColor());
00760         addStatusText("Goal state colliding links:");
00761         for (collision_detection::CollisionResult::ContactMap::const_iterator it = pairs.begin(); it != pairs.end();
00762              ++it)
00763           addStatusText(it->first.first + " - " + it->first.second);
00764         addStatusText(".");
00765       }
00766 
00767       if (!getCurrentPlanningGroup().empty())
00768       {
00769         const robot_model::JointModelGroup* jmg = state->getJointModelGroup(getCurrentPlanningGroup());
00770         if (jmg)
00771         {
00772           const std::vector<const robot_state::JointModel*>& jmodels = jmg->getActiveJointModels();
00773           std::vector<std::string> outside_bounds;
00774           for (std::size_t i = 0; i < jmodels.size(); ++i)
00775             if (!state->satisfiesBounds(jmodels[i], jmodels[i]->getMaximumExtent() * 1e-2))
00776             {
00777               outside_bounds.push_back(jmodels[i]->getChildLinkModel()->getName());
00778               status_links_goal_[outside_bounds.back()] = OUTSIDE_BOUNDS_LINK;
00779             }
00780 
00781           if (!outside_bounds.empty())
00782           {
00783             setStatusTextColor(query_goal_color_property_->getColor());
00784             addStatusText("Links descending from joints that are outside bounds in goal state:");
00785             addStatusText(outside_bounds);
00786           }
00787         }
00788       }
00789       updateLinkColors();
00790 
00791       // update metrics text
00792       displayMetrics(false);
00793     }
00794   }
00795   else
00796     query_robot_goal_->setVisible(false);
00797   context_->queueRender();
00798 }
00799 
00800 void MotionPlanningDisplay::resetInteractiveMarkers()
00801 {
00802   query_start_state_->clearError();
00803   query_goal_state_->clearError();
00804   addBackgroundJob(boost::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, false), "publishInteractiveMark"
00805                                                                                                 "ers");
00806 }
00807 
00808 void MotionPlanningDisplay::publishInteractiveMarkers(bool pose_update)
00809 {
00810   if (robot_interaction_)
00811   {
00812     if (pose_update &&
00813         robot_interaction_->showingMarkers(query_start_state_) == query_start_state_property_->getBool() &&
00814         robot_interaction_->showingMarkers(query_goal_state_) == query_goal_state_property_->getBool())
00815     {
00816       if (query_start_state_property_->getBool())
00817         robot_interaction_->updateInteractiveMarkers(query_start_state_);
00818       if (query_goal_state_property_->getBool())
00819         robot_interaction_->updateInteractiveMarkers(query_goal_state_);
00820     }
00821     else
00822     {
00823       robot_interaction_->clearInteractiveMarkers();
00824       if (query_start_state_property_->getBool())
00825         robot_interaction_->addInteractiveMarkers(query_start_state_, query_marker_scale_property_->getFloat());
00826       if (query_goal_state_property_->getBool())
00827         robot_interaction_->addInteractiveMarkers(query_goal_state_, query_marker_scale_property_->getFloat());
00828       robot_interaction_->publishInteractiveMarkers();
00829     }
00830     if (frame_)
00831     {
00832       frame_->updateExternalCommunication();
00833     }
00834   }
00835 }
00836 
00837 void MotionPlanningDisplay::changedQueryStartColor()
00838 {
00839   std_msgs::ColorRGBA color;
00840   QColor qcolor = query_start_color_property_->getColor();
00841   color.r = qcolor.redF();
00842   color.g = qcolor.greenF();
00843   color.b = qcolor.blueF();
00844   color.a = 1.0f;
00845   query_robot_start_->setDefaultAttachedObjectColor(color);
00846   changedQueryStartState();
00847 }
00848 
00849 void MotionPlanningDisplay::changedQueryStartAlpha()
00850 {
00851   query_robot_start_->setAlpha(query_start_alpha_property_->getFloat());
00852   changedQueryStartState();
00853 }
00854 
00855 void MotionPlanningDisplay::changedQueryMarkerScale()
00856 {
00857   if (!planning_scene_monitor_)
00858     return;
00859 
00860   if (isEnabled())
00861   {
00862     // Clear the interactive markers and re-add them:
00863     publishInteractiveMarkers(false);
00864   }
00865 }
00866 
00867 void MotionPlanningDisplay::changedQueryGoalColor()
00868 {
00869   std_msgs::ColorRGBA color;
00870   QColor qcolor = query_goal_color_property_->getColor();
00871   color.r = qcolor.redF();
00872   color.g = qcolor.greenF();
00873   color.b = qcolor.blueF();
00874   color.a = 1.0f;
00875   query_robot_goal_->setDefaultAttachedObjectColor(color);
00876   changedQueryGoalState();
00877 }
00878 
00879 void MotionPlanningDisplay::changedQueryGoalAlpha()
00880 {
00881   query_robot_goal_->setAlpha(query_goal_alpha_property_->getFloat());
00882   changedQueryGoalState();
00883 }
00884 
00885 void MotionPlanningDisplay::changedQueryCollidingLinkColor()
00886 {
00887   changedQueryStartState();
00888   changedQueryGoalState();
00889 }
00890 
00891 void MotionPlanningDisplay::changedQueryJointViolationColor()
00892 {
00893   changedQueryStartState();
00894   changedQueryGoalState();
00895 }
00896 
00897 void MotionPlanningDisplay::scheduleDrawQueryStartState(robot_interaction::RobotInteraction::InteractionHandler*,
00898                                                         bool error_state_changed)
00899 {
00900   if (!planning_scene_monitor_)
00901     return;
00902   addBackgroundJob(boost::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, !error_state_changed),
00903                    "publishInteractiveMarkers");
00904   recomputeQueryStartStateMetrics();
00905   addMainLoopJob(boost::bind(&MotionPlanningDisplay::drawQueryStartState, this));
00906   context_->queueRender();
00907 }
00908 
00909 void MotionPlanningDisplay::scheduleDrawQueryGoalState(robot_interaction::RobotInteraction::InteractionHandler*,
00910                                                        bool error_state_changed)
00911 {
00912   if (!planning_scene_monitor_)
00913     return;
00914   addBackgroundJob(boost::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, !error_state_changed),
00915                    "publishInteractiveMarkers");
00916   recomputeQueryGoalStateMetrics();
00917   addMainLoopJob(boost::bind(&MotionPlanningDisplay::drawQueryGoalState, this));
00918   context_->queueRender();
00919 }
00920 
00921 void MotionPlanningDisplay::updateQueryStartState()
00922 {
00923   recomputeQueryStartStateMetrics();
00924   addMainLoopJob(boost::bind(&MotionPlanningDisplay::changedQueryStartState, this));
00925   context_->queueRender();
00926 }
00927 
00928 void MotionPlanningDisplay::updateQueryGoalState()
00929 {
00930   recomputeQueryGoalStateMetrics();
00931   addMainLoopJob(boost::bind(&MotionPlanningDisplay::changedQueryGoalState, this));
00932   context_->queueRender();
00933 }
00934 
00935 void MotionPlanningDisplay::setQueryStartState(const robot_state::RobotState& start)
00936 {
00937   query_start_state_->setState(start);
00938   updateQueryStartState();
00939 }
00940 
00941 void MotionPlanningDisplay::setQueryGoalState(const robot_state::RobotState& goal)
00942 {
00943   query_goal_state_->setState(goal);
00944   updateQueryGoalState();
00945 }
00946 
00947 void MotionPlanningDisplay::useApproximateIK(bool flag)
00948 {
00949   if (query_start_state_)
00950   {
00951     kinematics::KinematicsQueryOptions o = query_start_state_->getKinematicsQueryOptions();
00952     o.return_approximate_solution = flag;
00953     query_start_state_->setKinematicsQueryOptions(o);
00954   }
00955   if (query_goal_state_)
00956   {
00957     kinematics::KinematicsQueryOptions o = query_goal_state_->getKinematicsQueryOptions();
00958     o.return_approximate_solution = flag;
00959     query_goal_state_->setKinematicsQueryOptions(o);
00960   }
00961 }
00962 
00963 bool MotionPlanningDisplay::isIKSolutionCollisionFree(robot_state::RobotState* state,
00964                                                       const robot_model::JointModelGroup* group,
00965                                                       const double* ik_solution) const
00966 {
00967   if (frame_->ui_->collision_aware_ik->isChecked() && planning_scene_monitor_)
00968   {
00969     state->setJointGroupPositions(group, ik_solution);
00970     state->update();
00971     bool res = !getPlanningSceneRO()->isStateColliding(*state, group->getName());
00972     return res;
00973   }
00974   else
00975     return true;
00976 }
00977 
00978 void MotionPlanningDisplay::updateLinkColors()
00979 {
00980   unsetAllColors(&query_robot_start_->getRobot());
00981   unsetAllColors(&query_robot_goal_->getRobot());
00982   std::string group = planning_group_property_->getStdString();
00983   if (!group.empty())
00984   {
00985     setGroupColor(&query_robot_start_->getRobot(), group, query_start_color_property_->getColor());
00986     setGroupColor(&query_robot_goal_->getRobot(), group, query_goal_color_property_->getColor());
00987 
00988     for (std::map<std::string, LinkDisplayStatus>::const_iterator it = status_links_start_.begin();
00989          it != status_links_start_.end(); ++it)
00990       if (it->second == COLLISION_LINK)
00991         setLinkColor(&query_robot_start_->getRobot(), it->first, query_colliding_link_color_property_->getColor());
00992       else
00993         setLinkColor(&query_robot_start_->getRobot(), it->first,
00994                      query_outside_joint_limits_link_color_property_->getColor());
00995 
00996     for (std::map<std::string, LinkDisplayStatus>::const_iterator it = status_links_goal_.begin();
00997          it != status_links_goal_.end(); ++it)
00998       if (it->second == COLLISION_LINK)
00999         setLinkColor(&query_robot_goal_->getRobot(), it->first, query_colliding_link_color_property_->getColor());
01000       else
01001         setLinkColor(&query_robot_goal_->getRobot(), it->first,
01002                      query_outside_joint_limits_link_color_property_->getColor());
01003   }
01004 }
01005 
01006 void MotionPlanningDisplay::changePlanningGroup(const std::string& group)
01007 {
01008   if (!getRobotModel() || !robot_interaction_)
01009     return;
01010 
01011   if (getRobotModel()->hasJointModelGroup(group))
01012   {
01013     planning_group_property_->setStdString(group);
01014     changedPlanningGroup();
01015   }
01016   else
01017     ROS_ERROR("Group [%s] not found in the robot model.", group.c_str());
01018 }
01019 
01020 void MotionPlanningDisplay::changedPlanningGroup()
01021 {
01022   if (!getRobotModel() || !robot_interaction_)
01023     return;
01024 
01025   if (!planning_group_property_->getStdString().empty())
01026     if (!getRobotModel()->hasJointModelGroup(planning_group_property_->getStdString()))
01027     {
01028       planning_group_property_->setStdString("");
01029       return;
01030     }
01031   modified_groups_.insert(planning_group_property_->getStdString());
01032 
01033   if (robot_interaction_)
01034     robot_interaction_->decideActiveComponents(planning_group_property_->getStdString());
01035 
01036   updateQueryStartState();
01037   updateQueryGoalState();
01038   updateLinkColors();
01039 
01040   if (frame_)
01041     frame_->changePlanningGroup();
01042   addBackgroundJob(boost::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, false), "publishInteractiveMark"
01043                                                                                                 "ers");
01044 }
01045 
01046 void MotionPlanningDisplay::changedWorkspace()
01047 {
01048   renderWorkspaceBox();
01049 }
01050 
01051 std::string MotionPlanningDisplay::getCurrentPlanningGroup() const
01052 {
01053   return planning_group_property_->getStdString();
01054 }
01055 
01056 void MotionPlanningDisplay::setQueryStateHelper(bool use_start_state, const std::string& state_name)
01057 {
01058   robot_state::RobotState state = use_start_state ? *getQueryStartState() : *getQueryGoalState();
01059 
01060   std::string v = "<" + state_name + ">";
01061 
01062   if (v == "<random>")
01063   {
01064     if (const robot_state::JointModelGroup* jmg = state.getJointModelGroup(getCurrentPlanningGroup()))
01065       state.setToRandomPositions(jmg);
01066   }
01067   else if (v == "<current>")
01068   {
01069     const planning_scene_monitor::LockedPlanningSceneRO& ps = getPlanningSceneRO();
01070     if (ps)
01071       state = ps->getCurrentState();
01072   }
01073   else if (v == "<same as goal>")
01074   {
01075     state = *getQueryGoalState();
01076   }
01077   else if (v == "<same as start>")
01078   {
01079     state = *getQueryStartState();
01080   }
01081   else
01082   {
01083     // maybe it is a named state
01084     if (const robot_model::JointModelGroup* jmg = state.getJointModelGroup(getCurrentPlanningGroup()))
01085       state.setToDefaultValues(jmg, state_name);
01086   }
01087 
01088   use_start_state ? setQueryStartState(state) : setQueryGoalState(state);
01089 }
01090 
01091 void MotionPlanningDisplay::populateMenuHandler(boost::shared_ptr<interactive_markers::MenuHandler>& mh)
01092 {
01093   typedef interactive_markers::MenuHandler immh;
01094   std::vector<std::string> state_names;
01095   state_names.push_back("random");
01096   state_names.push_back("current");
01097   state_names.push_back("same as start");
01098   state_names.push_back("same as goal");
01099 
01100   // hacky way to distinguish between the start and goal handlers...
01101   bool is_start = (mh.get() == menu_handler_start_.get());
01102 
01103   // Commands for changing the state
01104   immh::EntryHandle menu_states =
01105       mh->insert(is_start ? "Set start state to" : "Set goal state to", immh::FeedbackCallback());
01106   for (int i = 0; i < state_names.size(); ++i)
01107   {
01108     // Don't add "same as start" to the start state handler, and vice versa.
01109     if ((state_names[i] == "same as start" && is_start) || (state_names[i] == "same as goal" && !is_start))
01110       continue;
01111     mh->insert(menu_states, state_names[i],
01112                boost::bind(&MotionPlanningDisplay::setQueryStateHelper, this, is_start, state_names[i]));
01113   }
01114 
01115   //  // Group commands, which end up being the same for both interaction handlers
01116   //  const std::vector<std::string>& group_names = getRobotModel()->getJointModelGroupNames();
01117   //  immh::EntryHandle menu_groups = mh->insert("Planning Group", immh::FeedbackCallback());
01118   //  for (int i = 0; i < group_names.size(); ++i)
01119   //    mh->insert(menu_groups, group_names[i],
01120   //               boost::bind(&MotionPlanningDisplay::changePlanningGroup, this, group_names[i]));
01121 }
01122 
01123 void MotionPlanningDisplay::onRobotModelLoaded()
01124 {
01125   PlanningSceneDisplay::onRobotModelLoaded();
01126   trajectory_visual_->onRobotModelLoaded(getRobotModel());
01127 
01128   robot_interaction_.reset(new robot_interaction::RobotInteraction(getRobotModel(), "rviz_moveit_motion_planning_"
01129                                                                                     "display"));
01130   int_marker_display_->subProp("Update Topic")
01131       ->setValue(QString::fromStdString(robot_interaction_->getServerTopic() + "/update"));
01132   query_robot_start_->load(*getRobotModel()->getURDF());
01133   query_robot_goal_->load(*getRobotModel()->getURDF());
01134 
01135   robot_state::RobotStatePtr ks(new robot_state::RobotState(getPlanningSceneRO()->getCurrentState()));
01136   query_start_state_.reset(new robot_interaction::RobotInteraction::InteractionHandler(
01137       "start", *ks, planning_scene_monitor_->getTFClient()));
01138   query_goal_state_.reset(new robot_interaction::RobotInteraction::InteractionHandler(
01139       "goal", *getQueryStartState(), planning_scene_monitor_->getTFClient()));
01140   query_start_state_->setUpdateCallback(boost::bind(&MotionPlanningDisplay::scheduleDrawQueryStartState, this, _1, _2));
01141   query_goal_state_->setUpdateCallback(boost::bind(&MotionPlanningDisplay::scheduleDrawQueryGoalState, this, _1, _2));
01142   query_start_state_->setGroupStateValidityCallback(
01143       boost::bind(&MotionPlanningDisplay::isIKSolutionCollisionFree, this, _1, _2, _3));
01144   query_goal_state_->setGroupStateValidityCallback(
01145       boost::bind(&MotionPlanningDisplay::isIKSolutionCollisionFree, this, _1, _2, _3));
01146 
01147   // Interactive marker menus
01148   populateMenuHandler(menu_handler_start_);
01149   populateMenuHandler(menu_handler_goal_);
01150   query_start_state_->setMenuHandler(menu_handler_start_);
01151   query_goal_state_->setMenuHandler(menu_handler_goal_);
01152 
01153   if (!planning_group_property_->getStdString().empty())
01154     if (!getRobotModel()->hasJointModelGroup(planning_group_property_->getStdString()))
01155       planning_group_property_->setStdString("");
01156 
01157   const std::vector<std::string>& groups = getRobotModel()->getJointModelGroupNames();
01158   planning_group_property_->clearOptions();
01159   for (std::size_t i = 0; i < groups.size(); ++i)
01160     planning_group_property_->addOptionStd(groups[i]);
01161   planning_group_property_->sortOptions();
01162   if (!groups.empty() && planning_group_property_->getStdString().empty())
01163     planning_group_property_->setStdString(groups[0]);
01164 
01165   modified_groups_.clear();
01166   kinematics_metrics_.reset(new kinematics_metrics::KinematicsMetrics(getRobotModel()));
01167 
01168   geometry_msgs::Vector3 gravity_vector;
01169   gravity_vector.x = 0.0;
01170   gravity_vector.y = 0.0;
01171   gravity_vector.z = 9.81;
01172 
01173   dynamics_solver_.clear();
01174   for (std::size_t i = 0; i < groups.size(); ++i)
01175     if (getRobotModel()->getJointModelGroup(groups[i])->isChain())
01176       dynamics_solver_[groups[i]].reset(
01177           new dynamics_solver::DynamicsSolver(getRobotModel(), groups[i], gravity_vector));
01178   addMainLoopJob(boost::bind(&MotionPlanningDisplay::changedPlanningGroup, this));
01179 }
01180 
01181 void MotionPlanningDisplay::updateStateExceptModified(robot_state::RobotState& dest, const robot_state::RobotState& src)
01182 {
01183   robot_state::RobotState src_copy = src;
01184   for (std::set<std::string>::const_iterator it = modified_groups_.begin(); it != modified_groups_.end(); ++it)
01185   {
01186     const robot_model::JointModelGroup* jmg = dest.getJointModelGroup(*it);
01187     if (jmg)
01188     {
01189       std::vector<double> values_to_keep;
01190       dest.copyJointGroupPositions(jmg, values_to_keep);
01191       src_copy.setJointGroupPositions(jmg, values_to_keep);
01192     }
01193   }
01194 
01195   // overwrite the destination state
01196   dest = src_copy;
01197 }
01198 
01199 void MotionPlanningDisplay::onSceneMonitorReceivedUpdate(
01200     planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type)
01201 {
01202   PlanningSceneDisplay::onSceneMonitorReceivedUpdate(update_type);
01203   robot_state::RobotState current_state = getPlanningSceneRO()->getCurrentState();
01204   std::string group = planning_group_property_->getStdString();
01205 
01206   if (query_start_state_property_->getBool() && !group.empty())
01207   {
01208     robot_state::RobotState start = *getQueryStartState();
01209     updateStateExceptModified(start, current_state);
01210     setQueryStartState(start);
01211   }
01212 
01213   if (query_goal_state_property_->getBool() && !group.empty())
01214   {
01215     robot_state::RobotState goal = *getQueryGoalState();
01216     updateStateExceptModified(goal, current_state);
01217     setQueryGoalState(goal);
01218   }
01219 
01220   if (frame_)
01221     frame_->sceneUpdate(update_type);
01222 }
01223 
01224 // ******************************************************************************************
01225 // Enable
01226 // ******************************************************************************************
01227 void MotionPlanningDisplay::onEnable()
01228 {
01229   PlanningSceneDisplay::onEnable();
01230 
01231   // Planned Path Display
01232   trajectory_visual_->onEnable();
01233 
01234   text_to_display_->setVisible(false);
01235 
01236   query_robot_start_->setVisible(query_start_state_property_->getBool());
01237   query_robot_goal_->setVisible(query_goal_state_property_->getBool());
01238 
01239   int_marker_display_->setEnabled(true);
01240   int_marker_display_->setFixedFrame(fixed_frame_);
01241 }
01242 
01243 // ******************************************************************************************
01244 // Disable
01245 // ******************************************************************************************
01246 void MotionPlanningDisplay::onDisable()
01247 {
01248   if (robot_interaction_)
01249     robot_interaction_->clear();
01250   int_marker_display_->setEnabled(false);
01251 
01252   query_robot_start_->setVisible(false);
01253   query_robot_goal_->setVisible(false);
01254   text_to_display_->setVisible(false);
01255 
01256   PlanningSceneDisplay::onDisable();
01257 
01258   // Planned Path Display
01259   trajectory_visual_->onDisable();
01260 }
01261 
01262 // ******************************************************************************************
01263 // Update
01264 // ******************************************************************************************
01265 void MotionPlanningDisplay::update(float wall_dt, float ros_dt)
01266 {
01267   if (int_marker_display_)
01268     int_marker_display_->update(wall_dt, ros_dt);
01269   if (frame_)
01270     frame_->updateSceneMarkers(wall_dt, ros_dt);
01271 
01272   PlanningSceneDisplay::update(wall_dt, ros_dt);
01273 }
01274 
01275 void MotionPlanningDisplay::updateInternal(float wall_dt, float ros_dt)
01276 {
01277   PlanningSceneDisplay::updateInternal(wall_dt, ros_dt);
01278 
01279   // Planned Path Display
01280   trajectory_visual_->update(wall_dt, ros_dt);
01281 
01282   renderWorkspaceBox();
01283 }
01284 
01285 void MotionPlanningDisplay::load(const rviz::Config& config)
01286 {
01287   PlanningSceneDisplay::load(config);
01288   if (frame_)
01289   {
01290     QString host;
01291     ros::NodeHandle nh;
01292     std::string host_param;
01293     if (config.mapGetString("MoveIt_Warehouse_Host", &host))
01294       frame_->ui_->database_host->setText(host);
01295     else if (nh.getParam("warehouse_host", host_param))
01296     {
01297       host = QString::fromStdString(host_param);
01298       frame_->ui_->database_host->setText(host);
01299     }
01300     int port;
01301     if (config.mapGetInt("MoveIt_Warehouse_Port", &port) || nh.getParam("warehouse_port", port))
01302       frame_->ui_->database_port->setValue(port);
01303     float d;
01304     if (config.mapGetFloat("MoveIt_Planning_Time", &d))
01305       frame_->ui_->planning_time->setValue(d);
01306     int attempts;
01307     if (config.mapGetInt("MoveIt_Planning_Attempts", &attempts))
01308       frame_->ui_->planning_attempts->setValue(attempts);
01309     if (config.mapGetFloat("MoveIt_Goal_Tolerance", &d))
01310       frame_->ui_->goal_tolerance->setValue(d);
01311     bool b;
01312     if (config.mapGetBool("MoveIt_Use_Constraint_Aware_IK", &b))
01313       frame_->ui_->collision_aware_ik->setChecked(b);
01314 
01315     rviz::Config workspace = config.mapGetChild("MoveIt_Workspace");
01316     rviz::Config ws_center = workspace.mapGetChild("Center");
01317     float val;
01318     if (ws_center.mapGetFloat("X", &val))
01319       frame_->ui_->wcenter_x->setValue(val);
01320     if (ws_center.mapGetFloat("Y", &val))
01321       frame_->ui_->wcenter_y->setValue(val);
01322     if (ws_center.mapGetFloat("Z", &val))
01323       frame_->ui_->wcenter_z->setValue(val);
01324 
01325     rviz::Config ws_size = workspace.mapGetChild("Size");
01326     if (ws_size.isValid())
01327     {
01328       if (ws_size.mapGetFloat("X", &val))
01329         frame_->ui_->wsize_x->setValue(val);
01330       if (ws_size.mapGetFloat("Y", &val))
01331         frame_->ui_->wsize_y->setValue(val);
01332       if (ws_size.mapGetFloat("Z", &val))
01333         frame_->ui_->wsize_z->setValue(val);
01334     }
01335     else
01336     {
01337       std::string node_name = ros::names::append(getMoveGroupNS(), "move_group");
01338       ros::NodeHandle nh_(node_name);
01339       double val;
01340       if (nh_.getParam("default_workspace_bounds", val))
01341       {
01342         frame_->ui_->wsize_x->setValue(val);
01343         frame_->ui_->wsize_y->setValue(val);
01344         frame_->ui_->wsize_z->setValue(val);
01345       }
01346     }
01347   }
01348 }
01349 
01350 void MotionPlanningDisplay::save(rviz::Config config) const
01351 {
01352   PlanningSceneDisplay::save(config);
01353   if (frame_)
01354   {
01355     config.mapSetValue("MoveIt_Warehouse_Host", frame_->ui_->database_host->text());
01356     config.mapSetValue("MoveIt_Warehouse_Port", frame_->ui_->database_port->value());
01357     config.mapSetValue("MoveIt_Planning_Time", frame_->ui_->planning_time->value());
01358     config.mapSetValue("MoveIt_Planning_Attempts", frame_->ui_->planning_attempts->value());
01359     config.mapSetValue("MoveIt_Goal_Tolerance", frame_->ui_->goal_tolerance->value());
01360     config.mapSetValue("MoveIt_Use_Constraint_Aware_IK", frame_->ui_->collision_aware_ik->isChecked());
01361 
01362     rviz::Config workspace = config.mapMakeChild("MoveIt_Workspace");
01363     rviz::Config ws_center = workspace.mapMakeChild("Center");
01364     ws_center.mapSetValue("X", frame_->ui_->wcenter_x->value());
01365     ws_center.mapSetValue("Y", frame_->ui_->wcenter_y->value());
01366     ws_center.mapSetValue("Z", frame_->ui_->wcenter_z->value());
01367     rviz::Config ws_size = workspace.mapMakeChild("Size");
01368     ws_size.mapSetValue("X", frame_->ui_->wsize_x->value());
01369     ws_size.mapSetValue("Y", frame_->ui_->wsize_y->value());
01370     ws_size.mapSetValue("Z", frame_->ui_->wsize_z->value());
01371   }
01372 }
01373 
01374 void MotionPlanningDisplay::fixedFrameChanged()
01375 {
01376   PlanningSceneDisplay::fixedFrameChanged();
01377   if (int_marker_display_)
01378     int_marker_display_->setFixedFrame(fixed_frame_);
01379   changedPlanningGroup();
01380 }
01381 
01382 // Pick and place
01383 void MotionPlanningDisplay::clearPlaceLocationsDisplay()
01384 {
01385   for (std::size_t i = 0; i < place_locations_display_.size(); ++i)
01386     place_locations_display_[i].reset();
01387   place_locations_display_.clear();
01388 }
01389 
01390 void MotionPlanningDisplay::visualizePlaceLocations(const std::vector<geometry_msgs::PoseStamped>& place_poses)
01391 {
01392   clearPlaceLocationsDisplay();
01393   place_locations_display_.resize(place_poses.size());
01394   for (std::size_t i = 0; i < place_poses.size(); ++i)
01395   {
01396     place_locations_display_[i].reset(new rviz::Shape(rviz::Shape::Sphere, context_->getSceneManager()));
01397     place_locations_display_[i]->setColor(1.0f, 0.0f, 0.0f, 0.3f);
01398     Ogre::Vector3 center(place_poses[i].pose.position.x, place_poses[i].pose.position.y,
01399                          place_poses[i].pose.position.z);
01400     Ogre::Vector3 extents(0.02, 0.02, 0.02);
01401     place_locations_display_[i]->setScale(extents);
01402     place_locations_display_[i]->setPosition(center);
01403   }
01404 }
01405 
01406 }  // namespace moveit_rviz_plugin


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