FCL  0.6.0
Flexible Collision Library
interp_motion.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2016, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
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  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
38 #ifndef FCL_CCD_INTERPMOTION_H
39 #define FCL_CCD_INTERPMOTION_H
40 
41 #include <iostream>
42 #include <vector>
43 #include "fcl/math/geometry.h"
44 #include "fcl/math/motion/motion_base.h"
45 #include "fcl/math/motion/bv_motion_bound_visitor.h"
46 #include "fcl/math/motion/triangle_motion_bound_visitor.h"
47 
48 namespace fcl
49 {
50 
57 template <typename S>
58 class InterpMotion : public MotionBase<S>
59 {
60 public:
62  InterpMotion();
63 
65  InterpMotion(const Matrix3<S>& R1, const Vector3<S>& T1,
66  const Matrix3<S>& R2, const Vector3<S>& T2);
67 
68  InterpMotion(const Transform3<S>& tf1_, const Transform3<S>& tf2_);
69 
71  InterpMotion(const Matrix3<S>& R1, const Vector3<S>& T1,
72  const Matrix3<S>& R2, const Vector3<S>& T2,
73  const Vector3<S>& O);
74 
75  InterpMotion(const Transform3<S>& tf1_, const Transform3<S>& tf2_, const Vector3<S>& O);
76 
79  bool integrate(double dt) const;
80 
82  S computeMotionBound(const BVMotionBoundVisitor<S>& mb_visitor) const;
83 
85  S computeMotionBound(const TriangleMotionBoundVisitor<S>& mb_visitor) const;
86 
88  void getCurrentTransform(Transform3<S>& tf_) const;
89 
90  void getTaylorModel(TMatrix3<S>& tm, TVector3<S>& tv) const;
91 
92 protected:
93 
94  void computeVelocity();
95 
96  Quaternion<S> deltaRotation(S dt) const;
97 
98  Quaternion<S> absoluteRotation(S dt) const;
99 
101  Transform3<S> tf1;
102 
104  Transform3<S> tf2;
105 
107  mutable Transform3<S> tf;
108 
110  Vector3<S> linear_vel;
111 
114 
116  Vector3<S> angular_axis;
117 
119  Vector3<S> reference_p;
120 
121 public:
122  const Vector3<S>& getReferencePoint() const;
123 
124  const Vector3<S>& getAngularAxis() const;
125 
126  S getAngularVelocity() const;
127 
128  const Vector3<S>& getLinearVelocity() const;
129 
130  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
131 };
132 
133 } // namespace fcl
134 
135 #include "fcl/math/motion/interp_motion-inl.h"
136 
137 #endif
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
void getCurrentTransform(Transform3< S > &tf_) const
Get the rotation and translation in current step.
Definition: interp_motion-inl.h:156
InterpMotion()
Default transformations are all identities.
Definition: interp_motion-inl.h:52
Transform3< S > tf
The transformation at current time t.
Definition: interp_motion.h:107
Transform3< S > tf1
The transformation at time 0.
Definition: interp_motion.h:101
Vector3< S > linear_vel
Linear velocity.
Definition: interp_motion.h:110
S computeMotionBound(const BVMotionBoundVisitor< S > &mb_visitor) const
Compute the motion bound for a bounding volume along a given direction n, which is defined in the vis...
Definition: interp_motion-inl.h:142
S angular_vel
Angular speed.
Definition: interp_motion.h:113
bool integrate(double dt) const
Integrate the motion from 0 to dt We compute the current transformation from zero point instead of fr...
Definition: interp_motion-inl.h:130
Vector3< S > angular_axis
Angular velocity axis.
Definition: interp_motion.h:116
Vector3< S > reference_p
Reference point for the motion (in the object&#39;s local frame)
Definition: interp_motion.h:119
Transform3< S > tf2
The transformation at time 1.
Definition: interp_motion.h:104