moveit2
The MoveIt Motion Planning Framework for ROS 2.
robot_state_visualization.cpp
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 
40 #include <rviz_common/properties/parse_color.hpp>
41 #include <rviz_default_plugins/robot/robot_link.hpp>
42 #include <QApplication>
43 
44 namespace moveit_rviz_plugin
45 {
46 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.rviz_plugin_render_tools.robot_state_visualization");
47 RobotStateVisualization::RobotStateVisualization(Ogre::SceneNode* root_node, rviz_common::DisplayContext* context,
48  const std::string& name,
49  rviz_common::properties::Property* parent_property)
50  : robot_(root_node, context, name, parent_property)
51  , octree_voxel_render_mode_(OCTOMAP_OCCUPIED_VOXELS)
52  , octree_voxel_color_mode_(OCTOMAP_Z_AXIS_COLOR)
53  , visible_(true)
54  , visual_visible_(true)
55  , collision_visible_(false)
56 {
57  default_attached_object_color_.r = 0.0f;
58  default_attached_object_color_.g = 0.7f;
59  default_attached_object_color_.b = 0.0f;
60  default_attached_object_color_.a = 1.0f;
61  render_shapes_ = std::make_shared<RenderShapes>(context);
62 }
63 
64 void RobotStateVisualization::load(const urdf::ModelInterface& descr, bool visual, bool collision)
65 {
66  // clear previously loaded model
67  clear();
68 
69  robot_.load(descr, visual, collision);
70  robot_.setVisualVisible(visual_visible_);
71  robot_.setCollisionVisible(collision_visible_);
72  robot_.setVisible(visible_);
73 }
74 
76 {
77  render_shapes_->clear();
78  robot_.clear();
79 }
80 
81 void RobotStateVisualization::setDefaultAttachedObjectColor(const std_msgs::msg::ColorRGBA& default_attached_object_color)
82 {
83  default_attached_object_color_ = default_attached_object_color;
84 }
85 
86 void RobotStateVisualization::updateAttachedObjectColors(const std_msgs::msg::ColorRGBA& attached_object_color)
87 {
88  render_shapes_->updateShapeColors(attached_object_color.r, attached_object_color.g, attached_object_color.b,
89  robot_.getAlpha());
90 }
91 
92 void RobotStateVisualization::update(const moveit::core::RobotStateConstPtr& kinematic_state)
93 {
94  updateHelper(kinematic_state, default_attached_object_color_, nullptr);
95 }
96 
97 void RobotStateVisualization::update(const moveit::core::RobotStateConstPtr& kinematic_state,
98  const std_msgs::msg::ColorRGBA& default_attached_object_color)
99 {
100  updateHelper(kinematic_state, default_attached_object_color, nullptr);
101 }
102 
103 void RobotStateVisualization::update(const moveit::core::RobotStateConstPtr& kinematic_state,
104  const std_msgs::msg::ColorRGBA& default_attached_object_color,
105  const std::map<std::string, std_msgs::msg::ColorRGBA>& color_map)
106 {
107  updateHelper(kinematic_state, default_attached_object_color, &color_map);
108 }
109 
110 void RobotStateVisualization::updateHelper(const moveit::core::RobotStateConstPtr& kinematic_state,
111  const std_msgs::msg::ColorRGBA& default_attached_object_color,
112  const std::map<std::string, std_msgs::msg::ColorRGBA>* color_map)
113 {
114  robot_.update(PlanningLinkUpdater(kinematic_state));
115  render_shapes_->clear();
116 
117  std::vector<const moveit::core::AttachedBody*> attached_bodies;
118  kinematic_state->getAttachedBodies(attached_bodies);
119  for (const moveit::core::AttachedBody* attached_body : attached_bodies)
120  {
121  std_msgs::msg::ColorRGBA color = default_attached_object_color;
122  float alpha = robot_.getAlpha();
123  if (color_map)
124  {
125  std::map<std::string, std_msgs::msg::ColorRGBA>::const_iterator it = color_map->find(attached_body->getName());
126  if (it != color_map->end())
127  { // render attached bodies with a color that is a bit different
128  color.r = std::max(1.0f, it->second.r * 1.05f);
129  color.g = std::max(1.0f, it->second.g * 1.05f);
130  color.b = std::max(1.0f, it->second.b * 1.05f);
131  alpha = color.a = it->second.a;
132  }
133  }
134  rviz_default_plugins::robot::RobotLink* link = robot_.getLink(attached_body->getAttachedLinkName());
135  if (!link)
136  {
137  RCLCPP_ERROR_STREAM(LOGGER, "Link " << attached_body->getAttachedLinkName() << " not found in rviz::Robot");
138  continue;
139  }
140  Ogre::ColourValue rcolor(color.r, color.g, color.b);
141  const EigenSTL::vector_Isometry3d& ab_t = attached_body->getShapePosesInLinkFrame();
142  const std::vector<shapes::ShapeConstPtr>& ab_shapes = attached_body->getShapes();
143  for (std::size_t j = 0; j < ab_shapes.size(); ++j)
144  {
145  render_shapes_->renderShape(link->getVisualNode(), ab_shapes[j].get(), ab_t[j], octree_voxel_render_mode_,
146  octree_voxel_color_mode_, rcolor, alpha);
147  render_shapes_->renderShape(link->getCollisionNode(), ab_shapes[j].get(), ab_t[j], octree_voxel_render_mode_,
148  octree_voxel_color_mode_, rcolor, alpha);
149  }
150  }
151  robot_.setVisualVisible(visual_visible_);
152  robot_.setCollisionVisible(collision_visible_);
153  robot_.setVisible(visible_);
154 }
155 
156 void RobotStateVisualization::updateKinematicState(const moveit::core::RobotStateConstPtr& kinematic_state)
157 {
158  robot_.update(PlanningLinkUpdater(kinematic_state));
159 }
160 
162 {
163  visible_ = visible;
164  robot_.setVisible(visible);
165 }
166 
168 {
169  visual_visible_ = visible;
170  robot_.setVisualVisible(visible);
171 }
172 
174 {
175  collision_visible_ = visible;
176  robot_.setCollisionVisible(visible);
177 }
178 
180 {
181  robot_.setAlpha(alpha);
182 }
183 } // namespace moveit_rviz_plugin
Object defining bodies that can be attached to robot links.
Definition: attached_body.h:58
Update the links of an rviz::Robot using a moveit::core::RobotState.
void setCollisionVisible(bool visible)
Set whether the collision meshes/primitives of the robot should be visible.
void setVisualVisible(bool visible)
Set whether the visual meshes of the robot should be visible.
void setVisible(bool visible)
Set the robot as a whole to be visible or not.
RobotStateVisualization(Ogre::SceneNode *root_node, rviz_common::DisplayContext *context, const std::string &name, rviz_common::properties::Property *parent_property)
void load(const urdf::ModelInterface &descr, bool visual=true, bool collision=true)
void setDefaultAttachedObjectColor(const std_msgs::msg::ColorRGBA &default_attached_object_color)
void updateAttachedObjectColors(const std_msgs::msg::ColorRGBA &attached_object_color)
update color of all attached object shapes
void update(const moveit::core::RobotStateConstPtr &kinematic_state)
void updateKinematicState(const moveit::core::RobotStateConstPtr &kinematic_state)
name
Definition: setup.py:7
const rclcpp::Logger LOGGER
Definition: async_test.h:31