broadphase_collision_manager-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_BROADPHASE_BROADPHASECOLLISIONMANAGER_INL_H
39 #define FCL_BROADPHASE_BROADPHASECOLLISIONMANAGER_INL_H
40 
42 
43 #include "fcl/common/unused.h"
44 
45 namespace fcl {
46 
47 //==============================================================================
48 extern template
49 class FCL_EXPORT BroadPhaseCollisionManager<double>;
50 
51 //==============================================================================
52 template <typename S>
54  : enable_tested_set_(false)
55 {
56  // Do nothing
57 }
58 
59 //==============================================================================
60 template <typename S>
62 {
63  // Do nothing
64 }
65 
66 //==============================================================================
67 template <typename S>
69  const std::vector<CollisionObject<S>*>& other_objs)
70 {
71  for(size_t i = 0; i < other_objs.size(); ++i)
72  registerObject(other_objs[i]);
73 }
74 
75 //==============================================================================
76 template <typename S>
78 {
79  FCL_UNUSED(updated_obj);
80 
81  update();
82 }
83 
84 //==============================================================================
85 template <typename S>
87  const std::vector<CollisionObject<S>*>& updated_objs)
88 {
89  FCL_UNUSED(updated_objs);
90 
91  update();
92 }
93 
94 //==============================================================================
95 template <typename S>
98 {
99  if(a < b) return tested_set.find(std::make_pair(a, b)) != tested_set.end();
100  else return tested_set.find(std::make_pair(b, a)) != tested_set.end();
101 }
102 
103 //==============================================================================
104 template <typename S>
107 {
108  if(a < b) tested_set.insert(std::make_pair(a, b));
109  else tested_set.insert(std::make_pair(b, a));
110 }
111 
112 } // namespace fcl
113 
114 #endif
fcl::BroadPhaseCollisionManager::~BroadPhaseCollisionManager
virtual ~BroadPhaseCollisionManager()
Definition: broadphase_collision_manager-inl.h:61
fcl::BroadPhaseCollisionManager::registerObjects
virtual void registerObjects(const std::vector< CollisionObject< S > * > &other_objs)
add objects to the manager
Definition: broadphase_collision_manager-inl.h:68
broadphase_collision_manager.h
fcl::BroadPhaseCollisionManager::inTestedSet
bool inTestedSet(CollisionObject< S > *a, CollisionObject< S > *b) const
Definition: broadphase_collision_manager-inl.h:96
unused.h
fcl::BroadPhaseCollisionManager::insertTestedSet
void insertTestedSet(CollisionObject< S > *a, CollisionObject< S > *b) const
Definition: broadphase_collision_manager-inl.h:105
FCL_UNUSED
#define FCL_UNUSED(x)
Definition: unused.h:39
fcl::BroadPhaseCollisionManager< double >
template class FCL_EXPORT BroadPhaseCollisionManager< double >
fcl::BroadPhaseCollisionManager::update
virtual void update()=0
update the condition of manager
fcl::BroadPhaseCollisionManager::BroadPhaseCollisionManager
BroadPhaseCollisionManager()
Definition: broadphase_collision_manager-inl.h:53
fcl::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: collision_object.h:51
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45


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