planning_scene_display.h
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 #ifndef MOVEIT_VISUALIZATION_SCENE_DISPLAY_RVIZ_PLUGIN_SCENE_DISPLAY_
38 #define MOVEIT_VISUALIZATION_SCENE_DISPLAY_RVIZ_PLUGIN_SCENE_DISPLAY_
39 
40 #include <rviz/display.h>
41 
42 #ifndef Q_MOC_RUN
46 #include <ros/ros.h>
47 #endif
48 
49 namespace Ogre
50 {
51 class SceneNode;
52 }
53 
54 namespace rviz
55 {
56 class Robot;
57 class Property;
58 class StringProperty;
59 class BoolProperty;
60 class FloatProperty;
61 class RosTopicProperty;
62 class ColorProperty;
63 class EnumProperty;
64 }
65 
66 namespace moveit_rviz_plugin
67 {
69 {
70  Q_OBJECT
71 
72 public:
73  PlanningSceneDisplay(bool listen_to_planning_scene = true, bool show_scene_robot = true);
74  virtual ~PlanningSceneDisplay();
75 
76  virtual void load(const rviz::Config& config);
77  virtual void save(rviz::Config config) const;
78 
79  virtual void update(float wall_dt, float ros_dt);
80  virtual void reset();
81 
82  void setLinkColor(const std::string& link_name, const QColor& color);
83  void unsetLinkColor(const std::string& link_name);
84 
85  void queueRenderSceneGeometry();
86 
89  void addBackgroundJob(const boost::function<void()>& job, const std::string& name);
90 
95  void spawnBackgroundJob(const boost::function<void()>& job);
96 
98  void addMainLoopJob(const boost::function<void()>& job);
99 
100  void waitForAllMainLoopJobs();
101 
103  void clearJobs();
104 
105  const std::string getMoveGroupNS() const;
106  const robot_model::RobotModelConstPtr& getRobotModel() const;
107 
109  bool waitForCurrentRobotState(const ros::Time& t = ros::Time::now());
111  planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO() const;
114  const planning_scene_monitor::PlanningSceneMonitorPtr& getPlanningSceneMonitor();
115 
116 private Q_SLOTS:
117 
118  // ******************************************************************************************
119  // Slot Event Functions
120  // ******************************************************************************************
121  void changedMoveGroupNS();
122  void changedRobotDescription();
123  void changedSceneName();
124  void changedSceneEnabled();
125  void changedSceneRobotVisualEnabled();
126  void changedSceneRobotCollisionEnabled();
127  void changedRobotSceneAlpha();
128  void changedSceneAlpha();
129  void changedSceneColor();
130  void changedPlanningSceneTopic();
131  void changedSceneDisplayTime();
132  void changedOctreeRenderMode();
133  void changedOctreeColorMode();
134 
135 protected Q_SLOTS:
136  virtual void changedAttachedBodyColor();
137 
138 protected:
141  void loadRobotModel();
142 
145  void clearRobotModel();
146 
149  virtual planning_scene_monitor::PlanningSceneMonitorPtr createPlanningSceneMonitor();
150 
152  virtual void onRobotModelLoaded();
153 
157  void calculateOffsetPosition();
158 
159  void executeMainLoopJobs();
160  void sceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type);
161  void renderPlanningScene();
162  void setLinkColor(rviz::Robot* robot, const std::string& link_name, const QColor& color);
163  void unsetLinkColor(rviz::Robot* robot, const std::string& link_name);
164  void setGroupColor(rviz::Robot* robot, const std::string& group_name, const QColor& color);
165  void unsetGroupColor(rviz::Robot* robot, const std::string& group_name);
166  void unsetAllColors(rviz::Robot* robot);
167 
168  // overrides from Display
169  virtual void onInitialize();
170  virtual void onEnable();
171  virtual void onDisable();
172  virtual void fixedFrameChanged();
173 
174  // new virtual functions added by this plugin
175  virtual void updateInternal(float wall_dt, float ros_dt);
176  virtual void onSceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type);
177 
178  planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
181 
183  std::deque<boost::function<void()> > main_loop_jobs_;
184  boost::mutex main_loop_jobs_lock_;
186 
187  Ogre::SceneNode* planning_scene_node_;
188 
189  // render the planning scene
190  RobotStateVisualizationPtr planning_scene_robot_;
191  PlanningSceneRenderPtr planning_scene_render_;
192 
195 
198 
213 };
214 
215 } // namespace moveit_rviz_plugin
216 
217 #endif
rviz::RosTopicProperty * planning_scene_topic_property_
void loadRobotModel(urdf::ModelInterfaceSharedPtr &robot_model_out)
config
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
std::deque< boost::function< void()> > main_loop_jobs_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
Ogre::SceneNode * planning_scene_node_
displays planning scene with everything in it
moveit::tools::BackgroundProcessing background_process_
static Time now()
boost::condition_variable main_loop_jobs_empty_condition_


visualization
Author(s): Ioan Sucan , Dave Coleman , Sachin Chitta
autogenerated on Wed Jul 10 2019 04:04:24