| 
    moveit2
    
   The MoveIt Motion Planning Framework for ROS 2. 
   | 
 
Update the links of an rviz::Robot using a moveit::core::RobotState. More...
#include <robot_state_visualization.hpp>
Public Member Functions | |
| RobotStateVisualization (Ogre::SceneNode *root_node, rviz_common::DisplayContext *context, const std::string &name, rviz_common::properties::Property *parent_property) | |
| rviz_default_plugins::robot::Robot & | getRobot () | 
| void | load (const urdf::ModelInterface &descr, bool visual=true, bool collision=true) | 
| void | clear () | 
| void | update (const moveit::core::RobotStateConstPtr &robot_state) | 
| void | update (const moveit::core::RobotStateConstPtr &robot_state, const std_msgs::msg::ColorRGBA &default_attached_object_color) | 
| void | update (const moveit::core::RobotStateConstPtr &robot_state, const std_msgs::msg::ColorRGBA &default_attached_object_color, const std::map< std::string, std_msgs::msg::ColorRGBA > &color_map) | 
| void | updateKinematicState (const moveit::core::RobotStateConstPtr &robot_state) | 
| 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   | |
| bool | isVisible () const | 
| void | setVisible (bool visible) | 
| Set the robot as a whole to be visible or not.   | |
| void | setVisualVisible (bool visible) | 
| Set whether the visual meshes of the robot should be visible.   | |
| void | setCollisionVisible (bool visible) | 
| Set whether the collision meshes/primitives of the robot should be visible.   | |
| void | setAlpha (double alpha) | 
Update the links of an rviz::Robot using a moveit::core::RobotState.
Definition at line 50 of file robot_state_visualization.hpp.
| moveit_rviz_plugin::RobotStateVisualization::RobotStateVisualization | ( | Ogre::SceneNode * | root_node, | 
| rviz_common::DisplayContext * | context, | ||
| const std::string & | name, | ||
| rviz_common::properties::Property * | parent_property | ||
| ) | 
Definition at line 55 of file robot_state_visualization.cpp.
| void moveit_rviz_plugin::RobotStateVisualization::clear | ( | ) | 
Definition at line 83 of file robot_state_visualization.cpp.

      
  | 
  inline | 
Definition at line 56 of file robot_state_visualization.hpp.
      
  | 
  inline | 
Definition at line 75 of file robot_state_visualization.hpp.
| void moveit_rviz_plugin::RobotStateVisualization::load | ( | const urdf::ModelInterface & | descr, | 
| bool | visual = true,  | 
        ||
| bool | collision = true  | 
        ||
| ) | 
Definition at line 72 of file robot_state_visualization.cpp.

| void moveit_rviz_plugin::RobotStateVisualization::setAlpha | ( | double | alpha | ) | 
Definition at line 185 of file robot_state_visualization.cpp.
| void moveit_rviz_plugin::RobotStateVisualization::setCollisionVisible | ( | bool | visible | ) | 
Set whether the collision meshes/primitives of the robot should be visible.
| visible | Whether the collision meshes/primitives should be visible | 
Definition at line 179 of file robot_state_visualization.cpp.
| void moveit_rviz_plugin::RobotStateVisualization::setDefaultAttachedObjectColor | ( | const std_msgs::msg::ColorRGBA & | default_attached_object_color | ) | 
Definition at line 89 of file robot_state_visualization.cpp.
| void moveit_rviz_plugin::RobotStateVisualization::setVisible | ( | bool | visible | ) | 
Set the robot as a whole to be visible or not.
| visible | Should we be visible? | 
Definition at line 167 of file robot_state_visualization.cpp.
| void moveit_rviz_plugin::RobotStateVisualization::setVisualVisible | ( | bool | visible | ) | 
Set whether the visual meshes of the robot should be visible.
| visible | Whether the visual meshes of the robot should be visible | 
Definition at line 173 of file robot_state_visualization.cpp.
| void moveit_rviz_plugin::RobotStateVisualization::update | ( | const moveit::core::RobotStateConstPtr & | robot_state | ) | 
Definition at line 100 of file robot_state_visualization.cpp.
| void moveit_rviz_plugin::RobotStateVisualization::update | ( | const moveit::core::RobotStateConstPtr & | robot_state, | 
| const std_msgs::msg::ColorRGBA & | default_attached_object_color | ||
| ) | 
Definition at line 105 of file robot_state_visualization.cpp.
| void moveit_rviz_plugin::RobotStateVisualization::update | ( | const moveit::core::RobotStateConstPtr & | robot_state, | 
| const std_msgs::msg::ColorRGBA & | default_attached_object_color, | ||
| const std::map< std::string, std_msgs::msg::ColorRGBA > & | color_map | ||
| ) | 
Definition at line 111 of file robot_state_visualization.cpp.
| void moveit_rviz_plugin::RobotStateVisualization::updateAttachedObjectColors | ( | const std_msgs::msg::ColorRGBA & | attached_object_color | ) | 
update color of all attached object shapes
Definition at line 94 of file robot_state_visualization.cpp.
| void moveit_rviz_plugin::RobotStateVisualization::updateKinematicState | ( | const moveit::core::RobotStateConstPtr & | robot_state | ) | 
Definition at line 162 of file robot_state_visualization.cpp.