53 #include <QMessageBox>
54 #include <QInputDialog>
55 #include <QFileDialog>
57 #include "ui_motion_planning_rviz_plugin_frame.h"
63 QString status_text =
"\nIt has the subframes '";
64 for (
const auto& subframe : subframes)
66 status_text += QString::fromStdString(subframe.first) +
"', '";
78 switch (
ui_->shapes_combo_box->currentData().toInt())
81 ui_->shape_size_x_spin_box->setEnabled(
true);
82 ui_->shape_size_y_spin_box->setEnabled(
true);
83 ui_->shape_size_z_spin_box->setEnabled(
true);
86 ui_->shape_size_x_spin_box->setEnabled(
true);
87 ui_->shape_size_y_spin_box->setEnabled(
false);
88 ui_->shape_size_z_spin_box->setEnabled(
false);
92 ui_->shape_size_x_spin_box->setEnabled(
true);
93 ui_->shape_size_y_spin_box->setEnabled(
false);
94 ui_->shape_size_z_spin_box->setEnabled(
true);
97 ui_->shape_size_x_spin_box->setEnabled(
false);
98 ui_->shape_size_y_spin_box->setEnabled(
false);
99 ui_->shape_size_z_spin_box->setEnabled(
false);
108 ui_->publish_current_scene_button->setEnabled(dirty);
113 return ui_->publish_current_scene_button->isEnabled();
121 moveit_msgs::PlanningScene msg;
122 ps->getPlanningSceneMsg(msg);
131 QMessageBox::question(
this,
"Update PlanningScene",
132 "You have local changes to your planning scene.\n"
133 "Publish them to the move_group node?",
134 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes) == QMessageBox::Yes)
142 ps->getWorldNonConst()->clearObjects();
143 ps->getCurrentStateNonConst().clearAttachedBodies();
153 const double scaling_factor = (double)
value / 100.0;
165 s->scale(scaling_factor);
167 Eigen::Isometry3d scaled_shape_pose =
scaled_object_->shape_poses_[i];
168 scaled_shape_pose.translation() *= scaling_factor;
174 for (
auto& subframe_pair : scaled_subframes)
175 subframe_pair.second.translation() *= scaling_factor;
177 ps->getWorldNonConst()->setSubframesOfObject(
scaled_object_->id_, scaled_subframes);
193 auto current =
ui_->collision_objects_list->currentItem();
201 scaled_object_ = ps->getWorld()->getObject(current->text().toStdString());
211 ui_->scene_scale->setSliderPosition(100);
216 QList<QListWidgetItem*> selection =
ui_->collision_objects_list->selectedItems();
217 if (selection.empty())
222 bool removed_attached =
false;
223 for (QListWidgetItem* item : selection)
224 if (item->checkState() == Qt::Unchecked)
225 ps->getWorldNonConst()->removeObject(item->text().toStdString());
228 ps->getCurrentStateNonConst().clearAttachedBody(item->text().toStdString());
229 removed_attached =
true;
232 if (removed_attached)
244 QString status_text =
"'" + QString::fromStdString(
obj->id_) +
"' is a collision object with ";
245 if (
obj->shapes_.empty())
246 status_text +=
"no geometry";
249 std::vector<QString> shape_names;
252 if (shape_names.size() == 1)
253 status_text +=
"one " + shape_names[0];
256 status_text += QString::fromStdString(boost::lexical_cast<std::string>(shape_names.size())) +
" shapes:";
257 for (
const QString& shape_name : shape_names)
258 status_text +=
" " + shape_name;
262 if (!
obj->subframe_poses_.empty())
264 status_text += subframe_poses_to_qstring(
obj->subframe_poses_);
271 QString status_text =
"'" + QString::fromStdString(attached_body->
getName()) +
"' is attached to '" +
275 status_text += subframe_poses_to_qstring(attached_body->
getSubframes());
282 auto setValue = [](QDoubleSpinBox* w,
float value) {
283 QSignalBlocker block(w);
287 auto current =
ui_->collision_objects_list->currentItem();
290 setValue(
ui_->object_x, 0.0);
291 setValue(
ui_->object_y, 0.0);
292 setValue(
ui_->object_z, 0.0);
293 setValue(
ui_->object_rx, 0.0);
294 setValue(
ui_->object_ry, 0.0);
295 setValue(
ui_->object_rz, 0.0);
296 ui_->object_status->setText(
"");
298 ui_->pose_scale_group_box->setEnabled(
false);
303 if (current->checkState() == Qt::Unchecked)
305 ui_->pose_scale_group_box->setEnabled(
true);
306 bool update_scene_marker =
false;
307 Eigen::Isometry3d obj_pose;
310 if (
const auto&
obj = ps->getWorld()->getObject(current->text().toStdString()))
313 obj_pose =
obj->pose_;
314 Eigen::Vector3d xyz = obj_pose.linear().eulerAngles(0, 1, 2);
315 update_scene_marker =
true;
316 setValue(
ui_->object_x, obj_pose.translation()[0]);
317 setValue(
ui_->object_y, obj_pose.translation()[1]);
318 setValue(
ui_->object_z, obj_pose.translation()[2]);
319 setValue(
ui_->object_rx, xyz[0]);
320 setValue(
ui_->object_ry, xyz[1]);
321 setValue(
ui_->object_rz, xyz[2]);
324 ui_->object_status->setText(
"ERROR: '" + current->text() +
"' should be a collision object but it is not");
326 if (update_scene_marker &&
ui_->tabWidget->tabText(
ui_->tabWidget->currentIndex()).toStdString() ==
TAB_OBJECTS)
333 ui_->pose_scale_group_box->setEnabled(
false);
338 ps->getCurrentState().getAttachedBody(current->text().toStdString());
342 ui_->object_status->setText(
"ERROR: '" + current->text() +
"' should be an attached object but it is not");
354 auto current =
ui_->collision_objects_list->currentItem();
359 const std::string object_id = current->text().toStdString();
360 if (ps->getWorld()->hasObject(object_id))
363 p.translation()[0] =
ui_->object_x->value();
364 p.translation()[1] =
ui_->object_y->value();
365 p.translation()[2] =
ui_->object_z->value();
367 p = Eigen::Translation3d(p.translation()) *
368 (Eigen::AngleAxisd(
ui_->object_rx->value(), Eigen::Vector3d::UnitX()) *
369 Eigen::AngleAxisd(
ui_->object_ry->value(), Eigen::Vector3d::UnitY()) *
370 Eigen::AngleAxisd(
ui_->object_rz->value(), Eigen::Vector3d::UnitZ()));
372 ps->getWorldNonConst()->setObjectPose(object_id, p);
380 Eigen::Quaterniond eq(p.linear());
381 scene_marker_->setPose(Ogre::Vector3(
ui_->object_x->value(),
ui_->object_y->value(),
ui_->object_z->value()),
382 Ogre::Quaternion(eq.w(), eq.x(), eq.y(), eq.z()),
"");
397 bool checked = item->checkState() == Qt::Checked;
407 bool old_state =
ui_->object_x->blockSignals(
true);
408 ui_->object_x->setValue(feedback.pose.position.x);
409 ui_->object_x->blockSignals(old_state);
411 old_state =
ui_->object_y->blockSignals(
true);
412 ui_->object_y->setValue(feedback.pose.position.y);
413 ui_->object_y->blockSignals(old_state);
415 old_state =
ui_->object_z->blockSignals(
true);
416 ui_->object_z->setValue(feedback.pose.position.z);
417 ui_->object_z->blockSignals(old_state);
419 Eigen::Quaterniond
q;
421 Eigen::Vector3d xyz =
q.matrix().eulerAngles(0, 1, 2);
423 old_state =
ui_->object_rx->blockSignals(
true);
424 ui_->object_rx->setValue(xyz[0]);
425 ui_->object_rx->blockSignals(old_state);
427 old_state =
ui_->object_ry->blockSignals(
true);
428 ui_->object_ry->setValue(xyz[1]);
429 ui_->object_ry->blockSignals(old_state);
431 old_state =
ui_->object_rz->blockSignals(
true);
432 ui_->object_rz->setValue(xyz[2]);
433 ui_->object_rz->blockSignals(old_state);
440 QList<QListWidgetItem*> sel =
ui_->collision_objects_list->selectedItems();
448 for (
const QListWidgetItem* item : sel)
450 std::string
name = item->text().toStdString();
456 name.insert(0,
"Copy of ");
457 if (ps->getWorld()->hasObject(
name))
461 while (ps->getWorld()->hasObject(
name + boost::lexical_cast<std::string>(n)))
463 name += boost::lexical_cast<std::string>(n);
465 ps->getWorldNonConst()->addToObject(
name,
obj->shapes_,
obj->shape_poses_);
476 moveit_msgs::PlanningScene msg;
483 catch (std::exception& ex)
494 moveit_msgs::MotionPlanRequest mreq;
500 if (!query_name.empty())
504 catch (std::exception& ex)
517 QList<QTreeWidgetItem*> sel =
ui_->planning_scene_tree->selectedItems();
520 QTreeWidgetItem*
s = sel.front();
523 std::string scene =
s->text(0).toStdString();
528 catch (std::exception& ex)
536 std::string scene =
s->parent()->text(0).toStdString();
541 catch (std::exception& ex)
555 QList<QTreeWidgetItem*> sel =
ui_->planning_scene_tree->selectedItems();
558 QTreeWidgetItem*
s = sel.front();
561 std::string scene =
s->parent()->text(0).toStdString();
562 std::string query_name =
s->text(0).toStdString();
567 catch (std::exception& ex)
579 ui_->planning_scene_tree->setUpdatesEnabled(
false);
580 s->parent()->removeChild(
s);
581 ui_->planning_scene_tree->setUpdatesEnabled(
true);
586 QList<QTreeWidgetItem*> sel =
ui_->planning_scene_tree->selectedItems();
589 ui_->load_scene_button->setEnabled(
false);
590 ui_->load_query_button->setEnabled(
false);
591 ui_->save_query_button->setEnabled(
false);
592 ui_->delete_scene_button->setEnabled(
false);
596 ui_->save_query_button->setEnabled(
true);
598 QTreeWidgetItem*
s = sel.front();
603 ui_->load_scene_button->setEnabled(
true);
604 ui_->load_query_button->setEnabled(
false);
605 ui_->delete_scene_button->setEnabled(
true);
606 ui_->delete_query_button->setEnabled(
false);
607 ui_->save_query_button->setEnabled(
true);
612 ui_->load_scene_button->setEnabled(
false);
613 ui_->load_query_button->setEnabled(
true);
614 ui_->delete_scene_button->setEnabled(
false);
615 ui_->delete_query_button->setEnabled(
true);
624 QList<QTreeWidgetItem*> sel =
ui_->planning_scene_tree->selectedItems();
627 QTreeWidgetItem*
s = sel.front();
630 std::string scene =
s->text(0).toStdString();
631 ROS_DEBUG(
"Attempting to load scene '%s'", scene.c_str());
638 catch (std::exception& ex)
645 ROS_INFO(
"Loaded scene '%s'", scene.c_str());
650 ROS_INFO(
"Scene '%s' was saved for robot '%s' but we are using robot '%s'. Using scene geometry only",
651 scene.c_str(), scene_m->robot_model_name.c_str(),
655 moveit_msgs::PlanningScene diff;
657 diff.name = scene_m->name;
667 ROS_WARN(
"Failed to load scene '%s'. Has the message format changed since the scene was saved?",
678 QList<QTreeWidgetItem*> sel =
ui_->planning_scene_tree->selectedItems();
681 QTreeWidgetItem*
s = sel.front();
684 std::string scene =
s->parent()->text(0).toStdString();
685 std::string query_name =
s->text(0).toStdString();
692 catch (std::exception& ex)
699 moveit::core::RobotStatePtr start_state(
702 mp->start_state, *start_state);
706 for (
const moveit_msgs::Constraints& goal_constraint : mp->goal_constraints)
707 if (!goal_constraint.joint_constraints.empty())
709 std::map<std::string, double> vals;
710 for (
const moveit_msgs::JointConstraint& joint_constraint : goal_constraint.joint_constraints)
711 vals[joint_constraint.joint_name] = joint_constraint.position;
712 goal_state->setVariablePositions(vals);
718 ROS_ERROR(
"Failed to load planning query '%s'. Has the message format changed since the query was saved?",
725 visualization_msgs::InteractiveMarker
728 Eigen::Vector3d center = Eigen::Vector3d::Zero();
731 if (!
obj->shapes_.empty())
733 geometry_msgs::PoseStamped shape_pose =
tf2::toMsg(
735 scale = (scale + center.cwiseAbs().maxCoeff()) * 2.0 * 1.2;
738 visualization_msgs::InteractiveMarker imarker =
740 imarker.description =
obj->id_;
747 auto current =
ui_->collision_objects_list->currentItem();
755 if (
const auto&
obj = ps->getWorld()->getObject(current->text().toStdString()))
762 connect(
scene_marker_.get(), SIGNAL(userFeedback(visualization_msgs::InteractiveMarkerFeedback&)),
this,
774 if (item->text().isEmpty())
776 QMessageBox::warning(
this,
"Invalid object name",
"Cannot set an empty object name.");
782 std::string item_text = item->text().toStdString();
788 QMessageBox::warning(
this,
"Duplicate object name",
789 QString(
"The name '")
791 .append(
"' already exists. Not renaming object ")
798 if (item->checkState() == Qt::Unchecked)
806 ps->getWorldNonConst()->removeObject(
obj->id_);
809 ps->getWorldNonConst()->setSubframesOfObject(
obj->id_,
obj->subframe_poses_);
826 auto new_ab = std::make_unique<moveit::core::AttachedBody>(
839 bool checked = item->checkState() == Qt::Checked;
841 moveit_msgs::AttachedCollisionObject aco;
847 for (
const std::string& link : links_std)
848 links.append(QString::fromStdString(link));
851 QInputDialog::getItem(
this, tr(
"Select Link Name"), tr(
"Choose the link to attach to:"), links, 0,
false, &
ok);
855 item->setCheckState(Qt::Unchecked);
858 aco.link_name =
response.toStdString();
859 aco.object.id =
data.first;
860 aco.object.operation = moveit_msgs::CollisionObject::ADD;
869 aco.object.id = attached_body->
getName();
870 aco.object.operation = moveit_msgs::CollisionObject::REMOVE;
879 if (known_collision_object.first ==
data.first)
881 known_collision_object.second = checked;
884 ps->processAttachedCollisionObjectMsg(aco);
885 rs = ps->getCurrentState();
896 QListWidgetItem* item =
new QListWidgetItem(QString::fromStdString(
name),
ui_->collision_objects_list, row);
897 item->setFlags(item->flags() | Qt::ItemIsEditable);
898 item->setToolTip(item->text());
899 item->setCheckState(attached ? Qt::Checked : Qt::Unchecked);
906 ui_->collision_objects_list->setUpdatesEnabled(
false);
907 bool octomap_in_scene =
false;
910 QSignalBlocker block(
ui_->collision_objects_list);
912 QString current_item_text;
913 if (
auto* item =
ui_->collision_objects_list->currentItem())
914 current_item_text = item->text();
915 QListWidgetItem* current_item =
nullptr;
917 std::set<std::string> to_select;
918 QList<QListWidgetItem*> sel =
ui_->collision_objects_list->selectedItems();
919 for (QListWidgetItem* item : sel)
920 to_select.insert(item->text().toStdString());
921 ui_->collision_objects_list->clear();
928 for (
const std::string&
name : ps->getWorld()->getObjectIds())
932 octomap_in_scene =
true;
936 if (to_select.find(
name) != to_select.end())
937 item->setSelected(
true);
938 if (!current_item && !current_item_text.isEmpty() && item->text() == current_item_text)
942 std::vector<const moveit::core::AttachedBody*> attached_bodies;
943 ps->getCurrentState().getAttachedBodies(attached_bodies);
944 for (
const auto& body : attached_bodies)
947 if (to_select.find(body->getName()) != to_select.end())
948 item->setSelected(
true);
951 ui_->collision_objects_list->setCurrentItem(current_item);
954 ui_->clear_octomap_button->setEnabled(octomap_in_scene);
955 ui_->collision_objects_list->setUpdatesEnabled(
true);
962 QFileDialog::getSaveFileName(
this, tr(
"Export Scene Geometry"), tr(
""), tr(
"Scene Geometry (*.scene)"));
973 std::string p = (path.length() < 7 || path.substr(path.length() - 6) !=
".scene") ? path +
".scene" : path;
974 std::ofstream fout(p.c_str());
977 ps->saveGeometryToStream(fout);
979 ROS_INFO(
"Saved current scene geometry to '%s'", p.c_str());
982 ROS_WARN(
"Unable to save current scene geometry to '%s'", p.c_str());
988 bool success =
false;
991 std::ifstream fin(path.c_str());
992 if (ps->loadGeometryFromStream(fin))
994 ROS_INFO(
"Loaded scene geometry from '%s'", path.c_str());
1003 QMessageBox::warning(
nullptr,
"Loading scene geometry",
1004 "Failed to load scene geometry.\n"
1005 "See console output for more details.");
1012 QFileDialog::getOpenFileName(
this, tr(
"Import Scene Geometry"), tr(
""), tr(
"Scene Geometry (*.scene)"));
1013 if (!path.isEmpty())
1015 "import from text");