Public Slots | Public Member Functions | Protected Attributes | Private Types | Private Slots | Private Member Functions | Private Attributes | Friends | List of all members
rviz::RobotLink Struct Reference

Contains any data we need from a link in the robot. More...

#include <robot_link.h>

Inheritance diagram for rviz::RobotLink:
Inheritance graph
[legend]

Public Slots

void updateVisibility ()
 Update the visibility of the link elements: visual mesh, collision mesh, trail, and axes. More...
 

Public Member Functions

void expandDetails (bool expand)
 
const std::vector< std::string > & getChildJointNames () const
 
Ogre::SceneNode * getCollisionNode () const
 
const std::string & getGeometryErrors () const
 
PropertygetLinkProperty () const
 
const std::string & getName () const
 
bool getOnlyRenderDepth () const
 
Ogre::Quaternion getOrientation ()
 
const std::string & getParentJointName () const
 
Ogre::Vector3 getPosition ()
 
RobotgetRobot () const
 
bool getSelectable ()
 
Ogre::SceneNode * getVisualNode () const
 
bool hasGeometry () const
 
virtual void hideSubProperties (bool hide)
 
 RobotLink (Robot *robot, const urdf::LinkConstSharedPtr &link, const std::string &parent_joint_name, bool visual, bool collision)
 
void setColor (float red, float green, float blue)
 
void setOnlyRenderDepth (bool onlyRenderDepth)
 
void setParentProperty (Property *new_parent)
 
virtual void setRobotAlpha (float a)
 
bool setSelectable (bool selectable)
 
void setToErrorMaterial ()
 
void setToNormalMaterial ()
 
virtual void setTransforms (const Ogre::Vector3 &visual_position, const Ogre::Quaternion &visual_orientation, const Ogre::Vector3 &collision_position, const Ogre::Quaternion &collision_orientation)
 
void unsetColor ()
 
void useDetailProperty (bool use_detail)
 
 ~RobotLink () override
 

Protected Attributes

FloatPropertyalpha_property_
 
Propertyaxes_property_
 
std::vector< std::string > child_joint_names_
 
DisplayContextcontext_
 
Propertydetails_
 
Propertylink_property_
 
std::string name_
 Name of this link. More...
 
QuaternionPropertyorientation_property_
 
std::string parent_joint_name_
 
VectorPropertyposition_property_
 
Robotrobot_
 
Ogre::SceneManager * scene_manager_
 
Propertytrail_property_
 

Private Types

typedef std::map< Ogre::SubEntity *, Ogre::MaterialPtr > M_SubEntityToMaterial
 
enum  MaterialMode { ORIGINAL = 0, COLOR = 1, ERROR = 2 }
 

Private Slots

void updateAlpha ()
 
void updateAxes ()
 
void updateTrail ()
 

Private Member Functions

void addError (const char *format,...)
 
void createCollision (const urdf::LinkConstSharedPtr &link)
 
void createEntityForGeometryElement (const urdf::LinkConstSharedPtr &link, const urdf::Geometry &geom, const urdf::MaterialSharedPtr &material, const urdf::Pose &origin, Ogre::SceneNode *scene_node, Ogre::Entity *&entity)
 
void createSelection ()
 
void createVisual (const urdf::LinkConstSharedPtr &link)
 
bool getEnabled () const
 
Ogre::MaterialPtr getMaterialForLink (const urdf::LinkConstSharedPtr &link, urdf::MaterialConstSharedPtr material)
 
void setMaterialMode (unsigned char mode_flags)
 
void setRenderQueueGroup (Ogre::uint8 group)
 

Private Attributes

Axesaxes_
 
std::vector< Ogre::Entity * > collision_meshes_
 The entities representing the collision mesh of this link (if they exist) More...
 
Ogre::SceneNode * collision_node_
 The scene node the collision meshes are attached to. More...
 
Ogre::MaterialPtr color_material_
 
Ogre::MaterialPtr default_material_
 
std::string default_material_name_
 
bool is_selectable_
 
std::string joint_name_
 
float material_alpha_
 
unsigned char material_mode_flags_
 
M_SubEntityToMaterial materials_
 
bool only_render_depth_
 
float robot_alpha_
 Alpha value from top-level robot alpha Property (set via setRobotAlpha()). More...
 
RobotLinkSelectionHandlerPtr selection_handler_
 
Ogre::RibbonTrail * trail_
 
std::vector< Ogre::Entity * > visual_meshes_
 The entities representing the visual mesh of this link (if they exist) More...
 
Ogre::SceneNode * visual_node_
 The scene node the visual meshes are attached to. More...
 

Friends

class RobotLinkSelectionHandler
 

Detailed Description

Contains any data we need from a link in the robot.

Definition at line 84 of file robot_link.h.

Member Typedef Documentation

◆ M_SubEntityToMaterial

typedef std::map<Ogre::SubEntity*, Ogre::MaterialPtr> rviz::RobotLink::M_SubEntityToMaterial
private

Definition at line 231 of file robot_link.h.

Member Enumeration Documentation

◆ MaterialMode

Enumerator
ORIGINAL 
COLOR 
ERROR 

Definition at line 88 of file robot_link.h.

Constructor & Destructor Documentation

◆ RobotLink()

rviz::RobotLink::RobotLink ( Robot robot,
const urdf::LinkConstSharedPtr &  link,
const std::string &  parent_joint_name,
bool  visual,
bool  collision 
)

Definition at line 156 of file robot_link.cpp.

◆ ~RobotLink()

rviz::RobotLink::~RobotLink ( )
override

Definition at line 299 of file robot_link.cpp.

Member Function Documentation

◆ addError()

void rviz::RobotLink::addError ( const char *  format,
  ... 
)
private

Definition at line 325 of file robot_link.cpp.

◆ createCollision()

void rviz::RobotLink::createCollision ( const urdf::LinkConstSharedPtr &  link)
private

Definition at line 679 of file robot_link.cpp.

◆ createEntityForGeometryElement()

void rviz::RobotLink::createEntityForGeometryElement ( const urdf::LinkConstSharedPtr &  link,
const urdf::Geometry &  geom,
const urdf::MaterialSharedPtr &  material,
const urdf::Pose origin,
Ogre::SceneNode *  scene_node,
Ogre::Entity *&  entity 
)
private

Definition at line 547 of file robot_link.cpp.

◆ createSelection()

void rviz::RobotLink::createSelection ( )
private

Definition at line 799 of file robot_link.cpp.

◆ createVisual()

void rviz::RobotLink::createVisual ( const urdf::LinkConstSharedPtr &  link)
private

Definition at line 739 of file robot_link.cpp.

◆ expandDetails()

void rviz::RobotLink::expandDetails ( bool  expand)

Definition at line 1027 of file robot_link.cpp.

◆ getChildJointNames()

const std::vector<std::string>& rviz::RobotLink::getChildJointNames ( ) const
inline

Definition at line 119 of file robot_link.h.

◆ getCollisionNode()

Ogre::SceneNode* rviz::RobotLink::getCollisionNode ( ) const
inline

Definition at line 131 of file robot_link.h.

◆ getEnabled()

bool rviz::RobotLink::getEnabled ( ) const
private

Definition at line 349 of file robot_link.cpp.

◆ getGeometryErrors()

const std::string & rviz::RobotLink::getGeometryErrors ( ) const

Definition at line 339 of file robot_link.cpp.

◆ getLinkProperty()

Property* rviz::RobotLink::getLinkProperty ( ) const
inline

Definition at line 123 of file robot_link.h.

◆ getMaterialForLink()

Ogre::MaterialPtr rviz::RobotLink::getMaterialForLink ( const urdf::LinkConstSharedPtr &  link,
urdf::MaterialConstSharedPtr  material 
)
private

Definition at line 460 of file robot_link.cpp.

◆ getName()

const std::string& rviz::RobotLink::getName ( ) const
inline

Definition at line 111 of file robot_link.h.

◆ getOnlyRenderDepth()

bool rviz::RobotLink::getOnlyRenderDepth ( ) const
inline

Definition at line 169 of file robot_link.h.

◆ getOrientation()

Ogre::Quaternion rviz::RobotLink::getOrientation ( )

Definition at line 978 of file robot_link.cpp.

◆ getParentJointName()

const std::string& rviz::RobotLink::getParentJointName ( ) const
inline

Definition at line 115 of file robot_link.h.

◆ getPosition()

Ogre::Vector3 rviz::RobotLink::getPosition ( )

Definition at line 973 of file robot_link.cpp.

◆ getRobot()

Robot* rviz::RobotLink::getRobot ( ) const
inline

Definition at line 135 of file robot_link.h.

◆ getSelectable()

bool rviz::RobotLink::getSelectable ( )

Definition at line 959 of file robot_link.cpp.

◆ getVisualNode()

Ogre::SceneNode* rviz::RobotLink::getVisualNode ( ) const
inline

Definition at line 127 of file robot_link.h.

◆ hasGeometry()

bool rviz::RobotLink::hasGeometry ( ) const

Definition at line 344 of file robot_link.cpp.

◆ hideSubProperties()

void rviz::RobotLink::hideSubProperties ( bool  hide)
virtual

Definition at line 964 of file robot_link.cpp.

◆ setColor()

void rviz::RobotLink::setColor ( float  red,
float  green,
float  blue 
)

Definition at line 935 of file robot_link.cpp.

◆ setMaterialMode()

void rviz::RobotLink::setMaterialMode ( unsigned char  mode_flags)
private

Definition at line 911 of file robot_link.cpp.

◆ setOnlyRenderDepth()

void rviz::RobotLink::setOnlyRenderDepth ( bool  onlyRenderDepth)

Definition at line 380 of file robot_link.cpp.

◆ setParentProperty()

void rviz::RobotLink::setParentProperty ( Property new_parent)

Definition at line 983 of file robot_link.cpp.

◆ setRenderQueueGroup()

void rviz::RobotLink::setRenderQueueGroup ( Ogre::uint8  group)
private

Definition at line 362 of file robot_link.cpp.

◆ setRobotAlpha()

void rviz::RobotLink::setRobotAlpha ( float  a)
virtual

Definition at line 356 of file robot_link.cpp.

◆ setSelectable()

bool rviz::RobotLink::setSelectable ( bool  selectable)

set whether the link is selectable. If false objects behind/inside the link can be selected/manipulated. Returns old value.

Definition at line 952 of file robot_link.cpp.

◆ setToErrorMaterial()

void rviz::RobotLink::setToErrorMaterial ( )

Definition at line 901 of file robot_link.cpp.

◆ setToNormalMaterial()

void rviz::RobotLink::setToNormalMaterial ( )

Definition at line 906 of file robot_link.cpp.

◆ setTransforms()

void rviz::RobotLink::setTransforms ( const Ogre::Vector3 &  visual_position,
const Ogre::Quaternion &  visual_orientation,
const Ogre::Vector3 &  collision_position,
const Ogre::Quaternion &  collision_orientation 
)
virtual

Definition at line 874 of file robot_link.cpp.

◆ unsetColor()

void rviz::RobotLink::unsetColor ( )

Definition at line 947 of file robot_link.cpp.

◆ updateAlpha

void rviz::RobotLink::updateAlpha ( )
privateslot

Definition at line 387 of file robot_link.cpp.

◆ updateAxes

void rviz::RobotLink::updateAxes ( )
privateslot

Definition at line 848 of file robot_link.cpp.

◆ updateTrail

void rviz::RobotLink::updateTrail ( )
privateslot

Definition at line 812 of file robot_link.cpp.

◆ updateVisibility

void rviz::RobotLink::updateVisibility ( )
slot

Update the visibility of the link elements: visual mesh, collision mesh, trail, and axes.

Called by Robot when changing visual and collision visibilities, since each link may be enabled or disabled.

Definition at line 436 of file robot_link.cpp.

◆ useDetailProperty()

void rviz::RobotLink::useDetailProperty ( bool  use_detail)

Definition at line 999 of file robot_link.cpp.

Friends And Related Function Documentation

◆ RobotLinkSelectionHandler

friend class RobotLinkSelectionHandler
friend

Definition at line 263 of file robot_link.h.

Member Data Documentation

◆ alpha_property_

FloatProperty* rviz::RobotLink::alpha_property_
protected

Definition at line 228 of file robot_link.h.

◆ axes_

Axes* rviz::RobotLink::axes_
private

Definition at line 246 of file robot_link.h.

◆ axes_property_

Property* rviz::RobotLink::axes_property_
protected

Definition at line 227 of file robot_link.h.

◆ child_joint_names_

std::vector<std::string> rviz::RobotLink::child_joint_names_
protected

Definition at line 218 of file robot_link.h.

◆ collision_meshes_

std::vector<Ogre::Entity*> rviz::RobotLink::collision_meshes_
private

The entities representing the collision mesh of this link (if they exist)

Definition at line 239 of file robot_link.h.

◆ collision_node_

Ogre::SceneNode* rviz::RobotLink::collision_node_
private

The scene node the collision meshes are attached to.

Definition at line 242 of file robot_link.h.

◆ color_material_

Ogre::MaterialPtr rviz::RobotLink::color_material_
private

Definition at line 260 of file robot_link.h.

◆ context_

DisplayContext* rviz::RobotLink::context_
protected

Definition at line 214 of file robot_link.h.

◆ default_material_

Ogre::MaterialPtr rviz::RobotLink::default_material_
private

Definition at line 233 of file robot_link.h.

◆ default_material_name_

std::string rviz::RobotLink::default_material_name_
private

Definition at line 234 of file robot_link.h.

◆ details_

Property* rviz::RobotLink::details_
protected

Definition at line 223 of file robot_link.h.

◆ is_selectable_

bool rviz::RobotLink::is_selectable_
private

Definition at line 253 of file robot_link.h.

◆ joint_name_

std::string rviz::RobotLink::joint_name_
private

Definition at line 256 of file robot_link.h.

◆ link_property_

Property* rviz::RobotLink::link_property_
protected

Definition at line 222 of file robot_link.h.

◆ material_alpha_

float rviz::RobotLink::material_alpha_
private

If material is not a texture, this saves the alpha value set in the URDF, otherwise is 1.0.

Definition at line 248 of file robot_link.h.

◆ material_mode_flags_

unsigned char rviz::RobotLink::material_mode_flags_
private

Definition at line 261 of file robot_link.h.

◆ materials_

M_SubEntityToMaterial rviz::RobotLink::materials_
private

Definition at line 232 of file robot_link.h.

◆ name_

std::string rviz::RobotLink::name_
protected

Name of this link.

Definition at line 216 of file robot_link.h.

◆ only_render_depth_

bool rviz::RobotLink::only_render_depth_
private

Definition at line 252 of file robot_link.h.

◆ orientation_property_

QuaternionProperty* rviz::RobotLink::orientation_property_
protected

Definition at line 225 of file robot_link.h.

◆ parent_joint_name_

std::string rviz::RobotLink::parent_joint_name_
protected

Definition at line 217 of file robot_link.h.

◆ position_property_

VectorProperty* rviz::RobotLink::position_property_
protected

Definition at line 224 of file robot_link.h.

◆ robot_

Robot* rviz::RobotLink::robot_
protected

Definition at line 212 of file robot_link.h.

◆ robot_alpha_

float rviz::RobotLink::robot_alpha_
private

Alpha value from top-level robot alpha Property (set via setRobotAlpha()).

Definition at line 250 of file robot_link.h.

◆ scene_manager_

Ogre::SceneManager* rviz::RobotLink::scene_manager_
protected

Definition at line 213 of file robot_link.h.

◆ selection_handler_

RobotLinkSelectionHandlerPtr rviz::RobotLink::selection_handler_
private

Definition at line 258 of file robot_link.h.

◆ trail_

Ogre::RibbonTrail* rviz::RobotLink::trail_
private

Definition at line 244 of file robot_link.h.

◆ trail_property_

Property* rviz::RobotLink::trail_property_
protected

Definition at line 226 of file robot_link.h.

◆ visual_meshes_

std::vector<Ogre::Entity*> rviz::RobotLink::visual_meshes_
private

The entities representing the visual mesh of this link (if they exist)

Definition at line 237 of file robot_link.h.

◆ visual_node_

Ogre::SceneNode* rviz::RobotLink::visual_node_
private

The scene node the visual meshes are attached to.

Definition at line 241 of file robot_link.h.


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


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:26