Update the links of an rviz::Robot using a robot_state::RobotState.
More...
#include <robot_state_visualization.h>
|
void | clear () |
|
rviz::Robot & | getRobot () |
|
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) |
|
|
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) |
|
Update the links of an rviz::Robot using a robot_state::RobotState.
Definition at line 51 of file robot_state_visualization.h.
moveit_rviz_plugin::RobotStateVisualization::RobotStateVisualization |
( |
Ogre::SceneNode * |
root_node, |
|
|
rviz::DisplayContext * |
context, |
|
|
const std::string & |
name, |
|
|
rviz::Property * |
parent_property |
|
) |
| |
void moveit_rviz_plugin::RobotStateVisualization::clear |
( |
void |
| ) |
|
rviz::Robot& moveit_rviz_plugin::RobotStateVisualization::getRobot |
( |
| ) |
|
|
inline |
void moveit_rviz_plugin::RobotStateVisualization::load |
( |
const urdf::ModelInterface & |
descr, |
|
|
bool |
visual = true , |
|
|
bool |
collision = true |
|
) |
| |
void moveit_rviz_plugin::RobotStateVisualization::setAlpha |
( |
float |
alpha | ) |
|
void moveit_rviz_plugin::RobotStateVisualization::setCollisionVisible |
( |
bool |
visible | ) |
|
Set whether the collision meshes/primitives of the robot should be visible.
- Parameters
-
visible | Whether 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 | ) |
|
void moveit_rviz_plugin::RobotStateVisualization::setVisible |
( |
bool |
visible | ) |
|
void moveit_rviz_plugin::RobotStateVisualization::setVisualVisible |
( |
bool |
visible | ) |
|
Set whether the visual meshes of the robot should be visible.
- Parameters
-
visible | Whether 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 | ) |
|
void moveit_rviz_plugin::RobotStateVisualization::update |
( |
const robot_state::RobotStateConstPtr & |
kinematic_state, |
|
|
const std_msgs::ColorRGBA & |
default_attached_object_color |
|
) |
| |
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 |
|
) |
| |
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 |
bool moveit_rviz_plugin::RobotStateVisualization::collision_visible_ |
|
private |
std_msgs::ColorRGBA moveit_rviz_plugin::RobotStateVisualization::default_attached_object_color_ |
|
private |
RenderShapesPtr moveit_rviz_plugin::RobotStateVisualization::render_shapes_ |
|
private |
rviz::Robot moveit_rviz_plugin::RobotStateVisualization::robot_ |
|
private |
bool moveit_rviz_plugin::RobotStateVisualization::visible_ |
|
private |
bool moveit_rviz_plugin::RobotStateVisualization::visual_visible_ |
|
private |
The documentation for this class was generated from the following files: