DART  6.7.3
FixedFrame.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011-2019, 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_FIXEDFRAME_HPP_
34 #define DART_DYNAMICS_FIXEDFRAME_HPP_
35 
36 #include "dart/dynamics/Frame.hpp"
40 
41 namespace dart {
42 namespace dynamics {
43 
48 class FixedFrame :
49  public virtual Frame,
50  public virtual common::VersionCounter,
51  public common::EmbedProperties<FixedFrame, detail::FixedFrameProperties>
52 {
53 public:
55  explicit FixedFrame(Frame* refFrame,
56  const Eigen::Isometry3d& relativeTransform =
57  Eigen::Isometry3d::Identity());
58 
60  virtual ~FixedFrame();
61 
64 
66  virtual void setRelativeTransform(const Eigen::Isometry3d& transform);
67 
68  // Documentation inherited
69  const Eigen::Isometry3d& getRelativeTransform() const override;
70 
72  const Eigen::Vector6d& getRelativeSpatialVelocity() const override;
73 
75  const Eigen::Vector6d& getRelativeSpatialAcceleration() const override;
76 
78  const Eigen::Vector6d& getPrimaryRelativeAcceleration() const override;
79 
81  const Eigen::Vector6d& getPartialAcceleration() const override;
82 
83 protected:
84 
86  FixedFrame();
87 
90 
92  static const Eigen::Vector6d mZero;
93 
94 public:
95  // To get byte-aligned Eigen vectors
96  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
97 };
98 
99 } // namespace dynamics
100 } // namespace dart
101 
102 
103 #endif // DART_DYNAMICS_FIXEDFRAME_HPP_
BodyPropPtr properties
Definition: SdfParser.cpp:80
Inherit this class to embed Properties into your Composite object.
Definition: EmbeddedAspect.hpp:210
typename Aspect::Properties AspectProperties
Definition: EmbeddedAspect.hpp:215
VersionCounter is an interface for objects that count their versions.
Definition: VersionCounter.hpp:43
ConstructAbstractTag
Used when constructing a pure abstract class, because calling the Entity constructor is just a formal...
Definition: Entity.hpp:163
The FixedFrame class represents a Frame with zero relative velocity and zero relative acceleration.
Definition: FixedFrame.hpp:52
virtual ~FixedFrame()
Destructor.
Definition: FixedFrame.cpp:62
const Eigen::Vector6d & getPrimaryRelativeAcceleration() const override
Always returns a zero vector.
Definition: FixedFrame.cpp:103
void setAspectProperties(const AspectProperties &properties)
Set the AspectProperties of this FixedFrame.
Definition: FixedFrame.cpp:68
static const Eigen::Vector6d mZero
Used for Relative Velocity and Relative Acceleration of this Frame.
Definition: FixedFrame.hpp:92
FixedFrame()
Default constructor – calls the Abstract constructor.
Definition: FixedFrame.cpp:115
const Eigen::Vector6d & getRelativeSpatialAcceleration() const override
Always returns a zero vector.
Definition: FixedFrame.cpp:97
virtual void setRelativeTransform(const Eigen::Isometry3d &transform)
Set the relative transform of this FixedFrame.
Definition: FixedFrame.cpp:74
const Eigen::Vector6d & getPartialAcceleration() const override
Always returns a zero vector.
Definition: FixedFrame.cpp:109
const Eigen::Vector6d & getRelativeSpatialVelocity() const override
Always returns a zero vector.
Definition: FixedFrame.cpp:91
const Eigen::Isometry3d & getRelativeTransform() const override
Get the transform of this Frame with respect to its parent Frame.
Definition: FixedFrame.cpp:85
The Frame class serves as the backbone of DART's kinematic tree structure.
Definition: Frame.hpp:57
Matrix< double, 6, 1 > Vector6d
Definition: MathTypes.hpp:49
dart::collision::fcl::Vector3 transform(const dart::collision::fcl::Transform3 &t, const dart::collision::fcl::Vector3 &v)
Transforms a 3-dim vector by a transform and returns the result.
Definition: BackwardCompatibility.cpp:131
Definition: BulletCollisionDetector.cpp:63