Go to the documentation of this file.
   30 #ifndef RVIZ_ROBOT_LINK_H 
   31 #define RVIZ_ROBOT_LINK_H 
   40 #include <OgreQuaternion.h> 
   42 #include <OgreMaterial.h> 
   43 #include <OgreSharedPtr.h> 
   47 #include <urdf_model/pose.h> 
   52 #include <OgrePrerequisites.h> 
   67 class QuaternionProperty;
 
   69 class RobotLinkSelectionHandler;
 
   92             const urdf::LinkConstSharedPtr& link,
 
   93             const std::string& parent_joint_name,
 
  100   virtual void setTransforms(
const Ogre::Vector3& visual_position,
 
  101                              const Ogre::Quaternion& visual_orientation,
 
  102                              const Ogre::Vector3& collision_position,
 
  103                              const Ogre::Quaternion& collision_orientation);
 
  146   void setColor(
float red, 
float green, 
float blue);
 
  192                                       const urdf::Geometry& geom,
 
  193                                       const urdf::MaterialSharedPtr& material,
 
  194                                       const urdf::Pose& origin,
 
  195                                       Ogre::SceneNode* scene_node,
 
  196                                       Ogre::Entity*& entity);
 
  197   void addError(
const char* format, ...);
 
  199   void createVisual(
const urdf::LinkConstSharedPtr& link);
 
  203                                        urdf::MaterialConstSharedPtr material);
 
  228       std::map<Ogre::SubEntity*, std::pair<Ogre::MaterialPtr, Ogre::MaterialPtr>>;
 
  233   std::vector<Ogre::Entity*>
 
  235   std::vector<Ogre::Entity*>
 
  263 #endif // RVIZ_ROBOT_LINK_H 
  
void expandDetails(bool expand)
void setParentProperty(Property *new_parent)
Ogre::SceneNode * getVisualNode() const
Ogre::SceneNode * visual_node_
The scene node the visual meshes are attached to.
void updateVisibility()
Update the visibility of the link elements: visual mesh, collision mesh, trail, and axes.
boost::shared_ptr< RobotLinkSelectionHandler > RobotLinkSelectionHandlerPtr
std::string name_
Name of this link.
bool setSelectable(bool selectable)
std::vector< std::string > child_joint_names_
bool getOnlyRenderDepth() const
RobotLinkSelectionHandlerPtr selection_handler_
std::vector< Ogre::Entity * > visual_meshes_
The entities representing the visual mesh of this link (if they exist)
void setMaterialMode(unsigned char mode_flags)
Ogre::MaterialPtr default_material_
virtual void hideSubProperties(bool hide)
void createCollision(const urdf::LinkConstSharedPtr &link)
unsigned char material_mode_flags_
const std::string & getGeometryErrors() const
const std::string & getParentJointName() const
void setToErrorMaterial()
virtual void setTransforms(const Ogre::Vector3 &visual_position, const Ogre::Quaternion &visual_orientation, const Ogre::Vector3 &collision_position, const Ogre::Quaternion &collision_orientation)
FloatProperty * alpha_property_
Property specialized to enforce floating point max/min.
Ogre::SceneNode * collision_node_
The scene node the collision meshes are attached to.
A single element of a property tree, with a name, value, description, and possibly children.
Property * axes_property_
float robot_alpha_
Alpha value from top-level robot alpha Property (set via setRobotAlpha()).
void setRenderQueueGroup(Ogre::uint8 group)
Property * getLinkProperty() const
void createVisual(const urdf::LinkConstSharedPtr &link)
Ogre::MaterialPtr getMaterialForLink(const urdf::LinkConstSharedPtr &link, urdf::MaterialConstSharedPtr material)
void useDetailProperty(bool use_detail)
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)
DisplayContext * context_
void setToNormalMaterial()
Ogre::MaterialPtr color_material_
Contains any data we need from a joint in the robot.
VectorProperty * position_property_
void setColor(float red, float green, float blue)
const std::string & getName() const
Pure-virtual base class for objects which give Display subclasses context in which to work.
std::string parent_joint_name_
QuaternionProperty * orientation_property_
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
Property * trail_property_
const std::vector< std::string > & getChildJointNames() const
RobotLink(Robot *robot, const urdf::LinkConstSharedPtr &link, const std::string &parent_joint_name, bool visual, bool collision)
M_SubEntityToMaterial materials_
Ogre::Quaternion getOrientation()
void addError(const char *format,...)
Contains any data we need from a link in the robot.
std::vector< Ogre::Entity * > collision_meshes_
The entities representing the collision mesh of this link (if they exist)
std::map< Ogre::SubEntity *, std::pair< Ogre::MaterialPtr, Ogre::MaterialPtr > > M_SubEntityToMaterial
Property * link_property_
virtual void setRobotAlpha(float a)
Ogre::SceneNode * getCollisionNode() const
void setOnlyRenderDepth(bool onlyRenderDepth)
std::string default_material_name_
Ogre::SceneManager * scene_manager_
Ogre::RibbonTrail * trail_
Ogre::Vector3 getPosition()
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall 
autogenerated on Sun May 4 2025 02:31:26