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
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 #include <OgrePrerequisites.h>
53 
54 namespace Ogre
55 {
56 class Any;
57 }
58 
59 namespace rviz
60 {
61 class Shape;
62 class Axes;
63 class DisplayContext;
64 class FloatProperty;
65 class Property;
66 class BoolProperty;
67 class QuaternionProperty;
68 class Robot;
69 class RobotLinkSelectionHandler;
70 class VectorProperty;
71 class RobotJoint;
73 
74 
79 class RobotLink : public QObject
80 {
81  Q_OBJECT
82 
84  {
85  ORIGINAL = 0,
86  COLOR = 1,
87  ERROR = 2,
88  };
89 
90 public:
91  RobotLink(Robot* robot,
92  const urdf::LinkConstSharedPtr& link,
93  const std::string& parent_joint_name,
94  bool visual,
95  bool collision);
96  ~RobotLink() override;
97 
98  virtual void setRobotAlpha(float a);
99 
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);
104 
105  // access
106  const std::string& getName() const
107  {
108  return name_;
109  }
110  const std::string& getParentJointName() const
111  {
112  return parent_joint_name_;
113  }
114  const std::vector<std::string>& getChildJointNames() const
115  {
116  return child_joint_names_;
117  }
119  {
120  return link_property_;
121  }
122  Ogre::SceneNode* getVisualNode() const
123  {
124  return visual_node_;
125  }
126  Ogre::SceneNode* getCollisionNode() const
127  {
128  return collision_node_;
129  }
130  Robot* getRobot() const
131  {
132  return robot_;
133  }
134  const std::string& getGeometryErrors() const;
135 
136  // Remove link_property_ from its old parent and add to new_parent. If new_parent==NULL then leav
137  // unparented.
138  void setParentProperty(Property* new_parent);
139 
140  // hide or show all sub properties (hide to make tree easier to see)
141  virtual void hideSubProperties(bool hide);
142 
143  void setToErrorMaterial();
144  void setToNormalMaterial();
145 
146  void setColor(float red, float green, float blue);
147  void unsetColor();
148 
151  bool setSelectable(bool selectable);
152  bool getSelectable();
153 
154  Ogre::Vector3 getPosition();
155  Ogre::Quaternion getOrientation();
156 
157  bool hasGeometry() const;
158 
159  /* If set to true, the link will only render to the depth channel
160  * and be in render group 0, so it is rendered before anything else.
161  * Thus, it will occlude other objects without being visible.
162  */
163  void setOnlyRenderDepth(bool onlyRenderDepth);
164  bool getOnlyRenderDepth() const
165  {
166  return only_render_depth_;
167  }
168 
169  // place subproperties as children of details_ or joint_property_
170  void useDetailProperty(bool use_detail);
171 
172  // expand all sub properties
173  void expandDetails(bool expand);
174 
175 public Q_SLOTS:
180  void updateVisibility();
181 
182 private Q_SLOTS:
183  void updateAlpha();
184  void updateTrail();
185  void updateAxes();
186 
187 private:
188  void setMaterialMode(unsigned char mode_flags);
189  void setRenderQueueGroup(Ogre::uint8 group);
190  bool getEnabled() const;
191  void createEntityForGeometryElement(const urdf::LinkConstSharedPtr& link,
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, ...);
198 
199  void createVisual(const urdf::LinkConstSharedPtr& link);
200  void createCollision(const urdf::LinkConstSharedPtr& link);
201  void createSelection();
202  Ogre::MaterialPtr getMaterialForLink(const urdf::LinkConstSharedPtr& link,
203  urdf::MaterialConstSharedPtr material);
204 
205 
206 protected:
208  Ogre::SceneManager* scene_manager_;
210 
211  std::string name_;
212  std::string parent_joint_name_;
213  std::vector<std::string> child_joint_names_;
214 
215 
216  // properties
224 
225 private:
226  // maintain the original material of each SubEntity to restore it after unsetColor()
227  using M_SubEntityToMaterial =
228  std::map<Ogre::SubEntity*, std::pair<Ogre::MaterialPtr, Ogre::MaterialPtr>>;
230  Ogre::MaterialPtr default_material_;
232 
233  std::vector<Ogre::Entity*>
235  std::vector<Ogre::Entity*>
237 
238  Ogre::SceneNode* visual_node_;
239  Ogre::SceneNode* collision_node_;
240 
241  Ogre::RibbonTrail* trail_;
242 
244 
245  float robot_alpha_;
246 
249 
250  // joint stuff
251  std::string joint_name_;
252 
254 
255  Ogre::MaterialPtr color_material_;
256  unsigned char material_mode_flags_;
257 
259 };
260 
261 } // namespace rviz
262 
263 #endif // RVIZ_ROBOT_LINK_H
rviz::RobotLinkSelectionHandler
Definition: robot_link.cpp:70
Ogre
Definition: axes_display.h:35
boost::shared_ptr< RobotLinkSelectionHandler >
forwards.h
rviz::RobotLinkSelectionHandlerPtr
boost::shared_ptr< RobotLinkSelectionHandler > RobotLinkSelectionHandlerPtr
Definition: robot_link.h:71
rviz::QuaternionProperty
Definition: quaternion_property.h:38
rviz::FloatProperty
Property specialized to enforce floating point max/min.
Definition: float_property.h:37
rviz::Property
A single element of a property tree, with a name, value, description, and possibly children.
Definition: property.h:100
rviz
Definition: add_display_dialog.cpp:54
model.h
ogre_vector.h
rviz::RobotJoint
Contains any data we need from a joint in the robot.
Definition: robot_joint.h:79
rviz::DisplayContext
Pure-virtual base class for objects which give Display subclasses context in which to work.
Definition: display_context.h:81
Robot
rviz::Axes
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
Definition: axes.h:57
rviz::VectorProperty
Definition: vector_property.h:39
rviz::Robot
Definition: robot.h:79
object.h


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Sat Jun 1 2024 02:31:53