moveit2
The MoveIt Motion Planning Framework for ROS 2.
planning_scene_display.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * Copyright (c) 2013, Ioan A. Sucan
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Ioan Sucan */
37 
42 
43 #include <rviz_common/transformation/transformation_manager.hpp>
44 #include <rviz_default_plugins/robot/robot.hpp>
45 #include <rviz_default_plugins/robot/robot_link.hpp>
46 
47 #include <rviz_common/properties/property.hpp>
48 #include <rviz_common/properties/bool_property.hpp>
49 #include <rviz_common/properties/float_property.hpp>
50 #include <rviz_common/properties/color_property.hpp>
51 #include <rviz_common/properties/enum_property.hpp>
52 #include <rviz_common/display_context.hpp>
53 #include <tf2_ros/buffer.h>
54 
55 #include <OgreSceneManager.h>
56 #include <OgreSceneNode.h>
57 
59 
60 namespace moveit_rviz_plugin
61 {
62 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_ros_visualization.planning_scene_display");
63 // ******************************************************************************************
64 // Base class constructor
65 // ******************************************************************************************
66 PlanningSceneDisplay::PlanningSceneDisplay(bool listen_to_planning_scene, bool show_scene_robot)
67  : Display(), planning_scene_needs_render_(true), current_scene_time_(0.0f)
68 {
69  move_group_ns_property_ = new rviz_common::properties::StringProperty("Move Group Namespace", "",
70  "The name of the ROS namespace in "
71  "which the move_group node is running",
72  this, SLOT(changedMoveGroupNS()), this);
73  robot_description_property_ = new rviz_common::properties::StringProperty(
74  "Robot Description", "robot_description", "The name of the ROS parameter where the URDF for the robot is loaded",
75  this, SLOT(changedRobotDescription()), this);
76 
77  if (listen_to_planning_scene)
78  planning_scene_topic_property_ = new rviz_common::properties::RosTopicProperty(
79  "Planning Scene Topic", "/monitored_planning_scene",
80  rosidl_generator_traits::data_type<moveit_msgs::msg::PlanningScene>(),
81  "The topic on which the moveit_msgs::msg::PlanningScene messages are received", this,
82  SLOT(changedPlanningSceneTopic()), this);
83  else
85 
86  // Planning scene category -------------------------------------------------------------------------------------------
87  scene_category_ = new rviz_common::properties::Property("Scene Geometry", QVariant(), "", this);
88 
90  new rviz_common::properties::StringProperty("Scene Name", "(noname)", "Shows the name of the planning scene",
91  scene_category_, SLOT(changedSceneName()), this);
92  scene_name_property_->setShouldBeSaved(false);
94  new rviz_common::properties::BoolProperty("Show Scene Geometry", true,
95  "Indicates whether planning scenes should be displayed",
96  scene_category_, SLOT(changedSceneEnabled()), this);
97 
99  new rviz_common::properties::FloatProperty("Scene Alpha", 0.9f, "Specifies the alpha for the scene geometry",
100  scene_category_, SLOT(changedSceneAlpha()), this);
101  scene_alpha_property_->setMin(0.0);
102  scene_alpha_property_->setMax(1.0);
103 
104  scene_color_property_ = new rviz_common::properties::ColorProperty(
105  "Scene Color", QColor(50, 230, 50), "The color for the planning scene obstacles (if a color is not defined)",
106  scene_category_, SLOT(changedSceneColor()), this);
107 
109  new rviz_common::properties::EnumProperty("Voxel Rendering", "Occupied Voxels", "Select voxel type.",
110  scene_category_, SLOT(changedOctreeRenderMode()), this);
111 
112  octree_render_property_->addOption("Occupied Voxels", OCTOMAP_OCCUPIED_VOXELS);
113  octree_render_property_->addOption("Free Voxels", OCTOMAP_FREE_VOXELS);
115  octree_render_property_->addOption("Disabled", OCTOMAP_DISABLED);
116 
117  octree_coloring_property_ = new rviz_common::properties::EnumProperty(
118  "Voxel Coloring", "Z-Axis", "Select voxel coloring mode", scene_category_, SLOT(changedOctreeColorMode()), this);
119 
120  octree_coloring_property_->addOption("Z-Axis", OCTOMAP_Z_AXIS_COLOR);
121  octree_coloring_property_->addOption("Cell Probability", OCTOMAP_PROBABLILTY_COLOR);
122 
124  new rviz_common::properties::FloatProperty("Scene Display Time", 0.01f,
125  "The amount of wall-time to wait in between rendering "
126  "updates to the planning scene (if any)",
127  scene_category_, SLOT(changedSceneDisplayTime()), this);
128  scene_display_time_property_->setMin(0.0001);
129 
130  if (show_scene_robot)
131  {
132  robot_category_ = new rviz_common::properties::Property("Scene Robot", QVariant(), "", this);
133 
134  scene_robot_visual_enabled_property_ = new rviz_common::properties::BoolProperty(
135  "Show Robot Visual", true,
136  "Indicates whether the robot state specified by the planning scene should be "
137  "displayed as defined for visualisation purposes.",
138  robot_category_, SLOT(changedSceneRobotVisualEnabled()), this);
139 
140  scene_robot_collision_enabled_property_ = new rviz_common::properties::BoolProperty(
141  "Show Robot Collision", false,
142  "Indicates whether the robot state specified by the planning scene should be "
143  "displayed as defined for collision detection purposes.",
144  robot_category_, SLOT(changedSceneRobotCollisionEnabled()), this);
145 
147  new rviz_common::properties::FloatProperty("Robot Alpha", 1.0f, "Specifies the alpha for the robot links",
148  robot_category_, SLOT(changedRobotSceneAlpha()), this);
149  robot_alpha_property_->setMin(0.0);
150  robot_alpha_property_->setMax(1.0);
151 
153  new rviz_common::properties::ColorProperty("Attached Body Color", QColor(150, 50, 150),
154  "The color for the attached bodies", robot_category_,
155  SLOT(changedAttachedBodyColor()), this);
156  }
157  else
158  {
159  robot_category_ = nullptr;
162  robot_alpha_property_ = nullptr;
164  }
165 }
166 
167 // ******************************************************************************************
168 // Deconstructor
169 // ******************************************************************************************
171 {
172  clearJobs();
173 
174  planning_scene_render_.reset();
175  if (context_ && context_->getSceneManager() && planning_scene_node_)
176  context_->getSceneManager()->destroySceneNode(planning_scene_node_);
177  planning_scene_robot_.reset();
178  planning_scene_monitor_.reset();
179 }
180 
182 {
184  {
185  std::unique_lock<std::mutex> ulock(main_loop_jobs_lock_);
186  main_loop_jobs_.clear();
187  }
188 }
189 
191 {
192  Display::onInitialize();
193  auto ros_node_abstraction = context_->getRosNodeAbstraction().lock();
194  if (!ros_node_abstraction)
195  {
196  RVIZ_COMMON_LOG_WARNING("Unable to lock weak_ptr from DisplayContext in PlanningSceneDisplay constructor");
197  return;
198  }
199  node_ = ros_node_abstraction->get_raw_node();
200  planning_scene_topic_property_->initialize(ros_node_abstraction);
201 
202  // the scene node that contains everything and is located at the planning frame
203  planning_scene_node_ = scene_node_->createChildSceneNode();
204 
205  if (robot_category_)
206  {
208  std::make_shared<RobotStateVisualization>(planning_scene_node_, context_, "Planning Scene", robot_category_);
209  planning_scene_robot_->setVisible(true);
210  planning_scene_robot_->setVisualVisible(scene_robot_visual_enabled_property_->getBool());
211  planning_scene_robot_->setCollisionVisible(scene_robot_collision_enabled_property_->getBool());
212  changedRobotSceneAlpha();
214  }
215 }
216 
218 {
220  planning_scene_robot_->clear();
221  Display::reset();
222 
223  if (isEnabled())
224  addBackgroundJob([this] { loadRobotModel(); }, "loadRobotModel");
225 
227  {
228  planning_scene_robot_->setVisible(true);
229  planning_scene_robot_->setVisualVisible(scene_robot_visual_enabled_property_->getBool());
230  planning_scene_robot_->setCollisionVisible(scene_robot_collision_enabled_property_->getBool());
231  }
232 }
233 
234 void PlanningSceneDisplay::addBackgroundJob(const std::function<void()>& job, const std::string& name)
235 {
237 }
238 
239 void PlanningSceneDisplay::spawnBackgroundJob(const std::function<void()>& job)
240 {
241  std::thread t(job);
242  t.detach();
243 }
244 
245 void PlanningSceneDisplay::addMainLoopJob(const std::function<void()>& job)
246 {
247  std::unique_lock<std::mutex> ulock(main_loop_jobs_lock_);
248  main_loop_jobs_.push_back(job);
249 }
250 
252 {
253  std::unique_lock<std::mutex> ulock(main_loop_jobs_lock_);
254  while (!main_loop_jobs_.empty())
256 }
257 
259 {
260  main_loop_jobs_lock_.lock();
261  while (!main_loop_jobs_.empty())
262  {
263  std::function<void()> fn = main_loop_jobs_.front();
264  main_loop_jobs_.pop_front();
265  main_loop_jobs_lock_.unlock();
266  try
267  {
268  fn();
269  }
270  catch (std::exception& ex)
271  {
272  RCLCPP_ERROR(LOGGER, "Exception caught executing main loop job: %s", ex.what());
273  }
274  main_loop_jobs_lock_.lock();
275  }
276  main_loop_jobs_empty_condition_.notify_all();
277  main_loop_jobs_lock_.unlock();
278 }
279 
280 const planning_scene_monitor::PlanningSceneMonitorPtr& PlanningSceneDisplay::getPlanningSceneMonitor()
281 {
283 }
284 
285 const std::string PlanningSceneDisplay::getMoveGroupNS() const
286 {
287  return move_group_ns_property_->getStdString();
288 }
289 
290 const moveit::core::RobotModelConstPtr& PlanningSceneDisplay::getRobotModel() const
291 {
293  return planning_scene_monitor_->getRobotModel();
294  else
295  {
296  static moveit::core::RobotModelConstPtr empty;
297  return empty;
298  }
299 }
300 
302 {
304  return planning_scene_monitor_->waitForCurrentRobotState(t);
305  return false;
306 }
307 
309 {
311 }
312 
314 {
316 }
317 
319 {
321 }
322 
323 void PlanningSceneDisplay::changedSceneColor()
324 {
326 }
327 
328 void PlanningSceneDisplay::changedMoveGroupNS()
329 {
330  if (isEnabled())
331  reset();
332 }
333 
334 void PlanningSceneDisplay::changedRobotDescription()
335 {
336  if (isEnabled())
337  reset();
338 }
339 
340 void PlanningSceneDisplay::changedSceneName()
341 {
343  if (ps)
344  ps->setName(scene_name_property_->getStdString());
345 }
346 
348 {
349  QColor color = scene_color_property_->getColor();
350  Ogre::ColourValue env_color(color.redF(), color.greenF(), color.blueF(), scene_alpha_property_->getFloat());
352  color = attached_body_color_property_->getColor();
353  Ogre::ColourValue attached_color(color.redF(), color.greenF(), color.blueF(), robot_alpha_property_->getFloat());
354 
355  try
356  {
359  {
360  planning_scene_render_->renderPlanningScene(
361  ps, env_color, attached_color, static_cast<OctreeVoxelRenderMode>(octree_render_property_->getOptionInt()),
362  static_cast<OctreeVoxelColorMode>(octree_coloring_property_->getOptionInt()),
363  scene_alpha_property_->getFloat());
364  }
365  else
366  {
367  planning_scene_render_->updateRobotPosition(ps);
368  }
369  }
370  catch (std::exception& ex)
371  {
372  RCLCPP_ERROR(LOGGER, "Caught %s while rendering planning scene", ex.what());
373  }
374  planning_scene_render_->getGeometryNode()->setVisible(scene_enabled_property_->getBool());
375 }
376 
377 void PlanningSceneDisplay::changedSceneAlpha()
378 {
380 }
381 
382 void PlanningSceneDisplay::changedRobotSceneAlpha()
383 {
385  {
386  planning_scene_robot_->setAlpha(robot_alpha_property_->getFloat());
388  }
389 }
390 
391 void PlanningSceneDisplay::changedPlanningSceneTopic()
392 {
394  {
395  planning_scene_monitor_->startSceneMonitor(planning_scene_topic_property_->getStdString());
397  if (!getMoveGroupNS().empty())
398  service_name = rclcpp::names::append(getMoveGroupNS(), service_name);
399  auto bg_func = [=]() {
400  if (planning_scene_monitor_->requestPlanningSceneState(service_name))
402  else
403  setStatus(rviz_common::properties::StatusProperty::Warn, "PlanningScene", "Requesting initial scene failed");
404  };
405  addBackgroundJob(bg_func, "requestPlanningSceneState");
406  }
407 }
408 
409 void PlanningSceneDisplay::changedSceneDisplayTime()
410 {
411 }
412 
413 void PlanningSceneDisplay::changedOctreeRenderMode()
414 {
415 }
416 
417 void PlanningSceneDisplay::changedOctreeColorMode()
418 {
419 }
420 
421 void PlanningSceneDisplay::changedSceneRobotVisualEnabled()
422 {
423  if (isEnabled() && planning_scene_robot_)
424  {
425  planning_scene_robot_->setVisible(true);
426  planning_scene_robot_->setVisualVisible(scene_robot_visual_enabled_property_->getBool());
428  }
429 }
430 
431 void PlanningSceneDisplay::changedSceneRobotCollisionEnabled()
432 {
433  if (isEnabled() && planning_scene_robot_)
434  {
435  planning_scene_robot_->setVisible(true);
436  planning_scene_robot_->setCollisionVisible(scene_robot_collision_enabled_property_->getBool());
438  }
439 }
440 
441 void PlanningSceneDisplay::changedSceneEnabled()
442 {
444  planning_scene_render_->getGeometryNode()->setVisible(scene_enabled_property_->getBool());
445 }
446 
447 void PlanningSceneDisplay::setGroupColor(rviz_default_plugins::robot::Robot* robot, const std::string& group_name,
448  const QColor& color)
449 {
450  if (getRobotModel())
451  {
452  const moveit::core::JointModelGroup* jmg = getRobotModel()->getJointModelGroup(group_name);
453  if (jmg)
454  {
455  const std::vector<std::string>& links = jmg->getLinkModelNamesWithCollisionGeometry();
456  for (const std::string& link : links)
457  setLinkColor(robot, link, color);
458  }
459  }
460 }
461 
462 void PlanningSceneDisplay::unsetAllColors(rviz_default_plugins::robot::Robot* robot)
463 {
464  if (getRobotModel())
465  {
466  const std::vector<std::string>& links = getRobotModel()->getLinkModelNamesWithCollisionGeometry();
467  for (const std::string& link : links)
468  unsetLinkColor(robot, link);
469  }
470 }
471 
472 void PlanningSceneDisplay::unsetGroupColor(rviz_default_plugins::robot::Robot* robot, const std::string& group_name)
473 {
474  if (getRobotModel())
475  {
476  const moveit::core::JointModelGroup* jmg = getRobotModel()->getJointModelGroup(group_name);
477  if (jmg)
478  {
479  const std::vector<std::string>& links = jmg->getLinkModelNamesWithCollisionGeometry();
480  for (const std::string& link : links)
481  unsetLinkColor(robot, link);
482  }
483  }
484 }
485 
486 void PlanningSceneDisplay::setLinkColor(const std::string& link_name, const QColor& color)
487 {
489  setLinkColor(&planning_scene_robot_->getRobot(), link_name, color);
490 }
491 
492 void PlanningSceneDisplay::unsetLinkColor(const std::string& link_name)
493 {
495  unsetLinkColor(&planning_scene_robot_->getRobot(), link_name);
496 }
497 
498 void PlanningSceneDisplay::setLinkColor(rviz_default_plugins::robot::Robot* robot, const std::string& link_name,
499  const QColor& color)
500 {
501  rviz_default_plugins::robot::RobotLink* link = robot->getLink(link_name);
502 
503  // Check if link exists
504  if (link)
505  link->setColor(color.redF(), color.greenF(), color.blueF());
506 }
507 
508 void PlanningSceneDisplay::unsetLinkColor(rviz_default_plugins::robot::Robot* robot, const std::string& link_name)
509 {
510  rviz_default_plugins::robot::RobotLink* link = robot->getLink(link_name);
511 
512  // Check if link exists
513  if (link)
514  link->unsetColor();
515 }
516 // ******************************************************************************************
517 // Load
518 // ******************************************************************************************
519 planning_scene_monitor::PlanningSceneMonitorPtr PlanningSceneDisplay::createPlanningSceneMonitor()
520 {
522  return std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(node_, rml,
523  getNameStd() + "_planning_scene_monitor");
524 }
525 
527 {
528  planning_scene_render_.reset();
529  // Ensure old PSM is destroyed before we attempt to create a new one
530  planning_scene_monitor_.reset();
531 }
532 
534 {
535  // wait for other robot loadRobotModel() calls to complete;
536  std::scoped_lock _(robot_model_loading_lock_);
537 
538  // we need to make sure the clearing of the robot model is in the main thread,
539  // so that rendering operations do not have data removed from underneath,
540  // so the next function is executed in the main loop
541  addMainLoopJob([this] { clearRobotModel(); });
542 
544 
545  planning_scene_monitor::PlanningSceneMonitorPtr psm = createPlanningSceneMonitor();
546  if (psm->getPlanningScene())
547  {
548  planning_scene_monitor_.swap(psm);
549  planning_scene_monitor_->addUpdateCallback(
552  });
553  addMainLoopJob([this] { onRobotModelLoaded(); });
555  }
556  else
557  {
558  addMainLoopJob([this]() {
559  setStatus(rviz_common::properties::StatusProperty::Error, "PlanningScene", "No Planning Scene Loaded");
560  });
561  }
562 }
563 
564 // This should always run in the main GUI thread!
566 {
567  changedPlanningSceneTopic();
568  planning_scene_render_ = std::make_shared<PlanningSceneRender>(planning_scene_node_, context_, planning_scene_robot_);
569  planning_scene_render_->getGeometryNode()->setVisible(scene_enabled_property_->getBool());
570 
573  {
574  planning_scene_robot_->load(*getRobotModel()->getURDF());
575  moveit::core::RobotState* rs = new moveit::core::RobotState(ps->getCurrentState());
576  rs->update();
577  planning_scene_robot_->update(moveit::core::RobotStateConstPtr(rs));
578  }
579 
580  bool old_state = scene_name_property_->blockSignals(true);
581  scene_name_property_->setStdString(ps->getName());
582  scene_name_property_->blockSignals(old_state);
583 
584  setStatus(rviz_common::properties::StatusProperty::Ok, "PlanningScene", "Planning Scene Loaded Successfully");
585 }
586 
588 {
589 }
590 
593 {
594  onSceneMonitorReceivedUpdate(update_type);
595 }
596 
599 {
600  getPlanningSceneRW()->getCurrentStateNonConst().update();
601  QMetaObject::invokeMethod(this, "setSceneName", Qt::QueuedConnection,
602  Q_ARG(QString, QString::fromStdString(getPlanningSceneRO()->getName())));
604 }
605 
606 void PlanningSceneDisplay::setSceneName(const QString& name)
607 {
608  scene_name_property_->setString(name);
609 }
610 
612 {
613  Display::onEnable();
614 
615  addBackgroundJob([this] { loadRobotModel(); }, "loadRobotModel");
616 
618  {
619  planning_scene_robot_->setVisible(true);
620  planning_scene_robot_->setVisualVisible(scene_robot_visual_enabled_property_->getBool());
621  planning_scene_robot_->setCollisionVisible(scene_robot_collision_enabled_property_->getBool());
622  }
624  planning_scene_render_->getGeometryNode()->setVisible(scene_enabled_property_->getBool());
625 
628 }
629 
630 // ******************************************************************************************
631 // Disable
632 // ******************************************************************************************
634 {
636  {
637  planning_scene_monitor_->stopSceneMonitor();
639  planning_scene_render_->getGeometryNode()->setVisible(false);
640  }
642  planning_scene_robot_->setVisible(false);
643  Display::onDisable();
644 }
645 
647 {
649 }
650 
651 void PlanningSceneDisplay::update(float wall_dt, float ros_dt)
652 {
653  Display::update(wall_dt, ros_dt);
654 
656 
658 
660  updateInternal(wall_dt, ros_dt);
661 }
662 
663 void PlanningSceneDisplay::updateInternal(float wall_dt, float /*ros_dt*/)
664 {
665  current_scene_time_ += wall_dt;
669  {
671  current_scene_time_ = 0.0f;
674  }
675 }
676 
677 void PlanningSceneDisplay::load(const rviz_common::Config& config)
678 {
679  Display::load(config);
680 }
681 
682 void PlanningSceneDisplay::save(rviz_common::Config config) const
683 {
684  Display::save(config);
685 }
686 
687 // ******************************************************************************************
688 // Calculate Offset Position
689 // ******************************************************************************************
691 {
692  if (!getRobotModel())
693  return;
694 
695  Ogre::Vector3 position;
696  Ogre::Quaternion orientation;
697 
698  context_->getFrameManager()->getTransform(getRobotModel()->getModelFrame(), rclcpp::Time(0, 0, RCL_ROS_TIME),
699  position, orientation);
700 
701  planning_scene_node_->setPosition(position);
702  planning_scene_node_->setOrientation(orientation);
703 }
704 
706 {
707  Display::fixedFrameChanged();
709 }
710 
711 } // namespace moveit_rviz_plugin
const std::vector< std::string > & getLinkModelNamesWithCollisionGeometry() const
Get the names of the links that are part of this joint group and also have geometry associated with t...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void update(bool force=false)
Update all transforms.
void clear()
Clear the queue of jobs.
void addJob(const JobCallback &job, const std::string &name)
Add a job to the queue of jobs to execute. A name is also specifies for the job.
rviz_common::properties::Property * scene_category_
rviz_common::properties::EnumProperty * octree_coloring_property_
planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO() const
get read-only access to planning scene
rviz_common::properties::StringProperty * robot_description_property_
void unsetGroupColor(rviz_default_plugins::robot::Robot *robot, const std::string &group_name)
rviz_common::properties::BoolProperty * scene_robot_collision_enabled_property_
rviz_common::properties::ColorProperty * attached_body_color_property_
void setLinkColor(const std::string &link_name, const QColor &color)
rviz_common::properties::EnumProperty * octree_render_property_
void sceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type)
planning_scene_monitor::LockedPlanningSceneRW getPlanningSceneRW()
get write access to planning scene
void save(rviz_common::Config config) const override
void unsetLinkColor(const std::string &link_name)
void spawnBackgroundJob(const std::function< void()> &job)
std::deque< std::function< void()> > main_loop_jobs_
virtual void onRobotModelLoaded()
This is an event called by loadRobotModel() in the MainLoop; do not call directly.
rviz_common::properties::FloatProperty * scene_alpha_property_
void setGroupColor(rviz_default_plugins::robot::Robot *robot, const std::string &group_name, const QColor &color)
void calculateOffsetPosition()
Set the scene node's position, given the target frame and the planning frame.
virtual void updateInternal(float wall_dt, float ros_dt)
virtual void onSceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type)
void addMainLoopJob(const std::function< void()> &job)
queue the execution of this function for the next time the main update() loop gets called
virtual planning_scene_monitor::PlanningSceneMonitorPtr createPlanningSceneMonitor()
rviz_common::properties::FloatProperty * robot_alpha_property_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
const moveit::core::RobotModelConstPtr & getRobotModel() const
void addBackgroundJob(const std::function< void()> &job, const std::string &name)
rviz_common::properties::StringProperty * move_group_ns_property_
rviz_common::properties::StringProperty * scene_name_property_
void update(float wall_dt, float ros_dt) override
PlanningSceneDisplay(bool listen_to_planning_scene=true, bool show_scene_robot=true)
rviz_common::properties::FloatProperty * scene_display_time_property_
virtual void onNewPlanningSceneState()
This is called upon successful retrieval of the (initial) planning scene state.
rviz_common::properties::BoolProperty * scene_robot_visual_enabled_property_
rviz_common::properties::Property * robot_category_
void unsetAllColors(rviz_default_plugins::robot::Robot *robot)
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_
bool waitForCurrentRobotState(const rclcpp::Time &t)
wait for robot state more recent than t
const planning_scene_monitor::PlanningSceneMonitorPtr & getPlanningSceneMonitor()
rviz_common::properties::ColorProperty * scene_color_property_
moveit::tools::BackgroundProcessing background_process_
void load(const rviz_common::Config &config) override
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.
static const std::string DEFAULT_PLANNING_SCENE_SERVICE
The name of the service used by default for requesting full planning scene state.
robot_model_loader::RobotModelLoaderPtr getSharedRobotModelLoader(const rclcpp::Node::SharedPtr &node, const std::string &robot_description)
robot
Definition: pick.py:53
std::string append(const std::string &left, const std::string &right)
name
Definition: setup.py:7
const rclcpp::Logger LOGGER
Definition: async_test.h:31