45 #include <geometric_shapes/shape_operations.h>
47 #include <rviz_common/display_context.hpp>
48 #include <rviz_common/frame_manager_iface.hpp>
49 #include <tf2_ros/buffer.h>
51 #include <std_srvs/srv/empty.hpp>
53 #include <QMessageBox>
54 #include <QInputDialog>
55 #include <QFileDialog>
59 #include "ui_motion_planning_rviz_plugin_frame.h"
63 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros_visualization.motion_planning_frame");
67 : QWidget(parent), planning_display_(pdisplay), context_(context), ui_(new
Ui::MotionPlanningUI()), first_time_(true)
69 auto ros_node_abstraction =
context_->getRosNodeAbstraction().lock();
70 if (!ros_node_abstraction)
72 RCLCPP_INFO(LOGGER,
"Unable to lock weak_ptr from DisplayContext in MotionPlanningFrame constructor");
75 node_ = ros_node_abstraction->get_raw_node();
78 if (!node_->has_parameter(
"warehouse_host"))
79 node_->declare_parameter<std::string>(
"warehouse_host",
"127.0.0.1");
80 if (!node_->has_parameter(
"warehouse_plugin"))
81 node_->declare_parameter<std::string>(
"warehouse_plugin",
"warehouse_ros_mongo::MongoDatabaseConnection");
82 if (!node_->has_parameter(
"warehouse_port"))
83 node_->declare_parameter<
int>(
"warehouse_port", 33829);
87 ui_->shapes_combo_box->addItem(
"Box", shapes::BOX);
88 ui_->shapes_combo_box->addItem(
"Sphere", shapes::SPHERE);
89 ui_->shapes_combo_box->addItem(
"Cylinder", shapes::CYLINDER);
90 ui_->shapes_combo_box->addItem(
"Cone", shapes::CONE);
91 ui_->shapes_combo_box->addItem(
"Mesh from file", shapes::MESH);
92 ui_->shapes_combo_box->addItem(
"Mesh from URL", shapes::MESH);
93 setLocalSceneEdited(
false);
103 connect(
ui_->plan_button, SIGNAL(clicked()),
this, SLOT(planButtonClicked()));
104 connect(
ui_->execute_button, SIGNAL(clicked()),
this, SLOT(executeButtonClicked()));
105 connect(
ui_->plan_and_execute_button, SIGNAL(clicked()),
this, SLOT(planAndExecuteButtonClicked()));
106 connect(
ui_->stop_button, SIGNAL(clicked()),
this, SLOT(stopButtonClicked()));
107 connect(
ui_->start_state_combo_box, SIGNAL(activated(QString)),
this, SLOT(startStateTextChanged(QString)));
108 connect(
ui_->goal_state_combo_box, SIGNAL(activated(QString)),
this, SLOT(goalStateTextChanged(QString)));
109 connect(
ui_->planning_group_combo_box, SIGNAL(currentIndexChanged(QString)),
this,
110 SLOT(planningGroupTextChanged(QString)));
111 connect(
ui_->database_connect_button, SIGNAL(clicked()),
this, SLOT(databaseConnectButtonClicked()));
112 connect(
ui_->save_scene_button, SIGNAL(clicked()),
this, SLOT(saveSceneButtonClicked()));
113 connect(
ui_->save_query_button, SIGNAL(clicked()),
this, SLOT(saveQueryButtonClicked()));
114 connect(
ui_->delete_scene_button, SIGNAL(clicked()),
this, SLOT(deleteSceneButtonClicked()));
115 connect(
ui_->delete_query_button, SIGNAL(clicked()),
this, SLOT(deleteQueryButtonClicked()));
116 connect(
ui_->planning_scene_tree, SIGNAL(itemSelectionChanged()),
this, SLOT(planningSceneItemClicked()));
117 connect(
ui_->load_scene_button, SIGNAL(clicked()),
this, SLOT(loadSceneButtonClicked()));
118 connect(
ui_->load_query_button, SIGNAL(clicked()),
this, SLOT(loadQueryButtonClicked()));
119 connect(
ui_->allow_looking, SIGNAL(toggled(
bool)),
this, SLOT(allowLookingToggled(
bool)));
120 connect(
ui_->allow_replanning, SIGNAL(toggled(
bool)),
this, SLOT(allowReplanningToggled(
bool)));
121 connect(
ui_->allow_external_program, SIGNAL(toggled(
bool)),
this, SLOT(allowExternalProgramCommunication(
bool)));
122 connect(
ui_->planning_pipeline_combo_box, SIGNAL(currentIndexChanged(
int)),
this,
123 SLOT(planningPipelineIndexChanged(
int)));
124 connect(
ui_->planning_algorithm_combo_box, SIGNAL(currentIndexChanged(
int)),
this,
125 SLOT(planningAlgorithmIndexChanged(
int)));
126 connect(
ui_->clear_scene_button, SIGNAL(clicked()),
this, SLOT(clearScene()));
127 connect(
ui_->scene_scale, SIGNAL(valueChanged(
int)),
this, SLOT(sceneScaleChanged(
int)));
128 connect(
ui_->scene_scale, SIGNAL(sliderPressed()),
this, SLOT(sceneScaleStartChange()));
129 connect(
ui_->scene_scale, SIGNAL(sliderReleased()),
this, SLOT(sceneScaleEndChange()));
130 connect(
ui_->remove_object_button, SIGNAL(clicked()),
this, SLOT(removeSceneObject()));
131 connect(
ui_->object_x, SIGNAL(valueChanged(
double)),
this, SLOT(objectPoseValueChanged(
double)));
132 connect(
ui_->object_y, SIGNAL(valueChanged(
double)),
this, SLOT(objectPoseValueChanged(
double)));
133 connect(
ui_->object_z, SIGNAL(valueChanged(
double)),
this, SLOT(objectPoseValueChanged(
double)));
134 connect(
ui_->object_rx, SIGNAL(valueChanged(
double)),
this, SLOT(objectPoseValueChanged(
double)));
135 connect(
ui_->object_ry, SIGNAL(valueChanged(
double)),
this, SLOT(objectPoseValueChanged(
double)));
136 connect(
ui_->object_rz, SIGNAL(valueChanged(
double)),
this, SLOT(objectPoseValueChanged(
double)));
137 connect(
ui_->publish_current_scene_button, SIGNAL(clicked()),
this, SLOT(publishScene()));
138 connect(
ui_->collision_objects_list, SIGNAL(itemSelectionChanged()),
this, SLOT(selectedCollisionObjectChanged()));
139 connect(
ui_->collision_objects_list, SIGNAL(itemChanged(QListWidgetItem*)),
this,
140 SLOT(collisionObjectChanged(QListWidgetItem*)));
141 connect(
ui_->path_constraints_combo_box, SIGNAL(currentIndexChanged(
int)),
this,
142 SLOT(pathConstraintsIndexChanged(
int)));
143 connect(
ui_->clear_octomap_button, SIGNAL(clicked()),
this, SLOT(onClearOctomapClicked()));
144 connect(
ui_->planning_scene_tree, SIGNAL(itemChanged(QTreeWidgetItem*,
int)),
this,
145 SLOT(warehouseItemNameChanged(QTreeWidgetItem*,
int)));
146 connect(
ui_->reset_db_button, SIGNAL(clicked()),
this, SLOT(resetDbButtonClicked()));
148 connect(
ui_->add_object_button, &QPushButton::clicked,
this, &MotionPlanningFrame::addSceneObject);
149 connect(
ui_->shapes_combo_box, &QComboBox::currentTextChanged,
this, &MotionPlanningFrame::shapesComboBoxChanged);
150 connect(
ui_->export_scene_geometry_text_button, SIGNAL(clicked()),
this, SLOT(exportGeometryAsTextButtonClicked()));
151 connect(
ui_->import_scene_geometry_text_button, SIGNAL(clicked()),
this, SLOT(importGeometryFromTextButtonClicked()));
152 connect(
ui_->load_state_button, SIGNAL(clicked()),
this, SLOT(loadStateButtonClicked()));
153 connect(
ui_->save_start_state_button, SIGNAL(clicked()),
this, SLOT(saveStartStateButtonClicked()));
154 connect(
ui_->save_goal_state_button, SIGNAL(clicked()),
this, SLOT(saveGoalStateButtonClicked()));
155 connect(
ui_->set_as_start_state_button, SIGNAL(clicked()),
this, SLOT(setAsStartStateButtonClicked()));
156 connect(
ui_->set_as_goal_state_button, SIGNAL(clicked()),
this, SLOT(setAsGoalStateButtonClicked()));
157 connect(
ui_->remove_state_button, SIGNAL(clicked()),
this, SLOT(removeStateButtonClicked()));
158 connect(
ui_->clear_states_button, SIGNAL(clicked()),
this, SLOT(clearStatesButtonClicked()));
159 connect(
ui_->approximate_ik, SIGNAL(stateChanged(
int)),
this, SLOT(approximateIKChanged(
int)));
161 connect(
ui_->detect_objects_button, SIGNAL(clicked()),
this, SLOT(detectObjectsButtonClicked()));
162 connect(
ui_->pick_button, SIGNAL(clicked()),
this, SLOT(pickObjectButtonClicked()));
163 connect(
ui_->place_button, SIGNAL(clicked()),
this, SLOT(placeObjectButtonClicked()));
164 connect(
ui_->detected_objects_list, SIGNAL(itemSelectionChanged()),
this, SLOT(selectedDetectedObjectChanged()));
165 connect(
ui_->detected_objects_list, SIGNAL(itemChanged(QListWidgetItem*)),
this,
166 SLOT(detectedObjectChanged(QListWidgetItem*)));
167 connect(
ui_->support_surfaces_list, SIGNAL(itemSelectionChanged()),
this, SLOT(selectedSupportSurfaceChanged()));
169 connect(
ui_->tabWidget, SIGNAL(currentChanged(
int)),
this, SLOT(tabChanged(
int)));
172 connect(
ui_->database_host, SIGNAL(textChanged(QString)),
this, SIGNAL(
configChanged()));
173 connect(
ui_->database_port, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
175 connect(
ui_->planning_time, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
176 connect(
ui_->planning_attempts, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
177 connect(
ui_->velocity_scaling_factor, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
178 connect(
ui_->acceleration_scaling_factor, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
180 connect(
ui_->allow_replanning, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
181 connect(
ui_->allow_looking, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
182 connect(
ui_->allow_external_program, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
183 connect(
ui_->use_cartesian_path, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
184 connect(
ui_->collision_aware_ik, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
185 connect(
ui_->approximate_ik, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
187 connect(
ui_->wcenter_x, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
188 connect(
ui_->wcenter_y, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
189 connect(
ui_->wcenter_z, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
190 connect(
ui_->wsize_x, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
191 connect(
ui_->wsize_y, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
192 connect(
ui_->wsize_z, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
194 QShortcut* copy_object_shortcut =
new QShortcut(QKeySequence(Qt::CTRL + Qt::Key_C),
ui_->collision_objects_list);
195 connect(copy_object_shortcut, SIGNAL(activated()),
this, SLOT(copySelectedCollisionObject()));
197 ui_->reset_db_button->hide();
198 ui_->background_job_progress->hide();
199 ui_->background_job_progress->setMaximum(0);
201 ui_->tabWidget->setCurrentIndex(1);
203 known_collision_objects_version_ = 0;
207 object_recognition_client_ = rclcpp_action::create_client<object_recognition_msgs::action::ObjectRecognition>(
210 if (object_recognition_client_)
212 if (!object_recognition_client_->wait_for_action_server(std::chrono::seconds(3)))
215 object_recognition_client_.reset();
245 void MotionPlanningFrame::approximateIKChanged(
int state)
250 void MotionPlanningFrame::setItemSelectionInList(
const std::string& item_name,
bool selection, QListWidget* list)
252 QList<QListWidgetItem*> found_items = list->findItems(QString(item_name.c_str()), Qt::MatchExactly);
253 for (QListWidgetItem* found_item : found_items)
254 found_item->setSelected(selection);
257 void MotionPlanningFrame::allowExternalProgramCommunication(
bool enable)
268 using std::placeholders::_1;
269 plan_subscriber_ = node_->create_subscription<std_msgs::msg::Empty>(
270 "/rviz/moveit/plan", rclcpp::SystemDefaultsQoS(),
271 [
this](
const std_msgs::msg::Empty::ConstSharedPtr& msg) {
return remotePlanCallback(msg); });
272 execute_subscriber_ = node_->create_subscription<std_msgs::msg::Empty>(
273 "/rviz/moveit/execute", rclcpp::SystemDefaultsQoS(),
274 [
this](
const std_msgs::msg::Empty::ConstSharedPtr& msg) {
return remoteExecuteCallback(msg); });
275 stop_subscriber_ = node_->create_subscription<std_msgs::msg::Empty>(
276 "/rviz/moveit/stop", rclcpp::SystemDefaultsQoS(),
277 [
this](
const std_msgs::msg::Empty::ConstSharedPtr& msg) {
return remoteStopCallback(msg); });
278 update_start_state_subscriber_ = node_->create_subscription<std_msgs::msg::Empty>(
279 "/rviz/moveit/update_start_state", rclcpp::SystemDefaultsQoS(),
280 [
this](
const std_msgs::msg::Empty::ConstSharedPtr& msg) {
return remoteUpdateStartStateCallback(msg); });
281 update_goal_state_subscriber_ = node_->create_subscription<std_msgs::msg::Empty>(
282 "/rviz/moveit/update_goal_state", rclcpp::SystemDefaultsQoS(),
283 [
this](
const std_msgs::msg::Empty::ConstSharedPtr& msg) {
return remoteUpdateGoalStateCallback(msg); });
284 update_custom_start_state_subscriber_ = node_->create_subscription<moveit_msgs::msg::RobotState>(
285 "/rviz/moveit/update_custom_start_state", rclcpp::SystemDefaultsQoS(),
286 [
this](
const moveit_msgs::msg::RobotState::ConstSharedPtr& msg) {
287 return remoteUpdateCustomStartStateCallback(msg);
289 update_custom_goal_state_subscriber_ = node_->create_subscription<moveit_msgs::msg::RobotState>(
290 "/rviz/moveit/update_custom_goal_state", rclcpp::SystemDefaultsQoS(),
291 [
this](
const moveit_msgs::msg::RobotState::ConstSharedPtr& msg) {
292 return remoteUpdateCustomGoalStateCallback(msg);
297 plan_subscriber_.reset();
298 execute_subscriber_.reset();
299 stop_subscriber_.reset();
300 update_start_state_subscriber_.reset();
301 update_goal_state_subscriber_.reset();
302 update_custom_start_state_subscriber_.reset();
303 update_custom_goal_state_subscriber_.reset();
307 void MotionPlanningFrame::fillPlanningGroupOptions()
309 const QSignalBlocker planning_group_blocker(
ui_->planning_group_combo_box);
310 ui_->planning_group_combo_box->clear();
313 for (
const std::string& group_name : kmodel->getJointModelGroupNames())
314 ui_->planning_group_combo_box->addItem(QString::fromStdString(group_name));
317 void MotionPlanningFrame::fillStateSelectionOptions()
319 const QSignalBlocker start_state_blocker(
ui_->start_state_combo_box);
320 const QSignalBlocker goal_state_blocker(
ui_->goal_state_combo_box);
321 ui_->start_state_combo_box->clear();
322 ui_->goal_state_combo_box->clear();
334 ui_->start_state_combo_box->addItem(QString(
"<random valid>"));
335 ui_->start_state_combo_box->addItem(QString(
"<random>"));
336 ui_->start_state_combo_box->addItem(QString(
"<current>"));
337 ui_->start_state_combo_box->addItem(QString(
"<same as goal>"));
338 ui_->start_state_combo_box->addItem(QString(
"<previous>"));
340 ui_->goal_state_combo_box->addItem(QString(
"<random valid>"));
341 ui_->goal_state_combo_box->addItem(QString(
"<random>"));
342 ui_->goal_state_combo_box->addItem(QString(
"<current>"));
343 ui_->goal_state_combo_box->addItem(QString(
"<same as start>"));
344 ui_->goal_state_combo_box->addItem(QString(
"<previous>"));
347 if (!known_states.empty())
349 ui_->start_state_combo_box->insertSeparator(
ui_->start_state_combo_box->count());
350 ui_->goal_state_combo_box->insertSeparator(
ui_->goal_state_combo_box->count());
351 for (
const std::string& known_state : known_states)
353 ui_->start_state_combo_box->addItem(QString::fromStdString(known_state));
354 ui_->goal_state_combo_box->addItem(QString::fromStdString(known_state));
358 ui_->start_state_combo_box->setCurrentIndex(2);
359 ui_->goal_state_combo_box->setCurrentIndex(2);
363 void MotionPlanningFrame::changePlanningGroupHelper()
374 planning_display_->addMainLoopJob(
375 [=]() { ui_->planning_group_combo_box->setCurrentText(QString::fromStdString(
group)); });
377 if (!
group.empty() && robot_model)
379 RCLCPP_INFO(LOGGER,
"group %s",
group.c_str());
380 if (move_group_ && move_group_->getName() ==
group)
382 RCLCPP_INFO(LOGGER,
"Constructing new MoveGroup connection for group '%s' in namespace '%s'",
group.c_str(),
383 planning_display_->getMoveGroupNS().c_str());
386 opt.robot_model_ = robot_model;
387 opt.robot_description_.clear();
397 move_group_ = std::make_shared<moveit::planning_interface::MoveGroupInterface>(
398 node_,
opt, tf_buffer, rclcpp::Duration::from_seconds(30));
399 if (planning_scene_storage_)
400 move_group_->setConstraintsDatabase(ui_->database_host->text().toStdString(), ui_->database_port->value());
402 catch (std::exception& ex)
404 RCLCPP_ERROR(LOGGER,
"%s", ex.what());
406 planning_display_->addMainLoopJob([&
view = *ui_->planner_param_treeview,
this] { view.setMoveGroup(move_group_); });
409 move_group_->allowLooking(ui_->allow_looking->isChecked());
410 move_group_->allowReplanning(ui_->allow_replanning->isChecked());
411 bool has_unique_endeffector = !move_group_->getEndEffectorLink().empty();
412 planning_display_->addMainLoopJob([=]() { ui_->use_cartesian_path->setEnabled(has_unique_endeffector); });
413 std::vector<moveit_msgs::msg::PlannerInterfaceDescription> desc;
414 if (move_group_->getInterfaceDescriptions(desc))
415 planning_display_->addMainLoopJob([
this, desc] { populatePlannersList(desc); });
416 planning_display_->addBackgroundJob([
this]() { populateConstraintsList(); },
"populateConstraintsList");
424 planning_display_->setQueryStartState(ps->getCurrentState());
425 planning_display_->setQueryGoalState(ps->getCurrentState());
428 planning_display_->useApproximateIK(ui_->approximate_ik->isChecked());
429 if (ui_->allow_external_program->isChecked())
430 planning_display_->addMainLoopJob([
this] { allowExternalProgramCommunication(
true); });
436 void MotionPlanningFrame::clearRobotModel()
438 ui_->planner_param_treeview->setMoveGroup(moveit::planning_interface::MoveGroupInterfacePtr());
439 joints_tab_->clearRobotModel();
443 void MotionPlanningFrame::changePlanningGroup()
445 planning_display_->addBackgroundJob([
this] { changePlanningGroupHelper(); },
"Frame::changePlanningGroup");
446 joints_tab_->changePlanningGroup(planning_display_->getCurrentPlanningGroup(),
447 planning_display_->getQueryStartStateHandler(),
448 planning_display_->getQueryGoalStateHandler());
454 planning_display_->addMainLoopJob([
this] { populateCollisionObjectsList(); });
457 void MotionPlanningFrame::addSceneObject()
459 static const double MIN_VAL = 1e-6;
461 if (!planning_display_->getPlanningSceneMonitor())
467 double x_length = ui_->shape_size_x_spin_box->isEnabled() ? ui_->shape_size_x_spin_box->value() : MIN_VAL;
468 double y_length = ui_->shape_size_y_spin_box->isEnabled() ? ui_->shape_size_y_spin_box->value() : MIN_VAL;
469 double z_length = ui_->shape_size_z_spin_box->isEnabled() ? ui_->shape_size_z_spin_box->value() : MIN_VAL;
470 if (x_length < MIN_VAL || y_length < MIN_VAL || z_length < MIN_VAL)
472 QMessageBox::warning(
this, QString(
"Dimension is too small"), QString(
"Size values need to be >= %1").arg(MIN_VAL));
477 std::string selected_shape = ui_->shapes_combo_box->currentText().toStdString();
478 shapes::ShapeConstPtr shape;
479 switch (ui_->shapes_combo_box->currentData().toInt())
482 shape = std::make_shared<shapes::Box>(x_length, y_length, z_length);
485 shape = std::make_shared<shapes::Sphere>(0.5 * x_length);
488 shape = std::make_shared<shapes::Cone>(0.5 * x_length, z_length);
490 case shapes::CYLINDER:
491 shape = std::make_shared<shapes::Cylinder>(0.5 * x_length, z_length);
496 if (ui_->shapes_combo_box->currentText().contains(
"file"))
497 url = QFileDialog::getOpenFileUrl(
this, tr(
"Import Object Mesh"), QString(),
498 "CAD files (*.stl *.obj *.dae);;All files (*.*)");
500 url = QInputDialog::getText(
this, tr(
"Import Object Mesh"), tr(
"URL for file to import from:"),
501 QLineEdit::Normal, QString(
"http://"));
503 shape = loadMeshResource(url.toString().toStdString());
507 selected_shape = url.fileName().toStdString();
511 QMessageBox::warning(
this, QString(
"Unsupported shape"),
512 QString(
"The '%1' is not supported.").arg(ui_->shapes_combo_box->currentText()));
517 std::string shape_name = selected_shape +
"_" + std::to_string(idx);
518 while (planning_display_->getPlanningSceneRO()->getWorld()->hasObject(shape_name))
521 shape_name = selected_shape +
"_" + std::to_string(idx);
527 ps->getWorldNonConst()->addToObject(shape_name, shape, Eigen::Isometry3d::Identity());
529 setLocalSceneEdited();
531 planning_display_->addMainLoopJob([
this] { populateCollisionObjectsList(); });
534 planning_display_->addMainLoopJob([
this, shape_name, list_widget = ui_->collision_objects_list] {
535 setItemSelectionInList(shape_name,
true, list_widget);
538 planning_display_->queueRenderSceneGeometry();
541 shapes::ShapePtr MotionPlanningFrame::loadMeshResource(
const std::string& url)
543 shapes::Mesh* mesh = shapes::createMeshFromResource(url);
547 bool object_is_very_large =
false;
548 for (
unsigned int i = 0; i < mesh->vertex_count; ++i)
550 if ((abs(mesh->vertices[i * 3 + 0]) > LARGE_MESH_THRESHOLD) ||
551 (abs(mesh->vertices[i * 3 + 1]) > LARGE_MESH_THRESHOLD) ||
552 (abs(mesh->vertices[i * 3 + 2]) > LARGE_MESH_THRESHOLD))
554 object_is_very_large =
true;
558 if (object_is_very_large)
562 "The object is very large (greater than 10 m). The file may be in millimeters instead of meters.");
563 msg_box.setInformativeText(
"Attempt to fix the size by shrinking the object?");
564 msg_box.setStandardButtons(QMessageBox::Yes | QMessageBox::No);
565 msg_box.setDefaultButton(QMessageBox::Yes);
566 if (msg_box.exec() == QMessageBox::Yes)
568 for (
unsigned int i = 0; i < mesh->vertex_count; ++i)
570 unsigned int i3 = i * 3;
571 mesh->vertices[i3] *= 0.001;
572 mesh->vertices[i3 + 1] *= 0.001;
573 mesh->vertices[i3 + 2] *= 0.001;
578 return shapes::ShapePtr(mesh);
582 QMessageBox::warning(
this, QString(
"Import error"), QString(
"Unable to import object"));
583 return shapes::ShapePtr();
587 void MotionPlanningFrame::enable()
589 ui_->planning_algorithm_combo_box->clear();
590 ui_->library_label->setText(
"NO PLANNING LIBRARY LOADED");
591 ui_->library_label->setStyleSheet(
"QLabel { color : red; font: bold }");
592 ui_->object_status->setText(
"");
594 const std::string new_ns = planning_display_->getMoveGroupNS();
595 if (node_->get_namespace() != new_ns)
597 RCLCPP_INFO(LOGGER,
"MoveGroup namespace changed: %s -> %s. Reloading params.", node_->get_namespace(),
599 initFromMoveGroupNS();
604 parentWidget()->show();
609 void MotionPlanningFrame::initFromMoveGroupNS()
612 clear_octomap_service_client_ = node_->create_client<std_srvs::srv::Empty>(move_group::CLEAR_OCTOMAP_SERVICE_NAME);
614 object_recognition_subscriber_ = node_->create_subscription<object_recognition_msgs::msg::RecognizedObjectArray>(
615 "recognized_object_array", rclcpp::SystemDefaultsQoS(),
616 [
this](
const object_recognition_msgs::msg::RecognizedObjectArray::ConstSharedPtr& msg) {
617 return listenDetectedObjects(msg);
620 planning_scene_publisher_ = node_->create_publisher<moveit_msgs::msg::PlanningScene>(
"planning_scene", 1);
621 planning_scene_world_publisher_ =
622 node_->create_publisher<moveit_msgs::msg::PlanningSceneWorld>(
"planning_scene_world", 1);
625 if (!node_->has_parameter(planning_display_->getMoveGroupNS() +
"default_planning_pipeline"))
626 node_->declare_parameter<std::string>(planning_display_->getMoveGroupNS() +
"default_planning_pipeline",
"");
629 node_->get_parameter(planning_display_->getMoveGroupNS() +
"default_planning_pipeline", default_planning_pipeline_);
633 node_->get_parameter_or(
"robot_description_planning.default_velocity_scaling_factor", factor, 0.1);
634 ui_->velocity_scaling_factor->setValue(factor);
635 node_->get_parameter_or(
"robot_description_planning.default_acceleration_scaling_factor", factor, 0.1);
636 ui_->acceleration_scaling_factor->setValue(factor);
639 std::string host_param;
640 if (node_->get_parameter(
"warehouse_host", host_param))
642 ui_->database_host->setText(QString::fromStdString(host_param));
646 if (node_->get_parameter(
"warehouse_port", port))
648 ui_->database_port->setValue(port);
652 void MotionPlanningFrame::disable()
655 scene_marker_.reset();
657 parentWidget()->hide();
660 void MotionPlanningFrame::tabChanged(
int index)
662 if (scene_marker_ && ui_->tabWidget->tabText(index).toStdString() != TAB_OBJECTS)
663 scene_marker_.reset();
664 else if (ui_->tabWidget->tabText(index).toStdString() == TAB_OBJECTS)
665 selectedCollisionObjectChanged();
668 void MotionPlanningFrame::updateSceneMarkers(
float ,
float )
671 scene_marker_->update();
674 void MotionPlanningFrame::updateExternalCommunication()
676 if (ui_->allow_external_program->isChecked())
678 planning_display_->getRobotInteraction()->toggleMoveInteractiveMarkerTopic(
true);
const std::vector< std::string > & getDefaultStateNames() const
Get the names of the known default states (as specified in the SRDF)
static const std::string ROBOT_DESCRIPTION
Default ROS parameter name from where to read the robot's URDF. Set to 'robot_description'.
std::string getCurrentPlanningGroup() const
void useApproximateIK(bool flag)
void toggleSelectPlanningGroupSubscription(bool enable)
const robot_interaction::RobotInteractionPtr & getRobotInteraction() const
void initFromMoveGroupNS()
rviz_common::DisplayContext * context_
Ui::MotionPlanningUI * ui_
~MotionPlanningFrame() override
MotionPlanningFrameJointsWidget * joints_tab_
MotionPlanningDisplay * planning_display_
MotionPlanningFrame(const MotionPlanningFrame &)=delete
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
const planning_scene_monitor::PlanningSceneMonitorPtr & getPlanningSceneMonitor()
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.
@ UPDATE_GEOMETRY
The geometry of the scene was updated. This includes receiving new octomaps, collision objects,...
std::shared_ptr< tf2_ros::Buffer > getSharedTF()
const std::string OBJECT_RECOGNITION_ACTION
const rclcpp::Logger LOGGER
Specification of options to use when constructing the MoveGroupInterface class.