handeye_context_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 <QLabel>
41 #include <QWidget>
42 #include <QSlider>
43 #include <QComboBox>
44 #include <QLineEdit>
45 #include <QGroupBox>
46 #include <QFormLayout>
47 #include <QHBoxLayout>
48 #include <QRadioButton>
49 
50 // ros
51 #include <shape_msgs/Mesh.h>
52 #include <rviz/frame_manager.h>
53 #include <tf2_eigen/tf2_eigen.h>
54 #include <sensor_msgs/CameraInfo.h>
62 
63 #ifndef Q_MOC_RUN
64 #include <ros/ros.h>
65 #include <rviz/panel.h>
66 #endif
67 
68 namespace rvt = rviz_visual_tools;
70 
71 namespace moveit_rviz_plugin
72 {
73 class HandEyeCalibrationDisplay;
74 
75 enum FRAME_SOURCE
76 {
77  ROBOT_FRAME = 0,
78  CAMERA_FRAME = 1,
80 };
81 
82 // **************************************************
83 // Custom QComboBox for frame name
84 // **************************************************
85 class TFFrameNameComboBox : public QComboBox
86 {
87  Q_OBJECT
88 public:
89  TFFrameNameComboBox(FRAME_SOURCE source = ROBOT_FRAME, QWidget* parent = 0) : QComboBox(parent), frame_source_(source)
90  {
91  robot_model_loader_.reset(new robot_model_loader::RobotModelLoader("robot_description"));
93  }
94 
96  {
97  robot_model_loader_.reset();
98  }
99 
100  bool hasFrame(const std::string& frame_name);
101 
102 protected:
103  void mousePressEvent(QMouseEvent* event);
104 
105 private:
107  std::unique_ptr<rviz::FrameManager> frame_manager_;
108  robot_model_loader::RobotModelLoaderConstPtr robot_model_loader_;
109 };
110 
111 // **************************************************
112 // Custom slider class
113 // **************************************************
114 class SliderWidget : public QWidget
115 {
116  Q_OBJECT
117 
118 public:
119  SliderWidget(QWidget* parent, std::string name, double min, double max);
120 
121  ~SliderWidget() override = default;
122 
123  double getValue();
124 
125  void setValue(double value);
126 
127  QLabel* label_;
128  QSlider* slider_;
129  QLineEdit* edit_;
130 
131 private Q_SLOTS:
132 
133  // Called when the slider is changed
134  void changeValue(int value);
135 
136  // Called when the edit box is changed
137  void changeSlider();
138 
139 Q_SIGNALS:
140 
141  // Indicate value when slider widget changed
142  void valueChanged(double value);
143 
144 private:
145  // Max & min position
147  double min_position_;
148 };
149 
150 class ContextTabWidget : public QWidget
151 {
152  Q_OBJECT
153 public:
154  explicit ContextTabWidget(HandEyeCalibrationDisplay* pdisplay, QWidget* parent = Q_NULLPTR);
156  {
157  camera_info_.reset();
158  visual_tools_.reset();
159  tf_tools_.reset();
160  }
161 
162  void loadWidget(const rviz::Config& config);
163  void saveWidget(rviz::Config& config);
165 
166  void updateAllMarkers();
167 
168  void updateFOVPose();
169 
170  static shape_msgs::Mesh getCameraFOVMesh(const sensor_msgs::CameraInfo& camera_info, double maxdist);
171 
172  visualization_msgs::Marker getCameraFOVMarker(const Eigen::Isometry3d& pose, const shape_msgs::Mesh& mesh,
173  rvt::colors color, double alpha, std::string frame_id);
174 
175  visualization_msgs::Marker getCameraFOVMarker(const geometry_msgs::Pose& pose, const shape_msgs::Mesh& mesh,
176  rvt::colors color, double alpha, std::string frame_id);
177 
178  void setCameraPose(double tx, double ty, double tz, double rx, double ry, double rz);
179 
180 public Q_SLOTS:
181 
182  void setCameraInfo(sensor_msgs::CameraInfo camera_info);
183 
184  void setOpticalFrame(const std::string& frame_id);
185 
186  void updateCameraPose(double tx, double ty, double tz, double rx, double ry, double rz);
187 
188 private Q_SLOTS:
189 
190  // Called when the sensor_mount_type_ changed
191  void updateSensorMountType(int index);
192 
193  // Called when the TFFrameNameComboBox changed
194  void updateFrameName(int index);
195 
196  // Called when the slider of initial camera pose guess changed
197  void updateCameraMarkerPose(double value);
198 
199 Q_SIGNALS:
200 
201  void sensorMountTypeChanged(int index);
202 
203  void frameNameChanged(std::map<std::string, std::string> names);
204 
205 private:
207 
208  // **************************************************************
209  // Qt components
210  // **************************************************************
211 
212  // Calibration algorithm, sensor mount type area
213  QComboBox* sensor_mount_type_;
214 
215  // Frame selection area
216  std::map<std::string, TFFrameNameComboBox*> frames_;
217 
218  // Initial camera pose
219  std::map<std::string, SliderWidget*> guess_pose_;
220 
221  // **************************************************************
222  // Variables
223  // **************************************************************
224 
225  sensor_msgs::CameraInfoPtr camera_info_;
226 
227  // Transform from camera to robot base or end-effector
228  Eigen::Isometry3d camera_pose_;
229 
230  std::string optical_frame_;
231 
232  // Transform from camera to fov
233  Eigen::Isometry3d fov_pose_;
234 
235  // **************************************************************
236  // Ros components
237  // **************************************************************
238 
243 };
244 
245 } // namespace moveit_rviz_plugin
moveit_rviz_plugin::ContextTabWidget::updateFOVPose
void updateFOVPose()
Definition: handeye_context_widget.cpp:397
moveit_rviz_plugin::SliderWidget::~SliderWidget
~SliderWidget() override=default
moveit_rviz_plugin::TFFrameNameComboBox::~TFFrameNameComboBox
~TFFrameNameComboBox()
Definition: handeye_context_widget.h:127
moveit_rviz_plugin::ContextTabWidget::setCameraPose
void setCameraPose(double tx, double ty, double tz, double rx, double ry, double rz)
Definition: handeye_context_widget.cpp:494
panel.h
moveit_rviz_plugin::ContextTabWidget::tf_buffer_
tf2_ros::Buffer tf_buffer_
Definition: handeye_context_widget.h:273
moveit_rviz_plugin::ContextTabWidget::setCameraInfo
void setCameraInfo(sensor_msgs::CameraInfo camera_info)
Definition: handeye_context_widget.cpp:500
moveit_rviz_plugin::ContextTabWidget::saveWidget
void saveWidget(rviz::Config &config)
Definition: handeye_context_widget.cpp:315
moveit_rviz_plugin::ContextTabWidget::updateFrameName
void updateFrameName(int index)
Definition: handeye_context_widget.cpp:541
moveit_rviz_plugin::SliderWidget::getValue
double getValue()
Definition: handeye_context_widget.cpp:152
moveit_rviz_plugin::SliderWidget
Definition: handeye_context_widget.h:146
moveit_rviz_plugin::SliderWidget::setValue
void setValue(double value)
Definition: handeye_context_widget.cpp:157
boost::shared_ptr< TFVisualTools >
moveit_rviz_plugin::ContextTabWidget::sensorMountTypeChanged
void sensorMountTypeChanged(int index)
pinhole_camera_model.h
tf2_eigen.h
moveit_rviz_plugin::ContextTabWidget::tf_listener_
tf2_ros::TransformListener tf_listener_
Definition: handeye_context_widget.h:274
moveit_rviz_plugin::ContextTabWidget::updateSensorMountType
void updateSensorMountType(int index)
Definition: handeye_context_widget.cpp:531
ros.h
moveit_visual_tools.h
frame_manager.h
moveit_rviz_plugin::SliderWidget::changeSlider
void changeSlider()
Definition: handeye_context_widget.cpp:178
moveit_rviz_plugin::SliderWidget::changeValue
void changeValue(int value)
Definition: handeye_context_widget.cpp:167
moveit_rviz_plugin::SliderWidget::edit_
QLineEdit * edit_
Definition: handeye_context_widget.h:161
moveit_rviz_plugin::ContextTabWidget::setOpticalFrame
void setOpticalFrame(const std::string &frame_id)
Definition: handeye_context_widget.cpp:513
moveit_rviz_plugin::SliderWidget::valueChanged
void valueChanged(double value)
rviz_visual_tools
moveit_rviz_plugin::ContextTabWidget::getCameraFOVMarker
visualization_msgs::Marker getCameraFOVMarker(const Eigen::Isometry3d &pose, const shape_msgs::Mesh &mesh, rvt::colors color, double alpha, std::string frame_id)
Definition: handeye_context_widget.cpp:461
moveit_rviz_plugin::ROBOT_FRAME
@ ROBOT_FRAME
Definition: handeye_context_widget.h:109
moveit_rviz_plugin::ContextTabWidget::setTFTool
void setTFTool(rviz_visual_tools::TFVisualToolsPtr &tf_pub)
Definition: handeye_context_widget.cpp:326
moveit_rviz_plugin::ContextTabWidget::frames_
std::map< std::string, TFFrameNameComboBox * > frames_
Definition: handeye_context_widget.h:248
tf2_ros::TransformListener
moveit_rviz_plugin::ContextTabWidget::ContextTabWidget
ContextTabWidget(HandEyeCalibrationDisplay *pdisplay, QWidget *parent=Q_NULLPTR)
Definition: handeye_context_widget.cpp:189
moveit_rviz_plugin::HandEyeCalibrationDisplay
Definition: handeye_calibration_display.h:89
handeye_calibration_display.h
robot_model_loader::RobotModelLoader
moveit_visual_tools::MoveItVisualToolsPtr
std::shared_ptr< MoveItVisualTools > MoveItVisualToolsPtr
moveit_rviz_plugin::ContextTabWidget::frameNameChanged
void frameNameChanged(std::map< std::string, std::string > names)
moveit_rviz_plugin::ContextTabWidget::optical_frame_
std::string optical_frame_
Definition: handeye_context_widget.h:262
tf_visual_tools.h
moveit_rviz_plugin::ContextTabWidget::getCameraFOVMesh
static shape_msgs::Mesh getCameraFOVMesh(const sensor_msgs::CameraInfo &camera_info, double maxdist)
Definition: handeye_context_widget.cpp:421
moveit_rviz_plugin::CAMERA_FRAME
@ CAMERA_FRAME
Definition: handeye_context_widget.h:110
moveit_rviz_plugin::ContextTabWidget::camera_pose_
Eigen::Isometry3d camera_pose_
Definition: handeye_context_widget.h:260
handeye_solver_base.h
moveit_rviz_plugin::ContextTabWidget::updateAllMarkers
void updateAllMarkers()
Definition: handeye_context_widget.cpp:331
tf2_ros::Buffer
moveit_rviz_plugin::ContextTabWidget
Definition: handeye_context_widget.h:182
moveit_rviz_plugin::SliderWidget::min_position_
double min_position_
Definition: handeye_context_widget.h:179
moveit_rviz_plugin::ENVIRONMENT_FRAME
@ ENVIRONMENT_FRAME
Definition: handeye_context_widget.h:111
moveit_rviz_plugin::ContextTabWidget::loadWidget
void loadWidget(const rviz::Config &config)
Definition: handeye_context_widget.cpp:281
moveit_rviz_plugin::TFFrameNameComboBox::hasFrame
bool hasFrame(const std::string &frame_name)
Definition: handeye_context_widget.cpp:108
moveit_rviz_plugin::TFFrameNameComboBox::frame_source_
FRAME_SOURCE frame_source_
Definition: handeye_context_widget.h:138
rviz::FrameManager
rviz_visual_tools::colors
colors
moveit_rviz_plugin
transform_listener.h
moveit_rviz_plugin::ContextTabWidget::camera_info_
sensor_msgs::CameraInfoPtr camera_info_
Definition: handeye_context_widget.h:257
moveit_rviz_plugin::ContextTabWidget::tf_tools_
rviz_visual_tools::TFVisualToolsPtr tf_tools_
Definition: handeye_context_widget.h:272
moveit_rviz_plugin::TFFrameNameComboBox::mousePressEvent
void mousePressEvent(QMouseEvent *event)
Definition: handeye_context_widget.cpp:76
moveit_rviz_plugin::SliderWidget::label_
QLabel * label_
Definition: handeye_context_widget.h:159
moveit_handeye_calibration
moveit_rviz_plugin::ContextTabWidget::fov_pose_
Eigen::Isometry3d fov_pose_
Definition: handeye_context_widget.h:265
moveit_rviz_plugin::SliderWidget::max_position_
double max_position_
Definition: handeye_context_widget.h:178
moveit_rviz_plugin::FRAME_SOURCE
FRAME_SOURCE
Definition: handeye_context_widget.h:107
moveit_rviz_plugin::ContextTabWidget::visual_tools_
moveit_visual_tools::MoveItVisualToolsPtr visual_tools_
Definition: handeye_context_widget.h:271
moveit_rviz_plugin::TFFrameNameComboBox::frame_manager_
std::unique_ptr< rviz::FrameManager > frame_manager_
Definition: handeye_context_widget.h:139
moveit_rviz_plugin::TFFrameNameComboBox::robot_model_loader_
robot_model_loader::RobotModelLoaderConstPtr robot_model_loader_
Definition: handeye_context_widget.h:140
moveit_rviz_plugin::ContextTabWidget::~ContextTabWidget
~ContextTabWidget()
Definition: handeye_context_widget.h:187
moveit_rviz_plugin::SliderWidget::slider_
QSlider * slider_
Definition: handeye_context_widget.h:160
moveit_rviz_plugin::SliderWidget::SliderWidget
SliderWidget(QWidget *parent, std::string name, double min, double max)
Definition: handeye_context_widget.cpp:118
moveit_rviz_plugin::ContextTabWidget::calibration_display_
HandEyeCalibrationDisplay * calibration_display_
Definition: handeye_context_widget.h:238
moveit_rviz_plugin::TFFrameNameComboBox::TFFrameNameComboBox
TFFrameNameComboBox(FRAME_SOURCE source=ROBOT_FRAME, QWidget *parent=0)
Definition: handeye_context_widget.h:121
moveit_rviz_plugin::ContextTabWidget::guess_pose_
std::map< std::string, SliderWidget * > guess_pose_
Definition: handeye_context_widget.h:251
rviz::Config
moveit_rviz_plugin::ContextTabWidget::updateCameraPose
void updateCameraPose(double tx, double ty, double tz, double rx, double ry, double rz)
Definition: handeye_context_widget.cpp:519
moveit_rviz_plugin::ContextTabWidget::updateCameraMarkerPose
void updateCameraMarkerPose(double value)
Definition: handeye_context_widget.cpp:567
rviz_visual_tools.h
moveit_rviz_plugin::ContextTabWidget::sensor_mount_type_
QComboBox * sensor_mount_type_
Definition: handeye_context_widget.h:245


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