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

Update the links of an rviz::Robot using a moveit::core::RobotState. More...

#include <robot_state_visualization.h>

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 &kinematic_state)
 
void update (const moveit::core::RobotStateConstPtr &kinematic_state, const std_msgs::msg::ColorRGBA &default_attached_object_color)
 
void update (const moveit::core::RobotStateConstPtr &kinematic_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 &kinematic_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 More...
 
bool isVisible () const
 
void setVisible (bool visible)
 Set the robot as a whole to be visible or not. More...
 
void setVisualVisible (bool visible)
 Set whether the visual meshes of the robot should be visible. More...
 
void setCollisionVisible (bool visible)
 Set whether the collision meshes/primitives of the robot should be visible. More...
 
void setAlpha (float alpha)
 

Detailed Description

Update the links of an rviz::Robot using a moveit::core::RobotState.

Definition at line 50 of file robot_state_visualization.h.

Constructor & Destructor Documentation

◆ RobotStateVisualization()

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 47 of file robot_state_visualization.cpp.

Member Function Documentation

◆ clear()

void moveit_rviz_plugin::RobotStateVisualization::clear ( )

Definition at line 75 of file robot_state_visualization.cpp.

Here is the caller graph for this function:

◆ getRobot()

rviz_default_plugins::robot::Robot& moveit_rviz_plugin::RobotStateVisualization::getRobot ( )
inline

Definition at line 56 of file robot_state_visualization.h.

◆ isVisible()

bool moveit_rviz_plugin::RobotStateVisualization::isVisible ( ) const
inline

Definition at line 75 of file robot_state_visualization.h.

◆ load()

void moveit_rviz_plugin::RobotStateVisualization::load ( const urdf::ModelInterface &  descr,
bool  visual = true,
bool  collision = true 
)

Definition at line 64 of file robot_state_visualization.cpp.

Here is the call graph for this function:

◆ setAlpha()

void moveit_rviz_plugin::RobotStateVisualization::setAlpha ( float  alpha)

Definition at line 179 of file robot_state_visualization.cpp.

◆ setCollisionVisible()

void moveit_rviz_plugin::RobotStateVisualization::setCollisionVisible ( bool  visible)

Set whether the collision meshes/primitives of the robot should be visible.

Parameters
visibleWhether the collision meshes/primitives should be visible

Definition at line 173 of file robot_state_visualization.cpp.

◆ setDefaultAttachedObjectColor()

void moveit_rviz_plugin::RobotStateVisualization::setDefaultAttachedObjectColor ( const std_msgs::msg::ColorRGBA &  default_attached_object_color)

Definition at line 81 of file robot_state_visualization.cpp.

◆ setVisible()

void moveit_rviz_plugin::RobotStateVisualization::setVisible ( bool  visible)

Set the robot as a whole to be visible or not.

Parameters
visibleShould we be visible?

Definition at line 161 of file robot_state_visualization.cpp.

◆ setVisualVisible()

void moveit_rviz_plugin::RobotStateVisualization::setVisualVisible ( bool  visible)

Set whether the visual meshes of the robot should be visible.

Parameters
visibleWhether the visual meshes of the robot should be visible

Definition at line 167 of file robot_state_visualization.cpp.

◆ update() [1/3]

void moveit_rviz_plugin::RobotStateVisualization::update ( const moveit::core::RobotStateConstPtr &  kinematic_state)

Definition at line 92 of file robot_state_visualization.cpp.

◆ update() [2/3]

void moveit_rviz_plugin::RobotStateVisualization::update ( const moveit::core::RobotStateConstPtr &  kinematic_state,
const std_msgs::msg::ColorRGBA &  default_attached_object_color 
)

Definition at line 97 of file robot_state_visualization.cpp.

◆ update() [3/3]

void moveit_rviz_plugin::RobotStateVisualization::update ( const moveit::core::RobotStateConstPtr &  kinematic_state,
const std_msgs::msg::ColorRGBA &  default_attached_object_color,
const std::map< std::string, std_msgs::msg::ColorRGBA > &  color_map 
)

Definition at line 103 of file robot_state_visualization.cpp.

◆ updateAttachedObjectColors()

void moveit_rviz_plugin::RobotStateVisualization::updateAttachedObjectColors ( const std_msgs::msg::ColorRGBA &  attached_object_color)

update color of all attached object shapes

Definition at line 86 of file robot_state_visualization.cpp.

◆ updateKinematicState()

void moveit_rviz_plugin::RobotStateVisualization::updateKinematicState ( const moveit::core::RobotStateConstPtr &  kinematic_state)

Definition at line 156 of file robot_state_visualization.cpp.


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