44 #include <QMessageBox>
45 #include <QPushButton>
47 #include <QVBoxLayout>
51 #include <moveit_msgs/msg/display_robot_state.hpp>
65 QVBoxLayout* layout =
new QVBoxLayout();
66 layout->setAlignment(Qt::AlignTop);
71 "The following tool will auto-generate the URDF changes needed for Gazebo "
72 "compatibility with ROSControl and MoveIt. The needed changes are shown in green.",
74 layout->addWidget(header);
75 layout->addSpacerItem(
new QSpacerItem(1, 8, QSizePolicy::Fixed, QSizePolicy::Fixed));
78 QHBoxLayout* controls_layout =
new QHBoxLayout();
81 btn_overwrite_ =
new QPushButton(
"Over&write original URDF",
this);
82 btn_overwrite_->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
83 connect(btn_overwrite_, SIGNAL(clicked()),
this, SLOT(overwriteURDF()));
84 controls_layout->addWidget(btn_overwrite_);
86 btn_open_ =
new QPushButton(
"&Open original URDF",
this);
87 btn_open_->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
88 btn_open_->setToolTip(
"Open original URDF file in editor");
89 connect(btn_open_, SIGNAL(clicked()),
this, SLOT(openURDF()));
90 controls_layout->addWidget(btn_open_);
93 controls_layout->addItem(
new QSpacerItem(20, 20, QSizePolicy::Expanding, QSizePolicy::Fixed));
96 layout->addLayout(controls_layout);
99 no_changes_label_ =
new QLabel(
this);
100 no_changes_label_->setText(
"URDF is ready for Gazebo. No changes required.");
101 no_changes_label_->setFont(QFont(QFont().defaultFamily(), 18));
102 no_changes_label_->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Expanding);
103 no_changes_label_->setAlignment(Qt::AlignTop);
104 layout->addWidget(no_changes_label_);
107 simulation_text_ =
new QTextEdit(
this);
108 simulation_text_->setLineWrapMode(QTextEdit::NoWrap);
109 layout->addWidget(simulation_text_);
112 QTextCharFormat format;
113 format.setForeground(Qt::darkGreen);
114 highlighter->addTag(
"inertial", format);
115 highlighter->addTag(
"transmission", format);
116 highlighter->addTag(
"gazebo", format);
119 copy_urdf_ =
new QLabel(
this);
120 copy_urdf_->setText(
"<a href='contract'>Copy to Clipboard</a>");
121 connect(copy_urdf_, &QLabel::linkActivated,
this, &SimulationWidget::copyURDF);
122 layout->addWidget(copy_urdf_);
125 this->setLayout(layout);
130 if (!simulation_text_->document()->isEmpty())
133 simulation_text_->setVisible(
true);
136 simulation_text_->document()->setPlainText(QString::fromStdString(
text));
139 bool have_changes = !
text.empty();
140 config_data_->save_gazebo_urdf_ = have_changes;
143 simulation_text_->setVisible(have_changes);
144 btn_overwrite_->setVisible(have_changes);
145 btn_open_->setVisible(have_changes && !qgetenv(
"EDITOR").
isEmpty());
146 copy_urdf_->setVisible(have_changes);
147 no_changes_label_->setVisible(!have_changes);
150 btn_overwrite_->setDisabled(config_data_->urdf_from_xacro_);
152 if (btn_overwrite_->isEnabled())
153 tooltip = tr(
"Overwrite URDF in original location:\n").append(setup_step_.
getURDFPath().c_str());
155 tooltip = tr(
"Cannot overwrite original, <i>xacro-based</i> URDF");
156 btn_overwrite_->setToolTip(tooltip);
159 config_data_->changes |= MoveItConfigData::SIMULATION;
161 config_data_->changes &= ~MoveItConfigData::SIMULATION;
166 if (!config_data_->save_gazebo_urdf_)
170 std::string urdf = simulation_text_->document()->toPlainText().toStdString();
172 std::string error_description;
174 if (setup_step_.
isValidXML(urdf, error_row, error_description))
176 config_data_->gazebo_urdf_string_ = std::move(urdf);
181 QTextCursor cursor = simulation_text_->textCursor();
182 cursor.movePosition(QTextCursor::Start);
183 cursor.movePosition(QTextCursor::Down, QTextCursor::MoveAnchor, error_row);
184 simulation_text_->setTextCursor(cursor);
185 QMessageBox::warning(
this, tr(
"Gazebo URDF"), tr(
"Error parsing XML:\n").
append(error_description.c_str()));
186 simulation_text_->setFocus(Qt::OtherFocusReason);
194 void SimulationWidget::overwriteURDF()
200 QMessageBox::warning(
this,
"Gazebo URDF", tr(
"Failed to save to ").
append(config_data_->urdf_path_.c_str()));
202 QMessageBox::information(
this,
"Overwriting Successful",
203 "Original robot description URDF was successfully overwritten.");
206 config_data_->save_gazebo_urdf_ =
false;
207 config_data_->changes &= ~MoveItConfigData::SIMULATION;
210 void SimulationWidget::openURDF()
212 QProcess::startDetached(qgetenv(
"EDITOR"), { setup_step_.
getURDFPath().c_str() });
218 void SimulationWidget::copyURDF()
220 simulation_text_->selectAll();
221 simulation_text_->copy();
226 #include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
std::filesystem::path getURDFPath() const
bool isValidXML(const std::string &new_urdf_contents, int &error_row, std::string &error_description) const
Check if the given xml is valid.
bool outputGazeboURDFFile(const std::filesystem::path &file_path)
std::string getGazeboCompatibleURDF()
Parses the existing urdf and constructs a string from it with the elements required by gazebo simulat...
bool isEmpty(const moveit_msgs::msg::Constraints &constr)
Check if any constraints were specified.
std::string append(const std::string &left, const std::string &right)