Public Member Functions | Private Member Functions | Private Attributes | 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

void clear ()
 
rviz::RobotgetRobot ()
 
bool isVisible () const
 
void load (const urdf::ModelInterface &descr, bool visual=true, bool collision=true)
 
 RobotStateVisualization (Ogre::SceneNode *root_node, rviz::DisplayContext *context, const std::string &name, rviz::Property *parent_property)
 
void setAlpha (float alpha)
 
void setCollisionVisible (bool visible)
 Set whether the collision meshes/primitives of the robot should be visible. More...
 
void setDefaultAttachedObjectColor (const std_msgs::ColorRGBA &default_attached_object_color)
 
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 update (const moveit::core::RobotStateConstPtr &kinematic_state)
 
void update (const moveit::core::RobotStateConstPtr &kinematic_state, const std_msgs::ColorRGBA &default_attached_object_color)
 
void update (const moveit::core::RobotStateConstPtr &kinematic_state, const std_msgs::ColorRGBA &default_attached_object_color, const std::map< std::string, std_msgs::ColorRGBA > &color_map)
 
void updateAttachedObjectColors (const std_msgs::ColorRGBA &attached_object_color)
 update color of all attached object shapes More...
 
void updateKinematicState (const moveit::core::RobotStateConstPtr &kinematic_state)
 

Private Member Functions

void updateHelper (const moveit::core::RobotStateConstPtr &kinematic_state, const std_msgs::ColorRGBA &default_attached_object_color, const std::map< std::string, std_msgs::ColorRGBA > *color_map)
 

Private Attributes

bool collision_visible_
 
std_msgs::ColorRGBA default_attached_object_color_
 
OctreeVoxelColorMode octree_voxel_color_mode_
 
OctreeVoxelRenderMode octree_voxel_render_mode_
 
RenderShapesPtr render_shapes_
 
rviz::Robot robot_
 
bool visible_
 
bool visual_visible_
 

Detailed Description

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

Definition at line 82 of file robot_state_visualization.h.

Constructor & Destructor Documentation

◆ RobotStateVisualization()

moveit_rviz_plugin::RobotStateVisualization::RobotStateVisualization ( Ogre::SceneNode *  root_node,
rviz::DisplayContext context,
const std::string &  name,
rviz::Property parent_property 
)

Definition at line 77 of file robot_state_visualization.cpp.

Member Function Documentation

◆ clear()

void moveit_rviz_plugin::RobotStateVisualization::clear ( )

Definition at line 104 of file robot_state_visualization.cpp.

◆ getRobot()

rviz::Robot& moveit_rviz_plugin::RobotStateVisualization::getRobot ( )
inline

Definition at line 88 of file robot_state_visualization.h.

◆ isVisible()

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

Definition at line 107 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 93 of file robot_state_visualization.cpp.

◆ setAlpha()

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

Definition at line 206 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 200 of file robot_state_visualization.cpp.

◆ setDefaultAttachedObjectColor()

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

Definition at line 110 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 188 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 194 of file robot_state_visualization.cpp.

◆ update() [1/3]

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

Definition at line 121 of file robot_state_visualization.cpp.

◆ update() [2/3]

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

Definition at line 126 of file robot_state_visualization.cpp.

◆ update() [3/3]

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

Definition at line 132 of file robot_state_visualization.cpp.

◆ updateAttachedObjectColors()

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

update color of all attached object shapes

Definition at line 115 of file robot_state_visualization.cpp.

◆ updateHelper()

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

Definition at line 139 of file robot_state_visualization.cpp.

◆ updateKinematicState()

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

Definition at line 183 of file robot_state_visualization.cpp.

Member Data Documentation

◆ collision_visible_

bool moveit_rviz_plugin::RobotStateVisualization::collision_visible_
private

Definition at line 144 of file robot_state_visualization.h.

◆ default_attached_object_color_

std_msgs::ColorRGBA moveit_rviz_plugin::RobotStateVisualization::default_attached_object_color_
private

Definition at line 138 of file robot_state_visualization.h.

◆ octree_voxel_color_mode_

OctreeVoxelColorMode moveit_rviz_plugin::RobotStateVisualization::octree_voxel_color_mode_
private

Definition at line 140 of file robot_state_visualization.h.

◆ octree_voxel_render_mode_

OctreeVoxelRenderMode moveit_rviz_plugin::RobotStateVisualization::octree_voxel_render_mode_
private

Definition at line 139 of file robot_state_visualization.h.

◆ render_shapes_

RenderShapesPtr moveit_rviz_plugin::RobotStateVisualization::render_shapes_
private

Definition at line 137 of file robot_state_visualization.h.

◆ robot_

rviz::Robot moveit_rviz_plugin::RobotStateVisualization::robot_
private

Definition at line 136 of file robot_state_visualization.h.

◆ visible_

bool moveit_rviz_plugin::RobotStateVisualization::visible_
private

Definition at line 142 of file robot_state_visualization.h.

◆ visual_visible_

bool moveit_rviz_plugin::RobotStateVisualization::visual_visible_
private

Definition at line 143 of file robot_state_visualization.h.


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


visualization
Author(s): Ioan Sucan , Dave Coleman , Sachin Chitta
autogenerated on Thu Feb 27 2025 03:29:15