moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
urdf_modifications_widget.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2022, Metro Robots
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 Metro Robots 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: David V. Lu!! */
36
39#include <QVBoxLayout>
40#include <QHBoxLayout>
41#include <QGroupBox>
42#include <QLabel>
43
44namespace moveit_setup
45{
46namespace controllers
47{
49{
50 QVBoxLayout* layout = new QVBoxLayout();
51
52 layout->setAlignment(Qt::AlignTop);
53
54 // Top Header Area ------------------------------------------------
55 auto header = new HeaderWidget("ros2_control URDF Modifications",
56 "This step can add the tags to the URDF required for interfacing with ros2_control. "
57 "See https://control.ros.org/ for more info.",
58 this);
59 layout->addWidget(header);
60 content_widget_ = new QWidget(this);
61 layout->addWidget(content_widget_);
62
63 setLayout(layout);
64}
65
66QWidget* UrdfModificationsWidget::makeInterfacesBox(const std::string& interface_type,
67 const std::vector<std::string>& available_interfaces,
68 const std::vector<std::string>& selected_interfaces,
69 QWidget* parent)
70{
71 QGroupBox* box = new QGroupBox((interface_type + " Interfaces").c_str(), parent);
72 QVBoxLayout* box_layout = new QVBoxLayout(parent);
73 for (const std::string& interface_name : available_interfaces)
74 {
75 QCheckBox* check = new QCheckBox(interface_name.c_str(), parent);
76 box_layout->addWidget(check);
77
78 std::string key = interface_type[0] + interface_name;
79 check_boxes_[key] = check;
80 }
81 for (const std::string& interface_name : selected_interfaces)
82 {
83 std::string key = interface_type[0] + interface_name;
84 check_boxes_[key]->setChecked(true);
85 }
86 box->setLayout(box_layout);
87 return box;
88}
89
91{
92 setup_step_.refresh();
93 qDeleteAll(content_widget_->children());
94 check_boxes_.clear();
95
96 QVBoxLayout* layout = new QVBoxLayout();
97 if (!setup_step_.needsModification())
98 {
99 layout->addWidget(new QLabel("All of the joints used by this MoveIt config have already been configured using\n"
100 "ros2_control, so there is no need to modify the URDF with ros2_control tags."));
101 content_widget_->setLayout(layout);
102 return;
103 }
104
105 QWidget* interface_widget = new QWidget(this);
106 QHBoxLayout* interface_layout = new QHBoxLayout();
107
108 auto available_interfaces = setup_step_.getAvailableControlInterfaces(),
109 selected_interfaces = setup_step_.getDefaultControlInterfaces();
110
111 interface_layout->addWidget(makeInterfacesBox("Command", available_interfaces.command_interfaces,
112 selected_interfaces.command_interfaces, interface_widget));
113 interface_layout->addWidget(makeInterfacesBox("State", available_interfaces.state_interfaces,
114 selected_interfaces.state_interfaces, interface_widget));
115
116 interface_widget->setLayout(interface_layout);
117 layout->addWidget(interface_widget);
118
119 btn_add_interfaces_ = new QPushButton("Add interfaces");
120 connect(btn_add_interfaces_, SIGNAL(clicked()), this, SLOT(addInterfaces()));
121 layout->addWidget(btn_add_interfaces_);
122
123 generated_text_widget_ = new QTextEdit();
124 generated_text_widget_->setReadOnly(true);
125 generated_text_widget_->setText(setup_step_.getJointsXML().c_str());
126 layout->addWidget(generated_text_widget_);
127 content_widget_->setLayout(layout);
128}
129
130std::vector<std::string> UrdfModificationsWidget::getInterfaces(const char first_letter,
131 const std::vector<std::string>& available_interfaces)
132{
133 std::vector<std::string> interface_names;
134 for (const std::string& interface_name : available_interfaces)
135 {
136 std::string key = first_letter + interface_name;
137 if (check_boxes_[key]->isChecked())
138 {
139 interface_names.push_back(interface_name);
140 }
141 }
142 return interface_names;
143}
144
145void UrdfModificationsWidget::addInterfaces()
146{
147 auto available_interfaces = setup_step_.getAvailableControlInterfaces();
148 setup_step_.setInterfaces(getInterfaces('C', available_interfaces.command_interfaces),
149 getInterfaces('S', available_interfaces.state_interfaces));
150 generated_text_widget_->setText(setup_step_.getJointsXML().c_str());
151}
152
153} // namespace controllers
154} // namespace moveit_setup
155
156#include <pluginlib/class_list_macros.hpp> // NOLINT
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
The GUI code for one SetupStep.
void focusGiven() override
function called when widget is activated, allows to update/initialize GUI
const ControlInterfaces & getDefaultControlInterfaces() const
bool needsModification() const
Return true if there aren't ros2_control tags for all the joints.
const ControlInterfaces & getAvailableControlInterfaces() const
void setInterfaces(const std::vector< std::string > &command_interfaces, const std::vector< std::string > &state_interfaces)
Add ros2_control tags for all unconfigured joints with the specified interfaces.