robot_joint.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, 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_JOINT_H
31 #define RVIZ_ROBOT_JOINT_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 #endif
44 
45 #include <urdf/model.h>
46 #include <urdf_model/pose.h>
47 
50 
51 namespace Ogre
52 {
53 class SceneManager;
54 class Entity;
55 class SubEntity;
56 class SceneNode;
57 class Vector3;
58 class Quaternion;
59 class Any;
60 class RibbonTrail;
61 }
62 
63 namespace rviz
64 {
65 class Shape;
66 class Arrow;
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;
77 class StringProperty;
78 
79 
84 class RobotJoint: public QObject
85 {
86 Q_OBJECT
87 public:
88  RobotJoint( Robot* robot, const urdf::JointConstSharedPtr& joint );
89  virtual ~RobotJoint();
90 
91 
92  void setTransforms(const Ogre::Vector3& parent_link_position,
93  const Ogre::Quaternion& parent_link_orientation);
94 
95  const std::string& getName() const { return name_; }
96  const std::string& getParentLinkName() const { return parent_link_name_; }
97  const std::string& getChildLinkName() const { return child_link_name_; }
98  const Property* getJointProperty() const { return joint_property_; }
99  Property* getJointProperty() { return joint_property_; }
100  RobotJoint* getParentJoint();
101  void hideSubProperties(bool hide);
102 
103  // Remove joint_property_ from its old parent and add to new_parent. If new_parent==NULL then leav unparented.
104  void setParentProperty(Property* new_parent);
105 
106  Ogre::Vector3 getPosition();
107  Ogre::Quaternion getOrientation();
108 
109  void setRobotAlpha(float a) {}
110 
111  bool hasDescendentLinksWithGeometry() const { return has_decendent_links_with_geometry_; }
112 
113  // place subproperties as children of details_ or joint_property_
114  void useDetailProperty(bool use_detail);
115 
116  // expand all sub properties
117  void expandDetails(bool expand);
118 
119  // Set the description for the joint.
120  // Also sets the checkbox.
121  // Also sets has_decendent_links_with_geometry_.
122  // Called when the link_tree style changes.
123  void setJointPropertyDescription();
124 
125  // set checkboxes based on state of descendent link enables
126  // Should only be called by Robot::calculateJointCheckboxes()
127  void calculateJointCheckboxesRecursive(
128  int& links_with_geom, // returns # of children with geometry
129  int& links_with_geom_checked, // returns # of enabled children with geometry
130  int& links_with_geom_unchecked); // returns # of disabled children with geometry
131 
132 
133 private Q_SLOTS:
134  void updateAxes();
135  void updateAxis();
136  void updateChildVisibility();
137 
138 private:
139  bool getEnabled() const;
140 
141  // true if displaying in a tree style. False if list style.
142  bool styleIsTree() const;
143 
144  // determine the state of child link(s)
145  void getChildLinkState(
146  int& links_with_geom, // returns # of children with geometry
147  int& links_with_geom_checked, // returns # of enabled children with geometry
148  int& links_with_geom_unchecked, // returns # of disabled children with geometry
149  bool recursive) const; // True: all descendant links. False: just single child link.
150 
151  // set the value of the enable checkbox without touching child joints/links
152  void setJointCheckbox(QVariant val);
153 
154 
155 protected:
157  std::string name_;
158  std::string parent_link_name_;
159  std::string child_link_name_;
160 
161  // properties
167  // The joint axis if any, as opposed to the frame in which the joint exists above
173 
174 private:
175  Ogre::Vector3 joint_origin_pos_;
176  Ogre::Quaternion joint_origin_rot_;
178 
179  bool doing_set_checkbox_; // prevents updateChildVisibility() from touching children
180 
183 };
184 
185 } // namespace rviz
186 
187 #endif // RVIZ_ROBOT_LINK_H
VectorProperty * axis_property_
Definition: robot_joint.h:168
StringProperty * type_property_
Definition: robot_joint.h:170
Ogre::Quaternion joint_origin_rot_
Definition: robot_joint.h:176
Property * details_
Definition: robot_joint.h:163
QuaternionProperty * orientation_property_
Definition: robot_joint.h:165
std::string parent_link_name_
Definition: robot_joint.h:158
A single element of a property tree, with a name, value, description, and possibly children...
Definition: property.h:100
Property * joint_property_
Definition: robot_joint.h:162
Ogre::Vector3 joint_origin_pos_
Definition: robot_joint.h:175
Property specialized to enforce floating point max/min.
VectorProperty * position_property_
Definition: robot_joint.h:164
Property * show_axis_property_
Definition: robot_joint.h:169
Property * axes_property_
Definition: robot_joint.h:166
bool doing_set_checkbox_
Definition: robot_joint.h:179
bool hasDescendentLinksWithGeometry() const
Definition: robot_joint.h:111
TFSIMD_FORCE_INLINE Vector3()
const std::string & getName() const
Definition: robot_joint.h:95
FloatProperty * upper_limit_property_
Definition: robot_joint.h:172
std::string name_
Name of this joint.
Definition: robot_joint.h:157
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
void setRobotAlpha(float a)
Definition: robot_joint.h:109
FloatProperty * lower_limit_property_
Definition: robot_joint.h:171
Property specialized for string values.
std::string child_link_name_
Definition: robot_joint.h:159
const Property * getJointProperty() const
Definition: robot_joint.h:98
An arrow consisting of a cylinder and a cone.
Definition: arrow.h:59
const std::string & getParentLinkName() const
Definition: robot_joint.h:96
Property * getJointProperty()
Definition: robot_joint.h:99
const std::string & getChildLinkName() const
Definition: robot_joint.h:97
bool has_decendent_links_with_geometry_
Definition: robot_joint.h:177


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