robot_poses_widget.h
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 #ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_ROBOT_POSES_WIDGET_
38 #define MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_ROBOT_POSES_WIDGET_
39 
40 // Qt
41 #include <QWidget>
42 #include <QVBoxLayout>
43 #include <QHBoxLayout>
44 #include <QScrollArea>
45 #include <QGroupBox>
46 #include <QLabel>
47 #include <QPushButton>
48 #include <QTableWidget>
49 #include <QStackedLayout>
50 #include <QString>
51 #include <QComboBox>
52 
53 // SA
54 #ifndef Q_MOC_RUN
56 #include <moveit/planning_scene/planning_scene.h> // for collision stuff
57 #include <ros/ros.h>
58 #endif
59 
60 #include "header_widget.h"
61 #include "setup_screen_widget.h" // a base class for screens in the setup assistant
62 
63 namespace moveit_setup_assistant
64 {
66 {
67  Q_OBJECT
68 
69 public:
70  // ******************************************************************************************
71  // Public Functions
72  // ******************************************************************************************
73 
74  RobotPosesWidget(QWidget* parent, moveit_setup_assistant::MoveItConfigDataPtr config_data);
75 
77  virtual void focusGiven();
78 
79  // ******************************************************************************************
80  // Qt Components
81  // ******************************************************************************************
82  QTableWidget* data_table_;
83  QPushButton* btn_edit_;
84  QPushButton* btn_delete_;
85  QPushButton* btn_save_;
86  QPushButton* btn_cancel_;
87  QStackedLayout* stacked_layout_;
88  QScrollArea* scroll_area_;
89  QVBoxLayout* column2_;
90  QLineEdit* pose_name_field_;
91  QComboBox* group_name_field_;
93  QVBoxLayout* joint_list_layout_;
97 
98 private Q_SLOTS:
99 
100  // ******************************************************************************************
101  // Slot Event Functions
102  // ******************************************************************************************
103 
105  void showNewScreen();
106 
108  void editSelected();
109 
111  void editDoubleClicked(int row, int column);
112 
114  void previewClicked(int row, int column);
115 
117  void deleteSelected();
118 
120  void doneEditing();
121 
123  void cancelEditing();
124 
126  void loadJointSliders(const QString& selected);
127 
129  void showDefaultPose();
130 
132  void playPoses();
133 
140  void updateRobotModel(const std::string& name, double value);
141 
143  void publishJoints();
144 
145 private:
146  // ******************************************************************************************
147  // Variables
148  // ******************************************************************************************
149 
151  moveit_setup_assistant::MoveItConfigDataPtr config_data_;
152 
155 
157  std::map<std::string, double> joint_state_map_;
158 
160  std::vector<const robot_model::JointModel*> joint_models_;
161 
164 
165  // ******************************************************************************************
166  // Collision Variables
167  // ******************************************************************************************
169 
170  // ******************************************************************************************
171  // Private Functions
172  // ******************************************************************************************
173 
180  srdf::Model::GroupState* findPoseByName(const std::string& name, const std::string& group);
181 
187  QWidget* createContentsWidget();
188 
194  QWidget* createEditWidget();
195 
200  void loadDataTable();
201 
206  void loadGroupsComboBox();
207 
213  void edit(int row);
214 
218  void showPose(srdf::Model::GroupState* pose);
219 };
220 
221 // ******************************************************************************************
222 // ******************************************************************************************
223 // Slider Widget
224 // ******************************************************************************************
225 // ******************************************************************************************
226 class SliderWidget : public QWidget
227 {
228  Q_OBJECT
229 
230 public:
231  // ******************************************************************************************
232  // Public Functions
233  // ******************************************************************************************
234 
241  SliderWidget(QWidget* parent, const robot_model::JointModel* joint_model, double init_value);
242 
246  ~SliderWidget();
247 
248  // ******************************************************************************************
249  // Qt Components
250  // ******************************************************************************************
251 
252  QLabel* joint_label_;
253  QSlider* joint_slider_;
254  QLineEdit* joint_value_;
255 
256 private Q_SLOTS:
257 
258  // ******************************************************************************************
259  // Slot Event Functions
260  // ******************************************************************************************
261 
263  void changeJointValue(int value);
264 
266  void changeJointSlider();
267 
268 Q_SIGNALS:
269 
270  // ******************************************************************************************
271  // Emitted Signal Functions
272  // ******************************************************************************************
273 
275  void jointValueChanged(const std::string& name, double value);
276 
277 private:
278  // ******************************************************************************************
279  // Variables
280  // ******************************************************************************************
281 
282  // Ptr to the joint's data
283  const robot_model::JointModel* joint_model_;
284 
285  // Max & min position
288 
289  // ******************************************************************************************
290  // Private Functions
291  // ******************************************************************************************
292 };
293 
294 } // namespace
295 
296 // Declare std::string as metatype so we can use it in a signal
297 Q_DECLARE_METATYPE(std::string)
298 
299 #endif
srdf::Model::GroupState * current_edit_pose_
Pointer to currently edited group state.
void publishJoints()
Publishes a joint state message based on all the slider locations in a planning group, to rviz.
void deleteSelected()
Delete currently editing ite.
Q_DECLARE_METATYPE(PlanGroupType)
std::map< std::string, double > joint_state_map_
All the joint slider values that have thus far been seen. May contain more than just the current join...
RobotPosesWidget(QWidget *parent, moveit_setup_assistant::MoveItConfigDataPtr config_data)
void showPose(srdf::Model::GroupState *pose)
const robot_model::JointModel * joint_model_
void playPoses()
Play through the poses.
srdf::Model::GroupState * findPoseByName(const std::string &name, const std::string &group)
void editDoubleClicked(int row, int column)
Edit the double clicked element.
void editSelected()
Edit whatever element is selected.
virtual void focusGiven()
Received when this widget is chosen from the navigation menu.
void updateRobotModel(const std::string &name, double value)
std::vector< const robot_model::JointModel * > joint_models_
The joints currently in the selected planning group.
ros::Publisher pub_robot_state_
Remember the publisher for quick publishing later.
void previewClicked(int row, int column)
Preview whatever element is selected.
void showDefaultPose()
Show the robot in its default joint positions.
moveit_setup_assistant::MoveItConfigDataPtr config_data_
Contains all the configuration data for the setup assistant.
collision_detection::CollisionRequest request
void loadJointSliders(const QString &selected)
Run this whenever the group is changed.


moveit_setup_assistant
Author(s): Dave Coleman
autogenerated on Wed Jul 10 2019 04:04:34