00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00038 #ifndef FCL_COLLISION_DATA_H
00039 #define FCL_COLLISION_DATA_H
00040
00041 #include "fcl/collision_object.h"
00042 #include "fcl/math/vec_3f.h"
00043 #include <vector>
00044 #include <set>
00045 #include <limits>
00046
00047
00048 namespace fcl
00049 {
00050
00052 struct Contact
00053 {
00055 const CollisionGeometry* o1;
00056
00058 const CollisionGeometry* o2;
00059
00064 int b1;
00065
00066
00071 int b2;
00072
00074 Vec3f normal;
00075
00077 Vec3f pos;
00078
00080 FCL_REAL penetration_depth;
00081
00082
00084 static const int NONE = -1;
00085
00086 Contact() : o1(NULL),
00087 o2(NULL),
00088 b1(NONE),
00089 b2(NONE)
00090 {}
00091
00092 Contact(const CollisionGeometry* o1_, const CollisionGeometry* o2_, int b1_, int b2_) : o1(o1_),
00093 o2(o2_),
00094 b1(b1_),
00095 b2(b2_)
00096 {}
00097
00098 Contact(const CollisionGeometry* o1_, const CollisionGeometry* o2_, int b1_, int b2_,
00099 const Vec3f& pos_, const Vec3f& normal_, FCL_REAL depth_) : o1(o1_),
00100 o2(o2_),
00101 b1(b1_),
00102 b2(b2_),
00103 normal(normal_),
00104 pos(pos_),
00105 penetration_depth(depth_)
00106 {}
00107
00108 bool operator < (const Contact& other) const
00109 {
00110 if(b1 == other.b1)
00111 return b2 < other.b2;
00112 return b1 < other.b1;
00113 }
00114 };
00115
00117 struct CostSource
00118 {
00120 Vec3f aabb_min;
00121
00123 Vec3f aabb_max;
00124
00126 FCL_REAL cost_density;
00127
00128 FCL_REAL total_cost;
00129
00130 CostSource(const Vec3f& aabb_min_, const Vec3f& aabb_max_, FCL_REAL cost_density_) : aabb_min(aabb_min_),
00131 aabb_max(aabb_max_),
00132 cost_density(cost_density_)
00133 {
00134 total_cost = cost_density * (aabb_max[0] - aabb_min[0]) * (aabb_max[1] - aabb_min[1]) * (aabb_max[2] - aabb_min[2]);
00135 }
00136
00137 CostSource(const AABB& aabb, FCL_REAL cost_density_) : aabb_min(aabb.min_),
00138 aabb_max(aabb.max_),
00139 cost_density(cost_density_)
00140 {
00141 total_cost = cost_density * (aabb_max[0] - aabb_min[0]) * (aabb_max[1] - aabb_min[1]) * (aabb_max[2] - aabb_min[2]);
00142 }
00143
00144 CostSource() {}
00145
00146 bool operator < (const CostSource& other) const
00147 {
00148 if(total_cost < other.total_cost)
00149 return false;
00150 if(total_cost > other.total_cost)
00151 return true;
00152
00153 if(cost_density < other.cost_density)
00154 return false;
00155 if(cost_density > other.cost_density)
00156 return true;
00157
00158 for(size_t i = 0; i < 3; ++i)
00159 if(aabb_min[i] != other.aabb_min[i])
00160 return aabb_min[i] < other.aabb_min[i];
00161
00162 return false;
00163 }
00164 };
00165
00166 struct CollisionResult;
00167
00169 struct CollisionRequest
00170 {
00172 size_t num_max_contacts;
00173
00175 bool enable_contact;
00176
00178 size_t num_max_cost_sources;
00179
00181 bool enable_cost;
00182
00184 bool use_approximate_cost;
00185
00186 CollisionRequest(size_t num_max_contacts_ = 1,
00187 bool enable_contact_ = false,
00188 size_t num_max_cost_sources_ = 1,
00189 bool enable_cost_ = false,
00190 bool use_approximate_cost_ = true) : num_max_contacts(num_max_contacts_),
00191 enable_contact(enable_contact_),
00192 num_max_cost_sources(num_max_cost_sources_),
00193 enable_cost(enable_cost_),
00194 use_approximate_cost(use_approximate_cost_)
00195 {
00196 }
00197
00198 bool isSatisfied(const CollisionResult& result) const;
00199 };
00200
00202 struct CollisionResult
00203 {
00204 private:
00206 std::vector<Contact> contacts;
00207
00209 std::set<CostSource> cost_sources;
00210
00211 public:
00212 CollisionResult()
00213 {
00214 }
00215
00216
00218 inline void addContact(const Contact& c)
00219 {
00220 contacts.push_back(c);
00221 }
00222
00224 inline void addCostSource(const CostSource& c, std::size_t num_max_cost_sources)
00225 {
00226 cost_sources.insert(c);
00227 while (cost_sources.size() > num_max_cost_sources)
00228 cost_sources.erase(--cost_sources.end());
00229 }
00230
00232 bool isCollision() const
00233 {
00234 return contacts.size() > 0;
00235 }
00236
00238 size_t numContacts() const
00239 {
00240 return contacts.size();
00241 }
00242
00244 size_t numCostSources() const
00245 {
00246 return cost_sources.size();
00247 }
00248
00250 const Contact& getContact(size_t i) const
00251 {
00252 if(i < contacts.size())
00253 return contacts[i];
00254 else
00255 return contacts.back();
00256 }
00257
00259 void getContacts(std::vector<Contact>& contacts_)
00260 {
00261 contacts_.resize(contacts.size());
00262 std::copy(contacts.begin(), contacts.end(), contacts_.begin());
00263 }
00264
00266 void getCostSources(std::vector<CostSource>& cost_sources_)
00267 {
00268 cost_sources_.resize(cost_sources.size());
00269 std::copy(cost_sources.begin(), cost_sources.end(), cost_sources_.begin());
00270 }
00271
00273 void clear()
00274 {
00275 contacts.clear();
00276 cost_sources.clear();
00277 }
00278 };
00279
00280 struct DistanceResult;
00281
00283 struct DistanceRequest
00284 {
00286 bool enable_nearest_points;
00287
00288 DistanceRequest(bool enable_nearest_points_ = false) : enable_nearest_points(enable_nearest_points_)
00289 {
00290 }
00291
00292 bool isSatisfied(const DistanceResult& result) const;
00293 };
00294
00296 struct DistanceResult
00297 {
00298
00299 public:
00300
00302 FCL_REAL min_distance;
00303
00305 Vec3f nearest_points[2];
00306
00308 const CollisionGeometry* o1;
00309
00311 const CollisionGeometry* o2;
00312
00317 int b1;
00318
00323 int b2;
00324
00326 static const int NONE = -1;
00327
00328 DistanceResult(FCL_REAL min_distance_ = std::numeric_limits<FCL_REAL>::max()) : min_distance(min_distance_),
00329 o1(NULL),
00330 o2(NULL),
00331 b1(NONE),
00332 b2(NONE)
00333 {
00334 }
00335
00336
00338 void update(FCL_REAL distance, const CollisionGeometry* o1_, const CollisionGeometry* o2_, int b1_, int b2_)
00339 {
00340 if(min_distance > distance)
00341 {
00342 min_distance = distance;
00343 o1 = o1_;
00344 o2 = o2_;
00345 b1 = b1_;
00346 b2 = b2_;
00347 }
00348 }
00349
00351 void update(FCL_REAL distance, const CollisionGeometry* o1_, const CollisionGeometry* o2_, int b1_, int b2_, const Vec3f& p1, const Vec3f& p2)
00352 {
00353 if(min_distance > distance)
00354 {
00355 min_distance = distance;
00356 o1 = o1_;
00357 o2 = o2_;
00358 b1 = b1_;
00359 b2 = b2_;
00360 nearest_points[0] = p1;
00361 nearest_points[1] = p2;
00362 }
00363 }
00364
00366 void update(const DistanceResult& other_result)
00367 {
00368 if(min_distance > other_result.min_distance)
00369 {
00370 min_distance = other_result.min_distance;
00371 o1 = other_result.o1;
00372 o2 = other_result.o2;
00373 b1 = other_result.b1;
00374 b2 = other_result.b2;
00375 nearest_points[0] = other_result.nearest_points[0];
00376 nearest_points[1] = other_result.nearest_points[1];
00377 }
00378 }
00379
00381 void clear()
00382 {
00383 min_distance = std::numeric_limits<FCL_REAL>::max();
00384 o1 = NULL;
00385 o2 = NULL;
00386 b1 = NONE;
00387 b2 = NONE;
00388 }
00389 };
00390
00391
00392
00393
00394 }
00395
00396 #endif