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 robot_state::RobotState. More...

#include <robot_state_visualization.h>

Public Member Functions

void clear ()
 
rviz::RobotgetRobot ()
 
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 robot_state::RobotStateConstPtr &kinematic_state)
 
void update (const robot_state::RobotStateConstPtr &kinematic_state, const std_msgs::ColorRGBA &default_attached_object_color)
 
void update (const robot_state::RobotStateConstPtr &kinematic_state, const std_msgs::ColorRGBA &default_attached_object_color, const std::map< std::string, std_msgs::ColorRGBA > &color_map)
 

Private Member Functions

void updateHelper (const robot_state::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 robot_state::RobotState.

Definition at line 51 of file robot_state_visualization.h.

Constructor & Destructor Documentation

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

Definition at line 44 of file robot_state_visualization.cpp.

Member Function Documentation

void moveit_rviz_plugin::RobotStateVisualization::clear ( void  )

Definition at line 72 of file robot_state_visualization.cpp.

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

Definition at line 57 of file robot_state_visualization.h.

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

Definition at line 60 of file robot_state_visualization.cpp.

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

Definition at line 159 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.

Parameters
visibleWhether the collision meshes/primitives should be visible

Definition at line 153 of file robot_state_visualization.cpp.

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

Definition at line 78 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.

Parameters
visibleShould we be visible?

Definition at line 141 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.

Parameters
visibleWhether the visual meshes of the robot should be visible

Definition at line 147 of file robot_state_visualization.cpp.

void moveit_rviz_plugin::RobotStateVisualization::update ( const robot_state::RobotStateConstPtr &  kinematic_state)

Definition at line 83 of file robot_state_visualization.cpp.

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

Definition at line 88 of file robot_state_visualization.cpp.

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

Definition at line 94 of file robot_state_visualization.cpp.

void moveit_rviz_plugin::RobotStateVisualization::updateHelper ( const robot_state::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 101 of file robot_state_visualization.cpp.

Member Data Documentation

bool moveit_rviz_plugin::RobotStateVisualization::collision_visible_
private

Definition at line 105 of file robot_state_visualization.h.

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

Definition at line 99 of file robot_state_visualization.h.

OctreeVoxelColorMode moveit_rviz_plugin::RobotStateVisualization::octree_voxel_color_mode_
private

Definition at line 101 of file robot_state_visualization.h.

OctreeVoxelRenderMode moveit_rviz_plugin::RobotStateVisualization::octree_voxel_render_mode_
private

Definition at line 100 of file robot_state_visualization.h.

RenderShapesPtr moveit_rviz_plugin::RobotStateVisualization::render_shapes_
private

Definition at line 98 of file robot_state_visualization.h.

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

Definition at line 97 of file robot_state_visualization.h.

bool moveit_rviz_plugin::RobotStateVisualization::visible_
private

Definition at line 103 of file robot_state_visualization.h.

bool moveit_rviz_plugin::RobotStateVisualization::visual_visible_
private

Definition at line 104 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 Sun Oct 18 2020 13:19:09