40 #include <rviz_common/properties/parse_color.hpp> 
   41 #include <rviz_default_plugins/robot/robot_link.hpp> 
   42 #include <QApplication> 
   46 static const rclcpp::Logger 
LOGGER = rclcpp::get_logger(
"moveit.rviz_plugin_render_tools.robot_state_visualization");
 
   48                                                  const std::string& 
name,
 
   49                                                  rviz_common::properties::Property* parent_property)
 
   50   : robot_(root_node, context, 
name, parent_property)
 
   54   , visual_visible_(true)
 
   55   , collision_visible_(false)
 
   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);
 
   69   robot_.load(descr, visual, collision);
 
   70   robot_.setVisualVisible(visual_visible_);
 
   71   robot_.setCollisionVisible(collision_visible_);
 
   72   robot_.setVisible(visible_);
 
   77   render_shapes_->clear();
 
   83   default_attached_object_color_ = default_attached_object_color;
 
   88   render_shapes_->updateShapeColors(attached_object_color.r, attached_object_color.g, attached_object_color.b,
 
   94   updateHelper(kinematic_state, default_attached_object_color_, 
nullptr);
 
   98                                      const std_msgs::msg::ColorRGBA& default_attached_object_color)
 
  100   updateHelper(kinematic_state, default_attached_object_color, 
nullptr);
 
  104                                      const std_msgs::msg::ColorRGBA& default_attached_object_color,
 
  105                                      const std::map<std::string, std_msgs::msg::ColorRGBA>& color_map)
 
  107   updateHelper(kinematic_state, default_attached_object_color, &color_map);
 
  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)
 
  115   render_shapes_->clear();
 
  117   std::vector<const moveit::core::AttachedBody*> attached_bodies;
 
  118   kinematic_state->getAttachedBodies(attached_bodies);
 
  121     std_msgs::msg::ColorRGBA color = default_attached_object_color;
 
  122     float alpha = robot_.getAlpha();
 
  125       std::map<std::string, std_msgs::msg::ColorRGBA>::const_iterator it = color_map->find(attached_body->getName());
 
  126       if (it != color_map->end())
 
  132     rviz_default_plugins::robot::RobotLink* link = robot_.getLink(attached_body->getAttachedLinkName());
 
  135       RCLCPP_ERROR_STREAM(LOGGER, 
"Link " << attached_body->getAttachedLinkName() << 
" not found in rviz::Robot");
 
  138     Ogre::ColourValue rcolor(color.r, color.g, color.b, color.a);
 
  139     const EigenSTL::vector_Isometry3d& ab_t = attached_body->getShapePosesInLinkFrame();
 
  140     const std::vector<shapes::ShapeConstPtr>& ab_shapes = attached_body->getShapes();
 
  141     for (std::size_t j = 0; j < ab_shapes.size(); ++j)
 
  143       render_shapes_->renderShape(link->getVisualNode(), ab_shapes[j].get(), ab_t[j], octree_voxel_render_mode_,
 
  144                                   octree_voxel_color_mode_, rcolor, alpha);
 
  145       render_shapes_->renderShape(link->getCollisionNode(), ab_shapes[j].get(), ab_t[j], octree_voxel_render_mode_,
 
  146                                   octree_voxel_color_mode_, rcolor, alpha);
 
  149   robot_.setVisualVisible(visual_visible_);
 
  150   robot_.setCollisionVisible(collision_visible_);
 
  151   robot_.setVisible(visible_);
 
  162   robot_.setVisible(visible);
 
  167   visual_visible_ = visible;
 
  168   robot_.setVisualVisible(visible);
 
  173   collision_visible_ = visible;
 
  174   robot_.setCollisionVisible(visible);
 
  179   robot_.setAlpha(alpha);
 
Object defining bodies that can be attached to robot links.
 
Update the links of an rviz::Robot using a moveit::core::RobotState.
 
void setAlpha(float alpha)
 
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)
 
@ OCTOMAP_OCCUPIED_VOXELS
 
const rclcpp::Logger LOGGER