73  void load(
const rviz_common::Config& config) 
override;
 
   74  void update(
float wall_dt, 
float ros_dt) 
override;
 
   75  void reset() 
override;
 
   82  void setLinkColor(
const std::string& link_name, 
const QColor& color);
 
   93  void changedRobotDescription();
 
   94  void changedRootLinkName();
 
   95  void changedRobotSceneAlpha();
 
   96  void changedAttachedBodyColor();
 
   97  void changedRobotStateTopic();
 
   98  void changedEnableLinkHighlight();
 
   99  void changedEnableVisualVisible();
 
  100  void changedEnableCollisionVisible();
 
  101  void changedAllLinks();
 
  112  void setLinkColor(rviz_default_plugins::robot::Robot* robot, 
const std::string& link_name, 
const QColor& color);
 
  113  void unsetLinkColor(rviz_default_plugins::robot::Robot* robot, 
const std::string& link_name);
 
  117  void setRobotHighlights(
const moveit_msgs::msg::DisplayRobotState::_highlight_links_type& highlight_links);
 
  118  void setHighlight(
const std::string& link_name, 
const std_msgs::msg::ColorRGBA& color);