handeye_calibration_frame.cpp
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 
39 
40 #include <Eigen/Geometry>
41 #include <cmath>
42 
43 namespace moveit_rviz_plugin
44 {
45 HandEyeCalibrationFrame::HandEyeCalibrationFrame(HandEyeCalibrationDisplay* pdisplay, rviz::DisplayContext* context,
46  QWidget* parent)
47  : QWidget(parent), calibration_display_(pdisplay), context_(context)
48 {
49  setMinimumSize(695, 460);
50  // Basic widget container
51  QVBoxLayout* layout = new QVBoxLayout();
52  setLayout(layout);
53 
54  // Description
55  QLabel* description = new QLabel(this);
56  description->setText(QString("Configure the position and orientation of your 3D sensors to work with MoveIt"));
57  description->setWordWrap(true);
58  description->setMinimumWidth(1);
59  layout->addWidget(description);
60 
61  // Tab menu ------------------------------------------------------------
62  QTabWidget* tabs = new QTabWidget(this);
63  tab_target_ = new TargetTabWidget(calibration_display_);
64 
65  tf_tools_.reset(new rviz_visual_tools::TFVisualTools(250));
66 
67  tab_context_ = new ContextTabWidget(calibration_display_);
68  tab_context_->setTFTool(tf_tools_);
69  connect(tab_target_, SIGNAL(cameraInfoChanged(sensor_msgs::CameraInfo)), tab_context_,
70  SLOT(setCameraInfo(sensor_msgs::CameraInfo)));
71  connect(tab_target_, SIGNAL(opticalFrameChanged(const std::string&)), tab_context_,
72  SLOT(setOpticalFrame(const std::string&)));
73 
74  tab_control_ = new ControlTabWidget(calibration_display_);
75  tab_control_->setTFTool(tf_tools_);
76  tab_control_->UpdateSensorMountType(0);
77  connect(tab_context_, SIGNAL(sensorMountTypeChanged(int)), tab_control_, SLOT(UpdateSensorMountType(int)));
78  connect(tab_context_, SIGNAL(frameNameChanged(std::map<std::string, std::string>)), tab_control_,
79  SLOT(updateFrameNames(std::map<std::string, std::string>)));
80  connect(tab_control_, SIGNAL(sensorPoseUpdate(double, double, double, double, double, double)), tab_context_,
81  SLOT(updateCameraPose(double, double, double, double, double, double)));
82 
83  tabs->addTab(tab_target_, "Target");
84  tabs->addTab(tab_context_, "Context");
85  tabs->addTab(tab_control_, "Calibrate");
86  layout->addWidget(tabs);
87 
88  ROS_INFO_STREAM("handeye calibration gui created.");
89 }
90 
92 
94 {
95  tab_target_->saveWidget(config);
96  tab_context_->saveWidget(config);
97  tab_control_->saveWidget(config);
98 }
99 
100 // Load all configuration data for this panel from the given Config object.
102 {
103  tab_target_->loadWidget(config);
104  tab_context_->loadWidget(config);
105  tab_control_->loadWidget(config);
106 
107  ROS_INFO_STREAM("handeye calibration gui loaded.");
108 }
109 
110 } // namespace moveit_rviz_plugin
moveit_rviz_plugin::ControlTabWidget::saveWidget
void saveWidget(rviz::Config &config)
Definition: handeye_control_widget.cpp:309
moveit_rviz_plugin::ContextTabWidget::saveWidget
void saveWidget(rviz::Config &config)
Definition: handeye_context_widget.cpp:315
moveit_rviz_plugin::TargetTabWidget::saveWidget
void saveWidget(rviz::Config &config)
Definition: handeye_target_widget.cpp:263
moveit_rviz_plugin::HandEyeCalibrationFrame::tab_context_
ContextTabWidget * tab_context_
Definition: handeye_calibration_frame.h:114
description
description
moveit_rviz_plugin::HandEyeCalibrationFrame::tab_target_
TargetTabWidget * tab_target_
Definition: handeye_calibration_frame.h:113
handeye_calibration_frame.h
handeye_calibration_display.h
rviz::Property::connect
std::enable_if<!QtPrivate::FunctionPointer< Func >::IsPointerToMemberFunction, QMetaObject::Connection >::type connect(const QObject *context, Func &&slot, Qt::ConnectionType type=Qt::AutoConnection)
moveit_rviz_plugin::HandEyeCalibrationFrame::~HandEyeCalibrationFrame
~HandEyeCalibrationFrame() override
moveit_rviz_plugin::ControlTabWidget::loadWidget
void loadWidget(const rviz::Config &config)
Definition: handeye_control_widget.cpp:279
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
moveit_rviz_plugin::ContextTabWidget::loadWidget
void loadWidget(const rviz::Config &config)
Definition: handeye_context_widget.cpp:281
rviz::DisplayContext
moveit_rviz_plugin
moveit_rviz_plugin::HandEyeCalibrationFrame::loadWidget
virtual void loadWidget(const rviz::Config &config)
Definition: handeye_calibration_frame.cpp:133
rviz_visual_tools::TFVisualTools
moveit_rviz_plugin::TargetTabWidget::loadWidget
void loadWidget(const rviz::Config &config)
Definition: handeye_target_widget.cpp:195
moveit_rviz_plugin::HandEyeCalibrationFrame::HandEyeCalibrationFrame
HandEyeCalibrationFrame(HandEyeCalibrationDisplay *pdisplay, rviz::DisplayContext *context, QWidget *parent=0)
Definition: handeye_calibration_frame.cpp:77
moveit_rviz_plugin::HandEyeCalibrationFrame::saveWidget
virtual void saveWidget(rviz::Config config) const
Definition: handeye_calibration_frame.cpp:125
rviz::Config
moveit_rviz_plugin::HandEyeCalibrationFrame::tab_control_
ControlTabWidget * tab_control_
Definition: handeye_calibration_frame.h:115


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