37 #ifndef MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_ROBOT_STATE_VISUALIZATION_ 38 #define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_ROBOT_STATE_VISUALIZATION_ 62 void load(
const urdf::ModelInterface& descr,
bool visual =
true,
bool collision =
true);
65 void update(
const robot_state::RobotStateConstPtr& kinematic_state);
66 void update(
const robot_state::RobotStateConstPtr& kinematic_state,
67 const std_msgs::ColorRGBA& default_attached_object_color);
68 void update(
const robot_state::RobotStateConstPtr& kinematic_state,
69 const std_msgs::ColorRGBA& default_attached_object_color,
70 const std::map<std::string, std_msgs::ColorRGBA>& color_map);
94 void updateHelper(
const robot_state::RobotStateConstPtr& kinematic_state,
95 const std_msgs::ColorRGBA& default_attached_object_color,
96 const std::map<std::string, std_msgs::ColorRGBA>* color_map);
RenderShapesPtr render_shapes_
void setAlpha(float alpha)
void setDefaultAttachedObjectColor(const std_msgs::ColorRGBA &default_attached_object_color)
MOVEIT_CLASS_FORWARD(RobotStateVisualization)
Update the links of an rviz::Robot using a robot_state::RobotState.
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 load(const urdf::ModelInterface &descr, bool visual=true, bool collision=true)
OctreeVoxelRenderMode octree_voxel_render_mode_
std_msgs::ColorRGBA default_attached_object_color_
void setVisible(bool visible)
Set the robot as a whole to be visible or not.
void update(const robot_state::RobotStateConstPtr &kinematic_state)
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)
RobotStateVisualization(Ogre::SceneNode *root_node, rviz::DisplayContext *context, const std::string &name, rviz::Property *parent_property)
OctreeVoxelColorMode octree_voxel_color_mode_