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


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