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 #include <moveit/utils/logger.hpp>
60 
61 namespace moveit_rviz_plugin
62 {
63 // ******************************************************************************************
64 // Base class constructor
65 // ******************************************************************************************
66 PlanningSceneDisplay::PlanningSceneDisplay(bool listen_to_planning_scene, bool show_scene_robot)
67  : Display()
68  , planning_scene_needs_render_(true)
69  , current_scene_time_(0.0f)
70  , logger_(moveit::getLogger("moveit.ros.planning_scene_display"))
71 {
72  move_group_ns_property_ = new rviz_common::properties::StringProperty("Move Group Namespace", "",
73  "The name of the ROS namespace in "
74  "which the move_group node is running",
75  this, SLOT(changedMoveGroupNS()), this);
76  robot_description_property_ = new rviz_common::properties::StringProperty(
77  "Robot Description", "robot_description", "The name of the ROS parameter where the URDF for the robot is loaded",
78  this, SLOT(changedRobotDescription()), this);
79 
80  if (listen_to_planning_scene)
81  {
82  planning_scene_topic_property_ = new rviz_common::properties::RosTopicProperty(
83  "Planning Scene Topic", "/monitored_planning_scene",
84  rosidl_generator_traits::data_type<moveit_msgs::msg::PlanningScene>(),
85  "The topic on which the moveit_msgs::msg::PlanningScene messages are received", this,
86  SLOT(changedPlanningSceneTopic()), this);
87  }
88  else
89  {
91  }
92 
93  // Planning scene category -------------------------------------------------------------------------------------------
94  scene_category_ = new rviz_common::properties::Property("Scene Geometry", QVariant(), "", this);
95 
97  new rviz_common::properties::StringProperty("Scene Name", "(noname)", "Shows the name of the planning scene",
98  scene_category_, SLOT(changedSceneName()), this);
99  scene_name_property_->setShouldBeSaved(false);
101  new rviz_common::properties::BoolProperty("Show Scene Geometry", true,
102  "Indicates whether planning scenes should be displayed",
103  scene_category_, SLOT(changedSceneEnabled()), this);
104 
106  new rviz_common::properties::FloatProperty("Scene Alpha", 0.9f, "Specifies the alpha for the scene geometry",
107  scene_category_, SLOT(changedSceneAlpha()), this);
108  scene_alpha_property_->setMin(0.0);
109  scene_alpha_property_->setMax(1.0);
110 
111  scene_color_property_ = new rviz_common::properties::ColorProperty(
112  "Scene Color", QColor(50, 230, 50), "The color for the planning scene obstacles (if a color is not defined)",
113  scene_category_, SLOT(changedSceneColor()), this);
114 
116  new rviz_common::properties::EnumProperty("Voxel Rendering", "Occupied Voxels", "Select voxel type.",
117  scene_category_, SLOT(changedOctreeRenderMode()), this);
118 
119  octree_render_property_->addOption("Occupied Voxels", OCTOMAP_OCCUPIED_VOXELS);
120  octree_render_property_->addOption("Free Voxels", OCTOMAP_FREE_VOXELS);
122  octree_render_property_->addOption("Disabled", OCTOMAP_DISABLED);
123 
124  octree_coloring_property_ = new rviz_common::properties::EnumProperty(
125  "Voxel Coloring", "Z-Axis", "Select voxel coloring mode", scene_category_, SLOT(changedOctreeColorMode()), this);
126 
127  octree_coloring_property_->addOption("Z-Axis", OCTOMAP_Z_AXIS_COLOR);
128  octree_coloring_property_->addOption("Cell Probability", OCTOMAP_PROBABLILTY_COLOR);
129 
131  new rviz_common::properties::FloatProperty("Scene Display Time", 0.01f,
132  "The amount of wall-time to wait in between rendering "
133  "updates to the planning scene (if any)",
134  scene_category_, SLOT(changedSceneDisplayTime()), this);
135  scene_display_time_property_->setMin(0.0001);
136 
137  if (show_scene_robot)
138  {
139  robot_category_ = new rviz_common::properties::Property("Scene Robot", QVariant(), "", this);
140 
141  scene_robot_visual_enabled_property_ = new rviz_common::properties::BoolProperty(
142  "Show Robot Visual", true,
143  "Indicates whether the robot state specified by the planning scene should be "
144  "displayed as defined for visualisation purposes.",
145  robot_category_, SLOT(changedSceneRobotVisualEnabled()), this);
146 
147  scene_robot_collision_enabled_property_ = new rviz_common::properties::BoolProperty(
148  "Show Robot Collision", false,
149  "Indicates whether the robot state specified by the planning scene should be "
150  "displayed as defined for collision detection purposes.",
151  robot_category_, SLOT(changedSceneRobotCollisionEnabled()), this);
152 
154  new rviz_common::properties::FloatProperty("Robot Alpha", 1.0f, "Specifies the alpha for the robot links",
155  robot_category_, SLOT(changedRobotSceneAlpha()), this);
156  robot_alpha_property_->setMin(0.0);
157  robot_alpha_property_->setMax(1.0);
158 
160  new rviz_common::properties::ColorProperty("Attached Body Color", QColor(150, 50, 150),
161  "The color for the attached bodies", robot_category_,
162  SLOT(changedAttachedBodyColor()), this);
163  }
164  else
165  {
166  robot_category_ = nullptr;
169  robot_alpha_property_ = nullptr;
171  }
172 }
173 
174 // ******************************************************************************************
175 // Deconstructor
176 // ******************************************************************************************
178 {
179  clearJobs();
180 
181  planning_scene_render_.reset();
182  if (context_ && context_->getSceneManager() && planning_scene_node_)
183  context_->getSceneManager()->destroySceneNode(planning_scene_node_);
184  planning_scene_robot_.reset();
185  planning_scene_monitor_.reset();
186 }
187 
189 {
191  {
192  std::unique_lock<std::mutex> ulock(main_loop_jobs_lock_);
193  main_loop_jobs_.clear();
194  }
195 }
196 
198 {
199  Display::onInitialize();
200  auto ros_node_abstraction = context_->getRosNodeAbstraction().lock();
201  if (!ros_node_abstraction)
202  {
203  RVIZ_COMMON_LOG_WARNING("Unable to lock weak_ptr from DisplayContext in PlanningSceneDisplay constructor");
204  return;
205  }
206  node_ = ros_node_abstraction->get_raw_node();
207  planning_scene_topic_property_->initialize(ros_node_abstraction);
208 
209  // the scene node that contains everything and is located at the planning frame
210  planning_scene_node_ = scene_node_->createChildSceneNode();
211 
212  if (robot_category_)
213  {
215  std::make_shared<RobotStateVisualization>(planning_scene_node_, context_, "Planning Scene", robot_category_);
216  planning_scene_robot_->setVisible(true);
217  planning_scene_robot_->setVisualVisible(scene_robot_visual_enabled_property_->getBool());
218  planning_scene_robot_->setCollisionVisible(scene_robot_collision_enabled_property_->getBool());
219  changedRobotSceneAlpha();
221  }
222 }
223 
225 {
227  planning_scene_robot_->clear();
228  Display::reset();
229 
230  if (isEnabled())
231  addBackgroundJob([this] { loadRobotModel(); }, "loadRobotModel");
232 
234  {
235  planning_scene_robot_->setVisible(true);
236  planning_scene_robot_->setVisualVisible(scene_robot_visual_enabled_property_->getBool());
237  planning_scene_robot_->setCollisionVisible(scene_robot_collision_enabled_property_->getBool());
238  }
239 }
240 
241 void PlanningSceneDisplay::addBackgroundJob(const std::function<void()>& job, const std::string& name)
242 {
244 }
245 
246 void PlanningSceneDisplay::spawnBackgroundJob(const std::function<void()>& job)
247 {
248  std::thread t(job);
249  t.detach();
250 }
251 
252 void PlanningSceneDisplay::addMainLoopJob(const std::function<void()>& job)
253 {
254  std::unique_lock<std::mutex> ulock(main_loop_jobs_lock_);
255  main_loop_jobs_.push_back(job);
256 }
257 
259 {
260  std::unique_lock<std::mutex> ulock(main_loop_jobs_lock_);
261  while (!main_loop_jobs_.empty())
263 }
264 
266 {
267  main_loop_jobs_lock_.lock();
268  while (!main_loop_jobs_.empty())
269  {
270  std::function<void()> fn = main_loop_jobs_.front();
271  main_loop_jobs_.pop_front();
272  main_loop_jobs_lock_.unlock();
273  try
274  {
275  fn();
276  }
277  catch (std::exception& ex)
278  {
279  RCLCPP_ERROR(logger_, "Exception caught executing main loop job: %s", ex.what());
280  }
281  main_loop_jobs_lock_.lock();
282  }
283  main_loop_jobs_empty_condition_.notify_all();
284  main_loop_jobs_lock_.unlock();
285 }
286 
287 const planning_scene_monitor::PlanningSceneMonitorPtr& PlanningSceneDisplay::getPlanningSceneMonitor()
288 {
290 }
291 
292 const std::string PlanningSceneDisplay::getMoveGroupNS() const
293 {
294  return move_group_ns_property_->getStdString();
295 }
296 
297 const moveit::core::RobotModelConstPtr& PlanningSceneDisplay::getRobotModel() const
298 {
300  {
301  return planning_scene_monitor_->getRobotModel();
302  }
303  else
304  {
305  static moveit::core::RobotModelConstPtr empty;
306  return empty;
307  }
308 }
309 
311 {
313  return planning_scene_monitor_->waitForCurrentRobotState(t);
314  return false;
315 }
316 
318 {
320 }
321 
323 {
325 }
326 
328 {
330 }
331 
332 void PlanningSceneDisplay::changedSceneColor()
333 {
335 }
336 
337 void PlanningSceneDisplay::changedMoveGroupNS()
338 {
339  if (isEnabled())
340  reset();
341 }
342 
343 void PlanningSceneDisplay::changedRobotDescription()
344 {
345  if (isEnabled())
346  reset();
347 }
348 
349 void PlanningSceneDisplay::changedSceneName()
350 {
352  if (ps)
353  ps->setName(scene_name_property_->getStdString());
354 }
355 
357 {
358  QColor color = scene_color_property_->getColor();
359  Ogre::ColourValue env_color(color.redF(), color.greenF(), color.blueF(), scene_alpha_property_->getFloat());
361  color = attached_body_color_property_->getColor();
362  Ogre::ColourValue attached_color(color.redF(), color.greenF(), color.blueF(), robot_alpha_property_->getFloat());
363 
364  try
365  {
368  {
369  planning_scene_render_->renderPlanningScene(
370  ps, env_color, attached_color, static_cast<OctreeVoxelRenderMode>(octree_render_property_->getOptionInt()),
371  static_cast<OctreeVoxelColorMode>(octree_coloring_property_->getOptionInt()),
372  scene_alpha_property_->getFloat());
373  }
374  else
375  {
376  planning_scene_render_->updateRobotPosition(ps);
377  }
378  }
379  catch (std::exception& ex)
380  {
381  RCLCPP_ERROR(logger_, "Caught %s while rendering planning scene", ex.what());
382  }
383  planning_scene_render_->getGeometryNode()->setVisible(scene_enabled_property_->getBool());
384 }
385 
386 void PlanningSceneDisplay::changedSceneAlpha()
387 {
389 }
390 
391 void PlanningSceneDisplay::changedRobotSceneAlpha()
392 {
394  {
395  planning_scene_robot_->setAlpha(robot_alpha_property_->getFloat());
397  }
398 }
399 
400 void PlanningSceneDisplay::changedPlanningSceneTopic()
401 {
403  {
404  planning_scene_monitor_->startSceneMonitor(planning_scene_topic_property_->getStdString());
406  if (!getMoveGroupNS().empty())
407  service_name = rclcpp::names::append(getMoveGroupNS(), service_name);
408  auto bg_func = [=]() {
409  if (planning_scene_monitor_->requestPlanningSceneState(service_name))
410  {
412  }
413  else
414  {
415  setStatus(rviz_common::properties::StatusProperty::Warn, "PlanningScene", "Requesting initial scene failed");
416  }
417  };
418  addBackgroundJob(bg_func, "requestPlanningSceneState");
419  }
420 }
421 
422 void PlanningSceneDisplay::changedSceneDisplayTime()
423 {
424 }
425 
426 void PlanningSceneDisplay::changedOctreeRenderMode()
427 {
428 }
429 
430 void PlanningSceneDisplay::changedOctreeColorMode()
431 {
432 }
433 
434 void PlanningSceneDisplay::changedSceneRobotVisualEnabled()
435 {
436  if (isEnabled() && planning_scene_robot_)
437  {
438  planning_scene_robot_->setVisible(true);
439  planning_scene_robot_->setVisualVisible(scene_robot_visual_enabled_property_->getBool());
441  }
442 }
443 
444 void PlanningSceneDisplay::changedSceneRobotCollisionEnabled()
445 {
446  if (isEnabled() && planning_scene_robot_)
447  {
448  planning_scene_robot_->setVisible(true);
449  planning_scene_robot_->setCollisionVisible(scene_robot_collision_enabled_property_->getBool());
451  }
452 }
453 
454 void PlanningSceneDisplay::changedSceneEnabled()
455 {
457  planning_scene_render_->getGeometryNode()->setVisible(scene_enabled_property_->getBool());
458 }
459 
460 void PlanningSceneDisplay::setGroupColor(rviz_default_plugins::robot::Robot* robot, const std::string& group_name,
461  const QColor& color)
462 {
463  if (getRobotModel())
464  {
465  const moveit::core::JointModelGroup* jmg = getRobotModel()->getJointModelGroup(group_name);
466  if (jmg)
467  {
468  const std::vector<std::string>& links = jmg->getLinkModelNamesWithCollisionGeometry();
469  for (const std::string& link : links)
470  setLinkColor(robot, link, color);
471  }
472  }
473 }
474 
475 void PlanningSceneDisplay::unsetAllColors(rviz_default_plugins::robot::Robot* robot)
476 {
477  if (getRobotModel())
478  {
479  const std::vector<std::string>& links = getRobotModel()->getLinkModelNamesWithCollisionGeometry();
480  for (const std::string& link : links)
481  unsetLinkColor(robot, link);
482  }
483 }
484 
485 void PlanningSceneDisplay::unsetGroupColor(rviz_default_plugins::robot::Robot* robot, const std::string& group_name)
486 {
487  if (getRobotModel())
488  {
489  const moveit::core::JointModelGroup* jmg = getRobotModel()->getJointModelGroup(group_name);
490  if (jmg)
491  {
492  const std::vector<std::string>& links = jmg->getLinkModelNamesWithCollisionGeometry();
493  for (const std::string& link : links)
494  unsetLinkColor(robot, link);
495  }
496  }
497 }
498 
499 void PlanningSceneDisplay::setLinkColor(const std::string& link_name, const QColor& color)
500 {
502  setLinkColor(&planning_scene_robot_->getRobot(), link_name, color);
503 }
504 
505 void PlanningSceneDisplay::unsetLinkColor(const std::string& link_name)
506 {
508  unsetLinkColor(&planning_scene_robot_->getRobot(), link_name);
509 }
510 
511 void PlanningSceneDisplay::setLinkColor(rviz_default_plugins::robot::Robot* robot, const std::string& link_name,
512  const QColor& color)
513 {
514  rviz_default_plugins::robot::RobotLink* link = robot->getLink(link_name);
515 
516  // Check if link exists
517  if (link)
518  link->setColor(color.redF(), color.greenF(), color.blueF());
519 }
520 
521 void PlanningSceneDisplay::unsetLinkColor(rviz_default_plugins::robot::Robot* robot, const std::string& link_name)
522 {
523  rviz_default_plugins::robot::RobotLink* link = robot->getLink(link_name);
524 
525  // Check if link exists
526  if (link)
527  link->unsetColor();
528 }
529 // ******************************************************************************************
530 // Load
531 // ******************************************************************************************
532 planning_scene_monitor::PlanningSceneMonitorPtr PlanningSceneDisplay::createPlanningSceneMonitor()
533 {
535  return std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(node_, rml,
536  getNameStd() + "_planning_scene_monitor");
537 }
538 
540 {
541  planning_scene_render_.reset();
542  // Ensure old PSM is destroyed before we attempt to create a new one
543  planning_scene_monitor_.reset();
544 }
545 
547 {
548  // wait for other robot loadRobotModel() calls to complete;
549  std::scoped_lock _(robot_model_loading_lock_);
550 
551  // we need to make sure the clearing of the robot model is in the main thread,
552  // so that rendering operations do not have data removed from underneath,
553  // so the next function is executed in the main loop
554  addMainLoopJob([this] { clearRobotModel(); });
555 
557 
558  planning_scene_monitor::PlanningSceneMonitorPtr psm = createPlanningSceneMonitor();
559  if (psm->getPlanningScene())
560  {
561  planning_scene_monitor_.swap(psm);
562  planning_scene_monitor_->addUpdateCallback(
565  });
566  addMainLoopJob([this] { onRobotModelLoaded(); });
568  }
569  else
570  {
571  addMainLoopJob([this]() {
572  setStatus(rviz_common::properties::StatusProperty::Error, "PlanningScene", "No Planning Scene Loaded");
573  });
574  }
575 }
576 
577 // This should always run in the main GUI thread!
579 {
580  changedPlanningSceneTopic();
581  planning_scene_render_ = std::make_shared<PlanningSceneRender>(planning_scene_node_, context_, planning_scene_robot_);
582  planning_scene_render_->getGeometryNode()->setVisible(scene_enabled_property_->getBool());
583 
586  {
587  planning_scene_robot_->load(*getRobotModel()->getURDF());
588  moveit::core::RobotState* rs = new moveit::core::RobotState(ps->getCurrentState());
589  rs->update();
590  planning_scene_robot_->update(moveit::core::RobotStateConstPtr(rs));
591  }
592 
593  bool old_state = scene_name_property_->blockSignals(true);
594  scene_name_property_->setStdString(ps->getName());
595  scene_name_property_->blockSignals(old_state);
596 
597  setStatus(rviz_common::properties::StatusProperty::Ok, "PlanningScene", "Planning Scene Loaded Successfully");
598 }
599 
601 {
602 }
603 
606 {
607  onSceneMonitorReceivedUpdate(update_type);
608 }
609 
612 {
613  getPlanningSceneRW()->getCurrentStateNonConst().update();
614  QMetaObject::invokeMethod(this, "setSceneName", Qt::QueuedConnection,
615  Q_ARG(QString, QString::fromStdString(getPlanningSceneRO()->getName())));
617 }
618 
619 void PlanningSceneDisplay::setSceneName(const QString& name)
620 {
621  scene_name_property_->setString(name);
622 }
623 
625 {
626  Display::onEnable();
627 
628  addBackgroundJob([this] { loadRobotModel(); }, "loadRobotModel");
629 
631  {
632  planning_scene_robot_->setVisible(true);
633  planning_scene_robot_->setVisualVisible(scene_robot_visual_enabled_property_->getBool());
634  planning_scene_robot_->setCollisionVisible(scene_robot_collision_enabled_property_->getBool());
635  }
637  planning_scene_render_->getGeometryNode()->setVisible(scene_enabled_property_->getBool());
638 
641 }
642 
643 // ******************************************************************************************
644 // Disable
645 // ******************************************************************************************
647 {
649  {
650  planning_scene_monitor_->stopSceneMonitor();
652  planning_scene_render_->getGeometryNode()->setVisible(false);
653  }
655  planning_scene_robot_->setVisible(false);
656  Display::onDisable();
657 }
658 
660 {
662 }
663 
664 void PlanningSceneDisplay::update(float wall_dt, float ros_dt)
665 {
666  Display::update(wall_dt, ros_dt);
667 
669 
671 
673  updateInternal(wall_dt, ros_dt);
674 }
675 
676 void PlanningSceneDisplay::updateInternal(double wall_dt, double /*ros_dt*/)
677 {
678  current_scene_time_ += wall_dt;
682  {
684  current_scene_time_ = 0.0f;
687  }
688 }
689 
690 void PlanningSceneDisplay::load(const rviz_common::Config& config)
691 {
692  Display::load(config);
693 }
694 
695 void PlanningSceneDisplay::save(rviz_common::Config config) const
696 {
697  Display::save(config);
698 }
699 
700 // ******************************************************************************************
701 // Calculate Offset Position
702 // ******************************************************************************************
704 {
705  if (!getRobotModel())
706  return;
707 
708  Ogre::Vector3 position;
709  Ogre::Quaternion orientation;
710 
711  context_->getFrameManager()->getTransform(getRobotModel()->getModelFrame(), rclcpp::Time(0, 0, RCL_ROS_TIME),
712  position, orientation);
713 
714  planning_scene_node_->setPosition(position);
715  planning_scene_node_->setOrientation(orientation);
716 }
717 
719 {
720  Display::fixedFrameChanged();
722 }
723 
724 } // 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
virtual void updateInternal(double wall_dt, double ros_dt)
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 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)
void update(moveit::core::RobotState *self, bool force, std::string &category)
Definition: robot_state.cpp:47
Main namespace for MoveIt.
Definition: exceptions.h:43
std::string append(const std::string &left, const std::string &right)
name
Definition: setup.py:7