moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_display.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015, University of Colorado, Boulder
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 the Univ of CO, Boulder 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: Dave Coleman
36  Desc: Wraps a trajectory_visualization playback class for Rviz into a stand alone display
37 */
38 
40 #include <rviz_common/properties/string_property.hpp>
41 
42 #include <memory>
43 
44 namespace moveit_rviz_plugin
45 {
46 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.visualization.trajectory_display");
47 
49 {
50  // The robot description property is only needed when using the trajectory playback standalone (not within motion
51  // planning plugin)
52  robot_description_property_ = new rviz_common::properties::StringProperty(
53  "Robot Description", "robot_description", "The name of the ROS parameter where the URDF for the robot is loaded",
54  this, SLOT(changedRobotDescription()), this);
55 
56  trajectory_visual_ = std::make_shared<TrajectoryVisualization>(this, this);
57 }
58 
60 
62 {
63  Display::onInitialize();
64 
65  auto ros_node_abstraction = context_->getRosNodeAbstraction().lock();
66  if (!ros_node_abstraction)
67  {
68  RCLCPP_INFO(LOGGER, "Unable to lock weak_ptr from DisplayContext in TrajectoryDisplay constructor");
69  return;
70  }
71  node_ = ros_node_abstraction->get_raw_node();
72  trajectory_visual_->onInitialize(node_, scene_node_, context_);
73 }
74 
76 {
77  try
78  {
79  rdf_loader_ = std::make_shared<rdf_loader::RDFLoader>(node_, robot_description_property_->getStdString());
80 
81  if (!rdf_loader_->getURDF())
82  {
83  this->setStatus(rviz_common::properties::StatusProperty::Error, "Robot Model",
84  "Failed to load from parameter " + robot_description_property_->getString());
85  return;
86  }
87  this->setStatus(rviz_common::properties::StatusProperty::Ok, "Robot Model", "Successfully loaded");
88 
89  const srdf::ModelSharedPtr& srdf =
90  rdf_loader_->getSRDF() ? rdf_loader_->getSRDF() : std::make_shared<srdf::Model>();
91  robot_model_ = std::make_shared<moveit::core::RobotModel>(rdf_loader_->getURDF(), srdf);
92 
93  // Send to child class
94  trajectory_visual_->onRobotModelLoaded(robot_model_);
95  }
96  catch (std::exception& e)
97  {
98  setStatus(rviz_common::properties::StatusProperty::Error, "RobotModel", QString("Loading failed: %1").arg(e.what()));
99  }
100 }
101 
103 {
104  Display::reset();
105  loadRobotModel();
106  trajectory_visual_->reset();
107 }
108 
109 void TrajectoryDisplay::load(const rviz_common::Config& config)
110 {
111  // This property needs to be loaded in onEnable() below, which is triggered
112  // in the beginning of Display::load() before the other property would be available
113  robot_description_property_->load(config.mapGetChild("Robot Description"));
114  Display::load(config);
115 }
116 
118 {
119  Display::onEnable();
120  if (!rdf_loader_)
121  loadRobotModel();
122  trajectory_visual_->onEnable();
123 }
124 
126 {
127  Display::onDisable();
128  trajectory_visual_->onDisable();
129 }
130 
131 void TrajectoryDisplay::update(float wall_dt, float ros_dt)
132 {
133  Display::update(wall_dt, ros_dt);
134  trajectory_visual_->update(wall_dt, ros_dt);
135 }
136 
137 void TrajectoryDisplay::changedRobotDescription()
138 {
139  if (isEnabled())
140  reset();
141  else
142  loadRobotModel();
143 }
144 
145 } // namespace moveit_rviz_plugin
void load(const rviz_common::Config &config) override
moveit::core::RobotModelConstPtr robot_model_
TrajectoryVisualizationPtr trajectory_visual_
void update(float wall_dt, float ros_dt) override
rviz_common::properties::StringProperty * robot_description_property_
const rclcpp::Logger LOGGER
Definition: async_test.h:31