Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • gsaurel/hpp-fcl
  • coal-library/coal
2 results
Show changes
Showing
with 2467 additions and 12 deletions
#!/usr/bin/env python3
import pdb
import sys
# ABC = AB^AC
# (ABC^AJ).a = (j.c - j.b) a.a + (j.a - j.c) b.a + (j.b - j.a) c.a, for j = b or c
segment_fmt = "{j}a_aa"
plane_fmt = ""
edge_fmt = "{j}a * {b}a_{c}a + {j}{b} * {c}a_aa - {j}{c} * {b}a_aa"
# These checks must be negative and not positive, as in the cheat sheet.
# They are the same as in the cheat sheet, except that we consider (...).dot(A)
# instead of (...).dot(-A)
plane_tests = ["C.dot (a_cross_b)", "D.dot(a_cross_c)", "-D.dot(a_cross_b)"]
checks = (
plane_tests
+ [edge_fmt.format(**{"j": j, "b": "b", "c": "c"}) for j in ["b", "c"]]
+ [edge_fmt.format(**{"j": j, "b": "c", "c": "d"}) for j in ["c", "d"]]
+ [edge_fmt.format(**{"j": j, "b": "d", "c": "b"}) for j in ["d", "b"]]
+ [segment_fmt.format(**{"j": j}) for j in ["b", "c", "d"]]
)
checks_hr = (
["ABC.AO >= 0", "ACD.AO >= 0", "ADB.AO >= 0"]
+ ["(ABC ^ {}).AO >= 0".format(n) for n in ["AB", "AC"]]
+ ["(ACD ^ {}).AO >= 0".format(n) for n in ["AC", "AD"]]
+ ["(ADB ^ {}).AO >= 0".format(n) for n in ["AD", "AB"]]
+ ["AB.AO >= 0", "AC.AO >= 0", "AD.AO >= 0"]
)
# weights of the checks.
weights = (
[
2,
]
* 3
+ [
3,
]
* 6
+ [
1,
]
* 3
)
# Segment tests first, because they have lower weight.
# tests = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, ]
tests = [
9,
10,
11,
0,
1,
2,
3,
4,
5,
6,
7,
8,
]
assert len(tests) == len(checks)
assert sorted(tests) == list(range(len(tests)))
regions = [
"ABC",
"ACD",
"ADB",
"AB",
"AC",
"AD",
"A",
"Inside",
]
cases = list(range(len(regions)))
# The following 3 lists refer to table doc/GJK_tetrahedra_boolean_table.ods
# A check ID is (+/- (index+1)) where a minus sign encodes a NOT operation
# and index refers to an index in list checks.
# definitions is a list of list of check IDs to be ANDed.
# For instance, a0.a3.!a4 -> [ 1, 4, -5]
definitions = [
[1, 4, -5],
[2, 6, -7],
[3, 8, -9],
[-4, 9, 10],
[-6, 5, 11],
[-8, 7, 12],
[-10, -11, -12],
[-1, -2, -3],
]
# conditions is a list of (list of (list of check IDs to be ANDed) to be ORed).
conditions = [
[],
[],
[],
[],
[],
[],
[],
[], # [ [10, 11, 12], ], # I don't think this is always true...
]
# rejections is a list of (list of (list of check IDs to be ANDed) to be ORed).
rejections = [
[
[2, 6, 7],
[3, -8, -9],
],
[
[3, 8, 9],
[1, -4, -5],
],
[
[1, 4, 5],
[2, -6, -7],
],
[
[-1, -3],
],
[
[-2, -1],
],
[
[-3, -2],
],
[
[4, -5],
[6, -7],
[8, -9],
],
[],
]
implications = [
[
[
4,
5,
10,
],
[11],
],
[
[
6,
7,
11,
],
[12],
],
[
[
8,
9,
12,
],
[10],
],
[
[
-4,
-5,
11,
],
[10],
],
[
[
-6,
-7,
12,
],
[11],
],
[
[
-8,
-9,
10,
],
[12],
],
[[1, 4, 5, 6], [-7]],
[[2, 6, 9, 8], [-9]],
[[3, 8, 9, 4], [-5]],
[
[
-4,
5,
10,
],
[-11],
],
[
[
4,
-5,
-10,
],
[11],
],
[
[
-6,
7,
11,
],
[-12],
],
[
[
6,
-7,
-11,
],
[12],
],
[
[
-8,
9,
12,
],
[-10],
],
[
[
8,
-9,
-12,
],
[10],
],
[[10, 3, 9, -12, 4, -5], [1]],
[[10, -3, 1, -4], [9]],
[[10, -3, -1, 2, -6, 11], [5]],
[[-10, 11, 2, -12, -5, -1], [6]],
[[-10, 11, -2, 1, 5], [-6]],
[[-10, -11, 12, 1, -7, -2, 4], [-5]],
[[-10, -11, 12, -3, 2, 7], [-8]],
[[-10, -11, 12, -3, -2], [-1]],
]
def set_test_values(current_tests, test_values, itest, value):
def satisfies(values, indices):
for k in indices:
if k > 0 and values[k - 1] is not True:
return False
if k < 0 and values[-k - 1] is not False:
return False
return True
remaining_tests = list(current_tests)
next_test_values = list(test_values)
remaining_tests.remove(itest)
next_test_values[itest] = value
rerun = True
while rerun:
rerun = False
for impl in implications:
if satisfies(next_test_values, impl[0]):
for id in impl[1]:
k = (id - 1) if id > 0 else (-id - 1)
if k in remaining_tests:
next_test_values[k] = id > 0
remaining_tests.remove(k)
rerun = True
else:
if next_test_values[k] != (id > 0):
raise ValueError("Absurd case")
return remaining_tests, next_test_values
def set_tests_values(current_tests, test_values, itests, values):
for itest, value in zip(itests, values):
current_tests, test_values = set_test_values(
current_tests, test_values, itest, value
)
return current_tests, test_values
def apply_test_values(cases, test_values):
def canSatisfy(values, indices):
for k in indices:
if k > 0 and values[k - 1] is False:
return False
if k < 0 and values[-k - 1] is True:
return False
return True
def satisfies(values, indices):
for k in indices:
if k > 0 and values[k - 1] is not True:
return False
if k < 0 and values[-k - 1] is not False:
return False
return True
# Check all cases.
left_cases = []
for case in cases:
defi = definitions[case]
conds = conditions[case]
rejs = rejections[case]
if satisfies(test_values, defi):
# A definition is True, stop recursion
return [case]
if not canSatisfy(test_values, defi):
continue
for cond in conds:
if satisfies(test_values, cond):
# A condition is True, stop recursion
return [case]
append = True
for rej in rejs:
if satisfies(test_values, rej):
# A rejection is True, discard this case
append = False
break
if append:
left_cases.append(case)
return left_cases
def max_number_of_tests(
current_tests,
cases,
test_values=[
None,
]
* len(tests),
prevBestScore=float("inf"),
prevScore=0,
):
for test in current_tests:
assert test_values[test] is None, "Test " + str(test) + " already performed"
left_cases = apply_test_values(cases, test_values)
if len(left_cases) == 1:
return prevScore, {
"case": left_cases[0],
}
elif len(left_cases) == 0:
return prevScore, {
"case": None,
"comments": [
"applied " + str(test_values),
"to " + ", ".join([regions[c] for c in cases]),
],
}
assert len(current_tests) > 0, "No more test but " + str(left_cases) + " remains"
currentBestScore = prevBestScore
bestScore = float("inf")
bestOrder = [None, None]
for i, test in enumerate(current_tests):
assert bestScore >= currentBestScore
currentScore = prevScore + len(left_cases) * weights[test]
# currentScore = prevScore + weights[test]
if currentScore > currentBestScore: # Cannot do better -> stop
continue
try:
remaining_tests, next_test_values = set_test_values(
current_tests, test_values, test, True
)
except ValueError:
remaining_tests = None
if remaining_tests is not None:
# Do not put this in try catch as I do not want other ValueError to be
# understood as an infeasible branch.
score_if_t, order_if_t = max_number_of_tests(
remaining_tests,
left_cases,
next_test_values,
currentBestScore,
currentScore,
)
if score_if_t >= currentBestScore: # True didn't do better -> stop
continue
else:
score_if_t, order_if_t = prevScore, None
try:
remaining_tests, next_test_values = set_test_values(
current_tests, test_values, test, False
)
except ValueError:
remaining_tests = None
if remaining_tests is not None:
# Do not put this in try catch as I do not want other ValueError to be
# understood as an infeasible branch.
score_if_f, order_if_f = max_number_of_tests(
remaining_tests,
left_cases,
next_test_values,
currentBestScore,
currentScore,
)
else:
score_if_f, order_if_f = prevScore, None
currentScore = max(score_if_t, score_if_f)
if currentScore < bestScore:
if currentScore < currentBestScore:
bestScore = currentScore
bestOrder = {"test": test, "true": order_if_t, "false": order_if_f}
# pdb.set_trace()
currentBestScore = currentScore
if len(tests) == len(current_tests):
print("New best score: {}".format(currentBestScore))
return bestScore, bestOrder
def printComments(order, indent, file):
if "comments" in order:
for comment in order["comments"]:
print(indent + "// " + comment, file=file)
def printOrder(order, indent="", start=True, file=sys.stdout, curTests=[]):
if start:
print(
"bool GJK::projectTetrahedraOrigin(const Simplex& current, Simplex& next)",
file=file,
)
print("{", file=file)
print(
indent + "// The code of this function was generated using doc/gjk.py",
file=file,
)
print(indent + "const vertex_id_t a = 3, b = 2, c = 1, d = 0;", file=file)
for v in "abcd":
print(
indent
+ "const Vec3s& {} (current.vertex[{}]->w);".format(v.upper(), v),
file=file,
)
print(indent + "const CoalScalar aa = A.squaredNorm();".format(), file=file)
for v in "dcb":
for m in "abcd":
if m <= v:
print(
indent
+ "const CoalScalar {0}{1} = {2}.dot({3});".format(
v, m, v.upper(), m.upper()
),
file=file,
)
else:
print(
indent + "const CoalScalar& {0}{1} = {1}{0};".format(v, m),
file=file,
)
print(indent + "const CoalScalar {0}a_aa = {0}a - aa;".format(v), file=file)
for l0, l1 in zip("bcd", "cdb"):
print(
indent + "const CoalScalar {0}a_{1}a = {0}a - {1}a;".format(l0, l1),
file=file,
)
for v in "bc":
print(
indent + "const Vec3s a_cross_{0} = A.cross({1});".format(v, v.upper()),
file=file,
)
print("", file=file)
print("#define REGION_INSIDE() " + indent + "\\", file=file)
print(indent + " ray.setZero(); \\", file=file)
print(indent + " next.vertex[0] = current.vertex[d]; \\", file=file)
print(indent + " next.vertex[1] = current.vertex[c]; \\", file=file)
print(indent + " next.vertex[2] = current.vertex[b]; \\", file=file)
print(indent + " next.vertex[3] = current.vertex[a]; \\", file=file)
print(indent + " next.rank=4; \\", file=file)
print(indent + " return true;", file=file)
print("", file=file)
if "case" in order:
case = order["case"]
if case is None:
print(
indent + "// There are no case corresponding to this set of tests.",
file=file,
)
printComments(order, indent, file)
print(indent + "assert(false);", file=file)
return
region = regions[case]
print(indent + "// Region " + region, file=file)
printComments(order, indent, file)
toFree = ["b", "c", "d"]
if region == "Inside":
print(indent + "REGION_INSIDE()", file=file)
toFree = []
elif region == "A":
print(indent + "originToPoint (current, a, A, next, ray);", file=file)
elif len(region) == 2:
region[0]
B = region[1]
print(
indent
+ "originToSegment "
"(current, a, {b}, A, {B}, {B}-A, -{b}a_aa, next, ray);".format(
**{"b": B.lower(), "B": B}
),
file=file,
)
toFree.remove(B.lower())
elif len(region) == 3:
B = region[1]
C = region[2]
test = plane_tests[["ABC", "ACD", "ADB"].index(region)]
if test.startswith("-"):
test = test[1:]
else:
test = "-" + test
print(
indent
+ "originToTriangle "
"(current, a, {b}, {c}, ({B}-A).cross({C}-A), {t}, next, ray);".format(
**{"b": B.lower(), "c": C.lower(), "B": B, "C": C, "t": test}
),
file=file,
)
toFree.remove(B.lower())
toFree.remove(C.lower())
else:
assert False, "Unknown region " + region
for pt in toFree:
print(
indent + "free_v[nfree++] = current.vertex[{}];".format(pt), file=file
)
else:
assert "test" in order and "true" in order and "false" in order
check = checks[order["test"]]
check_hr = checks_hr[order["test"]]
printComments(order, indent, file)
nextTests_t = curTests + [
"a" + str(order["test"] + 1),
]
nextTests_f = curTests + [
"!a" + str(order["test"] + 1),
]
if order["true"] is None:
if order["false"] is None:
print(
indent
+ """assert(false && "Case {} should never happen.");""".format(
check_hr
)
)
else:
print(
indent
+ "assert(!({} <= 0)); // Not {} / {}".format(
check, check_hr, ".".join(nextTests_f)
),
file=file,
)
printOrder(
order["false"],
indent=indent,
start=False,
file=file,
curTests=nextTests_f,
)
elif order["false"] is None:
print(
indent
+ "assert({} <= 0); // {} / {}".format(
check, check_hr, ".".join(nextTests_t)
),
file=file,
)
printOrder(
order["true"],
indent=indent,
start=False,
file=file,
curTests=nextTests_t,
)
else:
print(
indent
+ "if ({} <= 0) {{ // if {} / {}".format(
check, check_hr, ".".join(nextTests_t)
),
file=file,
)
printOrder(
order["true"],
indent=indent + " ",
start=False,
file=file,
curTests=nextTests_t,
)
print(
indent
+ "}} else {{ // not {} / {}".format(check_hr, ".".join(nextTests_f)),
file=file,
)
printOrder(
order["false"],
indent=indent + " ",
start=False,
file=file,
curTests=nextTests_f,
)
print(indent + "}} // end of {}".format(check_hr), file=file)
if start:
print("", file=file)
print("#undef REGION_INSIDE", file=file)
print(indent + "return false;", file=file)
print("}", file=file)
def unit_tests():
# a4, a5, a10, a11, a12
cases = list(range(len(regions)))
pdb.set_trace()
left_cases = apply_test_values(
cases,
test_values=[
None,
None,
None,
True,
True,
None,
None,
None,
None,
True,
True,
True,
],
)
assert len(left_cases) > 1
# unit_tests()
score, order = max_number_of_tests(tests, cases)
print(score)
printOrder(order, indent=" ")
# TODO add weights such that:
# - it is preferred to have all the use of one check in one branch.
# idea: ponderate by the number of remaining tests.
doc/images/coal-performances.jpg

285 KiB

File added
doc/images/coal-vs-the-rest-of-the-world.png

95.9 KiB

digraph CD {
rankdir = BT
compound=true
size = 11.7
"std::size_t BVHCollide(const CollisionGeometry* o1,\nconst Transform3s& tf1, const CollisionGeometry* o2,\nconst Transform3s& tf2, const CollisionRequest& request,\nCollisionResult& result)" [shape = box]
"bool OBB::overlap(const OBB& other,\nconst CollisionRequest& request,\nCoalScalar& sqrDistLowerBound) const" [shape = box]
"bool OBBRSS::overlap(const OBBRSS& other,\nconst CollisionRequest& request,\nCoalScalar& sqrDistLowerBound) const" [shape = box]
"bool overlap(const Matrix3s& R0, const Vec3s& T0,\n const OBB& b1, const OBB& b2,\n const CollisionRequest& request, CoalScalar& sqrDistLowerBound)" [shape = box]
"bool overlap(const Matrix3s& R0, const Vec3s& T0,\n const OBBRSS& b1, const OBBRSS& b2,\nconst CollisionRequest& request, CoalScalar& sqrDistLowerBound)" [shape = box]
"bool BVNode::overlap(const BVNode& other,\nconst CollisionRequest& request,\nCoalScalar& sqrDistLowerBound) const" [shape = box]
"bool BVHCollisionTraversalNode::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\n -request\n - result" [shape = box]
"bool MeshCollisionTraversalNode<T_BVH>::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\n -request\n - result" [shape = box]
"void collide(MeshCollisionTraversalNode<T_BVH>* node,\n const CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)" [shape = box]
"void collisionRecurse(MeshCollisionTraversalNode<T_BVH>* node,\n int b1, int b2, BVHFrontList* front_list, CoalScalar& sqrDistLowerBound)" [shape = box]
"void propagateBVHFrontListCollisionRecurse(MeshCollisionTraversalNode<T_BVH>* node\n, BVHFrontList* front_list, const CollisionRequest& request, CollisionResult& result)" [shape = box]
"bool MeshCollisionTraversalNodeOBBRSS::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\n -request\n - result" [shape = box]
"MeshCollisionTraversalNode<T_BVH>::leafTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\n -request\n - result" [shape = box]
"bool obbDisjointAndLowerBoundDistance\n(const Matrix3s& B, const Vec3s& T, const Vec3s& a, const Vec3s& b,\n CoalScalar& squaredLowerBoundDistance)" [shape = box]
"std::size_t BVHCollide(const CollisionGeometry* o1,\nconst Transform3s& tf1, const CollisionGeometry* o2,\nconst Transform3s& tf2, const CollisionRequest& request,\nCollisionResult& result)" -> "void collide(MeshCollisionTraversalNode<T_BVH>* node,\n const CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)"
"bool OBB::overlap(const OBB& other,\nconst CollisionRequest& request,\nCoalScalar& sqrDistLowerBound) const" -> "bool obbDisjointAndLowerBoundDistance\n(const Matrix3s& B, const Vec3s& T, const Vec3s& a, const Vec3s& b,\n CoalScalar& squaredLowerBoundDistance)"
"bool overlap(const Matrix3s& R0, const Vec3s& T0,\n const OBB& b1, const OBB& b2,\n const CollisionRequest& request, CoalScalar& sqrDistLowerBound)" -> "bool obbDisjointAndLowerBoundDistance\n(const Matrix3s& B, const Vec3s& T, const Vec3s& a, const Vec3s& b,\n CoalScalar& squaredLowerBoundDistance)"
"bool overlap(const Matrix3s& R0, const Vec3s& T0,\n const OBBRSS& b1, const OBBRSS& b2,\nconst CollisionRequest& request, CoalScalar& sqrDistLowerBound)" -> "bool overlap(const Matrix3s& R0, const Vec3s& T0,\n const OBB& b1, const OBB& b2,\n const CollisionRequest& request, CoalScalar& sqrDistLowerBound)"
"void collide(MeshCollisionTraversalNode<T_BVH>* node,\n const CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)"-> "void propagateBVHFrontListCollisionRecurse(MeshCollisionTraversalNode<T_BVH>* node\n, BVHFrontList* front_list, const CollisionRequest& request, CollisionResult& result)"
"void collide(MeshCollisionTraversalNode<T_BVH>* node,\n const CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)" -> "void collisionRecurse(MeshCollisionTraversalNode<T_BVH>* node,\n int b1, int b2, BVHFrontList* front_list, CoalScalar& sqrDistLowerBound)"
"void collisionRecurse(MeshCollisionTraversalNode<T_BVH>* node,\n int b1, int b2, BVHFrontList* front_list, CoalScalar& sqrDistLowerBound)" -> "bool MeshCollisionTraversalNode<T_BVH>::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\n -request\n - result"
"void collisionRecurse(MeshCollisionTraversalNode<T_BVH>* node,\n int b1, int b2, BVHFrontList* front_list, CoalScalar& sqrDistLowerBound)" -> "MeshCollisionTraversalNode<T_BVH>::leafTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\n -request\n - result"
"void propagateBVHFrontListCollisionRecurse(MeshCollisionTraversalNode<T_BVH>* node\n, BVHFrontList* front_list, const CollisionRequest& request, CollisionResult& result)" -> "void collisionRecurse(MeshCollisionTraversalNode<T_BVH>* node,\n int b1, int b2, BVHFrontList* front_list, CoalScalar& sqrDistLowerBound)"
"void propagateBVHFrontListCollisionRecurse(MeshCollisionTraversalNode<T_BVH>* node\n, BVHFrontList* front_list, const CollisionRequest& request, CollisionResult& result)" -> "bool MeshCollisionTraversalNode<T_BVH>::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\n -request\n - result"
"bool MeshCollisionTraversalNodeOBBRSS::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\n -request\n - result" -> "bool overlap(const Matrix3s& R0, const Vec3s& T0,\n const OBBRSS& b1, const OBBRSS& b2,\nconst CollisionRequest& request, CoalScalar& sqrDistLowerBound)"
"bool MeshCollisionTraversalNode<T_BVH>::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\n -request\n - result" -> "bool MeshCollisionTraversalNodeOBBRSS::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\n -request\n - result" [color=red]
"bool MeshCollisionTraversalNode<T_BVH>::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\n -request\n - result" -> "bool BVHCollisionTraversalNode::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\n -request\n - result" [color = red]
"bool OBBRSS::overlap(const OBBRSS& other,\nconst CollisionRequest& request,\nCoalScalar& sqrDistLowerBound) const" -> "bool OBB::overlap(const OBB& other,\nconst CollisionRequest& request,\nCoalScalar& sqrDistLowerBound) const"
"bool BVNode::overlap(const BVNode& other,\nconst CollisionRequest& request,\nCoalScalar& sqrDistLowerBound) const" -> "bool OBB::overlap(const OBB& other,\nconst CollisionRequest& request,\nCoalScalar& sqrDistLowerBound) const"
"bool BVHCollisionTraversalNode::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\n -request\n - result" -> "bool BVNode::overlap(const BVNode& other,\nconst CollisionRequest& request,\nCoalScalar& sqrDistLowerBound) const"
}
\ No newline at end of file
File added
In include/hpp/fcl/traversal:
- some initialize method compute the position of all triangles in
global frame before performing collision test,
- bool initialize(MeshShapeCollisionTraversalNode<BV, S, NarrowPhaseSolver>& node, ...
- bool initialize(ShapeMeshCollisionTraversalNode<S, BV, NarrowPhaseSolver>& node, ...
- bool initialize(MeshCollisionTraversalNode<BV>& node,...
- other do not.
- bool initialize(MeshOcTreeCollisionTraversalNode<BV, NarrowPhaseSolver>& node, ...
- bool initialize(OcTreeMeshCollisionTraversalNode<BV, NarrowPhaseSolver>& node, ...
- bool initialize(MeshShapeCollisionTraversalNodeOBB<S, NarrowPhaseSolver>& node, ...
- bool initialize(MeshShapeCollisionTraversalNodeRSS<S, NarrowPhaseSolver>& node, ...
- bool initialize(MeshShapeCollisionTraversalNodekIOS<S, NarrowPhaseSolver>& node, ...
- bool initialize(MeshShapeCollisionTraversalNodeOBBRSS<S, NarrowPhaseSolver>& node, ...
- bool initialize(ShapeMeshCollisionTraversalNodeOBB<S, NarrowPhaseSolver>& node, ...
- bool initialize(ShapeMeshCollisionTraversalNodeRSS<S, NarrowPhaseSolver>& node, ...
- bool initialize(ShapeMeshCollisionTraversalNodekIOS<S, NarrowPhaseSolver>& node, ...
- bool initialize(ShapeMeshCollisionTraversalNodeOBBRSS<S, NarrowPhaseSolver>& node, ...
- bool initialize(MeshCollisionTraversalNodeOBB& node, ...
- bool initialize(MeshCollisionTraversalNodeRSS& node, ...
- bool initialize(MeshCollisionTraversalNodekIOS& node, ...
- bool initialize(MeshCollisionTraversalNodeOBBRSS& node, ...
-------------------------------------------------------------------------------
classes
- MeshCollisionTraversalNodeRSS,
- MeshCollisionTraversalNodekIOS,
- MeshCollisionTraversalNodeOBBRSS
derive from
- MeshCollisionTraversalNode <RSS>,
- MeshCollisionTraversalNode <kIOS>,
- MeshCollisionTraversalNode <OBBRSS>.
They store the relative position and orientation between two objects to test for
collision. before calling overlap function, this additional information computes
the relative positions of the bounding volumes.
-------------------------------------------------------------------------------
For primitive shapes, collision and distance computation are very close.
ShapeShapeCollide calls indeed ShapeShapeDistance. It would be convenient to
merge CollisionRequest and DistanceRequest on the one hand and CollisionResult
and DistanceResult on the other hand into two classes InteractionRequest and
InteractionResult.
\ No newline at end of file
#ifndef DOXYGEN_BOOST_DOC_HH
#define DOXYGEN_BOOST_DOC_HH
#ifndef DOXYGEN_DOC_HH
#error "You should have included doxygen.hh first."
#endif // DOXYGEN_DOC_HH
#include <boost/python.hpp>
namespace doxygen {
namespace visitor {
template <typename function_type,
typename policy_type = boost::python::default_call_policies>
struct member_func_impl : boost::python::def_visitor<
member_func_impl<function_type, policy_type> > {
member_func_impl(const char* n, const function_type& f)
: name(n), function(f) {}
member_func_impl(const char* n, const function_type& f, policy_type p)
: name(n), function(f), policy(p) {}
template <class classT>
inline void visit(classT& c) const {
// Either a boost::python::keyword<N> object or a void_ object
call(c, member_func_args(function));
}
template <class classT, std::size_t nkeywords>
inline void call(
classT& c, const boost::python::detail::keywords<nkeywords>& args) const {
c.def(name, function, member_func_doc(function), args, policy);
}
template <class classT>
inline void call(classT& c, const void_&) const {
c.def(name, function, member_func_doc(function), policy);
}
const char* name;
const function_type& function;
policy_type policy;
};
// TODO surprisingly, this does not work when defined here but it works when
// defined after the generated files are included.
template <typename function_type>
inline member_func_impl<function_type> member_func(
const char* name, const function_type& function) {
return member_func_impl<function_type>(name, function);
}
template <typename function_type, typename policy_type>
inline member_func_impl<function_type, policy_type> member_func(
const char* name, const function_type& function,
const policy_type& policy) {
return member_func_impl<function_type, policy_type>(name, function, policy);
}
#define DOXYGEN_DOC_DECLARE_INIT_VISITOR(z, nargs, unused) \
template <typename Class BOOST_PP_COMMA_IF(nargs) \
BOOST_PP_ENUM_PARAMS(nargs, class Arg)> \
struct init_##nargs##_impl \
: boost::python::def_visitor< \
init_##nargs##_impl<Class BOOST_PP_COMMA_IF(nargs) \
BOOST_PP_ENUM_PARAMS(nargs, Arg)> > { \
typedef constructor_##nargs##_impl<Class BOOST_PP_COMMA_IF(nargs) \
BOOST_PP_ENUM_PARAMS(nargs, Arg)> \
constructor; \
typedef boost::python::init<BOOST_PP_ENUM_PARAMS(nargs, Arg)> init_base; \
\
template <class classT> \
inline void visit(classT& c) const { \
call(c, constructor::args()); \
} \
\
template <class classT> \
void call(classT& c, \
const boost::python::detail::keywords<nargs + 1>& args) const { \
c.def(init_base(constructor::doc(), args)); \
} \
\
template <class classT> \
void call(classT& c, const void_&) const { \
c.def(init_base(constructor::doc())); \
} \
}; \
\
template <typename Class BOOST_PP_COMMA_IF(nargs) \
BOOST_PP_ENUM_PARAMS(nargs, class Arg)> \
inline init_##nargs##_impl<Class BOOST_PP_COMMA_IF(nargs) \
BOOST_PP_ENUM_PARAMS(nargs, Arg)> \
init() { \
return init_##nargs##_impl<Class BOOST_PP_COMMA_IF(nargs) \
BOOST_PP_ENUM_PARAMS(nargs, Arg)>(); \
}
BOOST_PP_REPEAT(DOXYGEN_DOC_MAX_NUMBER_OF_ARGUMENTS_IN_CONSTRUCTOR,
DOXYGEN_DOC_DECLARE_INIT_VISITOR, ~)
#undef DOXYGEN_DOC_DECLARE_INIT_VISITOR
} // namespace visitor
template <typename Func>
void def(const char* name, Func func) {
boost::python::def(name, func, member_func_doc(func));
}
} // namespace doxygen
#endif // DOXYGEN_BOOST_DOC_HH
#ifndef DOXYGEN_DOC_HH
#define DOXYGEN_DOC_HH
#include <boost/preprocessor/repetition.hpp>
#include <boost/preprocessor/punctuation/comma_if.hpp>
#include <boost/mpl/void.hpp>
#ifndef DOXYGEN_DOC_MAX_NUMBER_OF_ARGUMENTS_IN_CONSTRUCTOR
#define DOXYGEN_DOC_MAX_NUMBER_OF_ARGUMENTS_IN_CONSTRUCTOR 10
#endif
namespace doxygen {
typedef boost::mpl::void_ void_;
template <typename _class>
struct class_doc_impl {
static inline const char* run() { return ""; }
static inline const char* attribute(const char*) { return ""; }
};
template <typename _class>
inline const char* class_doc() {
return class_doc_impl<_class>::run();
}
template <typename _class>
inline const char* class_attrib_doc(const char* name) {
return class_doc_impl<_class>::attribute(name);
}
template <typename FuncPtr>
inline const char* member_func_doc(FuncPtr) {
return "";
}
template <typename FuncPtr>
inline void_ member_func_args(FuncPtr) {
return void_();
}
#define DOXYGEN_DOC_DECLARE_CONSTRUCTOR(z, nargs, unused) \
template <typename Class BOOST_PP_COMMA_IF(nargs) \
BOOST_PP_ENUM_PARAMS(nargs, class Arg)> \
struct constructor_##nargs##_impl { \
static inline const char* doc() { return ""; } \
static inline void_ args() { return void_(); } \
}; \
\
template <typename Class BOOST_PP_COMMA_IF(nargs) \
BOOST_PP_ENUM_PARAMS(nargs, class Arg)> \
inline const char* constructor_doc() { \
return constructor_##nargs##_impl<Class BOOST_PP_COMMA_IF( \
nargs) BOOST_PP_ENUM_PARAMS(nargs, Arg)>::doc(); \
}
BOOST_PP_REPEAT(DOXYGEN_DOC_MAX_NUMBER_OF_ARGUMENTS_IN_CONSTRUCTOR,
DOXYGEN_DOC_DECLARE_CONSTRUCTOR, ~)
#undef DOXYGEN_DOC_DECLARE_CONSTRUCTOR
/*
template <typename Class>
inline const char* constructor_doc ()
{
return "";
}
*/
template <typename Class>
struct destructor_doc_impl {
static inline const char* run() { return ""; }
};
template <typename Class>
inline const char* destructor_doc() {
return destructor_doc_impl<Class>::run();
}
/* TODO class attribute can be handled by
template <typename Class, typename AttributeType>
const char* attribute_doc (AttributeType Class::* ptr)
{
// Body looks like
// if (ptr == &Class::attributeName)
// return "attrib documentation";
return "undocumented";
}
*/
} // namespace doxygen
#endif // DOXYGEN_DOC_HH
This diff is collapsed.
class XmlDocString(object):
def __init__(self, index):
self.index = index
self.tags = {
"para": self.para,
"ref": self.ref,
"briefdescription": self.otherTags,
"detaileddescription": self.otherTags,
"parameterlist": self.parameterlist,
"parameterdescription": self.otherTags,
"emphasis": self.emphasis,
"simplesect": self.simplesect,
"formula": self.formula,
"itemizedlist": self.itemizedlist,
"listitem": self.listitem,
}
self.unkwownTags = set()
self.unkwownReferences = dict()
self._linesep = '\\n"\n"'
try:
from pylatexenc.latex2text import LatexNodes2Text
self.latex = LatexNodes2Text()
except ImportError:
self.latex = None
def clear(self):
self.lines = []
self.unkwownTags.clear()
self.unkwownReferences.clear()
def writeErrors(self, output):
ret = False
for t in self.unkwownTags:
output.warn("Unknown tag: ", t)
ret = True
for ref, node in self.unkwownReferences.items():
output.warn("Unknown reference: ", ref, node.text)
ret = True
return ret
def _write(self, str):
nlines = str.split("\n")
if len(self.lines) == 0:
self.lines += nlines
else:
self.lines[-1] += nlines[0]
self.lines += nlines[1:]
# self.lines += nlines[1:]
def _newline(self, n=1):
self.lines.extend(
[
"",
]
* n
)
def _clean(self):
s = 0
for line in self.lines:
if len(line.strip()) == 0:
s += 1
else:
break
e = len(self.lines)
for line in reversed(self.lines):
if len(line.strip()) == 0:
e -= 1
else:
break
self.lines = self.lines[s:e]
def getDocString(self, brief, detailled, output):
self.clear()
if brief is not None:
self.visit(brief)
if detailled is not None and len(detailled.getchildren()) > 0:
if brief is not None:
self._newline()
self.visit(detailled)
from sys import version_info
self.writeErrors(output)
self._clean()
if version_info[0] == 2:
return self._linesep.join(self.lines).encode("utf-8")
else:
return self._linesep.join(self.lines)
def visit(self, node):
assert isinstance(node.tag, str)
tag = node.tag
if tag not in self.tags:
self.unknownTag(node)
else:
self.tags[tag](node)
def unknownTag(self, node):
self.unkwownTags.add(node.tag)
self.otherTags(node)
def otherTags(self, node):
if node.text:
self._write(node.text.strip().replace('"', r"\""))
for c in node.iterchildren():
self.visit(c)
if c.tail:
self._write(c.tail.strip().replace('"', r"\""))
def emphasis(self, node):
self._write("*")
self.otherTags(node)
self._write("*")
def simplesect(self, node):
self._write(node.attrib["kind"].title() + ": ")
self.otherTags(node)
def para(self, node):
if node.text:
self._write(node.text.replace('"', r"\""))
for c in node.iterchildren():
self.visit(c)
if c.tail:
self._write(c.tail.replace('"', r"\""))
self._newline()
def ref(self, node):
refid = node.attrib["refid"]
if self.index.hasref(refid):
self._write(self.index.getref(refid).name)
else:
self.unkwownReferences[refid] = node
self._write(node.text)
assert len(node.getchildren()) == 0
def parameterlist(self, node):
self._newline()
self._write(node.attrib["kind"].title())
self._newline()
for item in node.iterchildren("parameteritem"):
self.parameteritem(item)
def parameteritem(self, node):
indent = " "
self._write(indent + "- ")
# should contain two children
assert len(node.getchildren()) == 2
namelist = node.find("parameternamelist")
desc = node.find("parameterdescription")
sep = ""
for name in namelist.iterchildren("parametername"):
self._write(sep + name.text)
sep = ", "
self._write(" ")
self.visit(desc)
def itemizedlist(self, node):
self._newline()
self.otherTags(node)
def listitem(self, node):
self._write("- ")
self.otherTags(node)
def formula(self, node):
if node.text:
if self.latex is None:
self._write(node.text.strip())
else:
self._write(self.latex.latex_to_text(node.text))
digraph CD {
rankdir = BT
compound=true
size = 11.7
"BVHShapeCollider<OBBRSS, Shape, NarrowPhaseSolver>::collide\n(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver,\nconst CollisionRequest& request, CollisionResult& result)\ncollision_func_matrix.cpp" [shape = box]
"details::orientedBVHShapeCollide<MeshShapeCollisionTraversalNodeOBBRSS\n<T_SH, NarrowPhaseSolver>, OBBRSS, T_SH, NarrowPhaseSolver>\n(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s&tf2,\nNarrowPhaseSolver* nsolver, const CollisionRequest& request,\nCollisionResult& result)\ncollision_func_matrix.cpp" [shape = box]
"void collide(CollisionTraversalNodeBase* node,\nconst CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)\ncollision_node.cpp" [shape = box]
"void propagateBVHFrontListCollisionRecurse\n(CollisionTraversalNodeBase* node, const CollisionRequest& request,\nCollisionResult& result, BVHFrontList* front_list)\ntraversal/traversal_recurse.cpp" [shape = box]
"void collisionRecurse(CollisionTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list,\nCoalScalar& sqrDistLowerBound)\ntraversal/traversal_recurse.cpp" [shape = box]
"virtual bool CollisionTraversalNodeBase::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const = 0\ntraversal/traversal_node_base.h" [shape = box]
"virtual void CollisionTraversalNodeBase::leafTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\ntraversal/traversal_node_base.h" [shape = box]
"bool MeshShapeCollisionTraversalNodeOBBRSS::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\ntraversal/traversal_node_bvh_shape.h" [shape = box]
"bool MeshShapeCollisionTraversalNodeOBBRSS::leafTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\ntraversal/traversal_node_bvh_shape.h" [shape = box]
"bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBBRSS& b1,\nconst OBBRSS& b2, const CollisionRequest& request,\nCoalScalar& sqrDistLowerBound)\nBV/OBBRSS.cpp" [shape = box]
"bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBB& b1, const OBB& b2,\nconst CollisionRequest& request, CoalScalar& sqrDistLowerBound)\nBV/OBB.cpp" [shape = box]
"bool obbDisjointAndLowerBoundDistance (const Matrix3s& B, const Vec3s& T,\nconst Vec3s& a, const Vec3s& b,\nconst CollisionRequest& request,\nCoalScalar& squaredLowerBoundDistance)\nBV/OBB.cpp" [shape = box]
"void details::meshShapeCollisionOrientedNodeLeafTesting <OBBRSS, Shape, NarrowPhaseSolver>\n(int b1, int b2, const BVHModel<BV>* model1, const S& model2,\nVec3s* vertices, Triangle* tri_indices, const Transform3s& tf1,\nconst Transform3s& tf2, const NarrowPhaseSolver* nsolver,\nbool enable_statistics, int& num_leaf_tests,\nconst CollisionRequest& request, CollisionResult& result,\nCoalScalar& sqrDistLowerBound)\ntraversal/traversal_node_bvh_shape.h:293" [shape = box]
"bool GJKSolver_indep::shapeTriangleIntersect<Shape>\n(const S& s, const Transform3s& tf,\nconst Vec3s& P1, const Vec3s& P2, const Vec3s& P3,\nCoalScalar* distance, Vec3s* p1, Vec3s* p2) const\nnarrowphase/narrowphase.h:156" [shape = box]
"BVHShapeCollider<OBBRSS, Shape, NarrowPhaseSolver>::collide\n(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver,\nconst CollisionRequest& request, CollisionResult& result)\ncollision_func_matrix.cpp" -> "details::orientedBVHShapeCollide<MeshShapeCollisionTraversalNodeOBBRSS\n<T_SH, NarrowPhaseSolver>, OBBRSS, T_SH, NarrowPhaseSolver>\n(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s&tf2,\nNarrowPhaseSolver* nsolver, const CollisionRequest& request,\nCollisionResult& result)\ncollision_func_matrix.cpp"
"details::orientedBVHShapeCollide<MeshShapeCollisionTraversalNodeOBBRSS\n<T_SH, NarrowPhaseSolver>, OBBRSS, T_SH, NarrowPhaseSolver>\n(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s&tf2,\nNarrowPhaseSolver* nsolver, const CollisionRequest& request,\nCollisionResult& result)\ncollision_func_matrix.cpp" -> "void collide(CollisionTraversalNodeBase* node,\nconst CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)\ncollision_node.cpp"
"void collide(CollisionTraversalNodeBase* node,\nconst CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)\ncollision_node.cpp" -> "void propagateBVHFrontListCollisionRecurse\n(CollisionTraversalNodeBase* node, const CollisionRequest& request,\nCollisionResult& result, BVHFrontList* front_list)\ntraversal/traversal_recurse.cpp"
"void collide(CollisionTraversalNodeBase* node,\nconst CollisionRequest& request, CollisionResult& result,\nBVHFrontList* front_list)\ncollision_node.cpp" -> "void collisionRecurse(CollisionTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list,\nCoalScalar& sqrDistLowerBound)\ntraversal/traversal_recurse.cpp"
"void propagateBVHFrontListCollisionRecurse\n(CollisionTraversalNodeBase* node, const CollisionRequest& request,\nCollisionResult& result, BVHFrontList* front_list)\ntraversal/traversal_recurse.cpp" -> "void collisionRecurse(CollisionTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list,\nCoalScalar& sqrDistLowerBound)\ntraversal/traversal_recurse.cpp"
"void collisionRecurse(CollisionTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list,\nCoalScalar& sqrDistLowerBound)\ntraversal/traversal_recurse.cpp" -> "virtual bool CollisionTraversalNodeBase::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const = 0\ntraversal/traversal_node_base.h"
"void collisionRecurse(CollisionTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list,\nCoalScalar& sqrDistLowerBound)\ntraversal/traversal_recurse.cpp" -> "virtual void CollisionTraversalNodeBase::leafTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\ntraversal/traversal_node_base.h"
"virtual bool CollisionTraversalNodeBase::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const = 0\ntraversal/traversal_node_base.h" -> "bool MeshShapeCollisionTraversalNodeOBBRSS::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\ntraversal/traversal_node_bvh_shape.h" [color=red]
"virtual void CollisionTraversalNodeBase::leafTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\ntraversal/traversal_node_base.h" -> "bool MeshShapeCollisionTraversalNodeOBBRSS::leafTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\ntraversal/traversal_node_bvh_shape.h" [color = red]
"bool MeshShapeCollisionTraversalNodeOBBRSS::BVTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\ntraversal/traversal_node_bvh_shape.h" -> "bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBBRSS& b1,\nconst OBBRSS& b2, const CollisionRequest& request,\nCoalScalar& sqrDistLowerBound)\nBV/OBBRSS.cpp"
"bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBBRSS& b1,\nconst OBBRSS& b2, const CollisionRequest& request,\nCoalScalar& sqrDistLowerBound)\nBV/OBBRSS.cpp" -> "bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBB& b1, const OBB& b2,\nconst CollisionRequest& request, CoalScalar& sqrDistLowerBound)\nBV/OBB.cpp"
"bool overlap(const Matrix3s& R0, const Vec3s& T0, const OBB& b1, const OBB& b2,\nconst CollisionRequest& request, CoalScalar& sqrDistLowerBound)\nBV/OBB.cpp" -> "bool obbDisjointAndLowerBoundDistance (const Matrix3s& B, const Vec3s& T,\nconst Vec3s& a, const Vec3s& b,\nconst CollisionRequest& request,\nCoalScalar& squaredLowerBoundDistance)\nBV/OBB.cpp"
"bool MeshShapeCollisionTraversalNodeOBBRSS::leafTesting\n(int b1, int b2, CoalScalar& sqrDistLowerBound) const\ntraversal/traversal_node_bvh_shape.h" -> "void details::meshShapeCollisionOrientedNodeLeafTesting <OBBRSS, Shape, NarrowPhaseSolver>\n(int b1, int b2, const BVHModel<BV>* model1, const S& model2,\nVec3s* vertices, Triangle* tri_indices, const Transform3s& tf1,\nconst Transform3s& tf2, const NarrowPhaseSolver* nsolver,\nbool enable_statistics, int& num_leaf_tests,\nconst CollisionRequest& request, CollisionResult& result,\nCoalScalar& sqrDistLowerBound)\ntraversal/traversal_node_bvh_shape.h:293"
"void details::meshShapeCollisionOrientedNodeLeafTesting <OBBRSS, Shape, NarrowPhaseSolver>\n(int b1, int b2, const BVHModel<BV>* model1, const S& model2,\nVec3s* vertices, Triangle* tri_indices, const Transform3s& tf1,\nconst Transform3s& tf2, const NarrowPhaseSolver* nsolver,\nbool enable_statistics, int& num_leaf_tests,\nconst CollisionRequest& request, CollisionResult& result,\nCoalScalar& sqrDistLowerBound)\ntraversal/traversal_node_bvh_shape.h:293" -> "bool GJKSolver_indep::shapeTriangleIntersect<Shape>\n(const S& s, const Transform3s& tf,\nconst Vec3s& P1, const Vec3s& P2, const Vec3s& P3,\nCoalScalar* distance, Vec3s* p1, Vec3s* p2) const\nnarrowphase/narrowphase.h:156"
}
File added
digraph CD {
rankdir = BT
compound=true
size = 11.7
"template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nstd::size_t ShapeShapeCollide(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver,const CollisionRequest& request,\nCollisionResult& result)" [shape = box]
"template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nCoalScalar ShapeShapeDistance(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver, const DistanceRequest& request,\nDistanceResult& result)" [shape = box]
"void distance(DistanceTraversalNodeBase* node,\nBVHFrontList* front_list, int qsize)" [shape = box]
"void distanceRecurse(DistanceTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list)" [shape = box]
"void ShapeDistanceTraversalNode::leafTesting(int, int) const\ntraversal/traversal_node_shapes.h" [shape = box]
"template<typename S1, typename S2> bool GJKSolver_indep::shapeDistance\n(const S1& s1, const Transform3s& tf1, const S2& s2, const Transform3s& tf2,\nCoalScalar* distance, Vec3s* p1, Vec3s* p2) const\nnarrowphase/narrowphase.h" [shape = box]
"template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nstd::size_t ShapeShapeCollide(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver,const CollisionRequest& request,\nCollisionResult& result)" -> "template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nCoalScalar ShapeShapeDistance(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver, const DistanceRequest& request,\nDistanceResult& result)"
"template<typename T_SH1, typename T_SH2, typename NarrowPhaseSolver>\nCoalScalar ShapeShapeDistance(const CollisionGeometry* o1, const Transform3s& tf1,\nconst CollisionGeometry* o2, const Transform3s& tf2,\nconst NarrowPhaseSolver* nsolver, const DistanceRequest& request,\nDistanceResult& result)" -> "void distance(DistanceTraversalNodeBase* node,\nBVHFrontList* front_list, int qsize)"
"void distance(DistanceTraversalNodeBase* node,\nBVHFrontList* front_list, int qsize)" -> "void distanceRecurse(DistanceTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list)"
"void distanceRecurse(DistanceTraversalNodeBase* node,\nint b1, int b2, BVHFrontList* front_list)" -> "void ShapeDistanceTraversalNode::leafTesting(int, int) const\ntraversal/traversal_node_shapes.h"
"void ShapeDistanceTraversalNode::leafTesting(int, int) const\ntraversal/traversal_node_shapes.h" -> "template<typename S1, typename S2> bool GJKSolver_indep::shapeDistance\n(const S1& s1, const Transform3s& tf1, const S2& s2, const Transform3s& tf2,\nCoalScalar* distance, Vec3s* p1, Vec3s* p2) const\nnarrowphase/narrowphase.h"
}
File added
# This file was generated by CMake for @PROJECT_NAME@
prefix=@CMAKE_INSTALL_PREFIX@
exec_prefix=${prefix}
libdir=${prefix}/lib
includedir=${prefix}/include
Name: @PROJECT_NAME@
Description: @PKG_DESC@
Version: @FCL_VERSION@
Requires: @PKG_EXTERNAL_DEPS@
Libs: -L${libdir} -lfcl
Cflags: -I${includedir}
{
"nodes": {
"flake-parts": {
"inputs": {
"nixpkgs-lib": "nixpkgs-lib"
},
"locked": {
"lastModified": 1738453229,
"narHash": "sha256-7H9XgNiGLKN1G1CgRh0vUL4AheZSYzPm+zmZ7vxbJdo=",
"owner": "hercules-ci",
"repo": "flake-parts",
"rev": "32ea77a06711b758da0ad9bd6a844c5740a87abd",
"type": "github"
},
"original": {
"owner": "hercules-ci",
"repo": "flake-parts",
"type": "github"
}
},
"nixpkgs": {
"locked": {
"lastModified": 1734122394,
"narHash": "sha256-TmVqB5V9ZIn66jlyPcp4yzsC6uF46YQLH00MSBio42c=",
"owner": "NixOS",
"repo": "nixpkgs",
"rev": "eb1b38d147a53360c11f0d033196f94d844bd86c",
"type": "github"
},
"original": {
"owner": "NixOS",
"ref": "refs/pull/357705/head",
"repo": "nixpkgs",
"type": "github"
}
},
"nixpkgs-lib": {
"locked": {
"lastModified": 1738452942,
"narHash": "sha256-vJzFZGaCpnmo7I6i416HaBLpC+hvcURh/BQwROcGIp8=",
"type": "tarball",
"url": "https://github.com/NixOS/nixpkgs/archive/072a6db25e947df2f31aab9eccd0ab75d5b2da11.tar.gz"
},
"original": {
"type": "tarball",
"url": "https://github.com/NixOS/nixpkgs/archive/072a6db25e947df2f31aab9eccd0ab75d5b2da11.tar.gz"
}
},
"root": {
"inputs": {
"flake-parts": "flake-parts",
"nixpkgs": "nixpkgs"
}
}
},
"root": "root",
"version": 7
}
{
description = "An extension of the Flexible Collision Library";
inputs = {
flake-parts.url = "github:hercules-ci/flake-parts";
# TODO: switch back to nixos-unstable after
# https://github.com/NixOS/nixpkgs/pull/357705
nixpkgs.url = "github:NixOS/nixpkgs/refs/pull/357705/head";
};
outputs =
inputs:
inputs.flake-parts.lib.mkFlake { inherit inputs; } {
systems = inputs.nixpkgs.lib.systems.flakeExposed;
perSystem =
{ pkgs, self', ... }:
{
apps.default = {
type = "app";
program = pkgs.python3.withPackages (_: [ self'.packages.default ]);
};
devShells.default = pkgs.mkShell { inputsFrom = [ self'.packages.default ]; };
packages = {
default = self'.packages.coal;
coal = pkgs.python3Packages.coal.overrideAttrs (_: {
src = pkgs.lib.fileset.toSource {
root = ./.;
fileset = pkgs.lib.fileset.unions [
./CMakeLists.txt
./doc
./hpp-fclConfig.cmake
./include
./package.xml
./python
./src
./test
];
};
});
};
};
};
}
# This file provide bacward compatiblity for `find_package(hpp-fcl)`.
message(WARNING "Please update your CMake from 'hpp-fcl' to 'coal'")
find_package(coal REQUIRED)
if(NOT TARGET hpp-fcl::hpp-fcl)
add_library(hpp-fcl::hpp-fcl INTERFACE IMPORTED)
# Compute the installation prefix relative to this file.
# This code is taken from generated cmake xxxTargets.cmake.
get_filename_component(_IMPORT_PREFIX "${CMAKE_CURRENT_LIST_FILE}" PATH)
get_filename_component(_IMPORT_PREFIX "${_IMPORT_PREFIX}" PATH)
get_filename_component(_IMPORT_PREFIX "${_IMPORT_PREFIX}" PATH)
get_filename_component(_IMPORT_PREFIX "${_IMPORT_PREFIX}" PATH)
if(_IMPORT_PREFIX STREQUAL "/")
set(_IMPORT_PREFIX "")
endif()
set_target_properties(
hpp-fcl::hpp-fcl
PROPERTIES INTERFACE_COMPILE_DEFINITIONS
"COAL_BACKWARD_COMPATIBILITY_WITH_HPP_FCL"
INTERFACE_INCLUDE_DIRECTORIES "${_IMPORT_PREFIX}/include"
INTERFACE_LINK_LIBRARIES "coal::coal")
endif()