joint.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Wim Meeussen */
36 
37 #ifndef TESSERACT_SCENE_GRAPH_JOINT_H
38 #define TESSERACT_SCENE_GRAPH_JOINT_H
39 
42 #include <boost/serialization/export.hpp>
43 #include <string>
44 #include <memory>
45 #include <iosfwd>
46 #include <Eigen/Geometry>
48 
49 #include <tesseract_common/fwd.h>
50 
51 namespace boost::serialization
52 {
53 class access;
54 }
55 
56 namespace tesseract_scene_graph
57 {
58 class Link;
59 
61 {
62 public:
63  using Ptr = std::shared_ptr<JointDynamics>;
64  using ConstPtr = std::shared_ptr<const JointDynamics>;
65 
66  JointDynamics() = default;
67  JointDynamics(double damping, double friction);
68  ~JointDynamics() = default;
69 
70  JointDynamics(const JointDynamics&) = default;
71  JointDynamics& operator=(const JointDynamics&) = default;
72  JointDynamics(JointDynamics&&) = default;
74 
75  double damping{ 0 };
76  double friction{ 0 };
77 
78  void clear();
79 
80  bool operator==(const JointDynamics& rhs) const;
81  bool operator!=(const JointDynamics& rhs) const;
82 
83 private:
86  template <class Archive>
87  void serialize(Archive& ar, const unsigned int version); // NOLINT
88 };
89 
90 std::ostream& operator<<(std::ostream& os, const JointDynamics& dynamics);
91 
93 {
94 public:
95  using Ptr = std::shared_ptr<JointLimits>;
96  using ConstPtr = std::shared_ptr<const JointLimits>;
97 
98  JointLimits() = default;
99  JointLimits(double l, double u, double e, double v, double a, double j);
100  ~JointLimits() = default;
101 
102  JointLimits(const JointLimits&) = default;
103  JointLimits& operator=(const JointLimits&) = default;
104  JointLimits(JointLimits&&) = default;
105  JointLimits& operator=(JointLimits&&) = default;
106 
107  double lower{ 0 };
108  double upper{ 0 };
109  double effort{ 0 };
110  double velocity{ 0 };
111  double acceleration{ 0 };
112  double jerk{ 0 };
113 
114  void clear();
115 
116  bool operator==(const JointLimits& rhs) const;
117  bool operator!=(const JointLimits& rhs) const;
118 
119 private:
122  template <class Archive>
123  void serialize(Archive& ar, const unsigned int version); // NOLINT
124 };
125 
126 std::ostream& operator<<(std::ostream& os, const JointLimits& limits);
127 
130 {
131 public:
132  using Ptr = std::shared_ptr<JointSafety>;
133  using ConstPtr = std::shared_ptr<const JointSafety>;
134 
135  JointSafety() = default;
136  JointSafety(double soft_upper_limit, double soft_lower_limit, double k_position, double k_velocity);
137  ~JointSafety() = default;
138 
139  JointSafety(const JointSafety&) = default;
140  JointSafety& operator=(const JointSafety&) = default;
141  JointSafety(JointSafety&&) = default;
142  JointSafety& operator=(JointSafety&&) = default;
143 
176  double soft_upper_limit{ 0 };
177  double soft_lower_limit{ 0 };
178  double k_position{ 0 };
179  double k_velocity{ 0 };
180 
181  void clear();
182 
183  bool operator==(const JointSafety& rhs) const;
184  bool operator!=(const JointSafety& rhs) const;
185 
186 private:
189  template <class Archive>
190  void serialize(Archive& ar, const unsigned int version); // NOLINT
191 };
192 
193 std::ostream& operator<<(std::ostream& os, const JointSafety& safety);
194 
196 {
197 public:
198  using Ptr = std::shared_ptr<JointCalibration>;
199  using ConstPtr = std::shared_ptr<const JointCalibration>;
200 
201  JointCalibration() = default;
202  JointCalibration(double reference_position, double rising, double falling);
203  ~JointCalibration() = default;
204 
205  JointCalibration(const JointCalibration&) = default;
206  JointCalibration& operator=(const JointCalibration&) = default;
207  JointCalibration(JointCalibration&&) = default;
209 
210  double reference_position{ 0 };
211  double rising{ 0 };
212  double falling{ 0 };
213 
214  void clear();
215 
216  bool operator==(const JointCalibration& rhs) const;
217  bool operator!=(const JointCalibration& rhs) const;
218 
219 private:
222  template <class Archive>
223  void serialize(Archive& ar, const unsigned int version); // NOLINT
224 };
225 
226 std::ostream& operator<<(std::ostream& os, const JointCalibration& calibration);
227 
229 {
230 public:
231  using Ptr = std::shared_ptr<JointMimic>;
232  using ConstPtr = std::shared_ptr<const JointMimic>;
233 
234  JointMimic() = default;
235  JointMimic(double offset, double multiplier, std::string joint_name);
236  ~JointMimic() = default;
237 
238  JointMimic(const JointMimic&) = default;
239  JointMimic& operator=(const JointMimic&) = default;
240  JointMimic(JointMimic&&) = default;
241  JointMimic& operator=(JointMimic&&) = default;
242 
243  double offset{ 0 };
244  double multiplier{ 1.0 };
245  std::string joint_name;
246 
247  void clear();
248 
249  bool operator==(const JointMimic& rhs) const;
250  bool operator!=(const JointMimic& rhs) const;
251 
252 private:
255  template <class Archive>
256  void serialize(Archive& ar, const unsigned int version); // NOLINT
257 };
258 
259 std::ostream& operator<<(std::ostream& os, const JointMimic& mimic);
260 
261 enum class JointType : std::uint8_t
262 {
263  UNKNOWN,
264  REVOLUTE,
265  CONTINUOUS,
266  PRISMATIC,
267  FLOATING,
268  PLANAR,
269  FIXED
270 };
271 
272 class Joint
273 {
274 public:
275  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
276 
277  using Ptr = std::shared_ptr<Joint>;
278  using ConstPtr = std::shared_ptr<const Joint>;
279 
280  Joint(std::string name);
281  Joint() = default;
282  ~Joint() = default;
283  // Joints are non-copyable as their name must be unique
284  Joint(const Joint& other) = delete;
285  Joint& operator=(const Joint& other) = delete;
286 
287  Joint(Joint&& other) = default;
288  Joint& operator=(Joint&& other) = default;
289 
290  const std::string& getName() const;
291 
294 
303  Eigen::Vector3d axis;
304 
307  std::string child_link_name;
308 
311  std::string parent_link_name;
312 
314  Eigen::Isometry3d parent_to_joint_origin_transform{ Eigen::Isometry3d::Identity() };
315 
318 
321 
324 
327 
330 
331  void clear();
332 
337  Joint clone() const;
338 
339  /* Create a clone of current joint, with a new name. Child link name and parent link name are unchanged.
340  * All underlying properties, such as dynamics, limits... are copied as well.*/
341  Joint clone(const std::string& name) const;
342 
343  bool operator==(const Joint& rhs) const;
344  bool operator!=(const Joint& rhs) const;
345 
346 private:
347  std::string name_;
348 
351  template <class Archive>
352  void serialize(Archive& ar, const unsigned int version); // NOLINT
353 };
354 
355 std::ostream& operator<<(std::ostream& os, const JointType& type);
356 
357 } // namespace tesseract_scene_graph
358 
359 BOOST_CLASS_EXPORT_KEY(tesseract_scene_graph::JointDynamics)
360 BOOST_CLASS_EXPORT_KEY(tesseract_scene_graph::JointLimits)
361 BOOST_CLASS_EXPORT_KEY(tesseract_scene_graph::JointSafety)
362 BOOST_CLASS_EXPORT_KEY(tesseract_scene_graph::JointCalibration)
363 BOOST_CLASS_EXPORT_KEY(tesseract_scene_graph::JointMimic)
364 BOOST_CLASS_EXPORT_KEY(tesseract_scene_graph::Joint)
365 
366 #endif // TESSERACT_SCENE_GRAPH_JOINT_H
tesseract_scene_graph::JointType::REVOLUTE
@ REVOLUTE
tesseract_scene_graph::JointMimic::operator=
JointMimic & operator=(const JointMimic &)=default
tesseract_scene_graph::JointType::UNKNOWN
@ UNKNOWN
tesseract_scene_graph::JointCalibration::~JointCalibration
~JointCalibration()=default
tesseract_scene_graph::JointType::FLOATING
@ FLOATING
tesseract_scene_graph::JointMimic::~JointMimic
~JointMimic()=default
tesseract_scene_graph::JointSafety::access
friend class boost::serialization::access
Definition: joint.h:187
tesseract_scene_graph::Joint::mimic
JointMimic::Ptr mimic
Option to Mimic another Joint.
Definition: joint.h:329
tesseract_scene_graph::Joint::clone
Joint clone() const
Clone the joint keeping the name.
Definition: joint.cpp:275
tesseract_scene_graph::JointMimic::access
friend class boost::serialization::access
Definition: joint.h:253
tesseract_scene_graph::JointCalibration::operator=
JointCalibration & operator=(const JointCalibration &)=default
tesseract_scene_graph::JointLimits::ConstPtr
std::shared_ptr< const JointLimits > ConstPtr
Definition: joint.h:96
tesseract_scene_graph::JointSafety::operator=
JointSafety & operator=(const JointSafety &)=default
tesseract_scene_graph::JointCalibration::JointCalibration
JointCalibration()=default
tesseract_scene_graph::JointSafety::k_position
double k_position
Definition: joint.h:178
tesseract_scene_graph::JointLimits::Ptr
std::shared_ptr< JointLimits > Ptr
Definition: joint.h:95
tesseract_scene_graph::JointLimits::serialize
void serialize(Archive &ar, const unsigned int version)
Definition: joint.cpp:107
tesseract_scene_graph::JointCalibration
Definition: joint.h:195
tesseract_scene_graph::Joint::parent_to_joint_origin_transform
Eigen::Isometry3d parent_to_joint_origin_transform
transform from Parent Link frame to Joint frame
Definition: joint.h:314
tesseract_scene_graph::Joint::safety
JointSafety::Ptr safety
Unsupported Hidden Feature.
Definition: joint.h:323
tesseract_scene_graph::JointCalibration::Ptr
std::shared_ptr< JointCalibration > Ptr
Definition: joint.h:198
tesseract_scene_graph::JointLimits::operator==
bool operator==(const JointLimits &rhs) const
Definition: joint.cpp:92
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_scene_graph::JointCalibration::rising
double rising
Definition: joint.h:211
tesseract_scene_graph::JointSafety::JointSafety
JointSafety()=default
tesseract_scene_graph::JointSafety::soft_lower_limit
double soft_lower_limit
Definition: joint.h:177
tesseract_scene_graph::Joint::axis
Eigen::Vector3d axis
Definition: joint.h:303
tesseract_scene_graph::Joint::ConstPtr
std::shared_ptr< const Joint > ConstPtr
Definition: joint.h:278
tesseract_common::Serialization
tesseract_scene_graph::JointDynamics::operator=
JointDynamics & operator=(const JointDynamics &)=default
tesseract_scene_graph::Joint::access
friend class boost::serialization::access
Definition: joint.h:349
tesseract_scene_graph::JointSafety::operator!=
bool operator!=(const JointSafety &rhs) const
Definition: joint.cpp:155
tesseract_scene_graph::JointSafety::clear
void clear()
Definition: joint.cpp:137
tesseract_scene_graph::JointSafety::serialize
void serialize(Archive &ar, const unsigned int version)
Definition: joint.cpp:158
tesseract_scene_graph::JointDynamics::clear
void clear()
Definition: joint.cpp:44
tesseract_scene_graph::JointDynamics::Ptr
std::shared_ptr< JointDynamics > Ptr
Definition: joint.h:63
tesseract_scene_graph::Joint::name_
std::string name_
Definition: joint.h:347
tesseract_scene_graph::JointDynamics::JointDynamics
JointDynamics()=default
tesseract_scene_graph::JointType::PLANAR
@ PLANAR
tesseract_scene_graph::Joint::operator=
Joint & operator=(const Joint &other)=delete
tesseract_scene_graph::JointLimits::upper
double upper
Definition: joint.h:108
tesseract_scene_graph::JointCalibration::serialize
void serialize(Archive &ar, const unsigned int version)
Definition: joint.cpp:200
tesseract_scene_graph::JointDynamics::ConstPtr
std::shared_ptr< const JointDynamics > ConstPtr
Definition: joint.h:64
tesseract_scene_graph::JointMimic::Ptr
std::shared_ptr< JointMimic > Ptr
Definition: joint.h:231
tesseract_scene_graph::JointMimic::ConstPtr
std::shared_ptr< const JointMimic > ConstPtr
Definition: joint.h:232
tesseract_scene_graph::JointLimits::jerk
double jerk
Definition: joint.h:112
tesseract_scene_graph::Joint::child_link_name
std::string child_link_name
Definition: joint.h:307
tesseract_scene_graph::Joint::limits
JointLimits::Ptr limits
Joint Limits.
Definition: joint.h:320
tesseract_scene_graph::Joint::clear
void clear()
Definition: joint.cpp:261
tesseract_scene_graph::JointMimic::JointMimic
JointMimic()=default
tesseract_scene_graph::Joint::serialize
void serialize(Archive &ar, const unsigned int version)
Definition: joint.cpp:327
tesseract_scene_graph::JointType::PRISMATIC
@ PRISMATIC
tesseract_scene_graph::JointCalibration::access
friend class boost::serialization::access
Definition: joint.h:220
tesseract_scene_graph::JointLimits::operator!=
bool operator!=(const JointLimits &rhs) const
Definition: joint.cpp:104
tesseract_scene_graph::JointMimic
Definition: joint.h:228
boost::serialization
tesseract_scene_graph::JointSafety::ConstPtr
std::shared_ptr< const JointSafety > ConstPtr
Definition: joint.h:133
tesseract_scene_graph::JointLimits::acceleration
double acceleration
Definition: joint.h:111
tesseract_scene_graph::JointSafety::Ptr
std::shared_ptr< JointSafety > Ptr
Definition: joint.h:132
tesseract_scene_graph::JointLimits::operator=
JointLimits & operator=(const JointLimits &)=default
tesseract_scene_graph::JointMimic::serialize
void serialize(Archive &ar, const unsigned int version)
Definition: joint.cpp:241
tesseract_scene_graph::JointDynamics::~JointDynamics
~JointDynamics()=default
tesseract_scene_graph::JointLimits
Definition: joint.h:92
tesseract_scene_graph::JointLimits::JointLimits
JointLimits()=default
fwd.h
tesseract_scene_graph::JointCalibration::operator==
bool operator==(const JointCalibration &rhs) const
Definition: joint.cpp:188
tesseract_scene_graph::JointType::CONTINUOUS
@ CONTINUOUS
tesseract_scene_graph::Joint
Definition: joint.h:272
tesseract_scene_graph::JointCalibration::falling
double falling
Definition: joint.h:212
tesseract_scene_graph::JointCalibration::reference_position
double reference_position
Definition: joint.h:210
tesseract_scene_graph::JointLimits::access
friend class boost::serialization::access
Definition: joint.h:120
tesseract_scene_graph::JointMimic::operator!=
bool operator!=(const JointMimic &rhs) const
Definition: joint.cpp:238
tesseract_scene_graph::JointCalibration::clear
void clear()
Definition: joint.cpp:181
tesseract_scene_graph::JointSafety
Parameters for Joint Safety Controllers.
Definition: joint.h:129
TESSERACT_COMMON_IGNORE_WARNINGS_POP
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
tesseract_scene_graph::JointSafety::~JointSafety
~JointSafety()=default
tesseract_scene_graph::JointSafety::operator==
bool operator==(const JointSafety &rhs) const
Definition: joint.cpp:145
tesseract_scene_graph::Joint::dynamics
JointDynamics::Ptr dynamics
Joint Dynamics.
Definition: joint.h:317
tesseract_scene_graph::JointDynamics::serialize
void serialize(Archive &ar, const unsigned int version)
Definition: joint.cpp:61
tesseract_scene_graph::operator<<
std::ostream & operator<<(std::ostream &os, const ShortestPath &path)
Definition: graph.cpp:1345
tesseract_scene_graph::Joint::operator==
bool operator==(const Joint &rhs) const
Definition: joint.cpp:308
tesseract_scene_graph::JointDynamics::operator==
bool operator==(const JointDynamics &rhs) const
Definition: joint.cpp:50
tesseract_scene_graph::JointLimits::effort
double effort
Definition: joint.h:109
tesseract_scene_graph::JointMimic::joint_name
std::string joint_name
Definition: joint.h:245
tesseract_scene_graph::JointType
JointType
Definition: joint.h:261
tesseract_scene_graph::JointLimits::~JointLimits
~JointLimits()=default
tesseract_scene_graph::JointDynamics
Definition: joint.h:60
tesseract_scene_graph::Joint::Ptr
std::shared_ptr< Joint > Ptr
Definition: joint.h:277
tesseract_scene_graph::JointCalibration::operator!=
bool operator!=(const JointCalibration &rhs) const
Definition: joint.cpp:197
tesseract_scene_graph::Joint::calibration
JointCalibration::Ptr calibration
Unsupported Hidden Feature.
Definition: joint.h:326
tesseract_scene_graph::JointDynamics::operator!=
bool operator!=(const JointDynamics &rhs) const
Definition: joint.cpp:58
tesseract_scene_graph::Joint::type
JointType type
The type of joint.
Definition: joint.h:293
tesseract_scene_graph::Joint::getName
const std::string & getName() const
Definition: joint.cpp:259
tesseract_scene_graph::JointLimits::velocity
double velocity
Definition: joint.h:110
tesseract_scene_graph::JointSafety::soft_upper_limit
double soft_upper_limit
Definition: joint.h:176
tesseract_scene_graph::Joint::operator!=
bool operator!=(const Joint &rhs) const
Definition: joint.cpp:324
tesseract_scene_graph::JointDynamics::damping
double damping
Definition: joint.h:75
tesseract_scene_graph::Joint::Joint
Joint()=default
macros.h
tesseract_scene_graph::JointSafety::k_velocity
double k_velocity
Definition: joint.h:179
tesseract_scene_graph::JointLimits::lower
double lower
Definition: joint.h:107
tesseract_scene_graph::JointMimic::offset
double offset
Definition: joint.h:243
tesseract_scene_graph::Joint::~Joint
~Joint()=default
tesseract_scene_graph
Definition: fwd.h:32
tesseract_scene_graph::JointMimic::operator==
bool operator==(const JointMimic &rhs) const
Definition: joint.cpp:229
tesseract_scene_graph::JointDynamics::access
friend class boost::serialization::access
Definition: joint.h:84
tesseract_scene_graph::Joint::parent_link_name
std::string parent_link_name
Definition: joint.h:311
tesseract_scene_graph::JointCalibration::ConstPtr
std::shared_ptr< const JointCalibration > ConstPtr
Definition: joint.h:199
tesseract_scene_graph::JointType::FIXED
@ FIXED
tesseract_scene_graph::JointLimits::clear
void clear()
Definition: joint.cpp:82
tesseract_scene_graph::JointMimic::multiplier
double multiplier
Definition: joint.h:244
tesseract_scene_graph::JointMimic::clear
void clear()
Definition: joint.cpp:222
tesseract_scene_graph::JointDynamics::friction
double friction
Definition: joint.h:76


tesseract_scene_graph
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:49