43 #include <interactive_markers/tools.hpp> 
   45 #include <rviz_common/display_context.hpp> 
   46 #include <rviz_common/frame_manager_iface.hpp> 
   47 #include <rviz_common/window_manager_interface.hpp> 
   49 #include <tf2_eigen/tf2_eigen.hpp> 
   50 #include <geometric_shapes/shape_operations.h> 
   52 #include <QMessageBox> 
   53 #include <QInputDialog> 
   54 #include <QFileDialog> 
   56 #include "ui_motion_planning_rviz_plugin_frame.h" 
   62   QString status_text = 
"\nIt has the subframes '";
 
   63   for (
const auto& subframe : subframes)
 
   65     status_text += QString::fromStdString(subframe.first) + 
"', '";
 
   75 static const rclcpp::Logger 
LOGGER = rclcpp::get_logger(
"moveit_ros_visualization.motion_planning_frame_objects");
 
   77 void MotionPlanningFrame::shapesComboBoxChanged(
const QString& )
 
   79   switch (
ui_->shapes_combo_box->currentData().toInt())  
 
   82       ui_->shape_size_x_spin_box->setEnabled(
true);
 
   83       ui_->shape_size_y_spin_box->setEnabled(
true);
 
   84       ui_->shape_size_z_spin_box->setEnabled(
true);
 
   87       ui_->shape_size_x_spin_box->setEnabled(
true);
 
   88       ui_->shape_size_y_spin_box->setEnabled(
false);
 
   89       ui_->shape_size_z_spin_box->setEnabled(
false);
 
   91     case shapes::CYLINDER:
 
   93       ui_->shape_size_x_spin_box->setEnabled(
true);
 
   94       ui_->shape_size_y_spin_box->setEnabled(
false);
 
   95       ui_->shape_size_z_spin_box->setEnabled(
true);
 
   98       ui_->shape_size_x_spin_box->setEnabled(
false);
 
   99       ui_->shape_size_y_spin_box->setEnabled(
false);
 
  100       ui_->shape_size_z_spin_box->setEnabled(
false);
 
  107 void MotionPlanningFrame::setLocalSceneEdited(
bool dirty)
 
  109   ui_->publish_current_scene_button->setEnabled(dirty);
 
  112 bool MotionPlanningFrame::isLocalSceneDirty()
 const 
  114   return ui_->publish_current_scene_button->isEnabled();
 
  117 void MotionPlanningFrame::publishScene()
 
  122     moveit_msgs::msg::PlanningScene msg;
 
  123     ps->getPlanningSceneMsg(msg);
 
  124     planning_scene_publisher_->publish(msg);
 
  125     setLocalSceneEdited(
false);
 
  129 void MotionPlanningFrame::publishSceneIfNeeded()
 
  131   if (isLocalSceneDirty() &&
 
  132       QMessageBox::question(
this, 
"Update PlanningScene",
 
  133                             "You have local changes to your planning scene.\n" 
  134                             "Publish them to the move_group node?",
 
  135                             QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes) == QMessageBox::Yes)
 
  139 void MotionPlanningFrame::clearScene()
 
  144     ps->getWorldNonConst()->clearObjects();
 
  145     ps->getCurrentStateNonConst().clearAttachedBodies();
 
  146     moveit_msgs::msg::PlanningScene msg;
 
  147     ps->getPlanningSceneMsg(msg);
 
  148     planning_scene_publisher_->publish(msg);
 
  149     setLocalSceneEdited(
false);
 
  155 void MotionPlanningFrame::sceneScaleChanged(
int value)
 
  157   const double scaling_factor = (double)value / 100.0;  
 
  163       if (ps->getWorld()->hasObject(scaled_object_->id_))
 
  165         ps->getWorldNonConst()->removeObject(scaled_object_->id_);
 
  166         for (std::size_t i = 0; i < scaled_object_->shapes_.size(); ++i)
 
  168           shapes::Shape* s = scaled_object_->shapes_[i]->clone();
 
  169           s->scale(scaling_factor);
 
  171           Eigen::Isometry3d scaled_shape_pose = scaled_object_->shape_poses_[i];
 
  172           scaled_shape_pose.translation() *= scaling_factor;
 
  174           ps->getWorldNonConst()->addToObject(scaled_object_->id_, scaled_object_->pose_, shapes::ShapeConstPtr(s),
 
  178         for (
auto& subframe_pair : scaled_subframes)
 
  179           subframe_pair.second.translation() *= scaling_factor;
 
  181         ps->getWorldNonConst()->setSubframesOfObject(scaled_object_->id_, scaled_subframes);
 
  182         setLocalSceneEdited();
 
  183         scene_marker_->processMessage(createObjectMarkerMsg(ps->getWorld()->getObject(scaled_object_->id_)));
 
  187         scaled_object_.reset();
 
  190       scaled_object_.reset();
 
  194 void MotionPlanningFrame::sceneScaleStartChange()
 
  196   QList<QListWidgetItem*> sel = 
ui_->collision_objects_list->selectedItems();
 
  204       scaled_object_ = ps->getWorld()->getObject(sel[0]->
text().toStdString());
 
  205       scaled_object_subframes_ = scaled_object_->subframe_poses_;
 
  206       scaled_object_shape_poses_ = scaled_object_->shape_poses_;
 
  211 void MotionPlanningFrame::sceneScaleEndChange()
 
  213   scaled_object_.reset();
 
  214   ui_->scene_scale->setSliderPosition(100);
 
  217 void MotionPlanningFrame::removeSceneObject()
 
  219   QList<QListWidgetItem*> sel = 
ui_->collision_objects_list->selectedItems();
 
  225     for (
int i = 0; i < sel.count(); ++i)
 
  226       if (sel[i]->checkState() == Qt::Unchecked)
 
  227         ps->getWorldNonConst()->removeObject(sel[i]->
text().toStdString());
 
  229         ps->getCurrentStateNonConst().clearAttachedBody(sel[i]->
text().toStdString());
 
  231     setLocalSceneEdited();
 
  239   QString status_text = 
"'" + QString::fromStdString(obj->id_) + 
"' is a collision object with ";
 
  240   if (obj->shapes_.empty())
 
  241     status_text += 
"no geometry";
 
  244     std::vector<QString> shape_names;
 
  245     for (
const shapes::ShapeConstPtr& shape : obj->shapes_)
 
  246       shape_names.push_back(QString::fromStdString(shapes::shapeStringName(shape.get())));
 
  247     if (shape_names.size() == 1)
 
  248       status_text += 
"one " + shape_names[0];
 
  251       status_text += QString::fromStdString(std::to_string(shape_names.size())) + 
" shapes:";
 
  252       for (
const QString& shape_name : shape_names)
 
  253         status_text += 
" " + shape_name;
 
  257   if (!obj->subframe_poses_.empty())
 
  259     status_text += subframe_poses_to_qstring(obj->subframe_poses_);
 
  266   QString status_text = 
"'" + QString::fromStdString(attached_body->
getName()) + 
"' is attached to '" +
 
  270     status_text += subframe_poses_to_qstring(attached_body->
getSubframes());
 
  275 void MotionPlanningFrame::selectedCollisionObjectChanged()
 
  277   QList<QListWidgetItem*> sel = 
ui_->collision_objects_list->selectedItems();
 
  280     bool old_state = 
ui_->object_x->blockSignals(
true);
 
  281     ui_->object_x->setValue(0.0);
 
  282     ui_->object_x->blockSignals(old_state);
 
  284     old_state = 
ui_->object_y->blockSignals(
true);
 
  285     ui_->object_y->setValue(0.0);
 
  286     ui_->object_y->blockSignals(old_state);
 
  288     old_state = 
ui_->object_z->blockSignals(
true);
 
  289     ui_->object_z->setValue(0.0);
 
  290     ui_->object_z->blockSignals(old_state);
 
  292     old_state = 
ui_->object_rx->blockSignals(
true);
 
  293     ui_->object_rx->setValue(0.0);
 
  294     ui_->object_rx->blockSignals(old_state);
 
  296     old_state = 
ui_->object_ry->blockSignals(
true);
 
  297     ui_->object_ry->setValue(0.0);
 
  298     ui_->object_ry->blockSignals(old_state);
 
  300     old_state = 
ui_->object_rz->blockSignals(
true);
 
  301     ui_->object_rz->setValue(0.0);
 
  302     ui_->object_rz->blockSignals(old_state);
 
  304     ui_->object_status->setText(
"");
 
  306     ui_->pose_scale_group_box->setEnabled(
false);
 
  311     if (sel[0]->checkState() == Qt::Unchecked)
 
  313       ui_->pose_scale_group_box->setEnabled(
true);
 
  314       bool update_scene_marker = 
false;
 
  315       Eigen::Isometry3d obj_pose;
 
  319             ps->getWorld()->getObject(sel[0]->
text().toStdString());
 
  322           ui_->object_status->setText(decideStatusText(obj));
 
  324           if (obj->shapes_.size() == 1)
 
  326             obj_pose = obj->pose_;  
 
  328             update_scene_marker = 
true;  
 
  330             bool old_state = 
ui_->object_x->blockSignals(
true);
 
  331             ui_->object_x->setValue(obj_pose.translation()[0]);
 
  332             ui_->object_x->blockSignals(old_state);
 
  334             old_state = 
ui_->object_y->blockSignals(
true);
 
  335             ui_->object_y->setValue(obj_pose.translation()[1]);
 
  336             ui_->object_y->blockSignals(old_state);
 
  338             old_state = 
ui_->object_z->blockSignals(
true);
 
  339             ui_->object_z->setValue(obj_pose.translation()[2]);
 
  340             ui_->object_z->blockSignals(old_state);
 
  342             old_state = 
ui_->object_rx->blockSignals(
true);
 
  343             ui_->object_rx->setValue(xyz[0]);
 
  344             ui_->object_rx->blockSignals(old_state);
 
  346             old_state = 
ui_->object_ry->blockSignals(
true);
 
  347             ui_->object_ry->setValue(xyz[1]);
 
  348             ui_->object_ry->blockSignals(old_state);
 
  350             old_state = 
ui_->object_rz->blockSignals(
true);
 
  351             ui_->object_rz->setValue(xyz[2]);
 
  352             ui_->object_rz->blockSignals(old_state);
 
  356           ui_->object_status->setText(
"ERROR: '" + sel[0]->
text() + 
"' should be a collision object but it is not");
 
  358       if (update_scene_marker && 
ui_->tabWidget->tabText(
ui_->tabWidget->currentIndex()).toStdString() == TAB_OBJECTS)
 
  360         createSceneInteractiveMarker();
 
  365       ui_->pose_scale_group_box->setEnabled(
false);
 
  370           ps->getCurrentState().getAttachedBody(sel[0]->
text().toStdString());
 
  372         ui_->object_status->setText(decideStatusText(attached_body));
 
  374         ui_->object_status->setText(
"ERROR: '" + sel[0]->
text() + 
"' should be an attached object but it is not");
 
  379 void MotionPlanningFrame::objectPoseValueChanged(
double )
 
  381   updateCollisionObjectPose(
true);
 
  384 void MotionPlanningFrame::updateCollisionObjectPose(
bool update_marker_position)
 
  386   QList<QListWidgetItem*> sel = 
ui_->collision_objects_list->selectedItems();
 
  396       p.translation()[0] = 
ui_->object_x->value();
 
  397       p.translation()[1] = 
ui_->object_y->value();
 
  398       p.translation()[2] = 
ui_->object_z->value();
 
  400       p = Eigen::Translation3d(
p.translation()) *
 
  401           (Eigen::AngleAxisd(
ui_->object_rx->value(), Eigen::Vector3d::UnitX()) *
 
  402            Eigen::AngleAxisd(
ui_->object_ry->value(), Eigen::Vector3d::UnitY()) *
 
  403            Eigen::AngleAxisd(
ui_->object_rz->value(), Eigen::Vector3d::UnitZ()));
 
  405       ps->getWorldNonConst()->setObjectPose(obj->id_, 
p);
 
  407       setLocalSceneEdited();
 
  413         Eigen::Quaterniond eq(
p.linear());
 
  414         scene_marker_->setPose(Ogre::Vector3(
ui_->object_x->value(), 
ui_->object_y->value(), 
ui_->object_z->value()),
 
  415                                Ogre::Quaternion(eq.w(), eq.x(), eq.y(), eq.z()), 
"");
 
  421 void MotionPlanningFrame::collisionObjectChanged(QListWidgetItem* item)
 
  426     if (known_collision_objects_[item->type()].first != item->text().toStdString())
 
  427       renameCollisionObject(item);
 
  430       bool checked = item->checkState() == Qt::Checked;
 
  431       if (known_collision_objects_[item->type()].second != checked)
 
  432         attachDetachCollisionObject(item);
 
  438 void MotionPlanningFrame::imProcessFeedback(visualization_msgs::msg::InteractiveMarkerFeedback& feedback)
 
  442     RCLCPP_ERROR_STREAM(LOGGER,
 
  443                         "Frame `" << feedback.header.frame_id << 
"` unknown doesn't exists in the planning scene");
 
  445   Eigen::Isometry3d fixed_frame_t_scene_marker;
 
  446   tf2::fromMsg(feedback.pose, fixed_frame_t_scene_marker);
 
  447   Eigen::Isometry3d model_frame_t_scene_marker =
 
  450   bool old_state = 
ui_->object_x->blockSignals(
true);
 
  451   ui_->object_x->setValue(model_frame_t_scene_marker.translation().x());
 
  452   ui_->object_x->blockSignals(old_state);
 
  454   old_state = 
ui_->object_y->blockSignals(
true);
 
  455   ui_->object_y->setValue(model_frame_t_scene_marker.translation().y());
 
  456   ui_->object_y->blockSignals(old_state);
 
  458   old_state = 
ui_->object_z->blockSignals(
true);
 
  459   ui_->object_z->setValue(model_frame_t_scene_marker.translation().z());
 
  460   ui_->object_z->blockSignals(old_state);
 
  462   Eigen::Vector3d xyz = model_frame_t_scene_marker.linear().eulerAngles(0, 1, 2);
 
  464   old_state = 
ui_->object_rx->blockSignals(
true);
 
  465   ui_->object_rx->setValue(xyz[0]);
 
  466   ui_->object_rx->blockSignals(old_state);
 
  468   old_state = 
ui_->object_ry->blockSignals(
true);
 
  469   ui_->object_ry->setValue(xyz[1]);
 
  470   ui_->object_ry->blockSignals(old_state);
 
  472   old_state = 
ui_->object_rz->blockSignals(
true);
 
  473   ui_->object_rz->setValue(xyz[2]);
 
  474   ui_->object_rz->blockSignals(old_state);
 
  476   updateCollisionObjectPose(
false);
 
  479 void MotionPlanningFrame::copySelectedCollisionObject()
 
  481   QList<QListWidgetItem*> sel = 
ui_->collision_objects_list->selectedItems();
 
  489   for (
const QListWidgetItem* item : sel)
 
  491     std::string 
name = item->text().toStdString();
 
  497     name.insert(0, 
"Copy of ");
 
  498     if (ps->getWorld()->hasObject(
name))
 
  502       while (ps->getWorld()->hasObject(
name + std::to_string(n)))
 
  504       name += std::to_string(n);
 
  506     ps->getWorldNonConst()->addToObject(
name, obj->shapes_, obj->shape_poses_);
 
  507     RCLCPP_DEBUG(LOGGER, 
"Copied collision object to '%s'", 
name.c_str());
 
  509   setLocalSceneEdited();
 
  513 void MotionPlanningFrame::computeSaveSceneButtonClicked()
 
  517     moveit_msgs::msg::PlanningScene msg;
 
  524     catch (std::exception& ex)
 
  526       RCLCPP_ERROR(LOGGER, 
"%s", ex.what());
 
  533 void MotionPlanningFrame::computeSaveQueryButtonClicked(
const std::string& 
scene, 
const std::string& query_name)
 
  541       if (!query_name.empty())
 
  545     catch (std::exception& ex)
 
  547       RCLCPP_ERROR(LOGGER, 
"%s", ex.what());
 
  554 void MotionPlanningFrame::computeDeleteSceneButtonClicked()
 
  558     QList<QTreeWidgetItem*> sel = 
ui_->planning_scene_tree->selectedItems();
 
  561       QTreeWidgetItem* s = sel.front();
 
  564         std::string 
scene = s->text(0).toStdString();
 
  569         catch (std::exception& ex)
 
  571           RCLCPP_ERROR(LOGGER, 
"%s", ex.what());
 
  577         std::string 
scene = s->parent()->text(0).toStdString();
 
  582         catch (std::exception& ex)
 
  584           RCLCPP_ERROR(LOGGER, 
"%s", ex.what());
 
  592 void MotionPlanningFrame::computeDeleteQueryButtonClicked()
 
  596     QList<QTreeWidgetItem*> sel = 
ui_->planning_scene_tree->selectedItems();
 
  599       QTreeWidgetItem* s = sel.front();
 
  602         std::string 
scene = s->parent()->text(0).toStdString();
 
  603         std::string query_name = s->text(0).toStdString();
 
  608         catch (std::exception& ex)
 
  610           RCLCPP_ERROR(LOGGER, 
"%s", ex.what());
 
  618 void MotionPlanningFrame::computeDeleteQueryButtonClickedHelper(QTreeWidgetItem* s)
 
  620   ui_->planning_scene_tree->setUpdatesEnabled(
false);
 
  621   s->parent()->removeChild(s);
 
  622   ui_->planning_scene_tree->setUpdatesEnabled(
true);
 
  625 void MotionPlanningFrame::checkPlanningSceneTreeEnabledButtons()
 
  627   QList<QTreeWidgetItem*> sel = 
ui_->planning_scene_tree->selectedItems();
 
  630     ui_->load_scene_button->setEnabled(
false);
 
  631     ui_->load_query_button->setEnabled(
false);
 
  632     ui_->save_query_button->setEnabled(
false);
 
  633     ui_->delete_scene_button->setEnabled(
false);
 
  637     ui_->save_query_button->setEnabled(
true);
 
  639     QTreeWidgetItem* s = sel.front();
 
  644       ui_->load_scene_button->setEnabled(
true);
 
  645       ui_->load_query_button->setEnabled(
false);
 
  646       ui_->delete_scene_button->setEnabled(
true);
 
  647       ui_->delete_query_button->setEnabled(
false);
 
  648       ui_->save_query_button->setEnabled(
true);
 
  653       ui_->load_scene_button->setEnabled(
false);
 
  654       ui_->load_query_button->setEnabled(
true);
 
  655       ui_->delete_scene_button->setEnabled(
false);
 
  656       ui_->delete_query_button->setEnabled(
true);
 
  661 void MotionPlanningFrame::computeLoadSceneButtonClicked()
 
  665     QList<QTreeWidgetItem*> sel = 
ui_->planning_scene_tree->selectedItems();
 
  668       QTreeWidgetItem* s = sel.front();
 
  671         std::string 
scene = s->text(0).toStdString();
 
  672         RCLCPP_DEBUG(LOGGER, 
"Attempting to load scene '%s'", 
scene.c_str());
 
  680         catch (std::exception& ex)
 
  682           RCLCPP_ERROR(LOGGER, 
"%s", ex.what());
 
  687           RCLCPP_INFO(LOGGER, 
"Loaded scene '%s'", 
scene.c_str());
 
  693                           "Scene '%s' was saved for robot '%s' but we are using robot '%s'. Using scene geometry only",
 
  694                           scene.c_str(), scene_m->robot_model_name.c_str(),
 
  696               planning_scene_world_publisher_->publish(scene_m->world);
 
  698               moveit_msgs::msg::PlanningScene diff;
 
  700               diff.name = scene_m->name;
 
  701               planning_scene_publisher_->publish(diff);
 
  704               planning_scene_publisher_->publish(
static_cast<const moveit_msgs::msg::PlanningScene&
>(*scene_m));
 
  707             planning_scene_publisher_->publish(
static_cast<const moveit_msgs::msg::PlanningScene&
>(*scene_m));
 
  710           RCLCPP_WARN(LOGGER, 
"Failed to load scene '%s'. Has the message format changed since the scene was saved?",
 
  717 void MotionPlanningFrame::computeLoadQueryButtonClicked()
 
  721     QList<QTreeWidgetItem*> sel = 
ui_->planning_scene_tree->selectedItems();
 
  724       QTreeWidgetItem* s = sel.front();
 
  727         std::string 
scene = s->parent()->text(0).toStdString();
 
  728         std::string query_name = s->text(0).toStdString();
 
  736         catch (std::exception& ex)
 
  738           RCLCPP_ERROR(LOGGER, 
"%s", ex.what());
 
  743           moveit::core::RobotStatePtr start_state(
 
  746                                                   mp->start_state, *start_state);
 
  750           for (
const moveit_msgs::msg::Constraints& goal_constraint : mp->goal_constraints)
 
  751             if (!goal_constraint.joint_constraints.empty())
 
  753               std::map<std::string, double> vals;
 
  754               for (
const moveit_msgs::msg::JointConstraint& joint_constraint : goal_constraint.joint_constraints)
 
  755                 vals[joint_constraint.joint_name] = joint_constraint.position;
 
  756               goal_state->setVariablePositions(vals);
 
  763                        "Failed to load planning query '%s'. Has the message format changed since the query was saved?",
 
  770 visualization_msgs::msg::InteractiveMarker
 
  775   shapes::computeShapeBoundingSphere(obj->shapes_[0].get(), center, scale);
 
  776   geometry_msgs::msg::PoseStamped shape_pose = tf2::toMsg(tf2::Stamped<Eigen::Isometry3d>(
 
  782   scale = (scale + center.cwiseAbs().maxCoeff()) * 2.0 * 1.2;  
 
  785   visualization_msgs::msg::InteractiveMarker imarker =
 
  787   imarker.description = obj->id_;
 
  788   interactive_markers::autoComplete(imarker);
 
  792 void MotionPlanningFrame::createSceneInteractiveMarker()
 
  794   QList<QListWidgetItem*> sel = 
ui_->collision_objects_list->selectedItems();
 
  803       ps->getWorld()->getObject(sel[0]->
text().toStdString());
 
  804   if (obj && obj->shapes_.size() == 1)
 
  806     scene_marker_ = std::make_shared<rviz_default_plugins::displays::InteractiveMarker>(
 
  812     connect(
scene_marker_.get(), SIGNAL(userFeedback(visualization_msgs::msg::InteractiveMarkerFeedback&)), 
this,
 
  813             SLOT(imProcessFeedback(visualization_msgs::msg::InteractiveMarkerFeedback&)));
 
  821 void MotionPlanningFrame::renameCollisionObject(QListWidgetItem* item)
 
  823   long unsigned int version = known_collision_objects_version_;
 
  824   if (item->text().isEmpty())
 
  826     QMessageBox::warning(
this, 
"Invalid object name", 
"Cannot set an empty object name.");
 
  827     if (
version == known_collision_objects_version_)
 
  828       item->setText(QString::fromStdString(known_collision_objects_[item->type()].first));
 
  832   std::string item_text = item->text().toStdString();
 
  838     QMessageBox::warning(
this, 
"Duplicate object name",
 
  839                          QString(
"The name '")
 
  841                              .append(
"' already exists. Not renaming object ")
 
  842                              .append((known_collision_objects_[item->type()].first.c_str())));
 
  843     if (
version == known_collision_objects_version_)
 
  844       item->setText(QString::fromStdString(known_collision_objects_[item->type()].first));
 
  848   if (item->checkState() == Qt::Unchecked)
 
  852         ps->getWorld()->getObject(known_collision_objects_[item->type()].first);
 
  855       known_collision_objects_[item->type()].first = item_text;
 
  856       ps->getWorldNonConst()->removeObject(obj->id_);
 
  857       ps->getWorldNonConst()->addToObject(known_collision_objects_[item->type()].first, obj->pose_, obj->shapes_,
 
  859       ps->getWorldNonConst()->setSubframesOfObject(obj->id_, obj->subframe_poses_);
 
  875       known_collision_objects_[item->type()].first = item_text;
 
  876       auto new_ab = std::make_unique<moveit::core::AttachedBody>(
 
  883   setLocalSceneEdited();
 
  886 void MotionPlanningFrame::attachDetachCollisionObject(QListWidgetItem* item)
 
  888   long unsigned int version = known_collision_objects_version_;
 
  889   bool checked = item->checkState() == Qt::Checked;
 
  890   std::pair<std::string, bool> data = known_collision_objects_[item->type()];
 
  891   moveit_msgs::msg::AttachedCollisionObject aco;
 
  897     for (
const std::string& link : links_std)
 
  898       links.append(QString::fromStdString(link));
 
  901         QInputDialog::getItem(
this, tr(
"Select Link Name"), tr(
"Choose the link to attach to:"), links, 0, 
false, &ok);
 
  904       if (
version == known_collision_objects_version_)
 
  905         item->setCheckState(Qt::Unchecked);
 
  908     aco.link_name = response.toStdString();
 
  909     aco.object.id = data.first;
 
  910     aco.object.operation = moveit_msgs::msg::CollisionObject::ADD;
 
  919       aco.object.id = attached_body->
getName();
 
  920       aco.object.operation = moveit_msgs::msg::CollisionObject::REMOVE;
 
  928     for (std::pair<std::string, bool>& known_collision_object : known_collision_objects_)
 
  929       if (known_collision_object.first == data.first)
 
  931         known_collision_object.second = checked;
 
  934     ps->processAttachedCollisionObjectMsg(aco);
 
  935     rs = ps->getCurrentState();
 
  938   selectedCollisionObjectChanged();
 
  939   setLocalSceneEdited();
 
  944 void MotionPlanningFrame::populateCollisionObjectsList()
 
  946   ui_->collision_objects_list->setUpdatesEnabled(
false);
 
  947   bool old_state = 
ui_->collision_objects_list->blockSignals(
true);
 
  948   bool octomap_in_scene = 
false;
 
  951     QList<QListWidgetItem*> sel = 
ui_->collision_objects_list->selectedItems();
 
  952     std::set<std::string> to_select;
 
  953     for (QListWidgetItem* item : sel)
 
  954       to_select.insert(item->text().toStdString());
 
  955     ui_->collision_objects_list->clear();
 
  956     known_collision_objects_.clear();
 
  957     known_collision_objects_version_++;
 
  962       const std::vector<std::string>& collision_object_names = ps->getWorld()->getObjectIds();
 
  963       for (std::size_t i = 0; i < collision_object_names.size(); ++i)
 
  967           octomap_in_scene = 
true;
 
  971         QListWidgetItem* item = 
new QListWidgetItem(QString::fromStdString(collision_object_names[i]),
 
  972                                                     ui_->collision_objects_list, 
static_cast<int>(i));
 
  973         item->setFlags(item->flags() | Qt::ItemIsEditable);
 
  974         item->setToolTip(item->text());
 
  975         item->setCheckState(Qt::Unchecked);
 
  976         if (to_select.find(collision_object_names[i]) != to_select.end())
 
  977           item->setSelected(
true);
 
  978         ui_->collision_objects_list->addItem(item);
 
  979         known_collision_objects_.push_back(std::make_pair(collision_object_names[i], 
false));
 
  983       std::vector<const moveit::core::AttachedBody*> attached_bodies;
 
  985       for (std::size_t i = 0; i < attached_bodies.size(); ++i)
 
  987         QListWidgetItem* item =
 
  988             new QListWidgetItem(QString::fromStdString(attached_bodies[i]->getName()), 
ui_->collision_objects_list,
 
  989                                 static_cast<int>(i + collision_object_names.size()));
 
  990         item->setFlags(item->flags() | Qt::ItemIsEditable);
 
  991         item->setToolTip(item->text());
 
  992         item->setCheckState(Qt::Checked);
 
  993         if (to_select.find(attached_bodies[i]->getName()) != to_select.end())
 
  994           item->setSelected(
true);
 
  995         ui_->collision_objects_list->addItem(item);
 
  996         known_collision_objects_.push_back(std::make_pair(attached_bodies[i]->getName(), 
true));
 
 1001   ui_->clear_octomap_button->setEnabled(octomap_in_scene);
 
 1002   ui_->collision_objects_list->blockSignals(old_state);
 
 1003   ui_->collision_objects_list->setUpdatesEnabled(
true);
 
 1004   selectedCollisionObjectChanged();
 
 1007 void MotionPlanningFrame::exportGeometryAsTextButtonClicked()
 
 1010       QFileDialog::getSaveFileName(
this, tr(
"Export Scene Geometry"), tr(
""), tr(
"Scene Geometry (*.scene)"));
 
 1011   if (!path.isEmpty())
 
 1016 void MotionPlanningFrame::computeExportGeometryAsText(
const std::string& path)
 
 1021     std::string 
p = (path.length() < 7 || path.substr(path.length() - 6) != 
".scene") ? path + 
".scene" : path;
 
 1022     std::ofstream fout(
p.c_str());
 
 1025       ps->saveGeometryToStream(fout);
 
 1027       RCLCPP_INFO(LOGGER, 
"Saved current scene geometry to '%s'", 
p.c_str());
 
 1030       RCLCPP_WARN(LOGGER, 
"Unable to save current scene geometry to '%s'", 
p.c_str());
 
 1034 void MotionPlanningFrame::computeImportGeometryFromText(
const std::string& path)
 
 1039     std::ifstream fin(path.c_str());
 
 1040     if (ps->loadGeometryFromStream(fin))
 
 1042       RCLCPP_INFO(LOGGER, 
"Loaded scene geometry from '%s'", path.c_str());
 
 1045       setLocalSceneEdited();
 
 1049       QMessageBox::warning(
nullptr, 
"Loading scene geometry",
 
 1050                            "Failed to load scene geometry.\n" 
 1051                            "See console output for more details.");
 
 1056 void MotionPlanningFrame::importGeometryFromTextButtonClicked()
 
 1059       QFileDialog::getOpenFileName(
this, tr(
"Import Scene Geometry"), tr(
""), tr(
"Scene Geometry (*.scene)"));
 
 1060   if (!path.isEmpty())
 
 1062                                         "import from text");
 
World::ObjectConstPtr ObjectConstPtr
 
Object defining bodies that can be attached to robot links.
 
const std::string & getAttachedLinkName() const
Get the name of the link this body is attached to.
 
const std::set< std::string > & getTouchLinks() const
Get the links that the attached body is allowed to touch.
 
const trajectory_msgs::msg::JointTrajectory & getDetachPosture() const
Return the posture that is necessary for the object to be released, (if any). This is useful for exam...
 
const moveit::core::FixedTransformsMap & getSubframes() const
Get subframes of this object (relative to the object pose). The returned transforms are guaranteed to...
 
const std::string & getName() const
Get the name of the attached body.
 
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get the shapes that make up this attached body.
 
const LinkModel * getAttachedLink() const
Get the model of the link this body is attached to.
 
const Eigen::Isometry3d & getPose() const
Get the pose of the attached body relative to the parent link.
 
const EigenSTL::vector_Isometry3d & getShapePoses() const
Get the shape poses (the transforms to the shapes of this body, relative to the pose)....
 
Representation of a robot's state. This includes position, velocity, acceleration and effort.
 
void attachBody(std::unique_ptr< AttachedBody > attached_body)
Add an attached body to this state.
 
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
 
bool clearAttachedBody(const std::string &id)
Remove the attached body named id. Return false if the object was not found (and thus not removed)....
 
const AttachedBody * getAttachedBody(const std::string &name) const
Get the attached body named name. Return nullptr if not found.
 
void setQueryGoalState(const moveit::core::RobotState &goal)
 
void setQueryStartState(const moveit::core::RobotState &start)
 
void updateQueryStates(const moveit::core::RobotState ¤t_state)
 
moveit::core::RobotStateConstPtr getQueryStartState() const
 
moveit::core::RobotStateConstPtr getQueryGoalState() const
 
moveit_warehouse::PlanningSceneStoragePtr planning_scene_storage_
 
static const int ITEM_TYPE_SCENE
 
std::shared_ptr< rviz_default_plugins::displays::InteractiveMarker > scene_marker_
 
rviz_common::DisplayContext * context_
 
Ui::MotionPlanningUI * ui_
 
static const int ITEM_TYPE_QUERY
 
void constructPlanningRequest(moveit_msgs::msg::MotionPlanRequest &mreq)
 
MotionPlanningDisplay * planning_display_
 
planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO() const
get read-only access to planning scene
 
planning_scene_monitor::LockedPlanningSceneRW getPlanningSceneRW()
get write access to planning scene
 
void addMainLoopJob(const std::function< void()> &job)
queue the execution of this function for the next time the main update() loop gets called
 
const moveit::core::RobotModelConstPtr & getRobotModel() const
 
void addBackgroundJob(const std::function< void()> &job, const std::string &name)
 
void queueRenderSceneGeometry()
 
const planning_scene_monitor::PlanningSceneMonitorPtr & getPlanningSceneMonitor()
 
static const std::string OCTOMAP_NS
 
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
 
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
 
Vec3fX< details::Vec3Data< double > > Vector3d
 
std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > > FixedTransformsMap
Map frame names to the transformation matrix that can transform objects from the frame name to the pl...
 
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
 
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::PlanningScene >::ConstPtr PlanningSceneWithMetadata
 
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::MotionPlanRequest >::ConstPtr MotionPlanRequestWithMetadata
 
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
 
std::string append(const std::string &left, const std::string &right)
 
visualization_msgs::msg::InteractiveMarker make6DOFMarker(const std::string &name, const geometry_msgs::msg::PoseStamped &stamped, double scale, bool orientation_fixed=false)
 
const rclcpp::Logger LOGGER