handeye_calibration_display.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 
41 
42 #include <Eigen/Geometry>
43 #include <cmath>
44 
45 #include <iostream>
46 
47 namespace moveit_rviz_plugin
48 {
50 {
51  move_group_ns_property_ = new rviz::StringProperty("Move Group Namespace", "",
52  "The name of the ROS namespace in "
53  "which the move_group node is running",
54  this, SLOT(fillPlanningGroupNameComboBox()), this);
55  planning_scene_topic_property_ =
56  new rviz::RosTopicProperty("Planning Scene Topic", "move_group/monitored_planning_scene",
57  ros::message_traits::datatype<moveit_msgs::PlanningScene>(),
58  "The topic on which the moveit_msgs::PlanningScene messages are received", this,
59  SLOT(fillPlanningGroupNameComboBox()), this);
60 
61  fov_marker_enabled_property_ = new rviz::BoolProperty(
62  "Camera FOV Marker", true, "Enable marker showing camera field of view", this, SLOT(updateMarkers()), this);
63  fov_marker_alpha_property_ =
64  new rviz::FloatProperty("Marker Alpha", 0.3f, "Specifies the alpha (transparency) for the rendered marker",
65  fov_marker_enabled_property_, SLOT(updateMarkers()), this);
66  fov_marker_size_property_ =
67  new rviz::FloatProperty("Marker Size", 1.5f, "Specifies the size (depth in meters) for the rendered marker",
68  fov_marker_enabled_property_, SLOT(updateMarkers()), this);
69 }
70 
71 HandEyeCalibrationDisplay::~HandEyeCalibrationDisplay()
72 {
73  if (frame_dock_)
74  delete frame_dock_;
75 }
76 
77 void HandEyeCalibrationDisplay::onInitialize()
78 {
79  Display::onInitialize();
80 
81  rviz::WindowManagerInterface* window_context = context_->getWindowManager();
82  frame_ = new HandEyeCalibrationFrame(this, context_, window_context ? window_context->getParentWindow() : nullptr);
83 
84  if (window_context)
85  {
86  frame_dock_ = window_context->addPane("HandEye Calibration", frame_);
87  }
88 }
89 
90 void HandEyeCalibrationDisplay::save(rviz::Config config) const
91 {
92  Display::save(config);
93  if (frame_)
94  {
95  frame_->saveWidget(config);
96  }
97 }
98 
99 // Load all configuration data for this panel from the given Config object.
100 void HandEyeCalibrationDisplay::load(const rviz::Config& config)
101 {
102  Display::load(config);
103  if (frame_)
104  {
105  frame_->loadWidget(config);
106  }
107 }
108 
109 void HandEyeCalibrationDisplay::fillPlanningGroupNameComboBox()
110 {
111  if (frame_ && frame_->tab_control_)
112  {
113  frame_->tab_control_->fillPlanningGroupNameComboBox();
114  }
115 }
116 
117 void HandEyeCalibrationDisplay::updateMarkers()
118 {
119  if (frame_ && frame_->tab_context_)
120  {
121  frame_->tab_context_->updateAllMarkers();
122  }
123 }
124 
125 } // namespace moveit_rviz_plugin
rviz::RosTopicProperty
rviz::BoolProperty
rviz::FloatProperty
handeye_calibration_frame.h
handeye_calibration_display.h
moveit_rviz_plugin::HandEyeCalibrationFrame
Definition: handeye_calibration_frame.h:95
window_manager_interface.h
rviz::StringProperty
rviz::WindowManagerInterface::getParentWindow
virtual QWidget * getParentWindow()=0
moveit_rviz_plugin
moveit_rviz_plugin::HandEyeCalibrationDisplay::HandEyeCalibrationDisplay
HandEyeCalibrationDisplay(QWidget *parent=0)
Definition: handeye_calibration_display.cpp:81
rviz::WindowManagerInterface::addPane
virtual PanelDockWidget * addPane(const QString &name, QWidget *pane, Qt::DockWidgetArea area=Qt::LeftDockWidgetArea, bool floating=false)=0
rviz::WindowManagerInterface
config
config
rviz::Config


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