77 void load(
const rviz_common::Config& config)
override;
80#if RCLCPP_VERSION_GTE(30, 0, 0)
81 using rviz_common::Display::update;
83 void update(std::chrono::nanoseconds wall_dt, std::chrono::nanoseconds ros_dt)
override;
86 void update(
float wall_dt,
float ros_dt)
override;
89 void reset()
override;
96 void setLinkColor(
const std::string& link_name,
const QColor& color);
107 void changedRobotDescription();
108 void changedRootLinkName();
109 void changedRobotSceneAlpha();
110 void changedAttachedBodyColor();
111 void changedRobotStateTopic();
112 void changedEnableLinkHighlight();
113 void changedEnableVisualVisible();
114 void changedEnableCollisionVisible();
115 void changedAllLinks();
126 void setLinkColor(rviz_default_plugins::robot::Robot* robot,
const std::string& link_name,
const QColor& color);
127 void unsetLinkColor(rviz_default_plugins::robot::Robot* robot,
const std::string& link_name);
131 void setRobotHighlights(
const moveit_msgs::msg::DisplayRobotState::_highlight_links_type& highlight_links);
132 void setHighlight(
const std::string& link_name,
const std_msgs::msg::ColorRGBA& color);