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 } // namespace Ogre
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 
89  {
90  ORIGINAL = 0,
91  COLOR = 1,
92  ERROR = 2,
93  };
94 
95 public:
96  RobotLink(Robot* robot,
97  const urdf::LinkConstSharedPtr& link,
98  const std::string& parent_joint_name,
99  bool visual,
100  bool collision);
101  ~RobotLink() override;
102 
103  virtual void setRobotAlpha(float a);
104 
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);
109 
110  // access
111  const std::string& getName() const
112  {
113  return name_;
114  }
115  const std::string& getParentJointName() const
116  {
117  return parent_joint_name_;
118  }
119  const std::vector<std::string>& getChildJointNames() const
120  {
121  return child_joint_names_;
122  }
124  {
125  return link_property_;
126  }
127  Ogre::SceneNode* getVisualNode() const
128  {
129  return visual_node_;
130  }
131  Ogre::SceneNode* getCollisionNode() const
132  {
133  return collision_node_;
134  }
135  Robot* getRobot() const
136  {
137  return robot_;
138  }
139  const std::string& getGeometryErrors() const;
140 
141  // Remove link_property_ from its old parent and add to new_parent. If new_parent==NULL then leav
142  // unparented.
143  void setParentProperty(Property* new_parent);
144 
145  // hide or show all sub properties (hide to make tree easier to see)
146  virtual void hideSubProperties(bool hide);
147 
148  void setToErrorMaterial();
149  void setToNormalMaterial();
150 
151  void setColor(float red, float green, float blue);
152  void unsetColor();
153 
156  bool setSelectable(bool selectable);
157  bool getSelectable();
158 
159  Ogre::Vector3 getPosition();
160  Ogre::Quaternion getOrientation();
161 
162  bool hasGeometry() const;
163 
164  /* If set to true, the link will only render to the depth channel
165  * and be in render group 0, so it is rendered before anything else.
166  * Thus, it will occlude other objects without being visible.
167  */
168  void setOnlyRenderDepth(bool onlyRenderDepth);
169  bool getOnlyRenderDepth() const
170  {
171  return only_render_depth_;
172  }
173 
174  // place subproperties as children of details_ or joint_property_
175  void useDetailProperty(bool use_detail);
176 
177  // expand all sub properties
178  void expandDetails(bool expand);
179 
180 public Q_SLOTS:
185  void updateVisibility();
186 
187 private Q_SLOTS:
188  void updateAlpha();
189  void updateTrail();
190  void updateAxes();
191 
192 private:
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, ...);
203 
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);
209 
210 
211 protected:
213  Ogre::SceneManager* scene_manager_;
215 
216  std::string name_;
217  std::string parent_joint_name_;
218  std::vector<std::string> child_joint_names_;
219 
220 
221  // properties
229 
230 private:
231  typedef std::map<Ogre::SubEntity*, Ogre::MaterialPtr> M_SubEntityToMaterial;
232  M_SubEntityToMaterial materials_;
233  Ogre::MaterialPtr default_material_;
235 
236  std::vector<Ogre::Entity*>
238  std::vector<Ogre::Entity*>
240 
241  Ogre::SceneNode* visual_node_;
242  Ogre::SceneNode* collision_node_;
243 
244  Ogre::RibbonTrail* trail_;
245 
247 
249  float robot_alpha_;
251 
254 
255  // joint stuff
256  std::string joint_name_;
257 
258  RobotLinkSelectionHandlerPtr selection_handler_;
259 
260  Ogre::MaterialPtr color_material_;
261  unsigned char material_mode_flags_;
262 
264 };
265 
266 } // namespace rviz
267 
268 #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
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:59


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