37 #ifndef MOVEIT_VISUALIZATION_ROBOT_STATE_DISPLAY_RVIZ_ROBOT_STATE_DISPLAY_ 38 #define MOVEIT_VISUALIZATION_ROBOT_STATE_DISPLAY_RVIZ_ROBOT_STATE_DISPLAY_ 45 #include <moveit_msgs/DisplayRobotState.h> 60 class RosTopicProperty;
66 class RobotStateVisualization;
76 virtual void update(
float wall_dt,
float ros_dt);
84 void setLinkColor(
const std::string& link_name,
const QColor& color);
85 void unsetLinkColor(
const std::string& link_name);
92 void changedRobotDescription();
93 void changedRootLinkName();
94 void changedRobotSceneAlpha();
95 void changedAttachedBodyColor();
96 void changedRobotStateTopic();
97 void changedEnableLinkHighlight();
98 void changedEnableVisualVisible();
99 void changedEnableCollisionVisible();
100 void changedAllLinks();
108 void calculateOffsetPosition();
110 void setLinkColor(
rviz::Robot* robot,
const std::string& link_name,
const QColor& color);
111 void unsetLinkColor(
rviz::Robot* robot,
const std::string& link_name);
113 void newRobotStateCallback(
const moveit_msgs::DisplayRobotState::ConstPtr& state);
115 void setRobotHighlights(
const moveit_msgs::DisplayRobotState::_highlight_links_type& highlight_links);
116 void setHighlight(
const std::string& link_name,
const std_msgs::ColorRGBA& color);
117 void unsetHighlight(
const std::string& link_name);
120 virtual void onInitialize();
121 virtual void onEnable();
122 virtual void onDisable();
123 virtual void fixedFrameChanged();
rviz::BoolProperty * enable_link_highlight_
rviz::StringProperty * root_link_name_property_
void loadRobotModel(urdf::ModelInterfaceSharedPtr &robot_model_out)
rviz::BoolProperty * enable_visual_visible_
rviz::BoolProperty * enable_collision_visible_
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
RobotStateVisualizationPtr robot_
ros::Subscriber robot_state_subscriber_
rdf_loader::RDFLoaderPtr rdf_loader_
const robot_model::RobotModelConstPtr & getRobotModel() const
rviz::StringProperty * robot_description_property_
rviz::RosTopicProperty * robot_state_topic_property_
std::map< std::string, std_msgs::ColorRGBA > highlights_
rviz::ColorProperty * attached_body_color_property_
robot_model::RobotModelConstPtr kmodel_
rviz::BoolProperty * show_all_links_
robot_state::RobotStatePtr kstate_
rviz::FloatProperty * robot_alpha_property_