58 #include <OgreSceneManager.h>    59 #include <OgreSceneNode.h>    67 #include <boost/format.hpp>    68 #include <boost/algorithm/string/replace.hpp>    69 #include <boost/algorithm/string/trim.hpp>    70 #include <boost/lexical_cast.hpp>    74 #include "ui_motion_planning_rviz_plugin_frame.h"    83   , text_to_display_(
NULL)
    84   , private_handle_(
"~")
    89   , int_marker_display_(
NULL)
    98       "Show Weight Limit", 
false, 
"Shows the weight limit at a particular pose for an end-effector", 
metrics_category_,
   102       new rviz::BoolProperty(
"Show Manipulability Index", 
false, 
"Shows the manipulability index for an end-effector",
   106       new rviz::BoolProperty(
"Show Manipulability", 
false, 
"Shows the manipulability for an end-effector",
   110                                                         "Shows the joint torques for a given configuration and payload",
   125       "Planning Group", 
"", 
"The name of the group of links to plan for (from the ones defined in the SRDF)",
   128                                                                              "the workspace allowed for planning",
   131       new rviz::BoolProperty(
"Query Start State", 
false, 
"Set a custom start state for the motion planning query",
   134       new rviz::BoolProperty(
"Query Goal State", 
true, 
"Shows the goal state for the motion planning query",
   138                               "Specifies scale of the interactive marker overlayed on the robot. 0 is auto scale.",
   143       new rviz::ColorProperty(
"Start State Color", QColor(0, 255, 0), 
"The highlight color for the start state",
   152       new rviz::ColorProperty(
"Goal State Color", QColor(250, 128, 0), 
"The highlight color for the goal state",
   162       new rviz::ColorProperty(
"Colliding Link Color", QColor(255, 0, 0), 
"The highlight color for colliding links",
   167                               "The highlight color for child links of joints that are outside bounds", 
plan_category_,
   207   std_msgs::ColorRGBA color;
   209   color.r = qcolor.redF();
   210   color.g = qcolor.greenF();
   211   color.b = qcolor.blueF();
   220   color.r = qcolor.redF();
   221   color.g = qcolor.greenF();
   222   color.b = qcolor.blueF();
   254     QShortcut* im_reset_shortcut =
   290     ROS_ERROR(
"Group [%s] not found in the robot model.", msg->data.c_str());
   314   BoolProperty::setName(name);
   332   QProgressBar* p = 
frame_->
ui_->background_job_progress;
   337     p->setValue(p->maximum());
   346       if (p->maximum() == 0)
   349         p->setValue(p->maximum() - 1);
   353       if (p->maximum() < n)
   356         p->setValue(p->maximum() - n);
   439                                          const Ogre::Vector3& pos, 
const Ogre::Quaternion& orient)
   442   std::stringstream ss;
   443   for (std::map<std::string, double>::const_iterator it = values.begin(); it != values.end(); ++it)
   444     ss << boost::format(
"%-10s %-4.2f") % it->first % it->second << std::endl;
   446   if (ss.str().empty())
   476   Ogre::Vector3 center(
frame_->
ui_->wcenter_x->value(), 
frame_->
ui_->wcenter_y->value(),
   487   const std::vector<robot_interaction::RobotInteraction::EndEffector>& eef =
   494   for (std::size_t i = 0; i < eef.size(); ++i)
   495     if (eef[i].parent_group == group)
   501                                                    const robot_state::RobotState& state, 
double payload)
   504   dynamics_solver::DynamicsSolverPtr ds;
   513     unsigned int saturated_joint;
   514     std::vector<double> joint_values;
   515     state.copyJointGroupPositions(ee.
parent_group, joint_values);
   516     if (ds->getMaxPayload(joint_values, max_payload, saturated_joint))
   518       metrics[
"max_payload"] = max_payload;
   519       metrics[
"saturated_joint"] = saturated_joint;
   521     std::vector<double> joint_torques;
   522     joint_torques.resize(joint_values.size());
   523     if (ds->getPayloadTorques(joint_values, payload, joint_torques))
   525       for (std::size_t i = 0; i < joint_torques.size(); ++i)
   527         std::stringstream stream;
   528         stream << 
"torque[" << i << 
"]";
   529         metrics[stream.str()] = joint_torques[i];
   539     double manipulability_index, manipulability;
   542       metrics[
"manipulability_index"] = manipulability_index;
   544       metrics[
"manipulability"] = manipulability;
   550 inline void copyItemIfExists(
const std::map<std::string, double>& source, std::map<std::string, double>& dest,
   551                              const std::string& key)
   553   std::map<std::string, double>::const_iterator it = source.find(key);
   554   if (it != source.end())
   555     dest[key] = it->second;
   564   static const Ogre::Quaternion orientation(1.0, 0.0, 0.0, 0.0);
   565   const std::vector<robot_interaction::RobotInteraction::EndEffector>& eef =
   572   for (std::size_t i = 0; i < eef.size(); ++i)
   574     Ogre::Vector3 position(0.0, 0.0, 0.0);
   575     std::map<std::string, double> text_table;
   576     const std::map<std::string, double>& metrics_table = 
computed_metrics_[std::make_pair(start, eef[i].parent_group)];
   579       copyItemIfExists(metrics_table, text_table, 
"max_payload");
   580       copyItemIfExists(metrics_table, text_table, 
"saturated_joint");
   583       copyItemIfExists(metrics_table, text_table, 
"manipulability_index");
   585       copyItemIfExists(metrics_table, text_table, 
"manipulability");
   588       std::size_t nj = 
getRobotModel()->getJointModelGroup(eef[i].parent_group)->getJointModelNames().size();
   589       for (
size_t j = 0; j < nj; ++j)
   591         std::stringstream stream;
   592         stream << 
"torque[" << j << 
"]";
   593         copyItemIfExists(metrics_table, text_table, stream.str());
   597     const robot_state::LinkModel* lm = 
NULL;
   598     const robot_model::JointModelGroup* jmg = 
getRobotModel()->getJointModelGroup(eef[i].parent_group);
   600       if (!jmg->getLinkModelNames().empty())
   601         lm = state->getLinkModel(jmg->getLinkModelNames().back());
   604       const Eigen::Vector3d& t = state->getGlobalLinkTransform(lm).translation();
   607       position[2] = t.z() + 0.2;  
   633       std::vector<std::string> collision_links;
   636       for (std::size_t i = 0; i < collision_links.size(); ++i)
   638       if (!collision_links.empty())
   644         for (collision_detection::CollisionResult::ContactMap::const_iterator it = pairs.begin(); it != pairs.end();
   654           std::vector<std::string> outside_bounds;
   655           const std::vector<const robot_model::JointModel*>& jmodels = jmg->getActiveJointModels();
   656           for (std::size_t i = 0; i < jmodels.size(); ++i)
   657             if (!state->satisfiesBounds(jmodels[i], jmodels[i]->getMaximumExtent() * 1e-2))
   659               outside_bounds.push_back(jmodels[i]->getChildLinkModel()->
getName());
   662           if (!outside_bounds.empty())
   665             addStatusText(
"Links descending from joints that are outside bounds in start state:");
   688     frame_->
ui_->status_text->setTextColor(color);
   694     frame_->
ui_->status_text->append(QString::fromStdString(text));
   699   for (std::size_t i = 0; i < text.size(); ++i)
   725                    "publishInteractiveMarkers");
   736                    "publishInteractiveMarkers");
   754       std::vector<std::string> collision_links;
   757       for (std::size_t i = 0; i < collision_links.size(); ++i)
   759       if (!collision_links.empty())
   765         for (collision_detection::CollisionResult::ContactMap::const_iterator it = pairs.begin(); it != pairs.end();
   776           const std::vector<const robot_state::JointModel*>& jmodels = jmg->getActiveJointModels();
   777           std::vector<std::string> outside_bounds;
   778           for (std::size_t i = 0; i < jmodels.size(); ++i)
   779             if (!state->satisfiesBounds(jmodels[i], jmodels[i]->getMaximumExtent() * 1e-2))
   781               outside_bounds.push_back(jmodels[i]->getChildLinkModel()->
getName());
   785           if (!outside_bounds.empty())
   788             addStatusText(
"Links descending from joints that are outside bounds in goal state:");
   809                    "publishInteractiveMarkers");
   843   std_msgs::ColorRGBA color;
   845   color.r = qcolor.redF();
   846   color.g = qcolor.greenF();
   847   color.b = qcolor.blueF();
   873   std_msgs::ColorRGBA color;
   875   color.r = qcolor.redF();
   876   color.g = qcolor.greenF();
   877   color.b = qcolor.blueF();
   910                                                         bool error_state_changed)
   915                    "publishInteractiveMarkers");
   922                                                        bool error_state_changed)
   927                    "publishInteractiveMarkers");
   976                                                       const robot_model::JointModelGroup* group,
   977                                                       const double* ik_solution)
 const   981     state->setJointGroupPositions(group, ik_solution);
  1000     for (std::map<std::string, LinkDisplayStatus>::const_iterator it = 
status_links_start_.begin();
  1008     for (std::map<std::string, LinkDisplayStatus>::const_iterator it = 
status_links_goal_.begin();
  1029     ROS_ERROR(
"Group [%s] not found in the robot model.", group.c_str());
  1055                    "publishInteractiveMarkers");
  1072   std::string v = 
"<" + state_name + 
">";
  1074   if (v == 
"<random>")
  1077       state.setToRandomPositions(jmg);
  1079   else if (v == 
"<current>")
  1083       state = ps->getCurrentState();
  1085   else if (v == 
"<same as goal>")
  1089   else if (v == 
"<same as start>")
  1097       state.setToDefaultValues(jmg, state_name);
  1106   std::vector<std::string> state_names;
  1107   state_names.push_back(
"random");
  1108   state_names.push_back(
"current");
  1109   state_names.push_back(
"same as start");
  1110   state_names.push_back(
"same as goal");
  1116   immh::EntryHandle menu_states =
  1117       mh->insert(is_start ? 
"Set start state to" : 
"Set goal state to", immh::FeedbackCallback());
  1118   for (std::size_t i = 0; i < state_names.size(); ++i)
  1121     if ((state_names[i] == 
"same as start" && is_start) || (state_names[i] == 
"same as goal" && !is_start))
  1123     mh->insert(menu_states, state_names[i],
  1147   robot_state::RobotStatePtr ks(
new robot_state::RobotState(
getPlanningSceneRO()->getCurrentState()));
  1171   for (std::size_t i = 0; i < groups.size(); ++i)
  1180   geometry_msgs::Vector3 gravity_vector;
  1181   gravity_vector.x = 0.0;
  1182   gravity_vector.y = 0.0;
  1183   gravity_vector.z = 9.81;
  1186   for (std::size_t i = 0; i < groups.size(); ++i)
  1187     if (
getRobotModel()->getJointModelGroup(groups[i])->isChain())
  1195   robot_state::RobotState src_copy = src;
  1198     const robot_model::JointModelGroup* jmg = dest.getJointModelGroup(*it);
  1201       std::vector<double> values_to_keep;
  1202       dest.copyJointGroupPositions(jmg, values_to_keep);
  1203       src_copy.setJointGroupPositions(jmg, values_to_keep);
  1255     frame_->parentWidget()->show();
  1277     frame_->parentWidget()->hide();
  1310     std::string host_param;
  1311     if (config.
mapGetString(
"MoveIt_Warehouse_Host", &host))
  1312       frame_->
ui_->database_host->setText(host);
  1313     else if (nh.
getParam(
"warehouse_host", host_param))
  1315       host = QString::fromStdString(host_param);
  1316       frame_->
ui_->database_host->setText(host);
  1319     if (config.
mapGetInt(
"MoveIt_Warehouse_Port", &port) || nh.
getParam(
"warehouse_port", port))
  1320       frame_->
ui_->database_port->setValue(port);
  1322     if (config.
mapGetFloat(
"MoveIt_Planning_Time", &d))
  1323       frame_->
ui_->planning_time->setValue(d);
  1325     if (config.
mapGetInt(
"MoveIt_Planning_Attempts", &attempts))
  1326       frame_->
ui_->planning_attempts->setValue(attempts);
  1327     if (config.
mapGetFloat(
"MoveIt_Goal_Tolerance", &d))
  1328       frame_->
ui_->goal_tolerance->setValue(d);
  1330     if (config.
mapGetBool(
"MoveIt_Use_Constraint_Aware_IK", &b))
  1331       frame_->
ui_->collision_aware_ik->setChecked(b);
  1332     if (config.
mapGetBool(
"MoveIt_Allow_Approximate_IK", &b))
  1333       frame_->
ui_->approximate_ik->setChecked(b);
  1334     if (config.
mapGetBool(
"MoveIt_Allow_External_Program", &b))
  1335       frame_->
ui_->allow_external_program->setChecked(b);
  1336     if (config.
mapGetBool(
"MoveIt_Allow_Replanning", &b))
  1337       frame_->
ui_->allow_replanning->setChecked(b);
  1338     if (config.
mapGetBool(
"MoveIt_Allow_Sensor_Positioning", &b))
  1339       frame_->
ui_->allow_looking->setChecked(b);
  1342     if (config.
mapGetFloat(
"Velocity_Scaling_Factor", &v))
  1343       frame_->
ui_->velocity_scaling_factor->setValue(v);
  1344     if (config.
mapGetFloat(
"Acceleration_Scaling_Factor", &v))
  1345       frame_->
ui_->acceleration_scaling_factor->setValue(v);
  1372       if (nh_.
getParam(
"default_workspace_bounds", val))
  1396     config.
mapSetValue(
"Acceleration_Scaling_Factor", 
frame_->
ui_->acceleration_scaling_factor->value());
  1399     config.
mapSetValue(
"MoveIt_Allow_Sensor_Positioning", 
frame_->
ui_->allow_looking->isChecked());
  1400     config.
mapSetValue(
"MoveIt_Allow_External_Program", 
frame_->
ui_->allow_external_program->isChecked());
  1401     config.
mapSetValue(
"MoveIt_Use_Constraint_Aware_IK", 
frame_->
ui_->collision_aware_ik->isChecked());
  1436   for (std::size_t i = 0; i < place_poses.size(); ++i)
  1440     Ogre::Vector3 center(place_poses[i].pose.position.x, place_poses[i].pose.position.y,
  1441                          place_poses[i].pose.position.z);
  1442     Ogre::Vector3 extents(0.02, 0.02, 0.02);
 void scheduleDrawQueryStartState(robot_interaction::RobotInteraction::InteractionHandler *handler, bool error_state_changed)
virtual QColor getColor() const 
virtual void changedAttachedBodyColor()
rviz::FloatProperty * query_marker_scale_property_
void showOnTop(bool show=true)
void toggleSelectPlanningGroupSubscription(bool enable)
rviz::FloatProperty * query_goal_alpha_property_
void changedQueryStartColor()
rviz::BoolProperty * show_joint_torques_property_
void setGroupColor(rviz::Robot *robot, const std::string &group_name, const QColor &color)
Ogre::ColourValue getOgreColor() const 
void updateStateExceptModified(robot_state::RobotState &dest, const robot_state::RobotState &src)
void resetInteractiveMarkers()
virtual void onRobotModelLoaded()
This is an event called by loadRobotModel() in the MainLoop; do not call directly. 
kinematics_metrics::KinematicsMetricsPtr kinematics_metrics_
std::shared_ptr< interactive_markers::MenuHandler > menu_handler_start_
void selectPlanningGroupCallback(const std_msgs::StringConstPtr &msg)
const std::string getMoveGroupNS() const 
virtual ~MotionPlanningDisplay()
RobotStateVisualizationPtr query_robot_start_
Handles drawing the robot at the start configuration. 
Update the links of an rviz::Robot using a robot_state::RobotState. 
void motionPanelVisibilityChange(bool enable)
virtual void onInitialize()
virtual void onSceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual void fixedFrameChanged()
DisplayContext * context_
void backgroundJobUpdate(moveit::tools::BackgroundProcessing::JobEvent event, const std::string &jobname)
virtual void clearOptions()
virtual void fixedFrameChanged()
virtual void load(const rviz::Config &config)
virtual bool setValue(const QVariant &new_value)
virtual QIcon getIcon() const 
rviz::ColorProperty * query_colliding_link_color_property_
void clearJobs()
remove all queued jobs 
ros::NodeHandle update_nh_
void changedMetricsSetPayload()
void setName(const QString &name)
void changedQueryStartAlpha()
MotionPlanningFrame * frame_
virtual void onInitialize()
void updateExternalCommunication()
virtual float getFloat() const 
rviz::BoolProperty * show_workspace_property_
bool mapGetFloat(const QString &key, float *value_out) const 
virtual QWidget * getParentWindow()=0
void drawQueryStartState()
void computeMetricsInternal(std::map< std::string, double > &metrics, const robot_interaction::RobotInteraction::EndEffector &eef, const robot_state::RobotState &state, double payload)
robot_state::RobotStateConstPtr getQueryStartState() const 
std::map< std::string, LinkDisplayStatus > status_links_start_
void recomputeQueryGoalStateMetrics()
void changedShowManipulabilityIndex()
void changePlanningGroup()
void setCharacterHeight(Ogre::Real height)
rviz::ColorProperty * query_start_color_property_
void changePlanningGroup(const std::string &group)
rviz::BoolProperty * query_goal_state_property_
void setQueryStartState(const robot_state::RobotState &start)
rviz::Property * metrics_category_
ros::NodeHandle private_handle_
void addOptionStd(const std::string &option)
void updateQueryStartState()
void changedShowManipulability()
void drawQueryGoalState()
virtual void onRobotModelLoaded()
This is an event called by loadRobotModel() in the MainLoop; do not call directly. 
virtual void updateInternal(float wall_dt, float ros_dt)
void displayMetrics(bool start)
rviz::Display * int_marker_display_
void sceneUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type)
virtual void onSceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type)
rviz::FloatProperty * metrics_set_payload_property_
std::shared_ptr< interactive_markers::MenuHandler > menu_handler_goal_
bool mapGetString(const QString &key, QString *value_out) const 
void setQueryGoalState(const robot_state::RobotState &goal)
std::vector< std::shared_ptr< rviz::Shape > > place_locations_display_
std::string getStdString()
void mapSetValue(const QString &key, QVariant value)
std::map< std::string, bool > position_only_ik_
Some groups use position only ik, calls to the metrics have to be modified appropriately. 
bool return_approximate_solution
robot_interaction::RobotInteractionPtr robot_interaction_
virtual bool getBool() const 
std::map< std::pair< std::string, std::string >, std::vector< Contact > > ContactMap
void clearPlaceLocationsDisplay()
std::unique_ptr< rviz::Shape > workspace_box_
virtual void update(float wall_dt, float ros_dt)
void changedQueryGoalState()
TrajectoryVisualizationPtr trajectory_visual_
virtual Property * subProp(const QString &sub_name)
rviz::PanelDockWidget * frame_dock_
void addBackgroundJob(const boost::function< void()> &job, const std::string &name)
bool text_display_for_start_
indicates whether the text display is for the start state or not 
void displayTable(const std::map< std::string, double > &values, const Ogre::ColourValue &color, const Ogre::Vector3 &pos, const Ogre::Quaternion &orient)
virtual void update(float wall_dt, float ros_dt)
virtual PanelDockWidget * addPane(const QString &name, QWidget *pane, Qt::DockWidgetArea area=Qt::LeftDockWidgetArea, bool floating=true)=0
rviz::ColorProperty * query_goal_color_property_
robot_interaction::RobotInteraction::InteractionHandlerPtr query_start_state_
void visualizePlaceLocations(const std::vector< geometry_msgs::PoseStamped > &place_poses)
virtual void save(rviz::Config config) const 
void resetStatusTextColor()
void recomputeQueryStartStateMetrics()
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
rviz::EditableEnumProperty * planning_group_property_
std::map< std::string, dynamics_solver::DynamicsSolverPtr > dynamics_solver_
void changedQueryGoalColor()
std::string getCurrentPlanningGroup() const 
void setCaption(const Ogre::String &caption)
rviz::FloatProperty * query_start_alpha_property_
rviz::BoolProperty * show_manipulability_property_
Config mapMakeChild(const QString &key)
bool mapGetBool(const QString &key, bool *value_out) const 
bool isIKSolutionCollisionFree(robot_state::RobotState *state, const robot_state::JointModelGroup *group, const double *ik_solution) const 
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
rviz::MovableText * text_to_display_
void changedQueryGoalAlpha()
Ogre::SceneNode * planning_scene_node_
displays planning scene with everything in it 
void setTextAlignment(const HorizontalAlignment &horizontalAlignment, const VerticalAlignment &verticalAlignment)
rviz::BoolProperty * query_start_state_property_
void setFixedFrame(const QString &fixed_frame)
void updateBackgroundJobProgressBar()
robot_state::RobotStateConstPtr getQueryGoalState() const 
bool mapGetInt(const QString &key, int *value_out) const 
void changedQueryCollidingLinkColor()
void changedAttachedBodyColor() override
boost::mutex update_metrics_lock_
Ui::MotionPlanningUI * ui_
virtual void load(const rviz::Config &config)
std::set< std::string > modified_groups_
void setStatusTextColor(const QColor &color)
void addMainLoopJob(const boost::function< void()> &job)
queue the execution of this function for the next time the main update() loop gets called ...
void unsetAllColors(rviz::Robot *robot)
virtual Ogre::SceneManager * getSceneManager() const =0
void populateMenuHandler(std::shared_ptr< interactive_markers::MenuHandler > &mh)
void setQueryStateHelper(bool use_start_state, const std::string &v)
virtual void queueRender()=0
ros::NodeHandle node_handle_
const robot_model::RobotModelConstPtr & getRobotModel() const 
void changedQueryStartState()
RobotStateVisualizationPtr query_robot_goal_
Handles drawing the robot at the goal configuration. 
void setEnabled(bool enabled)
void setColor(const Ogre::ColourValue &color)
ros::Subscriber planning_group_sub_
rviz::ColorProperty * attached_body_color_property_
rviz::Property * path_category_
rviz::BoolProperty * show_manipulability_index_property_
void changedMetricsTextHeight()
bool getParam(const std::string &key, std::string &s) const 
void addStatusText(const std::string &text)
virtual DisplayFactory * getDisplayFactory() const =0
moveit::tools::BackgroundProcessing background_process_
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
rviz::BoolProperty * compute_weight_limit_property_
void changedQueryJointViolationColor()
void initialize(DisplayContext *context)
virtual void update(float wall_dt, float ros_dt)
virtual void updateInternal(float wall_dt, float ros_dt)
virtual Display * make(const QString &class_id, QString *error_return=NULL)
Config mapGetChild(const QString &key) const 
robot_interaction::RobotInteraction::InteractionHandlerPtr query_goal_state_
void changedQueryMarkerScale()
virtual void save(rviz::Config config) const 
void scheduleDrawQueryGoalState(robot_interaction::RobotInteraction::InteractionHandler *handler, bool error_state_changed)
void updateSceneMarkers(float wall_dt, float ros_dt)
void setLinkColor(const std::string &link_name, const QColor &color)
void computeMetrics(bool start, const std::string &group, double payload)
void updateQueryGoalState()
bool setStdString(const std::string &std_str)
void changedPlanningGroup()
void publishInteractiveMarkers(bool pose_update)
void changedShowJointTorques()
void changedShowWeightLimit()
void renderWorkspaceBox()
rviz::FloatProperty * metrics_text_height_property_
virtual QString getName() const 
std::map< std::pair< bool, std::string >, std::map< std::string, double > > computed_metrics_
Ogre::SceneNode * text_display_scene_node_
displays texts 
virtual WindowManagerInterface * getWindowManager() const =0
void useApproximateIK(bool flag)
std::map< std::string, LinkDisplayStatus > status_links_goal_
rviz::ColorProperty * query_outside_joint_limits_link_color_property_
planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO() const 
get read-only access to planning scene 
rviz::Property * plan_category_