moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Slots | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
moveit_rviz_plugin::RobotStateDisplay Class Reference

#include <robot_state_display.h>

Inheritance diagram for moveit_rviz_plugin::RobotStateDisplay:
Inheritance graph
[legend]
Collaboration diagram for moveit_rviz_plugin::RobotStateDisplay:
Collaboration graph
[legend]

Public Slots

void setVisible (bool visible)
 

Public Member Functions

 RobotStateDisplay ()
 
 ~RobotStateDisplay () override
 
void load (const rviz_common::Config &config) override
 
void update (float wall_dt, float ros_dt) override
 
void reset () override
 
const moveit::core::RobotModelConstPtr & getRobotModel () const
 
void setLinkColor (const std::string &link_name, const QColor &color)
 
void unsetLinkColor (const std::string &link_name)
 

Protected Member Functions

void initializeLoader ()
 
void loadRobotModel ()
 
void calculateOffsetPosition ()
 Set the scene node's position, given the target frame and the planning frame. More...
 
void setLinkColor (rviz_default_plugins::robot::Robot *robot, const std::string &link_name, const QColor &color)
 
void unsetLinkColor (rviz_default_plugins::robot::Robot *robot, const std::string &link_name)
 
void newRobotStateCallback (const moveit_msgs::msg::DisplayRobotState::ConstSharedPtr &state)
 
void setRobotHighlights (const moveit_msgs::msg::DisplayRobotState::_highlight_links_type &highlight_links)
 
void setHighlight (const std::string &link_name, const std_msgs::msg::ColorRGBA &color)
 
void unsetHighlight (const std::string &link_name)
 
void onInitialize () override
 
void onEnable () override
 
void onDisable () override
 
void fixedFrameChanged () override
 

Protected Attributes

rclcpp::Node::SharedPtr node_
 
rclcpp::Subscription< moveit_msgs::msg::DisplayRobotState >::SharedPtr robot_state_subscriber_
 
RobotStateVisualizationPtr robot_
 
rdf_loader::RDFLoaderPtr rdf_loader_
 
moveit::core::RobotModelConstPtr robot_model_
 
moveit::core::RobotStatePtr robot_state_
 
std::map< std::string, std_msgs::msg::ColorRGBA > highlights_
 
bool update_state_
 
rviz_common::properties::StringProperty * robot_description_property_
 
rviz_common::properties::StringProperty * root_link_name_property_
 
rviz_common::properties::RosTopicProperty * robot_state_topic_property_
 
rviz_common::properties::FloatProperty * robot_alpha_property_
 
rviz_common::properties::ColorProperty * attached_body_color_property_
 
rviz_common::properties::BoolProperty * enable_link_highlight_
 
rviz_common::properties::BoolProperty * enable_visual_visible_
 
rviz_common::properties::BoolProperty * enable_collision_visible_
 
rviz_common::properties::BoolProperty * show_all_links_
 

Detailed Description

Definition at line 65 of file robot_state_display.h.

Constructor & Destructor Documentation

◆ RobotStateDisplay()

moveit_rviz_plugin::RobotStateDisplay::RobotStateDisplay ( )

Definition at line 64 of file robot_state_display.cpp.

◆ ~RobotStateDisplay()

moveit_rviz_plugin::RobotStateDisplay::~RobotStateDisplay ( )
overridedefault

Member Function Documentation

◆ calculateOffsetPosition()

void moveit_rviz_plugin::RobotStateDisplay::calculateOffsetPosition ( )
protected

Set the scene node's position, given the target frame and the planning frame.

Definition at line 475 of file robot_state_display.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ fixedFrameChanged()

void moveit_rviz_plugin::RobotStateDisplay::fixedFrameChanged ( )
overrideprotected

Definition at line 490 of file robot_state_display.cpp.

Here is the call graph for this function:

◆ getRobotModel()

const moveit::core::RobotModelConstPtr& moveit_rviz_plugin::RobotStateDisplay::getRobotModel ( ) const
inline

Definition at line 77 of file robot_state_display.h.

Here is the caller graph for this function:

◆ initializeLoader()

void moveit_rviz_plugin::RobotStateDisplay::initializeLoader ( )
protected

Definition at line 386 of file robot_state_display.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ load()

void moveit_rviz_plugin::RobotStateDisplay::load ( const rviz_common::Config &  config)
override

Definition at line 432 of file robot_state_display.cpp.

◆ loadRobotModel()

void moveit_rviz_plugin::RobotStateDisplay::loadRobotModel ( )
protected

Definition at line 399 of file robot_state_display.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ newRobotStateCallback()

void moveit_rviz_plugin::RobotStateDisplay::newRobotStateCallback ( const moveit_msgs::msg::DisplayRobotState::ConstSharedPtr &  state)
protected

Definition at line 311 of file robot_state_display.cpp.

Here is the call graph for this function:

◆ onDisable()

void moveit_rviz_plugin::RobotStateDisplay::onDisable ( )
overrideprotected

Definition at line 452 of file robot_state_display.cpp.

◆ onEnable()

void moveit_rviz_plugin::RobotStateDisplay::onEnable ( )
overrideprotected

Definition at line 440 of file robot_state_display.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onInitialize()

void moveit_rviz_plugin::RobotStateDisplay::onInitialize ( )
overrideprotected

Definition at line 114 of file robot_state_display.cpp.

◆ reset()

void moveit_rviz_plugin::RobotStateDisplay::reset ( )
override

Definition at line 131 of file robot_state_display.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setHighlight()

void moveit_rviz_plugin::RobotStateDisplay::setHighlight ( const std::string &  link_name,
const std_msgs::msg::ColorRGBA &  color 
)
protected

Definition at line 152 of file robot_state_display.cpp.

Here is the caller graph for this function:

◆ setLinkColor() [1/2]

void moveit_rviz_plugin::RobotStateDisplay::setLinkColor ( const std::string &  link_name,
const QColor &  color 
)

Definition at line 349 of file robot_state_display.cpp.

Here is the caller graph for this function:

◆ setLinkColor() [2/2]

void moveit_rviz_plugin::RobotStateDisplay::setLinkColor ( rviz_default_plugins::robot::Robot *  robot,
const std::string &  link_name,
const QColor &  color 
)
protected

Definition at line 364 of file robot_state_display.cpp.

◆ setRobotHighlights()

void moveit_rviz_plugin::RobotStateDisplay::setRobotHighlights ( const moveit_msgs::msg::DisplayRobotState::_highlight_links_type &  highlight_links)
protected

Definition at line 200 of file robot_state_display.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setVisible

void moveit_rviz_plugin::RobotStateDisplay::setVisible ( bool  visible)
slot

Definition at line 359 of file robot_state_display.cpp.

Here is the caller graph for this function:

◆ unsetHighlight()

void moveit_rviz_plugin::RobotStateDisplay::unsetHighlight ( const std::string &  link_name)
protected

Definition at line 162 of file robot_state_display.cpp.

Here is the caller graph for this function:

◆ unsetLinkColor() [1/2]

void moveit_rviz_plugin::RobotStateDisplay::unsetLinkColor ( const std::string &  link_name)

Definition at line 354 of file robot_state_display.cpp.

Here is the caller graph for this function:

◆ unsetLinkColor() [2/2]

void moveit_rviz_plugin::RobotStateDisplay::unsetLinkColor ( rviz_default_plugins::robot::Robot *  robot,
const std::string &  link_name 
)
protected

Definition at line 374 of file robot_state_display.cpp.

◆ update()

void moveit_rviz_plugin::RobotStateDisplay::update ( float  wall_dt,
float  ros_dt 
)
override

Definition at line 460 of file robot_state_display.cpp.

Here is the call graph for this function:

Member Data Documentation

◆ attached_body_color_property_

rviz_common::properties::ColorProperty* moveit_rviz_plugin::RobotStateDisplay::attached_body_color_property_
protected

Definition at line 142 of file robot_state_display.h.

◆ enable_collision_visible_

rviz_common::properties::BoolProperty* moveit_rviz_plugin::RobotStateDisplay::enable_collision_visible_
protected

Definition at line 145 of file robot_state_display.h.

◆ enable_link_highlight_

rviz_common::properties::BoolProperty* moveit_rviz_plugin::RobotStateDisplay::enable_link_highlight_
protected

Definition at line 143 of file robot_state_display.h.

◆ enable_visual_visible_

rviz_common::properties::BoolProperty* moveit_rviz_plugin::RobotStateDisplay::enable_visual_visible_
protected

Definition at line 144 of file robot_state_display.h.

◆ highlights_

std::map<std::string, std_msgs::msg::ColorRGBA> moveit_rviz_plugin::RobotStateDisplay::highlights_
protected

Definition at line 135 of file robot_state_display.h.

◆ node_

rclcpp::Node::SharedPtr moveit_rviz_plugin::RobotStateDisplay::node_
protected

Definition at line 128 of file robot_state_display.h.

◆ rdf_loader_

rdf_loader::RDFLoaderPtr moveit_rviz_plugin::RobotStateDisplay::rdf_loader_
protected

Definition at line 132 of file robot_state_display.h.

◆ robot_

RobotStateVisualizationPtr moveit_rviz_plugin::RobotStateDisplay::robot_
protected

Definition at line 131 of file robot_state_display.h.

◆ robot_alpha_property_

rviz_common::properties::FloatProperty* moveit_rviz_plugin::RobotStateDisplay::robot_alpha_property_
protected

Definition at line 141 of file robot_state_display.h.

◆ robot_description_property_

rviz_common::properties::StringProperty* moveit_rviz_plugin::RobotStateDisplay::robot_description_property_
protected

Definition at line 138 of file robot_state_display.h.

◆ robot_model_

moveit::core::RobotModelConstPtr moveit_rviz_plugin::RobotStateDisplay::robot_model_
protected

Definition at line 133 of file robot_state_display.h.

◆ robot_state_

moveit::core::RobotStatePtr moveit_rviz_plugin::RobotStateDisplay::robot_state_
protected

Definition at line 134 of file robot_state_display.h.

◆ robot_state_subscriber_

rclcpp::Subscription<moveit_msgs::msg::DisplayRobotState>::SharedPtr moveit_rviz_plugin::RobotStateDisplay::robot_state_subscriber_
protected

Definition at line 129 of file robot_state_display.h.

◆ robot_state_topic_property_

rviz_common::properties::RosTopicProperty* moveit_rviz_plugin::RobotStateDisplay::robot_state_topic_property_
protected

Definition at line 140 of file robot_state_display.h.

◆ root_link_name_property_

rviz_common::properties::StringProperty* moveit_rviz_plugin::RobotStateDisplay::root_link_name_property_
protected

Definition at line 139 of file robot_state_display.h.

◆ show_all_links_

rviz_common::properties::BoolProperty* moveit_rviz_plugin::RobotStateDisplay::show_all_links_
protected

Definition at line 146 of file robot_state_display.h.

◆ update_state_

bool moveit_rviz_plugin::RobotStateDisplay::update_state_
protected

Definition at line 136 of file robot_state_display.h.


The documentation for this class was generated from the following files: