42 #include <rviz_default_plugins/robot/robot.hpp> 
   54                           rviz_common::properties::Property* parent_property);
 
   61   void load(
const urdf::ModelInterface& descr, 
bool visual = 
true, 
bool collision = 
true);
 
   64   void update(
const moveit::core::RobotStateConstPtr& kinematic_state);
 
   65   void update(
const moveit::core::RobotStateConstPtr& kinematic_state,
 
   66               const std_msgs::msg::ColorRGBA& default_attached_object_color);
 
   67   void update(
const moveit::core::RobotStateConstPtr& kinematic_state,
 
   68               const std_msgs::msg::ColorRGBA& default_attached_object_color,
 
   69               const std::map<std::string, std_msgs::msg::ColorRGBA>& color_map);
 
  101   void updateHelper(
const moveit::core::RobotStateConstPtr& kinematic_state,
 
  102                     const std_msgs::msg::ColorRGBA& default_attached_object_color,
 
  103                     const std::map<std::string, std_msgs::msg::ColorRGBA>* color_map);
 
  104   rviz_default_plugins::robot::Robot robot_;
 
  105   RenderShapesPtr render_shapes_;
 
  106   std_msgs::msg::ColorRGBA default_attached_object_color_;
 
  111   bool visual_visible_;
 
  112   bool collision_visible_;
 
Update the links of an rviz::Robot using a moveit::core::RobotState.
 
rviz_default_plugins::robot::Robot & getRobot()
 
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)
 
MOVEIT_CLASS_FORWARD(RobotStateVisualization)