moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
robot_poses_widget.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Dave Coleman */
36
37// SA
40#include <moveit_msgs/msg/joint_limits.hpp>
41// Qt
42#include <QApplication>
43#include <QComboBox>
44#include <QDoubleValidator>
45#include <QFormLayout>
46#include <QLabel>
47#include <QLineEdit>
48#include <QMessageBox>
49#include <QPushButton>
50#include <QScrollArea>
51#include <QSlider>
52#include <QStackedWidget>
53#include <QTableWidget>
54
55namespace moveit_setup
56{
57namespace srdf_setup
58{
59// ******************************************************************************************
60// Outer User Interface for MoveIt Configuration Assistant
61// ******************************************************************************************
63{
64 // Set pointer to null so later we can tell if we need to delete it
65 joint_list_layout_ = nullptr;
66
67 // Basic widget container
68 QVBoxLayout* layout = new QVBoxLayout();
69
70 // Top Header Area ------------------------------------------------
71
72 auto header = new HeaderWidget("Define Robot Poses",
73 "Create poses for the robot. Poses are defined as sets of joint values for particular "
74 "planning groups. This is useful for things like <i>home position</i>. The "
75 "<i>first</i> listed pose will be the robot's initial pose in simulation.",
76 this);
77 layout->addWidget(header);
78
79 // Create contents screens ---------------------------------------
80 pose_list_widget_ = createContentsWidget();
81 pose_edit_widget_ = createEditWidget();
82
83 // Create stacked layout -----------------------------------------
84 stacked_widget_ = new QStackedWidget(this);
85 stacked_widget_->addWidget(pose_list_widget_); // screen index 0
86 stacked_widget_->addWidget(pose_edit_widget_); // screen index 1
87 layout->addWidget(stacked_widget_);
88
89 // Finish Layout --------------------------------------------------
90 setLayout(layout);
91}
92
93// ******************************************************************************************
94// Create the main content widget
95// ******************************************************************************************
96QWidget* RobotPosesWidget::createContentsWidget()
97{
98 // Main widget
99 QWidget* content_widget = new QWidget(this);
100
101 // Basic widget container
102 QVBoxLayout* layout = new QVBoxLayout(this);
103
104 // Table ------------ ------------------------------------------------
105
106 data_table_ = new QTableWidget(this);
107 data_table_->setColumnCount(2);
108 data_table_->setSortingEnabled(true);
109 data_table_->setSelectionBehavior(QAbstractItemView::SelectRows);
110 connect(data_table_, SIGNAL(cellDoubleClicked(int, int)), this, SLOT(editDoubleClicked(int, int)));
111 connect(data_table_, SIGNAL(currentCellChanged(int, int, int, int)), this, SLOT(previewClicked(int, int, int, int)));
112 layout->addWidget(data_table_);
113
114 // Set header labels
115 QStringList header_list;
116 header_list.append("Pose Name");
117 header_list.append("Group Name");
118 data_table_->setHorizontalHeaderLabels(header_list);
119
120 // Bottom Buttons --------------------------------------------------
121
122 QHBoxLayout* controls_layout = new QHBoxLayout();
123
124 // Set Default Button
125 QPushButton* btn_default = new QPushButton("&Show Default Pose", this);
126 btn_default->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
127 btn_default->setMaximumWidth(300);
128 connect(btn_default, SIGNAL(clicked()), this, SLOT(showDefaultPose()));
129 controls_layout->addWidget(btn_default);
130 controls_layout->setAlignment(btn_default, Qt::AlignLeft);
131
132 // Set play button
133 QPushButton* btn_play = new QPushButton("&MoveIt", this);
134 btn_play->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
135 btn_play->setMaximumWidth(300);
136 connect(btn_play, SIGNAL(clicked()), this, SLOT(playPoses()));
137 controls_layout->addWidget(btn_play);
138 controls_layout->setAlignment(btn_play, Qt::AlignLeft);
139
140 // Spacer
141 controls_layout->addItem(new QSpacerItem(20, 20, QSizePolicy::Expanding, QSizePolicy::Minimum));
142
143 // Edit Selected Button
144 btn_edit_ = new QPushButton("&Edit Selected", this);
145 btn_edit_->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
146 btn_edit_->setMaximumWidth(300);
147 btn_edit_->hide(); // show once we know if there are existing poses
148 connect(btn_edit_, SIGNAL(clicked()), this, SLOT(editSelected()));
149 controls_layout->addWidget(btn_edit_);
150 controls_layout->setAlignment(btn_edit_, Qt::AlignRight);
151
152 // Delete
153 btn_delete_ = new QPushButton("&Delete Selected", this);
154 connect(btn_delete_, SIGNAL(clicked()), this, SLOT(deleteSelected()));
155 controls_layout->addWidget(btn_delete_);
156 controls_layout->setAlignment(btn_delete_, Qt::AlignRight);
157
158 // Add Group Button
159 QPushButton* btn_add = new QPushButton("&Add Pose", this);
160 btn_add->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
161 btn_add->setMaximumWidth(300);
162 connect(btn_add, SIGNAL(clicked()), this, SLOT(showNewScreen()));
163 controls_layout->addWidget(btn_add);
164 controls_layout->setAlignment(btn_add, Qt::AlignRight);
165
166 // Add layout
167 layout->addLayout(controls_layout);
168
169 // Set layout -----------------------------------------------------
170 content_widget->setLayout(layout);
171
172 return content_widget;
173}
174
175// ******************************************************************************************
176// Create the edit widget
177// ******************************************************************************************
178QWidget* RobotPosesWidget::createEditWidget()
179{
180 // Main widget
181 QWidget* edit_widget = new QWidget(this);
182 // Layout
183 QVBoxLayout* layout = new QVBoxLayout();
184
185 // 2 columns -------------------------------------------------------
186
187 QHBoxLayout* columns_layout = new QHBoxLayout();
188 QVBoxLayout* column1 = new QVBoxLayout();
189 column2_ = new QVBoxLayout();
190
191 // Column 1 --------------------------------------------------------
192
193 // Simple form -------------------------------------------
194 QFormLayout* form_layout = new QFormLayout();
195 // form_layout->setContentsMargins( 0, 15, 0, 15 );
196 form_layout->setRowWrapPolicy(QFormLayout::WrapAllRows);
197
198 // Name input
199 pose_name_field_ = new QLineEdit(this);
200 // pose_name_field_->setMaximumWidth( 300 );
201 form_layout->addRow("Pose Name:", pose_name_field_);
202
203 // Group name input
204 group_name_field_ = new QComboBox(this);
205 group_name_field_->setEditable(false);
206 // Connect the signal for changes to the drop down box
207 connect(group_name_field_, SIGNAL(currentIndexChanged(const QString&)), this, SLOT(loadJointSliders(const QString&)));
208 // group_name_field_->setMaximumWidth( 300 );
209 form_layout->addRow("Planning Group:", group_name_field_);
210
211 // Indicator that robot is in collision or not
212 collision_warning_ = new QLabel("<font color='red'><b>Robot in Collision State</b></font>", this);
213 collision_warning_->setTextFormat(Qt::RichText);
214 collision_warning_->hide(); // show later
215 form_layout->addRow(" ", collision_warning_);
216
217 column1->addLayout(form_layout);
218 columns_layout->addLayout(column1);
219
220 // Column 2 --------------------------------------------------------
221
222 // Box to hold joint sliders
223 joint_list_widget_ = new QWidget(this);
224
225 // Create scroll area
226 scroll_area_ = new QScrollArea(this);
227 // scroll_area_->setBackgroundRole(QPalette::Dark);
229
230 column2_->addWidget(scroll_area_);
231
232 columns_layout->addLayout(column2_);
233
234 // Set columns in main layout
235 layout->addLayout(columns_layout);
236
237 // Bottom Buttons --------------------------------------------------
238
239 QHBoxLayout* controls_layout = new QHBoxLayout();
240 controls_layout->setContentsMargins(0, 25, 0, 15);
241
242 // Spacer
243 controls_layout->addItem(new QSpacerItem(20, 20, QSizePolicy::Expanding, QSizePolicy::Minimum));
244
245 // Save
246 btn_save_ = new QPushButton("&Save", this);
247 btn_save_->setMaximumWidth(200);
248 connect(btn_save_, SIGNAL(clicked()), this, SLOT(doneEditing()));
249 controls_layout->addWidget(btn_save_);
250 controls_layout->setAlignment(btn_save_, Qt::AlignRight);
251
252 // Cancel
253 btn_cancel_ = new QPushButton("&Cancel", this);
254 btn_cancel_->setMaximumWidth(200);
255 connect(btn_cancel_, SIGNAL(clicked()), this, SLOT(cancelEditing()));
256 controls_layout->addWidget(btn_cancel_);
257 controls_layout->setAlignment(btn_cancel_, Qt::AlignRight);
258
259 // Add layout
260 layout->addLayout(controls_layout);
261
262 // Set layout -----------------------------------------------------
263 edit_widget->setLayout(layout);
264
265 return edit_widget;
266}
267
268// ******************************************************************************************
269// Show edit screen for creating a new pose
270// ******************************************************************************************
271void RobotPosesWidget::showNewScreen()
272{
273 // Switch to screen - do this before clearEditText()
274 stacked_widget_->setCurrentIndex(1);
275
276 // Remember that this is a new pose
277 current_edit_pose_ = nullptr;
278
279 // Manually send the load joint sliders signal
280 if (!group_name_field_->currentText().isEmpty())
281 loadJointSliders(group_name_field_->currentText());
282
283 // Clear previous data
284 pose_name_field_->setText("");
285
286 // Announce that this widget is in modal mode
287 Q_EMIT setModalMode(true);
288}
289
290// ******************************************************************************************
291// Edit whatever element is selected
292// ******************************************************************************************
293void RobotPosesWidget::editDoubleClicked(int /*row*/, int /*column*/)
294{
295 // We'll just base the edit on the selection highlight
296 editSelected();
297}
298
299// ******************************************************************************************
300// Preview whatever element is selected
301// ******************************************************************************************
302void RobotPosesWidget::previewClicked(int row, int /*column*/, int /*previous_row*/, int /*previous_column*/)
303{
304 QTableWidgetItem* name = data_table_->item(row, 0);
305 QTableWidgetItem* group = data_table_->item(row, 1);
306
307 // nullptr check before dereferencing
308 if (name && group)
309 {
310 // Find the selected in datastructure
311 srdf::Model::GroupState* pose = setup_step_.findPoseByName(name->text().toStdString(), group->text().toStdString());
312
313 showPose(*pose);
314 }
315}
316
317// ******************************************************************************************
318// Show the robot in the current pose
319// ******************************************************************************************
320void RobotPosesWidget::showPose(const srdf::Model::GroupState& pose)
321{
322 // Set the joints based on the SRDF pose
323 moveit::core::RobotState& robot_state = setup_step_.getState();
324 for (const auto& key_value_pair : pose.joint_values_)
325 {
326 robot_state.setJointPositions(key_value_pair.first, key_value_pair.second);
327 }
328
329 // Update the joints
330 updateStateAndCollision(robot_state);
331
332 // Unhighlight all links
334
335 // Highlight group
336 rviz_panel_->highlightGroup(pose.group_);
337}
338
339// ******************************************************************************************
340// Show the robot in its default joint positions
341// ******************************************************************************************
342void RobotPosesWidget::showDefaultPose()
343{
344 moveit::core::RobotState& robot_state = setup_step_.getState();
345 robot_state.setToDefaultValues();
346
347 // Update the joints
348 updateStateAndCollision(robot_state);
349
350 // Unhighlight all links
352}
353
354// ******************************************************************************************
355// Play through the poses
356// ******************************************************************************************
357void RobotPosesWidget::playPoses()
358{
359 using namespace std::chrono_literals;
360
361 // Loop through each pose and play them
362 for (const srdf::Model::GroupState& pose : setup_step_.getGroupStates())
363 {
364 RCLCPP_INFO_STREAM(setup_step_.getLogger(), "Showing pose " << pose.name_);
365 showPose(pose);
366 rclcpp::sleep_for(50000000ns); // 0.05 s
367 QApplication::processEvents();
368 rclcpp::sleep_for(450000000ns); // 0.45 s
369 }
370}
371
372// ******************************************************************************************
373// Edit whatever element is selected
374// ******************************************************************************************
375void RobotPosesWidget::editSelected()
376{
377 const auto& ranges = data_table_->selectedRanges();
378 if (ranges.empty())
379 return;
380 edit(ranges[0].bottomRow());
381}
382
383// ******************************************************************************************
384// Edit pose
385// ******************************************************************************************
386void RobotPosesWidget::edit(int row)
387{
388 const std::string& name = data_table_->item(row, 0)->text().toStdString();
389 const std::string& group = data_table_->item(row, 1)->text().toStdString();
390
391 // Find the selected in datastruture
392 srdf::Model::GroupState* pose = setup_step_.findPoseByName(name, group);
393 current_edit_pose_ = pose;
394
395 // Set pose name
396 pose_name_field_->setText(pose->name_.c_str());
397
398 // Set group:
399 int index = group_name_field_->findText(pose->group_.c_str());
400 if (index == -1)
401 {
402 QMessageBox::critical(this, "Error Loading", "Unable to find group name in drop down box");
403 return;
404 }
405 group_name_field_->setCurrentIndex(index);
406
407 showPose(*pose);
408
409 // Switch to screen - do this before setCurrentIndex
410 stacked_widget_->setCurrentIndex(1);
411
412 // Announce that this widget is in modal mode
413 Q_EMIT setModalMode(true);
414
415 // Manually send the load joint sliders signal
416 loadJointSliders(QString(pose->group_.c_str()));
417}
418
419// ******************************************************************************************
420// Populate the combo dropdown box with avail group names
421// ******************************************************************************************
422void RobotPosesWidget::loadGroupsComboBox()
423{
424 // Remove all old groups
425 group_name_field_->clear();
426
427 // Add all group names to combo box
428 for (const std::string& group_name : setup_step_.getGroupNames())
429 {
430 group_name_field_->addItem(group_name.c_str());
431 }
432}
433
434// ******************************************************************************************
435// Load the joint sliders based on group selected from combo box
436// ******************************************************************************************
437void RobotPosesWidget::loadJointSliders(const QString& selected)
438{
439 // Ignore this event if the combo box is empty. This occurs when clearing the combo box and reloading with the
440 // newest groups. Also ignore if we are not on the edit screen
441 if (!group_name_field_->count() || selected.isEmpty() || stacked_widget_->currentIndex() == 0)
442 return;
443
444 // Get group name from input
445 const std::string group_name = selected.toStdString();
446
447 std::vector<const moveit::core::JointModel*> joint_models;
448
449 try
450 {
451 joint_models = setup_step_.getSimpleJointModels(group_name);
452 }
453 catch (const std::runtime_error& e)
454 {
455 QMessageBox::critical(this, "Error Loading", QString(e.what()));
456 return;
457 }
458
459 // Delete old sliders from joint_list_layout_ if this has been loaded before
461 {
462 delete joint_list_layout_;
463 qDeleteAll(joint_list_widget_->children());
464 }
465
466 // Create layout again
467 joint_list_layout_ = new QVBoxLayout();
469 // joint_list_widget_->setSizePolicy( QSizePolicy::Expanding, QSizePolicy::Expanding );
470 joint_list_widget_->setSizePolicy(QSizePolicy::Ignored, QSizePolicy::Ignored);
471 joint_list_widget_->setMinimumSize(50, 50); // w, h
472
473 // Get list of associated joints
474 const auto& robot_state = setup_step_.getState();
475
476 // Iterate through the joints
477 for (const moveit::core::JointModel* joint_model : joint_models)
478 {
479 double init_value = robot_state.getVariablePosition(joint_model->getVariableNames()[0]);
480
481 // For each joint in group add slider
482 SliderWidget* sw = new SliderWidget(this, joint_model, init_value);
483 joint_list_layout_->addWidget(sw);
484
485 // Connect value change event
486 connect(sw, SIGNAL(jointValueChanged(const std::string&, double)), this,
487 SLOT(updateRobotModel(const std::string&, double)));
488 }
489
490 // Copy the width of column 2 and manually calculate height from number of joints
491 joint_list_widget_->resize(300, joint_models.size() * 70); // w, h
492
493 // Update the robot model in Rviz with newly selected joint values
494 updateStateAndCollision(robot_state);
495
496 // Highlight the planning group
498 rviz_panel_->highlightGroup(group_name);
499}
500
501// ******************************************************************************************
502// Delete currently editing item
503// ******************************************************************************************
504void RobotPosesWidget::deleteSelected()
505{
506 const auto& ranges = data_table_->selectedRanges();
507 if (ranges.empty())
508 return;
509 int row = ranges[0].bottomRow();
510
511 const std::string& name = data_table_->item(row, 0)->text().toStdString();
512 const std::string& group = data_table_->item(row, 1)->text().toStdString();
513
514 // Confirm user wants to delete group
515 if (QMessageBox::question(this, "Confirm Pose Deletion",
516 QString("Are you sure you want to delete the pose '").append(name.c_str()).append("'?"),
517 QMessageBox::Ok | QMessageBox::Cancel) == QMessageBox::Cancel)
518 {
519 return;
520 }
521
522 setup_step_.removePoseByName(name, group);
523
524 // Reload main screen table
525 loadDataTable();
526}
527
528// ******************************************************************************************
529// Save editing changes
530// ******************************************************************************************
531void RobotPosesWidget::doneEditing()
532{
533 // Get a reference to the supplied strings
534 const std::string& name = pose_name_field_->text().toStdString();
535 const std::string& group = group_name_field_->currentText().toStdString();
536
537 // Used for editing existing groups
538 srdf::Model::GroupState* searched_data = nullptr;
539
540 // Check that name field is not empty
541 if (name.empty())
542 {
543 QMessageBox::warning(this, "Error Saving", "A name must be given for the pose!");
544 pose_name_field_->setFocus();
545 return;
546 }
547 // Check that a group was selected
548 if (group.empty())
549 {
550 QMessageBox::warning(this, "Error Saving", "A planning group must be chosen!");
551 group_name_field_->setFocus();
552 return;
553 }
554
555 // If creating a new pose, check if the (name, group) pair already exists
556 if (!current_edit_pose_)
557 {
558 searched_data = setup_step_.findPoseByName(name, group);
559 if (searched_data != current_edit_pose_)
560 {
561 if (QMessageBox::warning(this, "Warning Saving", "A pose already exists with that name! Overwrite?",
562 QMessageBox::Yes | QMessageBox::No, QMessageBox::No) == QMessageBox::No)
563 return;
564 }
565 }
566 else
567 searched_data = current_edit_pose_; // overwrite edited pose
568
569 // Save the new pose name or create the new pose ----------------------------
570 bool is_new = false;
571
572 if (searched_data == nullptr) // create new
573 {
574 is_new = true;
575 searched_data = new srdf::Model::GroupState();
576 }
577
578 // Copy name data ----------------------------------------------------
579 searched_data->name_ = name;
580 searched_data->group_ = group;
581
582 setup_step_.setToCurrentValues(*searched_data);
583
584 // Insert new poses into group state vector --------------------------
585 if (is_new)
586 {
587 setup_step_.getGroupStates().push_back(*searched_data);
588 delete searched_data;
589 }
590
591 // Finish up ------------------------------------------------------
592
593 // Reload main screen table
594 loadDataTable();
595
596 // Switch to screen
597 stacked_widget_->setCurrentIndex(0);
598
599 // Announce that this widget is done with modal mode
600 Q_EMIT setModalMode(false);
601}
602
603// ******************************************************************************************
604// Cancel changes
605// ******************************************************************************************
606void RobotPosesWidget::cancelEditing()
607{
608 // Switch to screen
609 stacked_widget_->setCurrentIndex(0);
610
611 // Announce that this widget is done with modal mode
612 Q_EMIT setModalMode(false);
613}
614
615// ******************************************************************************************
616// Load the robot poses into the table
617// ******************************************************************************************
618void RobotPosesWidget::loadDataTable()
619{
620 // Disable Table
621 data_table_->setUpdatesEnabled(false); // prevent table from updating until we are completely done
622 data_table_->setDisabled(true); // make sure we disable it so that the cellChanged event is not called
623 data_table_->clearContents();
624
625 std::vector<srdf::Model::GroupState>& group_states = setup_step_.getGroupStates();
626
627 // Set size of datatable
628 data_table_->setRowCount(group_states.size());
629
630 // Loop through every pose
631 int row = 0;
632 for (const auto& group_state : group_states)
633 {
634 // Create row elements
635 QTableWidgetItem* data_name = new QTableWidgetItem(group_state.name_.c_str());
636 data_name->setFlags(Qt::ItemIsEnabled | Qt::ItemIsSelectable);
637 QTableWidgetItem* group_name = new QTableWidgetItem(group_state.group_.c_str());
638 group_name->setFlags(Qt::ItemIsEnabled | Qt::ItemIsSelectable);
639
640 // Add to table
641 data_table_->setItem(row, 0, data_name);
642 data_table_->setItem(row, 1, group_name);
643
644 // Increment counter
645 ++row;
646 }
647
648 // Re-enable
649 data_table_->setUpdatesEnabled(true); // prevent table from updating until we are completely done
650 data_table_->setDisabled(false); // make sure we disable it so that the cellChanged event is not called
651
652 // Resize header
653 data_table_->resizeColumnToContents(0);
654 data_table_->resizeColumnToContents(1);
655
656 // Show edit button if applicable
657 if (!group_states.empty())
658 btn_edit_->show();
659}
660
661// ******************************************************************************************
662// Called when setup assistant navigation switches to this screen
663// ******************************************************************************************
665{
666 setup_step_.loadAllowedCollisionMatrix();
667
668 // Show the current poses screen
669 stacked_widget_->setCurrentIndex(0);
670
671 // Load the data to the tree
672 loadDataTable();
673
674 // Load the avail groups to the combo box
675 loadGroupsComboBox();
676}
677
678// ******************************************************************************************
679// Call when one of the sliders has its value changed
680// ******************************************************************************************
681void RobotPosesWidget::updateRobotModel(const std::string& name, double value)
682{
683 moveit::core::RobotState& robot_state = setup_step_.getState();
684 robot_state.setVariablePosition(name, value);
685
686 // Update the robot model/rviz
687 updateStateAndCollision(robot_state);
688}
689
690void RobotPosesWidget::updateStateAndCollision(const moveit::core::RobotState& robot_state)
691{
692 setup_step_.publishState(robot_state);
693
694 // if in collision, show warning
695 // if no collision, hide warning
696 collision_warning_->setHidden(!setup_step_.checkSelfCollision(robot_state));
697}
698
699// ******************************************************************************************
700// ******************************************************************************************
701// Slider Widget
702// ******************************************************************************************
703// ******************************************************************************************
704
705// ******************************************************************************************
706// Simple widget for adjusting joints of a robot
707// ******************************************************************************************
708SliderWidget::SliderWidget(QWidget* parent, const moveit::core::JointModel* joint_model, double init_value)
709 : QWidget(parent), joint_model_(joint_model)
710{
711 // Create layouts
712 QVBoxLayout* layout = new QVBoxLayout();
713 QHBoxLayout* row2 = new QHBoxLayout();
714
715 // Row 1
716 joint_label_ = new QLabel(joint_model_->getName().c_str(), this);
717 joint_label_->setContentsMargins(0, 0, 0, 0);
718 layout->addWidget(joint_label_);
719
720 // Row 2 -------------------------------------------------------------
721 joint_slider_ = new QSlider(Qt::Horizontal, this);
722 joint_slider_->setTickPosition(QSlider::TicksBelow);
723 joint_slider_->setSingleStep(10);
724 joint_slider_->setPageStep(500);
725 joint_slider_->setTickInterval(1000);
726 joint_slider_->setContentsMargins(0, 0, 0, 0);
727 row2->addWidget(joint_slider_);
728
729 // Joint Value Box ------------------------------------------------
730 joint_value_ = new QLineEdit(this);
731 joint_value_->setMaximumWidth(62);
732 joint_value_->setContentsMargins(0, 0, 0, 0);
733 connect(joint_value_, SIGNAL(editingFinished()), this, SLOT(changeJointSlider()));
734 row2->addWidget(joint_value_);
735
736 // Joint Limits ----------------------------------------------------
737 const std::vector<moveit_msgs::msg::JointLimits>& limits = joint_model_->getVariableBoundsMsg();
738 if (limits.empty())
739 {
740 QMessageBox::critical(this, "Error Loading", "An internal error has occurred while loading the joints");
741 return;
742 }
743
744 // Only use the first limit, because there is only 1 variable (as checked earlier)
745 moveit_msgs::msg::JointLimits joint_limit = limits[0];
746 max_position_ = joint_limit.max_position;
747 min_position_ = joint_limit.min_position;
748
749 // Set the slider limits
750 joint_slider_->setMaximum(max_position_ * 10000);
751 joint_slider_->setMinimum(min_position_ * 10000);
752
753 // Connect slider to joint value box
754 connect(joint_slider_, SIGNAL(valueChanged(int)), this, SLOT(changeJointValue(int)));
755
756 // Initial joint values -------------------------------------------
757 int value = init_value * 10000; // scale double to integer for slider use
758 joint_slider_->setSliderPosition(value); // set slider value
759 changeJointValue(value); // show in textbox
760
761 // Finish GUI ----------------------------------------
762 layout->addLayout(row2);
763
764 setContentsMargins(0, 0, 0, 0);
765 // setSizePolicy( QSizePolicy::Expanding, QSizePolicy::Preferred );
766 setGeometry(QRect(110, 80, 120, 80));
767 setLayout(layout);
768
769 // Declare std::string as metatype so we can use it in a signal
770 qRegisterMetaType<std::string>("std::string");
771}
772
773// ******************************************************************************************
774// Deconstructor
775// ******************************************************************************************
777
778// ******************************************************************************************
779// Called when the joint value slider is changed
780// ******************************************************************************************
781void SliderWidget::changeJointValue(int value)
782{
783 // Get joint value
784 const double double_value = double(value) / 10000;
785
786 // Set textbox
787 joint_value_->setText(QString("%1").arg(double_value, 0, 'f', 4));
788
789 // Send event to parent widget
790 Q_EMIT jointValueChanged(joint_model_->getName(), double_value);
791}
792
793// ******************************************************************************************
794// Called when the joint value box is changed
795// ******************************************************************************************
796void SliderWidget::changeJointSlider()
797{
798 // Get joint value
799 double value = joint_value_->text().toDouble();
800
801 if (min_position_ > value || value > max_position_)
802 {
803 value = (min_position_ > value) ? min_position_ : max_position_;
804 joint_value_->setText(QString("%1").arg(value, 0, 'f', 4));
805 }
806
807 // We assume it converts to double because of the validator
808 joint_slider_->setSliderPosition(value * 10000);
809
810 // Send event to parent widget
811 Q_EMIT jointValueChanged(joint_model_->getName(), value);
812}
813
814} // namespace srdf_setup
815} // namespace moveit_setup
816
817#include <pluginlib/class_list_macros.hpp> // NOLINT
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
const std::vector< moveit_msgs::msg::JointLimits > & getVariableBoundsMsg() const
Get the joint limits known to this model, as a message.
const std::string & getName() const
Get the name of the joint.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
void setVariablePosition(const std::string &variable, double value)
Set the position of a single variable. An exception is thrown if the variable name is not known.
double getVariablePosition(const std::string &variable) const
Get the position of a particular variable. An exception is thrown if the variable is not known.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
void setJointPositions(const std::string &joint_name, const double *position)
void highlightGroup(const std::string &group_name)
The GUI code for one SetupStep.
void setModalMode(bool isModal)
Event for when the current screen is in modal view. Disables the left navigation.
const rclcpp::Logger & getLogger() const
Makes a namespaced logger for this step available to the widget.
void focusGiven() override
Received when this widget is chosen from the navigation menu.
void setToCurrentValues(srdf::Model::GroupState &group_state)
moveit::core::RobotState & getState()
void loadAllowedCollisionMatrix()
Load the allowed collision matrix from the SRDF's list of link pairs.
std::vector< const moveit::core::JointModel * > getSimpleJointModels(const std::string &group_name) const
Returns a vector of joint models for the given group name.
void publishState(const moveit::core::RobotState &robot_state)
Publish the given state on the moveit_robot_state topic.
srdf::Model::GroupState * findPoseByName(const std::string &name, const std::string &group)
bool checkSelfCollision(const moveit::core::RobotState &robot_state)
Check if the given robot state is in collision.
std::vector< srdf::Model::GroupState > & getGroupStates()
void removePoseByName(const std::string &pose_name, const std::string &group_name)
SliderWidget(QWidget *parent, const moveit::core::JointModel *joint_model, double init_value)
void jointValueChanged(const std::string &name, double value)
Indicate joint name and value when slider widget changed.
std::string append(const std::string &left, const std::string &right)
name
Definition setup.py:7