handeye_control_widget.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, Intel Corporation.
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: Yu Yan */
36 
37 #pragma once
38 
39 // qt
40 #include <QFile>
41 #include <QLabel>
42 #include <QString>
43 #include <QTreeView>
44 #include <QComboBox>
45 #include <QGroupBox>
46 #include <QTextStream>
47 #include <QFileDialog>
48 #include <QHBoxLayout>
49 #include <QFormLayout>
50 #include <QVBoxLayout>
51 #include <QPushButton>
52 #include <QMessageBox>
53 #include <QProgressBar>
54 #include <QtConcurrent/QtConcurrent>
55 #include <QStandardItemModel>
56 
57 // ros
58 #include <tf2_eigen/tf2_eigen.h>
67 
68 #ifndef Q_MOC_RUN
69 #include <ros/ros.h>
70 #include <rviz/panel.h>
71 #endif
72 
73 #include <yaml-cpp/yaml.h>
74 
76 
77 namespace moveit_rviz_plugin
78 {
79 class HandEyeCalibrationDisplay;
80 
81 class ProgressBarWidget : public QWidget
82 {
83  Q_OBJECT
84 
85 public:
86  ProgressBarWidget(QWidget* parent, int min = 0, int max = 0, int value = 0);
87 
88  ~ProgressBarWidget() override = default;
89 
90  void setMax(int value);
91  void setMin(int value);
92  void setValue(int value);
93  int getValue();
94 
95  QLabel* name_label_;
96  QLabel* value_label_;
97  QLabel* max_label_;
98  QProgressBar* bar_;
99 };
100 
101 class ControlTabWidget : public QWidget
102 {
103  Q_OBJECT
104 
105  enum PLANNING_RESULT
106  {
107  SUCCESS = 0,
110  FAILURE_NO_PSM = 3,
114  };
115 
116 public:
117  explicit ControlTabWidget(HandEyeCalibrationDisplay* pdisplay, QWidget* parent = Q_NULLPTR);
119  {
120  tf_tools_.reset();
121  tf_buffer_.reset();
122  solver_.reset();
123  solver_plugins_loader_.reset();
124  move_group_.reset();
125  planning_scene_monitor_.reset();
126  }
127 
128  void loadWidget(const rviz::Config& config);
129  void saveWidget(rviz::Config& config);
130 
132 
133  void addPoseSampleToTreeView(const geometry_msgs::TransformStamped& camera_to_object_tf,
134  const geometry_msgs::TransformStamped& base_to_eef_tf, int id);
135 
136  bool loadSolverPlugin(std::vector<std::string>& plugins);
137 
138  bool createSolverInstance(const std::string& plugin_name);
139 
140  void fillSolverTypes(const std::vector<std::string>& plugins);
141 
142  std::string parseSolverName(const std::string& solver_name, char delimiter);
143 
145 
146  bool solveCameraRobotPose();
147 
148  bool frameNamesEmpty();
149 
151 
152  void computePlan();
153 
154  void computeExecution();
155 
157 
158 Q_SIGNALS:
159 
160  void sensorPoseUpdate(double x, double y, double z, double rx, double ry, double rz);
161 
162 public Q_SLOTS:
163 
164  void UpdateSensorMountType(int index);
165 
166  void updateFrameNames(std::map<std::string, std::string> names);
167 
168 private Q_SLOTS:
169 
170  void takeSampleBtnClicked(bool clicked);
171 
172  void clearSamplesBtnClicked(bool clicked);
173 
174  void solveBtnClicked(bool clicked);
175 
176  void saveCameraPoseBtnClicked(bool clicked);
177 
178  void loadSamplesBtnClicked(bool clicked);
179 
180  void saveSamplesBtnClicked(bool clicked);
181 
182  void planningGroupNameChanged(const QString& text);
183 
184  void setGroupName(const std::string& group_name);
185 
187 
188  void saveJointStateBtnClicked(bool clicked);
189 
190  void loadJointStateBtnClicked(bool clicked);
191 
192  void autoPlanBtnClicked(bool clicked);
193 
194  void autoExecuteBtnClicked(bool clicked);
195 
196  void autoSkipBtnClicked(bool clicked);
197 
198  void planFinished();
199 
200  void executeFinished();
201 
202 private:
204 
205  // **************************************************************
206  // Qt components
207  // **************************************************************
208 
209  QTreeView* sample_tree_view_;
211  QStandardItemModel* tree_view_model_;
212 
213  QComboBox* calibration_solver_;
214 
215  // Load & save pose samples and joint goals
216  QPushButton* save_joint_state_btn_;
217  QPushButton* load_joint_state_btn_;
218  QPushButton* save_camera_pose_btn_;
219  QPushButton* load_samples_btn_;
220  QPushButton* save_samples_btn_;
221 
222  // Manual calibration
223  QPushButton* take_sample_btn_;
224  QPushButton* reset_sample_btn_;
225  QPushButton* solve_btn_;
226 
227  // Auto calibration
228  QComboBox* group_name_;
229  QPushButton* auto_plan_btn_;
230  QPushButton* auto_execute_btn_;
231  QPushButton* auto_skip_btn_;
232 
233  // Progress of finished joint states for auto calibration
235 
236  QFutureWatcher<void>* plan_watcher_;
237  QFutureWatcher<void>* execution_watcher_;
238 
239  // **************************************************************
240  // Variables
241  // **************************************************************
242 
244  std::map<std::string, std::string> frame_names_;
245  // Transform samples
246  std::vector<Eigen::Isometry3d> effector_wrt_world_;
247  std::vector<Eigen::Isometry3d> object_wrt_sensor_;
248  std::string from_frame_tag_;
249  Eigen::Isometry3d camera_robot_pose_;
250  std::vector<std::vector<double>> joint_states_;
251  std::vector<std::string> joint_names_;
254 
255  // **************************************************************
256  // Ros components
257  // **************************************************************
258 
260  // ros::CallbackQueue callback_queue_;
261  // ros::AsyncSpinner spinner_;
262  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
265  std::unique_ptr<pluginlib::ClassLoader<moveit_handeye_calibration::HandEyeSolverBase>> solver_plugins_loader_;
266  pluginlib::UniquePtr<moveit_handeye_calibration::HandEyeSolverBase> solver_;
267  planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
268  moveit::planning_interface::MoveGroupInterfacePtr move_group_;
269  moveit::planning_interface::MoveGroupInterface::PlanPtr current_plan_;
270 };
271 
272 } // namespace moveit_rviz_plugin
moveit_rviz_plugin::ControlTabWidget::solve_btn_
QPushButton * solve_btn_
Definition: handeye_control_widget.h:257
panel.h
moveit_rviz_plugin::ProgressBarWidget::setMin
void setMin(int value)
Definition: handeye_control_widget.cpp:114
moveit_rviz_plugin::ControlTabWidget::saveWidget
void saveWidget(rviz::Config &config)
Definition: handeye_control_widget.cpp:309
moveit_rviz_plugin::ControlTabWidget::reprojection_error_label_
QLabel * reprojection_error_label_
Definition: handeye_control_widget.h:242
moveit_rviz_plugin::ControlTabWidget::FAILURE_NO_PSM
@ FAILURE_NO_PSM
Definition: handeye_control_widget.h:142
moveit_rviz_plugin::ControlTabWidget::saveJointStateBtnClicked
void saveJointStateBtnClicked(bool clicked)
Definition: handeye_control_widget.cpp:737
moveit_rviz_plugin::ControlTabWidget::joint_names_
std::vector< std::string > joint_names_
Definition: handeye_control_widget.h:283
moveit_rviz_plugin::ControlTabWidget::autoExecuteBtnClicked
void autoExecuteBtnClicked(bool clicked)
Definition: handeye_control_widget.cpp:1034
moveit_rviz_plugin::ProgressBarWidget::setValue
void setValue(int value)
Definition: handeye_control_widget.cpp:119
moveit_rviz_plugin::ControlTabWidget::clearSamplesBtnClicked
void clearSamplesBtnClicked(bool clicked)
Definition: handeye_control_widget.cpp:615
moveit_rviz_plugin::ControlTabWidget::FAILURE_NO_MOVE_GROUP
@ FAILURE_NO_MOVE_GROUP
Definition: handeye_control_widget.h:143
moveit_rviz_plugin::ProgressBarWidget::max_label_
QLabel * max_label_
Definition: handeye_control_widget.h:129
moveit_rviz_plugin::ControlTabWidget::save_samples_btn_
QPushButton * save_samples_btn_
Definition: handeye_control_widget.h:252
boost::shared_ptr< TFVisualTools >
moveit_rviz_plugin::ControlTabWidget::setGroupName
void setGroupName(const std::string &group_name)
Definition: handeye_control_widget.cpp:691
moveit_rviz_plugin::ControlTabWidget::UpdateSensorMountType
void UpdateSensorMountType(int index)
Definition: handeye_control_widget.cpp:550
moveit_rviz_plugin::ControlTabWidget::loadJointStateBtnClicked
void loadJointStateBtnClicked(bool clicked)
Definition: handeye_control_widget.cpp:892
moveit_rviz_plugin::ControlTabWidget::ControlTabWidget
ControlTabWidget(HandEyeCalibrationDisplay *pdisplay, QWidget *parent=Q_NULLPTR)
Definition: handeye_control_widget.cpp:130
moveit_rviz_plugin::ControlTabWidget::calibration_solver_
QComboBox * calibration_solver_
Definition: handeye_control_widget.h:245
tf2_eigen.h
moveit_rviz_plugin::ControlTabWidget::~ControlTabWidget
~ControlTabWidget()
Definition: handeye_control_widget.h:150
moveit_rviz_plugin::ControlTabWidget::takeSampleBtnClicked
void takeSampleBtnClicked(bool clicked)
Definition: handeye_control_widget.cpp:578
ros.h
moveit_rviz_plugin::ControlTabWidget::tree_view_model_
QStandardItemModel * tree_view_model_
Definition: handeye_control_widget.h:243
moveit_rviz_plugin::ControlTabWidget::autoPlanBtnClicked
void autoPlanBtnClicked(bool clicked)
Definition: handeye_control_widget.cpp:966
moveit_rviz_plugin::ControlTabWidget::reset_sample_btn_
QPushButton * reset_sample_btn_
Definition: handeye_control_widget.h:256
moveit_rviz_plugin::ControlTabWidget::loadSolverPlugin
bool loadSolverPlugin(std::vector< std::string > &plugins)
Definition: handeye_control_widget.cpp:315
moveit_rviz_plugin::ControlTabWidget::planning_scene_monitor_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
Definition: handeye_control_widget.h:299
moveit_rviz_plugin::ControlTabWidget::solveBtnClicked
void solveBtnClicked(bool clicked)
Definition: handeye_control_widget.cpp:419
moveit_rviz_plugin::ControlTabWidget::computeExecution
void computeExecution()
Definition: handeye_control_widget.cpp:1045
moveit_rviz_plugin::ControlTabWidget::SUCCESS
@ SUCCESS
Definition: handeye_control_widget.h:139
moveit_rviz_plugin::ControlTabWidget::planningGroupNamespaceChanged
void planningGroupNamespaceChanged()
moveit_rviz_plugin::ControlTabWidget::take_sample_btn_
QPushButton * take_sample_btn_
Definition: handeye_control_widget.h:255
moveit_rviz_plugin::ControlTabWidget::fillSolverTypes
void fillSolverTypes(const std::vector< std::string > &plugins)
Definition: handeye_control_widget.cpp:355
moveit_rviz_plugin::ControlTabWidget::FAILURE_WRONG_MOVE_GROUP
@ FAILURE_WRONG_MOVE_GROUP
Definition: handeye_control_widget.h:144
moveit_rviz_plugin::ControlTabWidget::createSolverInstance
bool createSolverInstance(const std::string &plugin_name)
Definition: handeye_control_widget.cpp:338
moveit_rviz_plugin::ControlTabWidget::addPoseSampleToTreeView
void addPoseSampleToTreeView(const geometry_msgs::TransformStamped &camera_to_object_tf, const geometry_msgs::TransformStamped &base_to_eef_tf, int id)
Definition: handeye_control_widget.cpp:529
moveit_rviz_plugin::ControlTabWidget::autoSkipBtnClicked
void autoSkipBtnClicked(bool clicked)
Definition: handeye_control_widget.cpp:1108
moveit_rviz_plugin::ControlTabWidget::solver_
pluginlib::UniquePtr< moveit_handeye_calibration::HandEyeSolverBase > solver_
Definition: handeye_control_widget.h:298
moveit_rviz_plugin::ControlTabWidget::execution_watcher_
QFutureWatcher< void > * execution_watcher_
Definition: handeye_control_widget.h:269
tf2_ros::TransformListener
moveit_rviz_plugin::HandEyeCalibrationDisplay
Definition: handeye_calibration_display.h:89
moveit_rviz_plugin::ProgressBarWidget::value_label_
QLabel * value_label_
Definition: handeye_control_widget.h:128
moveit_rviz_plugin::ProgressBarWidget::ProgressBarWidget
ProgressBarWidget(QWidget *parent, int min=0, int max=0, int value=0)
Definition: handeye_control_widget.cpp:76
moveit_rviz_plugin::ProgressBarWidget::getValue
int getValue()
Definition: handeye_control_widget.cpp:125
moveit_rviz_plugin::ControlTabWidget::saveCameraPoseBtnClicked
void saveCameraPoseBtnClicked(bool clicked)
Definition: handeye_control_widget.cpp:628
handeye_calibration_display.h
moveit_rviz_plugin::ControlTabWidget::checkJointStates
bool checkJointStates()
Definition: handeye_control_widget.cpp:512
moveit_rviz_plugin::ProgressBarWidget::name_label_
QLabel * name_label_
Definition: handeye_control_widget.h:127
moveit_rviz_plugin::ControlTabWidget::save_camera_pose_btn_
QPushButton * save_camera_pose_btn_
Definition: handeye_control_widget.h:250
moveit_rviz_plugin::ControlTabWidget::fillPlanningGroupNameComboBox
void fillPlanningGroupNameComboBox()
Definition: handeye_control_widget.cpp:712
moveit_rviz_plugin::ControlTabWidget::FAILURE_PLAN_FAILED
@ FAILURE_PLAN_FAILED
Definition: handeye_control_widget.h:145
planning_scene_monitor.h
moveit_rviz_plugin::ControlTabWidget::planning_res_
PLANNING_RESULT planning_res_
Definition: handeye_control_widget.h:285
tf_visual_tools.h
moveit_rviz_plugin::ControlTabWidget::auto_execute_btn_
QPushButton * auto_execute_btn_
Definition: handeye_control_widget.h:262
moveit_handeye_calibration::SensorMountType
SensorMountType
moveit_rviz_plugin::ControlTabWidget::sample_tree_view_
QTreeView * sample_tree_view_
Definition: handeye_control_widget.h:241
handeye_solver_base.h
moveit_rviz_plugin::ControlTabWidget::computePlan
void computePlan()
Definition: handeye_control_widget.cpp:972
moveit_rviz_plugin::ControlTabWidget::frame_names_
std::map< std::string, std::string > frame_names_
Definition: handeye_control_widget.h:276
moveit_rviz_plugin::ControlTabWidget::camera_robot_pose_
Eigen::Isometry3d camera_robot_pose_
Definition: handeye_control_widget.h:281
moveit_rviz_plugin::ControlTabWidget::sensorPoseUpdate
void sensorPoseUpdate(double x, double y, double z, double rx, double ry, double rz)
moveit_rviz_plugin::ControlTabWidget::auto_progress_
ProgressBarWidget * auto_progress_
Definition: handeye_control_widget.h:266
moveit_rviz_plugin::ControlTabWidget::takeTransformSamples
bool takeTransformSamples()
Definition: handeye_control_widget.cpp:381
moveit_rviz_plugin::ProgressBarWidget::~ProgressBarWidget
~ProgressBarWidget() override=default
moveit_rviz_plugin::ControlTabWidget::updateFrameNames
void updateFrameNames(std::map< std::string, std::string > names)
Definition: handeye_control_widget.cpp:570
moveit_rviz_plugin::ControlTabWidget::loadSamplesBtnClicked
void loadSamplesBtnClicked(bool clicked)
Definition: handeye_control_widget.cpp:791
moveit_rviz_plugin::ControlTabWidget::frameNamesEmpty
bool frameNamesEmpty()
Definition: handeye_control_widget.cpp:500
moveit_rviz_plugin::ControlTabWidget::loadWidget
void loadWidget(const rviz::Config &config)
Definition: handeye_control_widget.cpp:279
moveit_rviz_plugin::ControlTabWidget::auto_skip_btn_
QPushButton * auto_skip_btn_
Definition: handeye_control_widget.h:263
moveit_rviz_plugin::ControlTabWidget::sensor_mount_type_
mhc::SensorMountType sensor_mount_type_
Definition: handeye_control_widget.h:275
class_loader.hpp
moveit_rviz_plugin::ControlTabWidget::auto_started_
bool auto_started_
Definition: handeye_control_widget.h:284
moveit_rviz_plugin::ControlTabWidget::tf_buffer_
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
Definition: handeye_control_widget.h:294
moveit_rviz_plugin::ControlTabWidget::planFinished
void planFinished()
Definition: handeye_control_widget.cpp:1060
moveit_rviz_plugin::ControlTabWidget::planningGroupNameChanged
void planningGroupNameChanged(const QString &text)
Definition: handeye_control_widget.cpp:679
moveit_rviz_plugin::ControlTabWidget::saveSamplesBtnClicked
void saveSamplesBtnClicked(bool clicked)
Definition: handeye_control_widget.cpp:833
move_group_interface.h
moveit_rviz_plugin
transform_listener.h
moveit_rviz_plugin::ControlTabWidget::load_joint_state_btn_
QPushButton * load_joint_state_btn_
Definition: handeye_control_widget.h:249
moveit_rviz_plugin::ControlTabWidget::setTFTool
void setTFTool(rviz_visual_tools::TFVisualToolsPtr &tf_pub)
Definition: handeye_control_widget.cpp:524
moveit_rviz_plugin::ControlTabWidget::group_name_
QComboBox * group_name_
Definition: handeye_control_widget.h:260
moveit_rviz_plugin::ControlTabWidget::tf_listener_
tf2_ros::TransformListener tf_listener_
Definition: handeye_control_widget.h:295
moveit_rviz_plugin::ControlTabWidget::from_frame_tag_
std::string from_frame_tag_
Definition: handeye_control_widget.h:280
moveit_rviz_plugin::ProgressBarWidget::setMax
void setMax(int value)
Definition: handeye_control_widget.cpp:107
moveit_rviz_plugin::ProgressBarWidget::bar_
QProgressBar * bar_
Definition: handeye_control_widget.h:130
moveit_rviz_plugin::ControlTabWidget::solver_plugins_loader_
std::unique_ptr< pluginlib::ClassLoader< moveit_handeye_calibration::HandEyeSolverBase > > solver_plugins_loader_
Definition: handeye_control_widget.h:297
background_processing.h
moveit_handeye_calibration
moveit_rviz_plugin::ControlTabWidget::tf_tools_
rviz_visual_tools::TFVisualToolsPtr tf_tools_
Definition: handeye_control_widget.h:296
moveit_rviz_plugin::ControlTabWidget::joint_states_
std::vector< std::vector< double > > joint_states_
Definition: handeye_control_widget.h:282
moveit_rviz_plugin::ControlTabWidget::move_group_
moveit::planning_interface::MoveGroupInterfacePtr move_group_
Definition: handeye_control_widget.h:300
moveit_rviz_plugin::ControlTabWidget::FAILURE_NO_JOINT_STATE
@ FAILURE_NO_JOINT_STATE
Definition: handeye_control_widget.h:140
moveit_rviz_plugin::ControlTabWidget::nh_
ros::NodeHandle nh_
Definition: handeye_control_widget.h:291
moveit_rviz_plugin::ControlTabWidget::current_plan_
moveit::planning_interface::MoveGroupInterface::PlanPtr current_plan_
Definition: handeye_control_widget.h:301
moveit_rviz_plugin::ControlTabWidget::object_wrt_sensor_
std::vector< Eigen::Isometry3d > object_wrt_sensor_
Definition: handeye_control_widget.h:279
moveit_rviz_plugin::ControlTabWidget::plan_watcher_
QFutureWatcher< void > * plan_watcher_
Definition: handeye_control_widget.h:268
moveit_rviz_plugin::ControlTabWidget::FAILURE_INVALID_JOINT_STATE
@ FAILURE_INVALID_JOINT_STATE
Definition: handeye_control_widget.h:141
moveit_rviz_plugin::ControlTabWidget::load_samples_btn_
QPushButton * load_samples_btn_
Definition: handeye_control_widget.h:251
moveit_rviz_plugin::ControlTabWidget::effector_wrt_world_
std::vector< Eigen::Isometry3d > effector_wrt_world_
Definition: handeye_control_widget.h:278
moveit_rviz_plugin::ControlTabWidget::calibration_display_
HandEyeCalibrationDisplay * calibration_display_
Definition: handeye_control_widget.h:235
moveit_rviz_plugin::ControlTabWidget::save_joint_state_btn_
QPushButton * save_joint_state_btn_
Definition: handeye_control_widget.h:248
rviz::Config
moveit_rviz_plugin::ControlTabWidget::solveCameraRobotPose
bool solveCameraRobotPose()
Definition: handeye_control_widget.cpp:424
moveit_rviz_plugin::ProgressBarWidget
Definition: handeye_control_widget.h:113
moveit_rviz_plugin::ControlTabWidget::parseSolverName
std::string parseSolverName(const std::string &solver_name, char delimiter)
Definition: handeye_control_widget.cpp:369
moveit_rviz_plugin::ControlTabWidget::auto_plan_btn_
QPushButton * auto_plan_btn_
Definition: handeye_control_widget.h:261
ros::NodeHandle
moveit_rviz_plugin::ControlTabWidget::executeFinished
void executeFinished()
Definition: handeye_control_widget.cpp:1093
moveit_rviz_plugin::ControlTabWidget::PLANNING_RESULT
PLANNING_RESULT
Definition: handeye_control_widget.h:137


moveit_calibration_gui
Author(s): Yu Yan
autogenerated on Fri Oct 18 2024 02:14:15