continuous_collision_object-inl.h
Go to the documentation of this file.
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_CONTINUOUS_COLLISION_OBJECT_INL_H
39 #define FCL_CONTINUOUS_COLLISION_OBJECT_INL_H
40 
42 
43 namespace fcl
44 {
45 
46 //==============================================================================
47 extern template
48 class FCL_EXPORT ContinuousCollisionObject<double>;
49 
50 //==============================================================================
51 template <typename S>
53  const std::shared_ptr<CollisionGeometry<S>>& cgeom_)
54  : cgeom(cgeom_), cgeom_const(cgeom_)
55 {
56  // Do nothing
57 }
58 
59 //==============================================================================
60 template <typename S>
62  const std::shared_ptr<CollisionGeometry<S>>& cgeom_,
63  const std::shared_ptr<MotionBase<S>>& motion_)
64  : cgeom(cgeom_), cgeom_const(cgeom), motion(motion_)
65 {
66  // Do nothing
67 }
68 
69 //==============================================================================
70 template <typename S>
72 {
73  // Do nothing
74 }
75 
76 //==============================================================================
77 template <typename S>
79 {
80  return cgeom->getObjectType();
81 }
82 
83 //==============================================================================
84 template <typename S>
86 {
87  return cgeom->getNodeType();
88 }
89 
90 //==============================================================================
91 template <typename S>
93 {
94  return aabb;
95 }
96 
97 //==============================================================================
98 template <typename S>
100 {
101  IVector3<S> box;
102  TMatrix3<S> R;
103  TVector3<S> T;
104  motion->getTaylorModel(R, T);
105 
106  Vector3<S> p = cgeom->aabb_local.min_;
107  box = (R * p + T).getTightBound();
108 
109  p[2] = cgeom->aabb_local.max_[2];
110  box = bound(box, (R * p + T).getTightBound());
111 
112  p[1] = cgeom->aabb_local.max_[1];
113  p[2] = cgeom->aabb_local.min_[2];
114  box = bound(box, (R * p + T).getTightBound());
115 
116  p[2] = cgeom->aabb_local.max_[2];
117  box = bound(box, (R * p + T).getTightBound());
118 
119  p[0] = cgeom->aabb_local.max_[0];
120  p[1] = cgeom->aabb_local.min_[1];
121  p[2] = cgeom->aabb_local.min_[2];
122  box = bound(box, (R * p + T).getTightBound());
123 
124  p[2] = cgeom->aabb_local.max_[2];
125  box = bound(box, (R * p + T).getTightBound());
126 
127  p[1] = cgeom->aabb_local.max_[1];
128  p[2] = cgeom->aabb_local.min_[2];
129  box = bound(box, (R * p + T).getTightBound());
130 
131  p[2] = cgeom->aabb_local.max_[2];
132  box = bound(box, (R * p + T).getTightBound());
133 
134  aabb.min_ = box.getLow();
135  aabb.max_ = box.getHigh();
136 }
137 
138 //==============================================================================
139 template <typename S>
141 {
142  return user_data;
143 }
144 
145 //==============================================================================
146 template <typename S>
148 {
149  user_data = data;
150 }
151 
152 //==============================================================================
153 template <typename S>
155 {
156  return motion.get();
157 }
158 
159 //==============================================================================
160 template <typename S>
163 {
164  return cgeom.get();
165 }
166 
167 //==============================================================================
168 template <typename S>
169 const std::shared_ptr<const CollisionGeometry<S>>&
171 {
172  return cgeom_const;
173 }
174 
175 } // namespace fcl
176 
177 #endif
fcl::ContinuousCollisionObject::setUserData
void setUserData(void *data)
set user data in object
Definition: continuous_collision_object-inl.h:147
fcl::ContinuousCollisionObject::getUserData
void * getUserData() const
get user data in object
Definition: continuous_collision_object-inl.h:140
fcl::ContinuousCollisionObject::computeAABB
void computeAABB()
compute the AABB in the world space for the motion
Definition: continuous_collision_object-inl.h:99
fcl::ContinuousCollisionObject::getCollisionGeometry
const FCL_DEPRECATED CollisionGeometry< S > * getCollisionGeometry() const
get geometry from the object instance
Definition: continuous_collision_object-inl.h:162
fcl::AABB< S >
fcl::IVector3::getLow
Vector3< S > getLow() const
Definition: interval_vector-inl.h:266
fcl::Vector3
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
fcl::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: collision_geometry.h:58
fcl::ContinuousCollisionObject::ContinuousCollisionObject
ContinuousCollisionObject(const std::shared_ptr< CollisionGeometry< S >> &cgeom)
Definition: continuous_collision_object-inl.h:52
fcl::ContinuousCollisionObject< double >
template class FCL_EXPORT ContinuousCollisionObject< double >
fcl::MotionBase
Definition: bv_motion_bound_visitor.h:45
continuous_collision_object.h
fcl::ContinuousCollisionObject::collisionGeometry
const std::shared_ptr< const CollisionGeometry< S > > & collisionGeometry() const
get geometry from the object instance
Definition: continuous_collision_object-inl.h:170
fcl::ContinuousCollisionObject::getMotion
MotionBase< S > * getMotion() const
get motion from the object instance
Definition: continuous_collision_object-inl.h:154
fcl::bound
template Interval< double > bound(const Interval< double > &i, double v)
fcl::OBJECT_TYPE
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Definition: collision_geometry.h:50
fcl::IVector3::getHigh
Vector3< S > getHigh() const
Definition: interval_vector-inl.h:273
fcl::TMatrix3
Definition: taylor_matrix.h:48
fcl::TVector3
Definition: taylor_vector.h:48
fcl::ContinuousCollisionObject::getNodeType
NODE_TYPE getNodeType() const
get the node type
Definition: continuous_collision_object-inl.h:85
fcl::ContinuousCollisionObject::getAABB
const AABB< S > & getAABB() const
get the AABB in the world space for the motion
Definition: continuous_collision_object-inl.h:92
aabb
SaPCollisionManager< S >::SaPAABB * aabb
back pointer to SAP interval
Definition: broadphase_SaP.h:184
fcl::ContinuousCollisionObject::~ContinuousCollisionObject
~ContinuousCollisionObject()
Definition: continuous_collision_object-inl.h:71
fcl::NODE_TYPE
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: collision_geometry.h:53
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
fcl::ContinuousCollisionObject::getObjectType
OBJECT_TYPE getObjectType() const
get the type of the object
Definition: continuous_collision_object-inl.h:78
fcl::IVector3
Definition: interval_vector.h:47


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:48