Public Slots | Public Member Functions | Protected Attributes | Private Types | Private Slots | Private Member Functions | Private Attributes | Friends
rviz::RobotLink Struct Reference

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

#include <robot_link.h>

List of all members.

Public Slots

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

Public Member Functions

void expandDetails (bool expand)
const std::vector< std::string > & getChildJointNames () const
Ogre::SceneNode * getCollisionNode () 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::LinkConstPtr &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)
 set whether the link is selectable. If false objects behind/inside the link can be selected/manipulated. Returns old value.
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)
virtual ~RobotLink ()

Protected Attributes

FloatPropertyalpha_property_
Propertyaxes_property_
std::vector< std::string > child_joint_names_
DisplayContextcontext_
Propertydetails_
Propertylink_property_
std::string name_
 Name of this link.
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

Private Slots

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

Private Member Functions

void createCollision (const urdf::LinkConstPtr &link)
void createEntityForGeometryElement (const urdf::LinkConstPtr &link, const urdf::Geometry &geom, const urdf::Pose &origin, Ogre::SceneNode *scene_node, Ogre::Entity *&entity)
void createSelection ()
void createVisual (const urdf::LinkConstPtr &link)
bool getEnabled () const
Ogre::MaterialPtr getMaterialForLink (const urdf::LinkConstPtr &link)
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)
Ogre::SceneNode * collision_node_
 The scene node the collision meshes are attached to.
Ogre::MaterialPtr color_material_
Ogre::MaterialPtr default_material_
std::string default_material_name_
bool is_selectable_
std::string joint_name_
float material_alpha_
 If material is not a texture, this saves the alpha value set in the URDF, otherwise is 1.0.
M_SubEntityToMaterial materials_
bool only_render_depth_
float robot_alpha_
 Alpha value from top-level robot alpha Property (set via setRobotAlpha()).
RobotLinkSelectionHandlerPtr selection_handler_
Ogre::RibbonTrail * trail_
bool using_color_
std::vector< Ogre::Entity * > visual_meshes_
 The entities representing the visual mesh of this link (if they exist)
Ogre::SceneNode * visual_node_
 The scene node the visual meshes are attached to.

Friends

class RobotLinkSelectionHandler

Detailed Description

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

Definition at line 89 of file robot_link.h.


Member Typedef Documentation

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

Definition at line 192 of file robot_link.h.


Constructor & Destructor Documentation

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

Definition at line 153 of file robot_link.cpp.

Definition at line 300 of file robot_link.cpp.


Member Function Documentation

void rviz::RobotLink::createCollision ( const urdf::LinkConstPtr &  link) [private]

Definition at line 646 of file robot_link.cpp.

void rviz::RobotLink::createEntityForGeometryElement ( const urdf::LinkConstPtr &  link,
const urdf::Geometry &  geom,
const urdf::Pose origin,
Ogre::SceneNode *  scene_node,
Ogre::Entity *&  entity 
) [private]

Definition at line 509 of file robot_link.cpp.

Definition at line 724 of file robot_link.cpp.

void rviz::RobotLink::createVisual ( const urdf::LinkConstPtr &  link) [private]

Definition at line 685 of file robot_link.cpp.

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

Definition at line 954 of file robot_link.cpp.

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

Definition at line 108 of file robot_link.h.

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

Definition at line 111 of file robot_link.h.

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

Definition at line 330 of file robot_link.cpp.

Definition at line 109 of file robot_link.h.

Ogre::MaterialPtr rviz::RobotLink::getMaterialForLink ( const urdf::LinkConstPtr &  link) [private]

Definition at line 441 of file robot_link.cpp.

const std::string& rviz::RobotLink::getName ( void  ) const [inline]

Definition at line 106 of file robot_link.h.

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

Definition at line 140 of file robot_link.h.

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

Definition at line 905 of file robot_link.cpp.

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

Definition at line 107 of file robot_link.h.

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

Definition at line 900 of file robot_link.cpp.

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

Definition at line 112 of file robot_link.h.

Definition at line 886 of file robot_link.cpp.

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

Definition at line 110 of file robot_link.h.

Definition at line 325 of file robot_link.cpp.

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

Definition at line 891 of file robot_link.cpp.

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

Definition at line 860 of file robot_link.cpp.

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

Definition at line 361 of file robot_link.cpp.

Definition at line 910 of file robot_link.cpp.

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

Definition at line 343 of file robot_link.cpp.

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

Definition at line 337 of file robot_link.cpp.

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 879 of file robot_link.cpp.

Definition at line 824 of file robot_link.cpp.

Definition at line 836 of file robot_link.cpp.

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 799 of file robot_link.cpp.

Definition at line 873 of file robot_link.cpp.

void rviz::RobotLink::updateAlpha ( ) [private, slot]

Definition at line 368 of file robot_link.cpp.

void rviz::RobotLink::updateAxes ( ) [private, slot]

Definition at line 773 of file robot_link.cpp.

void rviz::RobotLink::updateTrail ( ) [private, slot]

Definition at line 737 of file robot_link.cpp.

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 417 of file robot_link.cpp.

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

Definition at line 926 of file robot_link.cpp.


Friends And Related Function Documentation

friend class RobotLinkSelectionHandler [friend]

Definition at line 221 of file robot_link.h.


Member Data Documentation

Definition at line 189 of file robot_link.h.

Definition at line 205 of file robot_link.h.

Definition at line 188 of file robot_link.h.

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

Definition at line 178 of file robot_link.h.

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

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

Definition at line 198 of file robot_link.h.

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

The scene node the collision meshes are attached to.

Definition at line 201 of file robot_link.h.

Ogre::MaterialPtr rviz::RobotLink::color_material_ [private]

Definition at line 218 of file robot_link.h.

Definition at line 174 of file robot_link.h.

Ogre::MaterialPtr rviz::RobotLink::default_material_ [private]

Definition at line 194 of file robot_link.h.

Definition at line 195 of file robot_link.h.

Definition at line 184 of file robot_link.h.

Definition at line 211 of file robot_link.h.

std::string rviz::RobotLink::joint_name_ [private]

Definition at line 214 of file robot_link.h.

Definition at line 183 of file robot_link.h.

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

Definition at line 207 of file robot_link.h.

Definition at line 193 of file robot_link.h.

std::string rviz::RobotLink::name_ [protected]

Name of this link.

Definition at line 176 of file robot_link.h.

Definition at line 210 of file robot_link.h.

Definition at line 186 of file robot_link.h.

std::string rviz::RobotLink::parent_joint_name_ [protected]

Definition at line 177 of file robot_link.h.

Definition at line 185 of file robot_link.h.

Definition at line 172 of file robot_link.h.

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

Definition at line 208 of file robot_link.h.

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

Definition at line 173 of file robot_link.h.

Definition at line 216 of file robot_link.h.

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

Definition at line 203 of file robot_link.h.

Definition at line 187 of file robot_link.h.

Definition at line 219 of file robot_link.h.

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

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

Definition at line 197 of file robot_link.h.

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

The scene node the visual meshes are attached to.

Definition at line 200 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 Thu Aug 27 2015 15:02:29