moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
planning_scene_display.hpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
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: Ioan Sucan */
36
37#pragma once
38
39#include <rclcpp/version.h>
40
41#include <rviz_common/display.hpp>
42#include <rviz_default_plugins/robot/robot.hpp>
43#include <rviz_common/properties/string_property.hpp>
44#include <rviz_common/properties/ros_topic_property.hpp>
45#ifndef Q_MOC_RUN
49#include <rclcpp/rclcpp.hpp>
50#endif
51
52#include <moveit_planning_scene_rviz_plugin_core_export.h>
53
54#include <chrono>
55
56namespace Ogre
57{
58class SceneNode;
59}
60
61namespace rviz
62{
63class Robot;
64class Property;
65class StringProperty;
66class BoolProperty;
67class FloatProperty;
68class RosTopicProperty;
69class ColorProperty;
70class EnumProperty;
71} // namespace rviz
72
73namespace moveit_rviz_plugin
74{
75class MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_CORE_EXPORT PlanningSceneDisplay : public rviz_common::Display
76{
77 Q_OBJECT
78
79public:
80 PlanningSceneDisplay(bool listen_to_planning_scene = true, bool show_scene_robot = true);
81 ~PlanningSceneDisplay() override;
82
83 void load(const rviz_common::Config& config) override;
84 void save(rviz_common::Config config) const override;
85
86 // For Rolling, L-turtle, and newer
87#if RCLCPP_VERSION_GTE(30, 0, 0)
88 using rviz_common::Display::update;
89 // `using` handles update(float, float) deprecation warning and redirect
90 void update(std::chrono::nanoseconds wall_dt, std::chrono::nanoseconds ros_dt) override;
91// For Kilted and older
92#else
93 void update(float wall_dt, float ros_dt) override;
94#endif
95
96 void reset() override;
97
98 void setLinkColor(const std::string& link_name, const QColor& color);
99 void unsetLinkColor(const std::string& link_name);
100
101 void queueRenderSceneGeometry();
102
105 void addBackgroundJob(const std::function<void()>& job, const std::string& name);
106
111 void spawnBackgroundJob(const std::function<void()>& job);
112
114 void addMainLoopJob(const std::function<void()>& job);
115
116 void waitForAllMainLoopJobs();
117
119 void clearJobs();
120
121 const std::string getMoveGroupNS() const;
122 const moveit::core::RobotModelConstPtr& getRobotModel() const;
123
125 bool waitForCurrentRobotState(const rclcpp::Time& t);
127 planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO() const;
130 const planning_scene_monitor::PlanningSceneMonitorPtr& getPlanningSceneMonitor();
131
132private Q_SLOTS:
133
134 // ******************************************************************************************
135 // Slot Event Functions
136 // ******************************************************************************************
137 void changedMoveGroupNS();
138 void changedRobotDescription();
139 void changedSceneName();
140 void changedSceneEnabled();
141 void changedSceneRobotVisualEnabled();
142 void changedSceneRobotCollisionEnabled();
143 void changedRobotSceneAlpha();
144 void changedSceneAlpha();
145 void changedSceneColor();
146 void changedPlanningSceneTopic();
147 void changedSceneDisplayTime();
148 void changedOctreeRenderMode();
149 void changedOctreeColorMode();
150 void setSceneName(const QString& name);
151
152protected Q_SLOTS:
153 virtual void changedAttachedBodyColor();
154
155protected:
158 void loadRobotModel();
159
162 virtual void clearRobotModel();
163
166 virtual planning_scene_monitor::PlanningSceneMonitorPtr createPlanningSceneMonitor();
167
169 virtual void onRobotModelLoaded();
171 virtual void onNewPlanningSceneState();
172
176 void calculateOffsetPosition();
177
178 void executeMainLoopJobs();
179 void sceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type);
180 void renderPlanningScene();
181 void setLinkColor(rviz_default_plugins::robot::Robot* robot, const std::string& link_name, const QColor& color);
182 void unsetLinkColor(rviz_default_plugins::robot::Robot* robot, const std::string& link_name);
183 void setGroupColor(rviz_default_plugins::robot::Robot* robot, const std::string& group_name, const QColor& color);
184 void unsetGroupColor(rviz_default_plugins::robot::Robot* robot, const std::string& group_name);
185 void unsetAllColors(rviz_default_plugins::robot::Robot* robot);
186
187 // overrides from Display
188 void onInitialize() override;
189 void onEnable() override;
190 void onDisable() override;
191 void fixedFrameChanged() override;
192
193 // new virtual functions added by this plugin
194 virtual void updateInternal(std::chrono::nanoseconds wall_dt, std::chrono::nanoseconds ros_dt);
195// For Rolling, L-turtle, and newer
196#if RCLCPP_VERSION_GTE(30, 0, 0)
197 [[deprecated("Use updateInternal(std::chrono::nanoseconds, std::chrono::nanoseconds) instead")]] virtual void
198 updateInternal(double wall_dt, double ros_dt);
199// For Kilted and older
200#else
201 virtual void updateInternal(double wall_dt, double ros_dt);
202#endif
203 virtual void onSceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type);
204
205 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
207
209 std::deque<std::function<void()> > main_loop_jobs_;
211 std::condition_variable main_loop_jobs_empty_condition_;
212
213 Ogre::SceneNode* planning_scene_node_;
214
215 // render the planning scene
216 RobotStateVisualizationPtr planning_scene_robot_;
217 PlanningSceneRenderPtr planning_scene_render_;
218
219 // full update required
221 // or only the robot position (excluding attached object changes)
224
225 rviz_common::properties::Property* scene_category_;
226 rviz_common::properties::Property* robot_category_;
227
228 rviz_common::properties::StringProperty* move_group_ns_property_;
229 rviz_common::properties::StringProperty* robot_description_property_;
230 rviz_common::properties::StringProperty* scene_name_property_;
231 rviz_common::properties::BoolProperty* scene_enabled_property_;
232 rviz_common::properties::BoolProperty* scene_robot_visual_enabled_property_;
233 rviz_common::properties::BoolProperty* scene_robot_collision_enabled_property_;
234 rviz_common::properties::RosTopicProperty* planning_scene_topic_property_;
235 rviz_common::properties::FloatProperty* robot_alpha_property_;
236 rviz_common::properties::FloatProperty* scene_alpha_property_;
237 rviz_common::properties::ColorProperty* scene_color_property_;
238 rviz_common::properties::ColorProperty* attached_body_color_property_;
239 rviz_common::properties::FloatProperty* scene_display_time_property_;
240 rviz_common::properties::EnumProperty* octree_render_property_;
241 rviz_common::properties::EnumProperty* octree_coloring_property_;
242
243 // rclcpp node
244 rclcpp::Node::SharedPtr node_;
245 rclcpp::Logger logger_;
246};
247
248} // namespace moveit_rviz_plugin
This class provides simple API for executing background jobs. A queue of jobs is created and the spec...
rviz_common::properties::Property * scene_category_
rviz_common::properties::EnumProperty * octree_coloring_property_
rviz_common::properties::StringProperty * robot_description_property_
rviz_common::properties::BoolProperty * scene_robot_collision_enabled_property_
rviz_common::properties::ColorProperty * attached_body_color_property_
rviz_common::properties::EnumProperty * octree_render_property_
std::deque< std::function< void()> > main_loop_jobs_
rviz_common::properties::FloatProperty * scene_alpha_property_
rviz_common::properties::FloatProperty * robot_alpha_property_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
rviz_common::properties::StringProperty * move_group_ns_property_
rviz_common::properties::StringProperty * scene_name_property_
rviz_common::properties::FloatProperty * scene_display_time_property_
rviz_common::properties::BoolProperty * scene_robot_visual_enabled_property_
rviz_common::properties::Property * robot_category_
rviz_common::properties::RosTopicProperty * planning_scene_topic_property_
Ogre::SceneNode * planning_scene_node_
displays planning scene with everything in it
rviz_common::properties::BoolProperty * scene_enabled_property_
rviz_common::properties::ColorProperty * scene_color_property_
moveit::tools::BackgroundProcessing background_process_
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
This is a convenience class for obtaining access to an instance of a locked PlanningScene.