moveit2
The MoveIt Motion Planning Framework for ROS 2.
rviz_panel.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021, PickNik Robotics
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 PickNik Robotics 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: David V. Lu!! */
36 
37 #pragma once
38 
40 #include <rviz_common/render_panel.hpp>
41 #include <rviz_common/window_manager_interface.hpp>
42 #include <rviz_common/visualization_manager.hpp>
43 #include <rviz_common/view_manager.hpp>
44 #include <rviz_common/view_controller.hpp>
46 #include <QWidget>
47 #include <QCheckBox>
48 #include <QHBoxLayout>
49 #include <QVBoxLayout>
50 
51 namespace moveit_setup
52 {
53 // Used for loading kinematic model
54 static const std::string ROBOT_DESCRIPTION = "robot_description";
55 static const std::string MOVEIT_ROBOT_STATE = "moveit_robot_state";
56 
57 class RVizPanel : public QWidget, public rviz_common::WindowManagerInterface
58 {
59  Q_OBJECT
60 public:
61  RVizPanel(QWidget* parent, const rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr& node_abstraction,
62  const DataWarehousePtr& config_data);
63  ~RVizPanel() override;
64 
66  {
67  return rviz_render_panel_ == nullptr && getRobotModel() != nullptr;
68  }
69  void initialize();
70  void updateFixedFrame();
71 
72  QWidget* getParentWindow() override
73  {
74  return parent_;
75  }
76 
77  rviz_common::PanelDockWidget* addPane(const QString& /*name*/, QWidget* /*pane*/,
78  Qt::DockWidgetArea /*area*/ = Qt::LeftDockWidgetArea,
79  bool /*floating*/ = true) override
80  {
81  // Stub for now...just to define the WindowManagerInterface methods
82  return nullptr;
83  }
84 
85  void setStatus(const QString& /*message*/) override
86  {
87  // Stub for now...just to define the WindowManagerInterface methods
88  }
89 
90 public Q_SLOTS:
96  void highlightLink(const std::string& link_name, const QColor& color)
97  {
98  Q_EMIT highlightLinkSignal(link_name, color);
99  }
100 
104  void highlightGroup(const std::string& group_name)
105  {
106  Q_EMIT highlightGroupSignal(group_name);
107  }
108 
113  {
114  Q_EMIT unhighlightAllSignal();
115  }
116 
117 Q_SIGNALS:
118  // Protected event handlers
119  void highlightLinkSignal(const std::string& link_name, const QColor& color);
120  void highlightGroupSignal(const std::string& group_name);
122 
123 protected Q_SLOTS:
124  void highlightLinkEvent(const std::string& link_name, const QColor& color);
125  void highlightGroupEvent(const std::string& group_name);
126  void unhighlightAllEvent();
127 
128 protected:
129  moveit::core::RobotModelPtr getRobotModel() const;
130 
131  QWidget* parent_;
132  rviz_common::RenderPanel* rviz_render_panel_{ nullptr };
133  rviz_common::VisualizationManager* rviz_manager_{ nullptr };
135  rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr node_abstraction_;
136  rclcpp::Node::SharedPtr node_;
137  std::shared_ptr<rclcpp::Logger> logger_;
138 
139  DataWarehousePtr config_data_;
140 };
141 } // namespace moveit_setup
void highlightLinkEvent(const std::string &link_name, const QColor &color)
Definition: rviz_panel.cpp:159
rviz_common::VisualizationManager * rviz_manager_
Definition: rviz_panel.hpp:133
DataWarehousePtr config_data_
Definition: rviz_panel.hpp:139
rclcpp::Node::SharedPtr node_
Definition: rviz_panel.hpp:136
bool isReadyForInitialization() const
Definition: rviz_panel.hpp:65
void setStatus(const QString &) override
Definition: rviz_panel.hpp:85
std::shared_ptr< rclcpp::Logger > logger_
Definition: rviz_panel.hpp:137
void highlightGroup(const std::string &group_name)
Definition: rviz_panel.hpp:104
void highlightLinkSignal(const std::string &link_name, const QColor &color)
rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr node_abstraction_
Definition: rviz_panel.hpp:135
void highlightGroupEvent(const std::string &group_name)
Definition: rviz_panel.cpp:172
void highlightGroupSignal(const std::string &group_name)
moveit::core::RobotModelPtr getRobotModel() const
Definition: rviz_panel.cpp:130
void highlightLink(const std::string &link_name, const QColor &color)
Definition: rviz_panel.hpp:96
moveit_rviz_plugin::RobotStateDisplay * robot_state_display_
Definition: rviz_panel.hpp:134
rviz_common::PanelDockWidget * addPane(const QString &, QWidget *, Qt::DockWidgetArea=Qt::LeftDockWidgetArea, bool=true) override
Definition: rviz_panel.hpp:77
RVizPanel(QWidget *parent, const rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr &node_abstraction, const DataWarehousePtr &config_data)
Definition: rviz_panel.cpp:45
rviz_common::RenderPanel * rviz_render_panel_
Definition: rviz_panel.hpp:132
QWidget * getParentWindow() override
Definition: rviz_panel.hpp:72