40 #include <moveit_msgs/msg/joint_limits.hpp>
42 #include <QApplication>
44 #include <QDoubleValidator>
45 #include <QFormLayout>
48 #include <QMessageBox>
49 #include <QPushButton>
50 #include <QScrollArea>
52 #include <QStackedWidget>
53 #include <QTableWidget>
68 QVBoxLayout* layout =
new QVBoxLayout();
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.",
77 layout->addWidget(header);
96 QWidget* RobotPosesWidget::createContentsWidget()
99 QWidget* content_widget =
new QWidget(
this);
102 QVBoxLayout* layout =
new QVBoxLayout(
this);
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)));
115 QStringList header_list;
116 header_list.append(
"Pose Name");
117 header_list.append(
"Group Name");
118 data_table_->setHorizontalHeaderLabels(header_list);
122 QHBoxLayout* controls_layout =
new QHBoxLayout();
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);
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);
141 controls_layout->addItem(
new QSpacerItem(20, 20, QSizePolicy::Expanding, QSizePolicy::Minimum));
144 btn_edit_ =
new QPushButton(
"&Edit Selected",
this);
145 btn_edit_->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
148 connect(
btn_edit_, SIGNAL(clicked()),
this, SLOT(editSelected()));
150 controls_layout->setAlignment(
btn_edit_, Qt::AlignRight);
153 btn_delete_ =
new QPushButton(
"&Delete Selected",
this);
154 connect(
btn_delete_, SIGNAL(clicked()),
this, SLOT(deleteSelected()));
156 controls_layout->setAlignment(
btn_delete_, Qt::AlignRight);
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);
167 layout->addLayout(controls_layout);
170 content_widget->setLayout(layout);
172 return content_widget;
178 QWidget* RobotPosesWidget::createEditWidget()
181 QWidget* edit_widget =
new QWidget(
this);
183 QVBoxLayout* layout =
new QVBoxLayout();
187 QHBoxLayout* columns_layout =
new QHBoxLayout();
188 QVBoxLayout* column1 =
new QVBoxLayout();
194 QFormLayout* form_layout =
new QFormLayout();
196 form_layout->setRowWrapPolicy(QFormLayout::WrapAllRows);
207 connect(
group_name_field_, SIGNAL(currentIndexChanged(
const QString&)),
this, SLOT(loadJointSliders(
const QString&)));
212 collision_warning_ =
new QLabel(
"<font color='red'><b>Robot in Collision State</b></font>",
this);
217 column1->addLayout(form_layout);
218 columns_layout->addLayout(column1);
232 columns_layout->addLayout(
column2_);
235 layout->addLayout(columns_layout);
239 QHBoxLayout* controls_layout =
new QHBoxLayout();
240 controls_layout->setContentsMargins(0, 25, 0, 15);
243 controls_layout->addItem(
new QSpacerItem(20, 20, QSizePolicy::Expanding, QSizePolicy::Minimum));
246 btn_save_ =
new QPushButton(
"&Save",
this);
248 connect(
btn_save_, SIGNAL(clicked()),
this, SLOT(doneEditing()));
250 controls_layout->setAlignment(
btn_save_, Qt::AlignRight);
255 connect(
btn_cancel_, SIGNAL(clicked()),
this, SLOT(cancelEditing()));
257 controls_layout->setAlignment(
btn_cancel_, Qt::AlignRight);
260 layout->addLayout(controls_layout);
263 edit_widget->setLayout(layout);
271 void RobotPosesWidget::showNewScreen()
277 current_edit_pose_ =
nullptr;
293 void RobotPosesWidget::editDoubleClicked(
int ,
int )
302 void RobotPosesWidget::previewClicked(
int row,
int ,
int ,
int )
305 QTableWidgetItem* group =
data_table_->item(row, 1);
311 srdf::Model::GroupState* pose = setup_step_.
findPoseByName(
name->text().toStdString(), group->text().toStdString());
320 void RobotPosesWidget::showPose(
const srdf::Model::GroupState& pose)
324 for (
const auto& key_value_pair : pose.joint_values_)
330 updateStateAndCollision(robot_state);
342 void RobotPosesWidget::showDefaultPose()
348 updateStateAndCollision(robot_state);
357 void RobotPosesWidget::playPoses()
359 using namespace std::chrono_literals;
362 for (
const srdf::Model::GroupState& pose : setup_step_.getGroupStates())
364 RCLCPP_INFO_STREAM(setup_step_.getLogger(),
"Showing pose " << pose.name_);
366 rclcpp::sleep_for(50000000ns);
367 QApplication::processEvents();
368 rclcpp::sleep_for(450000000ns);
375 void RobotPosesWidget::editSelected()
377 const auto& ranges =
data_table_->selectedRanges();
380 edit(ranges[0].bottomRow());
386 void RobotPosesWidget::edit(
int row)
388 const std::string&
name =
data_table_->item(row, 0)->text().toStdString();
389 const std::string& group =
data_table_->item(row, 1)->text().toStdString();
393 current_edit_pose_ = pose;
402 QMessageBox::critical(
this,
"Error Loading",
"Unable to find group name in drop down box");
416 loadJointSliders(QString(pose->group_.c_str()));
422 void RobotPosesWidget::loadGroupsComboBox()
428 for (
const std::string& group_name : setup_step_.
getGroupNames())
437 void RobotPosesWidget::loadJointSliders(
const QString& selected)
445 const std::string group_name = selected.toStdString();
447 std::vector<const moveit::core::JointModel*> joint_models;
453 catch (
const std::runtime_error& e)
455 QMessageBox::critical(
this,
"Error Loading", QString(e.what()));
474 const auto& robot_state = setup_step_.
getState();
482 SliderWidget* sw =
new SliderWidget(
this, joint_model, init_value);
486 connect(sw, SIGNAL(jointValueChanged(
const std::string&,
double)),
this,
487 SLOT(updateRobotModel(
const std::string&,
double)));
494 updateStateAndCollision(robot_state);
504 void RobotPosesWidget::deleteSelected()
506 const auto& ranges =
data_table_->selectedRanges();
509 int row = ranges[0].bottomRow();
511 const std::string&
name =
data_table_->item(row, 0)->text().toStdString();
512 const std::string& group =
data_table_->item(row, 1)->text().toStdString();
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)
531 void RobotPosesWidget::doneEditing()
538 srdf::Model::GroupState* searched_data =
nullptr;
543 QMessageBox::warning(
this,
"Error Saving",
"A name must be given for the pose!");
550 QMessageBox::warning(
this,
"Error Saving",
"A planning group must be chosen!");
556 if (!current_edit_pose_)
559 if (searched_data != current_edit_pose_)
561 if (QMessageBox::warning(
this,
"Warning Saving",
"A pose already exists with that name! Overwrite?",
562 QMessageBox::Yes | QMessageBox::No, QMessageBox::No) == QMessageBox::No)
567 searched_data = current_edit_pose_;
572 if (searched_data ==
nullptr)
575 searched_data =
new srdf::Model::GroupState();
579 searched_data->name_ =
name;
580 searched_data->group_ = group;
588 delete searched_data;
606 void RobotPosesWidget::cancelEditing()
618 void RobotPosesWidget::loadDataTable()
625 std::vector<srdf::Model::GroupState>& group_states = setup_step_.
getGroupStates();
632 for (
const auto& group_state : group_states)
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);
657 if (!group_states.empty())
675 loadGroupsComboBox();
681 void RobotPosesWidget::updateRobotModel(
const std::string&
name,
double value)
687 updateStateAndCollision(robot_state);
709 : QWidget(parent), joint_model_(joint_model)
712 QVBoxLayout* layout =
new QVBoxLayout();
713 QHBoxLayout* row2 =
new QHBoxLayout();
733 connect(
joint_value_, SIGNAL(editingFinished()),
this, SLOT(changeJointSlider()));
737 const std::vector<moveit_msgs::msg::JointLimits>& limits = joint_model_->
getVariableBoundsMsg();
740 QMessageBox::critical(
this,
"Error Loading",
"An internal error has occurred while loading the joints");
745 moveit_msgs::msg::JointLimits joint_limit = limits[0];
746 max_position_ = joint_limit.max_position;
747 min_position_ = joint_limit.min_position;
754 connect(
joint_slider_, SIGNAL(valueChanged(
int)),
this, SLOT(changeJointValue(
int)));
757 int value = init_value * 10000;
759 changeJointValue(value);
762 layout->addLayout(row2);
764 setContentsMargins(0, 0, 0, 0);
766 setGeometry(QRect(110, 80, 120, 80));
770 qRegisterMetaType<std::string>(
"std::string");
781 void SliderWidget::changeJointValue(
int value)
784 const double double_value = double(value) / 10000;
787 joint_value_->setText(QString(
"%1").arg(double_value, 0,
'f', 4));
796 void SliderWidget::changeJointSlider()
801 if (min_position_ > value || value > max_position_)
803 value = (min_position_ > value) ? min_position_ : max_position_;
804 joint_value_->setText(QString(
"%1").arg(value, 0,
'f', 4));
817 #include <pluginlib/class_list_macros.hpp>
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.
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)
void setToCurrentValues(srdf::Model::GroupState &group_state)
std::vector< srdf::Model::GroupState > & getGroupStates()
moveit::core::RobotState & getState()
void loadAllowedCollisionMatrix()
Load the allowed collision matrix from the SRDF's list of link pairs.
std::vector< std::string > getGroupNames() const
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.
void removePoseByName(const std::string &pose_name, const std::string &group_name)
std::string append(const std::string &left, const std::string &right)