Skip to content

Commit ff83249

Browse files
author
C. Andy Martin
authored
change contact, distance primitive id to intptr_t; add fcl::OcTree API to get info from opaque ids (#472)
* fix doxygen to examine conditional config includes Some includes only contain code when prerequisite libraries exist. For example, if FCL_HAVE_OCTOMAP is not nonzero, the OcTree class is not declared. These preprocessor macros are defined in the generated fcl/config.h. Doxygen was not configured to search for inclues in the generated include directory. Therefore Doxygen would never add documentation for OcTree. Fix this by adding the generated include path to DOXYGEN_INCLUDE_PATH, and actually have the Doxyfile.in make use of the DOXYGEN_INCLUDE_PATH by providing it as an environment variable to the doxygen tool. * change contact, distance primitive id to intptr_t The contact and distance result brief primitive information stored the brief information in an `int`. However, some primitive ids can only be stored by relative pointer (namely octree nodes), and `int` is not wide enough on 64-bit platforms to safely store a pointer. So upgrade the brief information to be `intptr_t` which is guaranteed to be wide enough. Also, provide a method, getNode, to make use of the query cell id returned for `fcl::OcTree` cells. For getNode to efficiently find the cell from the query cell id, it must be passed the contact point or nearest point returned by the query to work correctly. The getNode method returns a pointer to the corresponding OcTree node, and also optionally returns the AABB representing the cell, the octomap::OcTreeKey (which can be used with various octomap APIs) and the depth of the cell in the tree (which may also be needed when using octomap APIs). Refer the contact info and distance result documentation to the new getNode method for callers to know how to make use of these OcTree query cell ids. Add OcTree query cell id tests to test the new getNode method at the same time as testing the BVH mesh ids in test_fcl_octomap_collision.cpp.
1 parent 83a1af6 commit ff83249

File tree

7 files changed

+191
-18
lines changed

7 files changed

+191
-18
lines changed

doc/Doxyfile.in

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2037,7 +2037,7 @@ INCLUDE_FILE_PATTERNS =
20372037
# recursively expanded use the := operator instead of the = operator.
20382038
# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.
20392039

2040-
PREDEFINED = FCL_DOXYGEN_CXX=1
2040+
PREDEFINED = FCL_DOXYGEN_CXX=1 FCL_HAVE_OCTOMAP
20412041

20422042
# If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then this
20432043
# tag can be used to specify a list of macro names that should be expanded. The

include/fcl/common/types.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -60,6 +60,8 @@ using int64 = std::int64_t;
6060
using uint64 = std::uint64_t;
6161
using int32 = std::int32_t;
6262
using uint32 = std::uint32_t;
63+
using intptr_t = std::intptr_t;
64+
using uintptr_t = std::uintptr_t;
6365

6466
template <typename S>
6567
using Vector2 = Eigen::Matrix<S, 2, 1>;

include/fcl/geometry/octree/octree-inl.h

Lines changed: 80 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,8 @@
4242

4343
#include "fcl/config.h"
4444

45+
#include "fcl/geometry/shape/utility.h"
46+
4547
#if FCL_HAVE_OCTOMAP
4648

4749
namespace fcl
@@ -296,6 +298,84 @@ void computeChildBV(const AABB<S>& root_bv, unsigned int i, AABB<S>& child_bv)
296298
}
297299
}
298300

301+
//==============================================================================
302+
template <typename S>
303+
const typename OcTree<S>::OcTreeNode* OcTree<S>::getNodeByQueryCellId(
304+
intptr_t id,
305+
const Vector3<S>& point,
306+
AABB<S>* aabb,
307+
octomap::OcTreeKey* key,
308+
unsigned int* depth) const
309+
{
310+
octomap::OcTree::leaf_bbx_iterator it;
311+
if (!getOctomapIterator(id, point, &it))
312+
{
313+
return nullptr;
314+
}
315+
if (aabb != nullptr)
316+
{
317+
Vector3<S> center(it.getX(), it.getY(), it.getZ());
318+
double half_size = it.getSize() / 2.0;
319+
Vector3<S> half_extent(half_size, half_size, half_size);
320+
aabb->min_ = center - half_extent;
321+
aabb->max_ = center + half_extent;
322+
}
323+
if (key != nullptr)
324+
*key = it.getKey();
325+
if (depth != nullptr)
326+
*depth = it.getDepth();
327+
return &(*it);
328+
}
329+
330+
//==============================================================================
331+
template <typename S>
332+
bool OcTree<S>::getOctomapIterator(
333+
intptr_t id,
334+
const Vector3<S>& point,
335+
octomap::OcTree::leaf_bbx_iterator* out) const
336+
{
337+
assert(out != nullptr);
338+
// The octomap tree structure provides no way to find a node from its pointer
339+
// short of an exhaustive search. This could take a long time on a large
340+
// tree. Instead, require the user to supply the contact point or nearest
341+
// point returned by the query that also returned the id. Use the point to
342+
// create the bounds to search for the node pointer.
343+
const octomap::OcTreeKey point_key = tree->coordToKey(
344+
point[0], point[1], point[2]);
345+
// Set the min and max keys used for the bbx to the point key plus or minus
346+
// one (if not at the limits of the data type) so we are guaranteed to hit
347+
// the correct cell even when the point is on a boundary and rounds to the
348+
// wrong cell.
349+
octomap::OcTreeKey min_key, max_key;
350+
for (unsigned int i = 0; i < 3; ++i)
351+
{
352+
min_key[i] = (point_key[i] > std::numeric_limits<octomap::key_type>::min() ?
353+
point_key[i] - 1 : point_key[i]);
354+
max_key[i] = (point_key[i] < std::numeric_limits<octomap::key_type>::max() ?
355+
point_key[i] + 1 : point_key[i]);
356+
}
357+
octomap::OcTree::leaf_bbx_iterator it = tree->begin_leafs_bbx(
358+
min_key, max_key);
359+
const octomap::OcTree::leaf_bbx_iterator end = tree->end_leafs_bbx();
360+
const OcTreeNode* const node = getRoot() + id;
361+
// While it may appear like this loop could take forever, in reality it will
362+
// only take a few iterations. Octomap iterators use a fixed end iterator
363+
// (copied above), and we are guaranteed to get to the end iterator after
364+
// incrementing past the bounds of the octomap::OcTree::leaf_bbx_iterator.
365+
// Incrementing end will keep the iterator at end as well. This functionality
366+
// of octomap iterators is tested extensively in the octomap package tests.
367+
while (it != end)
368+
{
369+
if (node == &(*it))
370+
{
371+
*out = it;
372+
return true;
373+
}
374+
++it;
375+
}
376+
return false;
377+
}
378+
299379
} // namespace fcl
300380

301381
#endif

include/fcl/geometry/octree/octree.h

Lines changed: 52 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -47,13 +47,19 @@
4747

4848
#include <octomap/octomap.h>
4949
#include "fcl/math/bv/AABB.h"
50+
#include "fcl/geometry/shape/box.h"
5051
#include "fcl/narrowphase/collision_object.h"
5152

5253
namespace fcl
5354
{
5455

5556
/// @brief Octree is one type of collision geometry which can encode uncertainty
5657
/// information in the sensor data.
58+
///
59+
/// @note OcTree will only be declared if octomap was found when FCL was built.
60+
/// For any particular FCL install, FCL_HAVE_OCTOMAP will be set to 1 in
61+
/// fcl/config.h if and only if octomap was found. Doxygen documentation will
62+
/// be generated whether or not octomap was found.
5763
template <typename S>
5864
class FCL_EXPORT OcTree : public CollisionGeometry<S>
5965
{
@@ -131,6 +137,52 @@ class FCL_EXPORT OcTree : public CollisionGeometry<S>
131137

132138
/// @brief return node type, it is an octree
133139
NODE_TYPE getNodeType() const;
140+
141+
/// @brief Access the node and corresponding info by query cell id
142+
///
143+
/// The results of distance and collision queries include various pieces of
144+
/// information about the objects involved in the query (in DistanceResult
145+
/// and Contact, respectively). When an object in the query is an OcTree the
146+
/// corresponding member (b1 or b2) contains an opaque identifier refered to
147+
/// as the "query cell id" of the corresponding tree cell.
148+
///
149+
/// This method returns the node pointer of the given query cell id.
150+
/// In order to efficiently find the cell by its query cell id, the contact
151+
/// point or nearest point in or on the cell must be given. This method also
152+
/// provides optional access to properties of the OcTree cell associated
153+
/// with the cell.
154+
///
155+
/// If the given cell can not be found, nullptr is returned and no
156+
/// information is stored in the output pointer locations. This might happen
157+
/// if some other point not in or on the cell is provided or if given a stale
158+
/// or invalid query cell id.
159+
///
160+
/// @param[in] id The query cell id, as given in b1 or b2 in
161+
/// DistanceResult or Contact.
162+
/// @param[in] point A point in or on the given cell id, from DistanceResult
163+
/// or Contact.
164+
/// @param[out] aabb If valid, output pointer for the AABB of the cell.
165+
/// @param[out] key If valid, output pointer for the octomap::OcTreeKey of
166+
/// the cell.
167+
/// @param[out] depth If valid, output pointer for the tree depth of the
168+
/// cell.
169+
/// @return The node pointer for the given query cell id, or nullptr if not
170+
/// found.
171+
const OcTreeNode* getNodeByQueryCellId(
172+
intptr_t id,
173+
const Vector3<S>& point,
174+
AABB<S>* aabb = nullptr,
175+
octomap::OcTreeKey* key = nullptr,
176+
unsigned int* depth = nullptr) const;
177+
178+
private:
179+
// Get the leaf_bbx_iterator pointing to the given cell given a point on or
180+
// in the cell and the query id.
181+
// Returns true if the cell was found, and false otherwise.
182+
bool getOctomapIterator(
183+
intptr_t id,
184+
const Vector3<S>& point,
185+
octomap::OcTree::leaf_bbx_iterator* out) const;
134186
};
135187

136188
using OcTreef = OcTree<float>;

include/fcl/narrowphase/contact.h

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -56,14 +56,16 @@ struct FCL_EXPORT Contact
5656
/// @brief contact primitive in object 1
5757
/// if object 1 is mesh or point cloud, it is the triangle or point id
5858
/// if object 1 is geometry shape, it is NONE (-1),
59-
/// if object 1 is octree, it is the id of the cell
60-
int b1;
59+
/// if object 1 is octree, it is the query cell id (see
60+
/// OcTree::getNodeByQueryCellId)
61+
intptr_t b1;
6162

6263
/// @brief contact primitive in object 2
6364
/// if object 2 is mesh or point cloud, it is the triangle or point id
6465
/// if object 2 is geometry shape, it is NONE (-1),
65-
/// if object 2 is octree, it is the id of the cell
66-
int b2;
66+
/// if object 2 is octree, it is the query cell id (see
67+
/// OcTree::getNodeByQueryCellId)
68+
intptr_t b2;
6769

6870
/// @brief contact normal, pointing from o1 to o2
6971
Vector3<S> normal;

include/fcl/narrowphase/distance_result.h

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -77,14 +77,16 @@ struct FCL_EXPORT DistanceResult
7777
/// @brief information about the nearest point in object 1
7878
/// if object 1 is mesh or point cloud, it is the triangle or point id
7979
/// if object 1 is geometry shape, it is NONE (-1),
80-
/// if object 1 is octree, it is the id of the cell
81-
int b1;
80+
/// if object 1 is octree, it is the query cell id (see
81+
/// OcTree::getNodeByQueryCellId)
82+
intptr_t b1;
8283

8384
/// @brief information about the nearest point in object 2
8485
/// if object 2 is mesh or point cloud, it is the triangle or point id
8586
/// if object 2 is geometry shape, it is NONE (-1),
86-
/// if object 2 is octree, it is the id of the cell
87-
int b2;
87+
/// if object 2 is octree, it is the query cell id (see
88+
/// OcTree::getNodeByQueryCellId)
89+
intptr_t b2;
8890

8991
/// @brief invalid contact primitive information
9092
static const int NONE = -1;

test/test_fcl_octomap_collision.cpp

Lines changed: 44 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,11 @@ void octomap_collision_test(S env_scale, std::size_t env_size, bool exhaustive,
6161
/// @brief Octomap collision with an environment mesh with 3 * env_size objects, asserting that correct triangle ids
6262
/// are returned when performing collision tests
6363
template <typename S>
64-
void octomap_collision_test_mesh_triangle_id(S env_scale, std::size_t env_size, std::size_t num_max_contacts, double resolution = 0.1);
64+
void octomap_collision_test_contact_primitive_id(
65+
S env_scale,
66+
std::size_t env_size,
67+
std::size_t num_max_contacts,
68+
double resolution = 0.1);
6569

6670
template<typename BV>
6771
void octomap_collision_test_BVH(std::size_t n, bool exhaustive, double resolution = 0.1);
@@ -109,19 +113,19 @@ GTEST_TEST(FCL_OCTOMAP, test_octomap_collision_mesh)
109113
}
110114

111115
template <typename S>
112-
void test_octomap_collision_mesh_triangle_id()
116+
void test_octomap_collision_contact_primitive_id()
113117
{
114118
#ifdef NDEBUG
115-
octomap_collision_test_mesh_triangle_id<S>(1, 30, 100000);
119+
octomap_collision_test_contact_primitive_id<S>(1, 30, 100000);
116120
#else
117-
octomap_collision_test_mesh_triangle_id<S>(1, 10, 10000, 1.0);
121+
octomap_collision_test_contact_primitive_id<S>(1, 10, 10000, 1.0);
118122
#endif
119123
}
120124

121-
GTEST_TEST(FCL_OCTOMAP, test_octomap_collision_mesh_triangle_id)
125+
GTEST_TEST(FCL_OCTOMAP, test_octomap_collision_contact_primitive_id)
122126
{
123-
// test_octomap_collision_mesh_triangle_id<float>();
124-
test_octomap_collision_mesh_triangle_id<double>();
127+
// test_octomap_collision_contact_primitive_id<float>();
128+
test_octomap_collision_contact_primitive_id<double>();
125129
}
126130

127131
template <typename S>
@@ -329,12 +333,18 @@ void octomap_collision_test(S env_scale, std::size_t env_size, bool exhaustive,
329333
}
330334

331335
template <typename S>
332-
void octomap_collision_test_mesh_triangle_id(S env_scale, std::size_t env_size, std::size_t num_max_contacts, double resolution)
336+
void octomap_collision_test_contact_primitive_id(
337+
S env_scale,
338+
std::size_t env_size,
339+
std::size_t num_max_contacts,
340+
double resolution)
333341
{
334342
std::vector<CollisionObject<S>*> env;
335343
test::generateEnvironmentsMesh(env, env_scale, env_size);
336344

337-
OcTree<S>* tree = new OcTree<S>(std::shared_ptr<const octomap::OcTree>(test::generateOcTree(resolution)));
345+
std::shared_ptr<const octomap::OcTree> octree(
346+
test::generateOcTree(resolution));
347+
OcTree<S>* tree = new OcTree<S>(octree);
338348
CollisionObject<S> tree_obj((std::shared_ptr<CollisionGeometry<S>>(tree)));
339349

340350
std::vector<CollisionObject<S>*> boxes;
@@ -348,6 +358,31 @@ void octomap_collision_test_mesh_triangle_id(S env_scale, std::size_t env_size,
348358
for(std::size_t index=0; index<cResult.numContacts(); ++index)
349359
{
350360
const Contact<S>& contact = cResult.getContact(index);
361+
362+
const fcl::OcTree<S>* contact_tree = static_cast<const fcl::OcTree<S>*>(
363+
contact.o1);
364+
fcl::AABB<S> aabb;
365+
octomap::OcTreeKey key;
366+
unsigned int depth;
367+
auto get_node_rv = contact_tree->getNodeByQueryCellId(
368+
contact.b1,
369+
contact.pos,
370+
&aabb,
371+
&key,
372+
&depth);
373+
EXPECT_TRUE(get_node_rv != nullptr);
374+
auto center_octomap_point = octree->keyToCoord(key);
375+
double cell_size = octree->getNodeSize(depth);
376+
for (unsigned i = 0; i < 3; ++i)
377+
{
378+
EXPECT_FLOAT_EQ(
379+
aabb.min_[i], center_octomap_point(i) - cell_size / 2.0);
380+
EXPECT_FLOAT_EQ(
381+
aabb.max_[i], center_octomap_point(i) + cell_size / 2.0);
382+
}
383+
auto octree_node = octree->search(key, depth);
384+
EXPECT_TRUE(octree_node == get_node_rv);
385+
351386
const fcl::BVHModel<fcl::OBBRSS<S>>* surface = static_cast<const fcl::BVHModel<fcl::OBBRSS<S>>*> (contact.o2);
352387
EXPECT_TRUE(surface->num_tris > contact.b2);
353388
}

0 commit comments

Comments
 (0)