hpp-fcl
1.4.5
HPP fork of FCL -- The Flexible Collision Library
collision.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-2015, 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
39
#ifndef HPP_FCL_COLLISION_H
40
#define HPP_FCL_COLLISION_H
41
42
#include <
hpp/fcl/data_types.h
>
43
#include <
hpp/fcl/collision_object.h
>
44
#include <
hpp/fcl/collision_data.h
>
45
46
namespace
hpp
47
{
48
namespace
fcl
49
{
50
55
std::size_t
collide
(
const
CollisionObject* o1,
const
CollisionObject* o2,
56
const
CollisionRequest& request, CollisionResult& result)
HPP_FCL_DLLAPI
;
57
59
std::size_t
collide
(
const
CollisionGeometry* o1,
const
Transform3f& tf1,
60
const
CollisionGeometry* o2,
const
Transform3f& tf2,
61
const
CollisionRequest& request, CollisionResult& result)
HPP_FCL_DLLAPI
;
62
66
inline
std::size_t
collide
(
const
CollisionObject
* o1,
const
CollisionObject
* o2,
67
CollisionRequest
& request,
CollisionResult
& result)
68
{
69
std::size_t res =
collide
(o1, o2, (
const
CollisionRequest
&) request, result);
70
request.
updateGuess
(result);
71
return
res;
72
}
73
77
inline
std::size_t
collide
(
const
CollisionGeometry
* o1,
const
Transform3f
& tf1,
78
const
CollisionGeometry
* o2,
const
Transform3f
& tf2,
79
CollisionRequest
& request,
CollisionResult
& result)
80
{
81
std::size_t res =
collide
(o1, tf1, o2, tf2,
82
(
const
CollisionRequest
&) request, result);
83
request.
updateGuess
(result);
84
return
res;
85
}
86
}
87
88
}
// namespace hpp
89
90
#endif
HPP_FCL_DLLAPI
#define HPP_FCL_DLLAPI
Definition:
config.hh:64
data_types.h
collision_object.h
hpp::fcl::QueryRequest::updateGuess
void updateGuess(const QueryResult &result)
Definition:
collision_data.h:172
hpp::fcl::collide
std::size_t collide(const CollisionObject *o1, const CollisionObject *o2, const CollisionRequest &request, CollisionResult &result) HPP_FCL_DLLAPI
Main collision interface: given two collision objects, and the requirements for contacts,...
hpp::fcl::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition:
collision_object.h:63
collision_data.h
hpp
Main namespace.
Definition:
AABB.h:43
hpp::fcl::CollisionRequest
request to the collision algorithm
Definition:
collision_data.h:191
hpp::fcl::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition:
collision_object.h:157
hpp::fcl::CollisionResult
collision result
Definition:
collision_data.h:240
hpp::fcl::Transform3f
Simple transform class used locally by InterpMotion.
Definition:
transform.h:59
include
hpp
fcl
collision.h
Generated by
1.8.17