30 #ifndef RVIZ_ROBOT_LINK_H 31 #define RVIZ_ROBOT_LINK_H 39 #include <OgreVector3.h> 40 #include <OgreQuaternion.h> 42 #include <OgreMaterial.h> 43 #include <OgreSharedPtr.h> 47 #include <urdf_model/pose.h> 72 class QuaternionProperty;
74 class RobotLinkSelectionHandler;
97 const urdf::LinkConstSharedPtr& link,
98 const std::string& parent_joint_name,
103 virtual void setRobotAlpha(
float a);
105 virtual void setTransforms(
const Ogre::Vector3& visual_position,
106 const Ogre::Quaternion& visual_orientation,
107 const Ogre::Vector3& collision_position,
108 const Ogre::Quaternion& collision_orientation);
117 return parent_joint_name_;
121 return child_joint_names_;
125 return link_property_;
133 return collision_node_;
139 const std::string& getGeometryErrors()
const;
143 void setParentProperty(
Property* new_parent);
146 virtual void hideSubProperties(
bool hide);
148 void setToErrorMaterial();
149 void setToNormalMaterial();
151 void setColor(
float red,
float green,
float blue);
156 bool setSelectable(
bool selectable);
157 bool getSelectable();
159 Ogre::Vector3 getPosition();
160 Ogre::Quaternion getOrientation();
162 bool hasGeometry()
const;
168 void setOnlyRenderDepth(
bool onlyRenderDepth);
171 return only_render_depth_;
175 void useDetailProperty(
bool use_detail);
178 void expandDetails(
bool expand);
185 void updateVisibility();
193 void setMaterialMode(
unsigned char mode_flags);
194 void setRenderQueueGroup(Ogre::uint8 group);
195 bool getEnabled()
const;
196 void createEntityForGeometryElement(
const urdf::LinkConstSharedPtr& link,
197 const urdf::Geometry& geom,
198 const urdf::MaterialSharedPtr& material,
199 const urdf::Pose& origin,
200 Ogre::SceneNode* scene_node,
201 Ogre::Entity*& entity);
202 void addError(
const char* format, ...);
204 void createVisual(
const urdf::LinkConstSharedPtr& link);
205 void createCollision(
const urdf::LinkConstSharedPtr& link);
206 void createSelection();
207 Ogre::MaterialPtr getMaterialForLink(
const urdf::LinkConstSharedPtr& link,
208 urdf::MaterialConstSharedPtr material);
236 std::vector<Ogre::Entity*>
238 std::vector<Ogre::Entity*>
268 #endif // RVIZ_ROBOT_LINK_H std::map< Ogre::SubEntity *, Ogre::MaterialPtr > M_SubEntityToMaterial
std::vector< std::string > child_joint_names_
Ogre::SceneNode * visual_node_
The scene node the visual meshes are attached to.
RobotLinkSelectionHandlerPtr selection_handler_
Ogre::SceneNode * getVisualNode() const
A single element of a property tree, with a name, value, description, and possibly children...
Ogre::MaterialPtr default_material_
unsigned char material_mode_flags_
bool getOnlyRenderDepth() const
std::vector< Ogre::Entity * > visual_meshes_
The entities representing the visual mesh of this link (if they exist)
Property specialized to enforce floating point max/min.
std::string name_
Name of this link.
FloatProperty * alpha_property_
std::string parent_joint_name_
Pure-virtual base class for objects which give Display subclasses context in which to work...
QuaternionProperty * orientation_property_
const std::string & getParentJointName() const
Ogre::MaterialPtr color_material_
Property * trail_property_
boost::shared_ptr< RobotLinkSelectionHandler > RobotLinkSelectionHandlerPtr
const std::vector< std::string > & getChildJointNames() const
Ogre::SceneNode * collision_node_
The scene node the collision meshes are attached to.
M_SubEntityToMaterial materials_
Property * axes_property_
DisplayContext * context_
Property * getLinkProperty() const
VectorProperty * position_property_
Contains any data we need from a joint in the robot.
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
std::vector< Ogre::Entity * > collision_meshes_
The entities representing the collision mesh of this link (if they exist)
Contains any data we need from a link in the robot.
const std::string & getName() const
std::string default_material_name_
Property * link_property_
Ogre::RibbonTrail * trail_
Ogre::SceneNode * getCollisionNode() const
Ogre::SceneManager * scene_manager_