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/robot/robot_link.h>
41 #include <QApplication>
42 
43 namespace moveit_rviz_plugin
44 {
46  const std::string& name, rviz::Property* parent_property)
47  : robot_(root_node, context, name, parent_property)
48  , octree_voxel_render_mode_(OCTOMAP_OCCUPIED_VOXELS)
49  , octree_voxel_color_mode_(OCTOMAP_Z_AXIS_COLOR)
50  , visible_(true)
51  , visual_visible_(true)
52  , collision_visible_(false)
53 {
54  default_attached_object_color_.r = 0.0f;
55  default_attached_object_color_.g = 0.7f;
56  default_attached_object_color_.b = 0.0f;
57  default_attached_object_color_.a = 1.0f;
58  render_shapes_ = std::make_shared<RenderShapes>(context);
59 }
60 
61 void RobotStateVisualization::load(const urdf::ModelInterface& descr, bool visual, bool collision)
62 {
63  // clear previously loaded model
64  clear();
65 
66  robot_.load(descr, visual, collision);
70 }
71 
73 {
74  render_shapes_->clear();
75  robot_.clear();
76 }
77 
78 void RobotStateVisualization::setDefaultAttachedObjectColor(const std_msgs::ColorRGBA& default_attached_object_color)
79 {
80  default_attached_object_color_ = default_attached_object_color;
81 }
82 
83 void RobotStateVisualization::updateAttachedObjectColors(const std_msgs::ColorRGBA& attached_object_color)
84 {
85  render_shapes_->updateShapeColors(attached_object_color.r, attached_object_color.g, attached_object_color.b,
86  robot_.getAlpha());
87 }
88 
89 void RobotStateVisualization::update(const moveit::core::RobotStateConstPtr& kinematic_state)
90 {
91  updateHelper(kinematic_state, default_attached_object_color_, nullptr);
92 }
93 
94 void RobotStateVisualization::update(const moveit::core::RobotStateConstPtr& kinematic_state,
95  const std_msgs::ColorRGBA& default_attached_object_color)
96 {
97  updateHelper(kinematic_state, default_attached_object_color, nullptr);
98 }
99 
100 void RobotStateVisualization::update(const moveit::core::RobotStateConstPtr& kinematic_state,
101  const std_msgs::ColorRGBA& default_attached_object_color,
102  const std::map<std::string, std_msgs::ColorRGBA>& color_map)
103 {
104  updateHelper(kinematic_state, default_attached_object_color, &color_map);
105 }
106 
107 void RobotStateVisualization::updateHelper(const moveit::core::RobotStateConstPtr& kinematic_state,
108  const std_msgs::ColorRGBA& default_attached_object_color,
109  const std::map<std::string, std_msgs::ColorRGBA>* color_map)
110 {
111  robot_.update(PlanningLinkUpdater(kinematic_state));
112  render_shapes_->clear();
113 
114  std::vector<const moveit::core::AttachedBody*> attached_bodies;
115  kinematic_state->getAttachedBodies(attached_bodies);
116  for (const moveit::core::AttachedBody* attached_body : attached_bodies)
117  {
118  std_msgs::ColorRGBA color = default_attached_object_color;
119  float alpha = robot_.getAlpha();
120  if (color_map)
121  {
122  std::map<std::string, std_msgs::ColorRGBA>::const_iterator it = color_map->find(attached_body->getName());
123  if (it != color_map->end())
124  {
125  color = it->second;
126  alpha = color.a;
127  }
128  }
129  rviz::RobotLink* link = robot_.getLink(attached_body->getAttachedLinkName());
130  if (!link)
131  {
132  ROS_ERROR_STREAM("Link " << attached_body->getAttachedLinkName() << " not found in rviz::Robot");
133  continue;
134  }
135  rviz::Color rcolor(color.r, color.g, color.b);
136  const EigenSTL::vector_Isometry3d& ab_t = attached_body->getShapePosesInLinkFrame();
137  const std::vector<shapes::ShapeConstPtr>& ab_shapes = attached_body->getShapes();
138  for (std::size_t j = 0; j < ab_shapes.size(); ++j)
139  {
140  render_shapes_->renderShape(link->getVisualNode(), ab_shapes[j].get(), ab_t[j], octree_voxel_render_mode_,
141  octree_voxel_color_mode_, rcolor, alpha);
142  render_shapes_->renderShape(link->getCollisionNode(), ab_shapes[j].get(), ab_t[j], octree_voxel_render_mode_,
143  octree_voxel_color_mode_, rcolor, alpha);
144  }
145  }
149 }
150 
151 void RobotStateVisualization::updateKinematicState(const moveit::core::RobotStateConstPtr& kinematic_state)
152 {
153  robot_.update(PlanningLinkUpdater(kinematic_state));
154 }
155 
156 void RobotStateVisualization::setVisible(bool visible)
157 {
158  visible_ = visible;
159  robot_.setVisible(visible);
160 }
161 
163 {
164  visual_visible_ = visible;
165  robot_.setVisualVisible(visible);
166 }
167 
169 {
170  collision_visible_ = visible;
171  robot_.setCollisionVisible(visible);
172 }
173 
174 void RobotStateVisualization::setAlpha(float alpha)
175 {
176  robot_.setAlpha(alpha);
177 }
178 } // namespace moveit_rviz_plugin
moveit_rviz_plugin::RobotStateVisualization::collision_visible_
bool collision_visible_
Definition: robot_state_visualization.h:144
rviz::Robot::setCollisionVisible
void setCollisionVisible(bool visible)
moveit_rviz_plugin::OCTOMAP_OCCUPIED_VOXELS
@ OCTOMAP_OCCUPIED_VOXELS
Definition: octomap_render.h:55
EigenSTL::vector_Isometry3d
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
moveit_rviz_plugin::RobotStateVisualization::setAlpha
void setAlpha(float alpha)
Definition: robot_state_visualization.cpp:206
moveit_rviz_plugin::RobotStateVisualization::updateKinematicState
void updateKinematicState(const moveit::core::RobotStateConstPtr &kinematic_state)
Definition: robot_state_visualization.cpp:183
moveit_rviz_plugin::RobotStateVisualization::clear
void clear()
Definition: robot_state_visualization.cpp:104
moveit_rviz_plugin::RobotStateVisualization::setVisualVisible
void setVisualVisible(bool visible)
Set whether the visual meshes of the robot should be visible.
Definition: robot_state_visualization.cpp:194
moveit_rviz_plugin::OCTOMAP_Z_AXIS_COLOR
@ OCTOMAP_Z_AXIS_COLOR
Definition: octomap_render.h:60
moveit_rviz_plugin::RobotStateVisualization::visual_visible_
bool visual_visible_
Definition: robot_state_visualization.h:143
rviz::Robot::getAlpha
float getAlpha()
moveit_rviz_plugin::RobotStateVisualization::robot_
rviz::Robot robot_
Definition: robot_state_visualization.h:136
moveit::core::AttachedBody
rviz::Property
rviz::Robot::setVisualVisible
void setVisualVisible(bool visible)
moveit_rviz_plugin::RobotStateVisualization::octree_voxel_render_mode_
OctreeVoxelRenderMode octree_voxel_render_mode_
Definition: robot_state_visualization.h:139
moveit_rviz_plugin::RobotStateVisualization::render_shapes_
RenderShapesPtr render_shapes_
Definition: robot_state_visualization.h:137
moveit_rviz_plugin::RobotStateVisualization::updateAttachedObjectColors
void updateAttachedObjectColors(const std_msgs::ColorRGBA &attached_object_color)
update color of all attached object shapes
Definition: robot_state_visualization.cpp:115
rviz::DisplayContext
rviz::Robot::setAlpha
void setAlpha(float a)
name
name
moveit_rviz_plugin::RobotStateVisualization::octree_voxel_color_mode_
OctreeVoxelColorMode octree_voxel_color_mode_
Definition: robot_state_visualization.h:140
moveit_rviz_plugin::RobotStateVisualization::RobotStateVisualization
RobotStateVisualization(Ogre::SceneNode *root_node, rviz::DisplayContext *context, const std::string &name, rviz::Property *parent_property)
Definition: robot_state_visualization.cpp:77
moveit_rviz_plugin::RobotStateVisualization::setDefaultAttachedObjectColor
void setDefaultAttachedObjectColor(const std_msgs::ColorRGBA &default_attached_object_color)
Definition: robot_state_visualization.cpp:110
moveit_rviz_plugin::RobotStateVisualization::setVisible
void setVisible(bool visible)
Set the robot as a whole to be visible or not.
Definition: robot_state_visualization.cpp:188
moveit_rviz_plugin::RobotStateVisualization::visible_
bool visible_
Definition: robot_state_visualization.h:142
moveit_rviz_plugin
Definition: motion_planning_display.h:80
moveit_rviz_plugin::RobotStateVisualization::setCollisionVisible
void setCollisionVisible(bool visible)
Set whether the collision meshes/primitives of the robot should be visible.
Definition: robot_state_visualization.cpp:200
rviz::Robot::update
virtual void update(const LinkUpdater &updater)
moveit_rviz_plugin::RobotStateVisualization::updateHelper
void updateHelper(const moveit::core::RobotStateConstPtr &kinematic_state, const std_msgs::ColorRGBA &default_attached_object_color, const std::map< std::string, std_msgs::ColorRGBA > *color_map)
Definition: robot_state_visualization.cpp:139
moveit_rviz_plugin::RobotStateVisualization::update
void update(const moveit::core::RobotStateConstPtr &kinematic_state)
Definition: robot_state_visualization.cpp:121
moveit_rviz_plugin::PlanningLinkUpdater
Update the links of an rviz::Robot using a moveit::core::RobotState.
Definition: planning_link_updater.h:77
rviz::Robot::setVisible
virtual void setVisible(bool visible)
robot_state_visualization.h
rviz::Robot::getLink
RobotLink * getLink(const std::string &name)
moveit_rviz_plugin::RobotStateVisualization::default_attached_object_color_
std_msgs::ColorRGBA default_attached_object_color_
Definition: robot_state_visualization.h:138
render_shapes.h
rviz::Robot::load
virtual void load(const urdf::ModelInterface &urdf, bool visual=true, bool collision=true)
moveit_rviz_plugin::RobotStateVisualization::load
void load(const urdf::ModelInterface &descr, bool visual=true, bool collision=true)
Definition: robot_state_visualization.cpp:93
rviz::Color
rviz::Robot::clear
virtual void clear()


visualization
Author(s): Ioan Sucan , Dave Coleman , Sachin Chitta
autogenerated on Sat Mar 15 2025 02:27:26