DART 6.10.1
Loading...
Searching...
No Matches
FreeJoint.hpp
Go to the documentation of this file.
1/*
2 * Copyright (c) 2011-2021, The DART development contributors
3 * All rights reserved.
4 *
5 * The list of contributors can be found at:
6 * https://github.com/dartsim/dart/blob/master/LICENSE
7 *
8 * This file is provided under the following "BSD-style" License:
9 * Redistribution and use in source and binary forms, with or
10 * without modification, are permitted provided that the following
11 * conditions are met:
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
19 * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20 * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21 * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23 * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
24 * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
25 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
26 * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30 * POSSIBILITY OF SUCH DAMAGE.
31 */
32
33#ifndef DART_DYNAMICS_FREEJOINT_HPP_
34#define DART_DYNAMICS_FREEJOINT_HPP_
35
36#include <string>
37
38#include <Eigen/Dense>
39
42
43namespace dart {
44namespace dynamics {
45
47class FreeJoint : public GenericJoint<math::SE3Space>
48{
49public:
50 friend class Skeleton;
51
53
62
63 FreeJoint(const FreeJoint&) = delete;
64
66 virtual ~FreeJoint();
67
70
71 // Documentation inherited
72 const std::string& getType() const override;
73
75 static const std::string& getStaticType();
76
77 // Documentation inherited
78 bool isCyclic(std::size_t _index) const override;
79
86 static Eigen::Vector6d convertToPositions(const Eigen::Isometry3d& _tf);
87
89 static Eigen::Isometry3d convertToTransform(
91
99 Joint* joint,
101 const Frame* withRespectTo = Frame::World());
102
107 Joint* joint,
109 const Frame* withRespectTo = Frame::World());
110
116 DART_DEPRECATED(6.9)
117 static void setTransform(
120 const Frame* withRespectTo = Frame::World());
121
128 const Frame* withRespectTo = Frame::World());
129
136 DART_DEPRECATED(6.9)
137 static void setTransform(
140 const Frame* withRespectTo = Frame::World(),
142
150 const Frame* withRespectTo = Frame::World(),
152
179 void setSpatialMotion(
182 const Eigen::Vector6d* newSpatialVelocity,
188
192
196 void setTransform(
198 const Frame* withRespectTo = Frame::World());
199
206
214
222 const Eigen::Vector6d& newSpatialVelocity,
225
237 const Frame* relativeTo = Frame::World(),
238 const Frame* inCoordinatesOf = Frame::World());
239
251 const Frame* relativeTo = Frame::World(),
252 const Frame* inCoordinatesOf = Frame::World());
253
261
271
283
295 const Frame* relativeTo = Frame::World(),
296 const Frame* inCoordinatesOf = Frame::World());
297
310 const Frame* relativeTo = Frame::World(),
311 const Frame* inCoordinatesOf = Frame::World());
312
313 // Documentation inherited
315 const Eigen::Vector6d& _positions) const override;
316
317 // Documentation inherited
319 const Eigen::Vector6d& _q2, const Eigen::Vector6d& _q1) const override;
320
324
325 // Documentation inherited
327
329
330 // Documentation inherited
331 void integratePositions(double _dt) override;
332
333 // Documentation inherited
335
336 // Documentation inherited
338
339 // Documentation inherited
341
342 // Documentation inherited
344
348
353
354public:
355 // To get byte-aligned Eigen vectors
357};
358
359} // namespace dynamics
360} // namespace dart
361
362#endif // DART_DYNAMICS_FREEJOINT_HPP_
#define DART_DEPRECATED(version)
Definition Deprecated.hpp:51
#define DART_DEFINE_ALIGNED_SHARED_OBJECT_CREATOR(class_name)
Definition Memory.hpp:155
BodyPropPtr properties
Definition SdfParser.cpp:80
BodyNode class represents a single node of the skeleton.
Definition BodyNode.hpp:79
The Frame class serves as the backbone of DART's kinematic tree structure.
Definition Frame.hpp:58
class FreeJoint
Definition FreeJoint.hpp:48
void setRelativeTransform(const Eigen::Isometry3d &newTransform)
Set the transform of the child BodyNode relative to the parent BodyNode.
Definition FreeJoint.cpp:186
Eigen::Vector6d getPositionDifferencesStatic(const Eigen::Vector6d &_q2, const Eigen::Vector6d &_q1) const override
Definition FreeJoint.cpp:542
FreeJoint(const FreeJoint &)=delete
void setLinearAcceleration(const Eigen::Vector3d &newLinearAcceleration, const Frame *relativeTo=Frame::World(), const Frame *inCoordinatesOf=Frame::World())
Set the linear portion of classical acceleration of the child BodyNode relative to an arbitrary Frame...
Definition FreeJoint.cpp:455
Properties getFreeJointProperties() const
Get the Properties of this FreeJoint.
Definition FreeJoint.cpp:58
void updateDegreeOfFreedomNames() override
Definition FreeJoint.cpp:599
static const std::string & getStaticType()
Get joint type for this class.
Definition FreeJoint.cpp:576
static void setTransformOf(Joint *joint, const Eigen::Isometry3d &tf, const Frame *withRespectTo=Frame::World())
If the given joint is a FreeJoint, then set the transform of the given Joint's child BodyNode so that...
Definition FreeJoint.cpp:90
void updateRelativeJacobian(bool _mandatory=true) const override
Definition FreeJoint.cpp:627
void updateRelativeTransform() const override
Definition FreeJoint.cpp:616
void setRelativeSpatialVelocity(const Eigen::Vector6d &newSpatialVelocity)
Set the spatial velocity of the child BodyNode relative to the parent BodyNode.
Definition FreeJoint.cpp:205
void setLinearVelocity(const Eigen::Vector3d &newLinearVelocity, const Frame *relativeTo=Frame::World(), const Frame *inCoordinatesOf=Frame::World())
Set the linear portion of classical velocity of the child BodyNode relative to an arbitrary Frame.
Definition FreeJoint.cpp:283
void setRelativeSpatialAcceleration(const Eigen::Vector6d &newSpatialAcceleration)
Set the spatial acceleration of the child BodyNode relative to the parent BodyNode.
Definition FreeJoint.cpp:357
void setSpatialMotion(const Eigen::Isometry3d *newTransform, const Frame *withRespectTo, const Eigen::Vector6d *newSpatialVelocity, const Frame *velRelativeTo, const Frame *velInCoordinatesOf, const Eigen::Vector6d *newSpatialAcceleration, const Frame *accRelativeTo, const Frame *accInCoordinatesOf)
Set the transform, spatial velocity, and spatial acceleration of the child BodyNode relative to an ar...
Definition FreeJoint.cpp:162
void setAngularAcceleration(const Eigen::Vector3d &newAngularAcceleration, const Frame *relativeTo=Frame::World(), const Frame *inCoordinatesOf=Frame::World())
Set the angular portion of classical acceleration of the child BodyNode relative to an arbitrary Fram...
Definition FreeJoint.cpp:496
void updateRelativeJacobianTimeDeriv() const override
Definition FreeJoint.cpp:635
void setSpatialAcceleration(const Eigen::Vector6d &newSpatialAcceleration, const Frame *relativeTo, const Frame *inCoordinatesOf)
Set the spatial acceleration of the child BodyNode relative to an arbitrary Frame.
Definition FreeJoint.cpp:386
void integratePositions(double _dt) override
Definition FreeJoint.cpp:590
Joint * clone() const override
Definition FreeJoint.cpp:564
const std::string & getType() const override
Definition FreeJoint.cpp:570
static void setTransform(Joint *joint, const Eigen::Isometry3d &tf, const Frame *withRespectTo=Frame::World())
If the given joint is a FreeJoint, then set the transform of the given Joint's child BodyNode so that...
Definition FreeJoint.cpp:83
void setAngularVelocity(const Eigen::Vector3d &newAngularVelocity, const Frame *relativeTo=Frame::World(), const Frame *inCoordinatesOf=Frame::World())
Set the angular portion of classical velocity of the child BodyNode relative to an arbitrary Frame.
Definition FreeJoint.cpp:320
static Eigen::Isometry3d convertToTransform(const Eigen::Vector6d &_positions)
Convert a FreeJoint-style 6D vector into a transform.
Definition FreeJoint.cpp:73
static Eigen::Vector6d convertToPositions(const Eigen::Isometry3d &_tf)
Convert a transform into a 6D vector that can be used to set the positions of a FreeJoint.
Definition FreeJoint.cpp:64
const Eigen::Isometry3d & getQ() const
Access mQ, which is an auto-updating variable.
Definition FreeJoint.cpp:641
Eigen::Isometry3d mQ
Transformation matrix dependent on generalized coordinates.
Definition FreeJoint.hpp:352
virtual ~FreeJoint()
Destructor.
Definition FreeJoint.cpp:52
void setSpatialVelocity(const Eigen::Vector6d &newSpatialVelocity, const Frame *relativeTo, const Frame *inCoordinatesOf)
Set the spatial velocity of the child BodyNode relative to an arbitrary Frame.
Definition FreeJoint.cpp:230
bool isCyclic(std::size_t _index) const override
Definition FreeJoint.cpp:583
Definition GenericJoint.hpp:48
typename ConfigSpaceT::Matrix Matrix
Definition GenericJoint.hpp:59
const GenericJoint< math::SE3Space >::JacobianMatrix & getRelativeJacobianStatic() const
Fixed-size version of getRelativeJacobian()
Definition GenericJoint.hpp:1570
detail::GenericJointProperties< math::SE3Space > Properties
Definition GenericJoint.hpp:62
class Joint
Definition Joint.hpp:60
class Skeleton
Definition Skeleton.hpp:59
Definition Random-impl.hpp:92
Matrix< double, 6, 1 > Vector6d
Definition MathTypes.hpp:49
Definition BulletCollisionDetector.cpp:65
Definition FreeJoint.hpp:55