robot_link.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef RVIZ_ROBOT_LINK_H
31 #define RVIZ_ROBOT_LINK_H
32 
33 #include <string>
34 #include <map>
35 
36 #include <QObject>
37 
38 #ifndef Q_MOC_RUN
39 #include <OgreVector3.h>
40 #include <OgreQuaternion.h>
41 #include <OgreAny.h>
42 #include <OgreMaterial.h>
43 #include <OgreSharedPtr.h>
44 #endif
45 
46 #include <urdf/model.h> // can be replaced later by urdf_model/types.h
47 #include <urdf_model/pose.h>
48 
51 
52 namespace Ogre
53 {
54 class SceneManager;
55 class Entity;
56 class SubEntity;
57 class SceneNode;
58 class Vector3;
59 class Quaternion;
60 class Any;
61 class RibbonTrail;
62 }
63 
64 namespace rviz
65 {
66 class Shape;
67 class Axes;
68 class DisplayContext;
69 class FloatProperty;
70 class Property;
71 class BoolProperty;
72 class QuaternionProperty;
73 class Robot;
74 class RobotLinkSelectionHandler;
75 class VectorProperty;
76 class RobotJoint;
78 
79 
84 class RobotLink: public QObject
85 {
86 Q_OBJECT
87 public:
88  RobotLink( Robot* robot,
89  const urdf::LinkConstSharedPtr& link,
90  const std::string& parent_joint_name,
91  bool visual,
92  bool collision);
93  virtual ~RobotLink();
94 
95  virtual void setRobotAlpha(float a);
96 
97  virtual void setTransforms(const Ogre::Vector3& visual_position, const Ogre::Quaternion& visual_orientation,
98  const Ogre::Vector3& collision_position, const Ogre::Quaternion& collision_orientation);
99 
100  // access
101  const std::string& getName() const { return name_; }
102  const std::string& getParentJointName() const { return parent_joint_name_; }
103  const std::vector<std::string>& getChildJointNames() const { return child_joint_names_; }
104  Property* getLinkProperty() const { return link_property_; }
105  Ogre::SceneNode* getVisualNode() const { return visual_node_; }
106  Ogre::SceneNode* getCollisionNode() const { return collision_node_; }
107  Robot* getRobot() const { return robot_; }
108 
109  // Remove link_property_ from its old parent and add to new_parent. If new_parent==NULL then leav unparented.
110  void setParentProperty(Property* new_parent);
111 
112  // hide or show all sub properties (hide to make tree easier to see)
113  virtual void hideSubProperties(bool hide);
114 
115  void setToErrorMaterial();
116  void setToNormalMaterial();
117 
118  void setColor( float red, float green, float blue );
119  void unsetColor();
120 
122  bool setSelectable( bool selectable );
123  bool getSelectable();
124 
125  Ogre::Vector3 getPosition();
126  Ogre::Quaternion getOrientation();
127 
128  bool hasGeometry() const;
129 
130  /* If set to true, the link will only render to the depth channel
131  * and be in render group 0, so it is rendered before anything else.
132  * Thus, it will occlude other objects without being visible.
133  */
134  void setOnlyRenderDepth( bool onlyRenderDepth );
135  bool getOnlyRenderDepth() const { return only_render_depth_; }
136 
137  // place subproperties as children of details_ or joint_property_
138  void useDetailProperty(bool use_detail);
139 
140  // expand all sub properties
141  void expandDetails(bool expand);
142 
143 public Q_SLOTS:
148  void updateVisibility();
149 
150 private Q_SLOTS:
151  void updateAlpha();
152  void updateTrail();
153  void updateAxes();
154 
155 private:
156  void setRenderQueueGroup( Ogre::uint8 group );
157  bool getEnabled() const;
158  void createEntityForGeometryElement( const urdf::LinkConstSharedPtr& link, const urdf::Geometry& geom, const urdf::Pose& origin, const std::string material_name, Ogre::SceneNode* scene_node, Ogre::Entity*& entity );
159 
160  void createVisual( const urdf::LinkConstSharedPtr& link);
161  void createCollision( const urdf::LinkConstSharedPtr& link);
162  void createSelection();
163  Ogre::MaterialPtr getMaterialForLink( const urdf::LinkConstSharedPtr& link, const std::string material_name = "" );
164 
165 
166 protected:
168  Ogre::SceneManager* scene_manager_;
170 
171  std::string name_;
172  std::string parent_joint_name_;
173  std::vector<std::string> child_joint_names_;
174 
175 
176 
177  // properties
185 
186 private:
187  typedef std::map<Ogre::SubEntity*, Ogre::MaterialPtr> M_SubEntityToMaterial;
188  M_SubEntityToMaterial materials_;
189  Ogre::MaterialPtr default_material_;
191 
192  std::vector<Ogre::Entity*> visual_meshes_;
193  std::vector<Ogre::Entity*> collision_meshes_;
194 
195  Ogre::SceneNode* visual_node_;
196  Ogre::SceneNode* collision_node_;
197 
198  Ogre::RibbonTrail* trail_;
199 
201 
203  float robot_alpha_;
204 
207 
208  // joint stuff
209  std::string joint_name_;
210 
211  RobotLinkSelectionHandlerPtr selection_handler_;
212 
213  Ogre::MaterialPtr color_material_;
215 
217 };
218 
219 } // namespace rviz
220 
221 #endif // RVIZ_ROBOT_LINK_H
A single element of a property tree, with a name, value, description, and possibly children...
Definition: property.h:100
Property specialized to enforce floating point max/min.
Pure-virtual base class for objects which give Display subclasses context in which to work...
boost::shared_ptr< RobotLinkSelectionHandler > RobotLinkSelectionHandlerPtr
Definition: robot_link.h:76
TFSIMD_FORCE_INLINE Vector3()
Contains any data we need from a joint in the robot.
Definition: robot_joint.h:84
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
Definition: axes.h:58


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:51