Skip to content

Commit 2af546b

Browse files
Mx7fSeanCurtis-TRI
authored andcommitted
Update README code snippets; reflects syntax changes. (#410)
* Update README code snippets; reflects syntax changes. The example code was based on syntax used in the pre-Eigen days.
1 parent 2112037 commit 2af546b

File tree

1 file changed

+32
-28
lines changed

1 file changed

+32
-28
lines changed

README.md

+32-28
Original file line numberDiff line numberDiff line change
@@ -50,45 +50,47 @@ Before starting the proximity computation, we need first to set the geometry and
5050

5151
```cpp
5252
// set mesh triangles and vertice indices
53-
std::vector<Vec3f> vertices;
53+
std::vector<Vector3f> vertices;
5454
std::vector<Triangle> triangles;
5555
// code to set the vertices and triangles
5656
...
5757
// BVHModel is a template class for mesh geometry, for default OBBRSS template is used
58-
typedef BVHModel<OBBRSS> Model;
59-
Model* model = new Model();
58+
typedef BVHModel<OBBRSSf> Model;
59+
std::shared_ptr<Model> geom = std::make_shared<Model>();
6060
// add the mesh data into the BVHModel structure
61-
model->beginModel();
62-
model->addSubModel(vertices, triangles);
63-
model->endModel();
61+
geom->beginModel();
62+
geom->addSubModel(vertices, triangles);
63+
geom->endModel();
6464
```
6565
6666
The transform of an object includes the rotation and translation:
6767
```cpp
6868
// R and T are the rotation matrix and translation vector
6969
Matrix3f R;
70-
Vec3f T;
70+
Vector3f T;
7171
// code for setting R and T
7272
...
7373
// transform is configured according to R and T
74-
Transform3f pose(R, T);
74+
Transform3f pose = Transform3f::Identity();
75+
pose.linear() = R;
76+
pose.translation() = T;
7577
```
7678

7779

7880
Given the geometry and the transform, we can also combine them together to obtain a collision object instance and here is an example:
7981
```cpp
8082
//geom and tf are the geometry and the transform of the object
81-
BVHModel<OBBRSS>* geom = ...
83+
std::shared_ptr<BVHModel<OBBRSSf>> geom = ...
8284
Transform3f tf = ...
8385
//Combine them together
84-
CollisionObject* obj = new CollisionObject(geom, tf);
86+
CollisionObjectf* obj = new CollisionObjectf(geom, tf);
8587
```
8688

8789
Once the objects are set, we can perform the proximity computation between them. All the proximity queries in FCL follow a common pipeline: first, set the query request data structure and then run the query function by using request as the input. The result is returned in a query result data structure. For example, for collision checking, we first set the CollisionRequest data structure, and then run the collision function:
8890
```cpp
8991
// Given two objects o1 and o2
90-
CollisionObject* o1 = ...
91-
CollisionObject* o2 = ...
92+
CollisionObjectf* o1 = ...
93+
CollisionObjectf* o2 = ...
9294
// set the collision request structure, here we just use the default setting
9395
CollisionRequest request;
9496
// result will be returned via the collision result structure
@@ -104,8 +106,8 @@ For distance computation, the pipeline is almost the same:
104106
105107
```cpp
106108
// Given two objects o1 and o2
107-
CollisionObject* o1 = ...
108-
CollisionObject* o2 = ...
109+
CollisionObjectf* o1 = ...
110+
CollisionObjectf* o2 = ...
109111
// set the distance request structure, here we just use the default setting
110112
DistanceRequest request;
111113
// result will be returned via the collision result structure
@@ -118,8 +120,8 @@ For continuous collision, FCL requires the goal transform to be provided (the in
118120

119121
```cpp
120122
// Given two objects o1 and o2
121-
CollisionObject* o1 = ...
122-
CollisionObject* o2 = ...
123+
CollisionObjectf* o1 = ...
124+
CollisionObjectf* o2 = ...
123125
// The goal transforms for o1 and o2
124126
Transform3f tf_goal_o1 = ...
125127
Transform3f tf_goal_o2 = ...
@@ -136,41 +138,43 @@ FCL supports broadphase collision/distance between two groups of objects and can
136138
// Initialize the collision manager for the first group of objects.
137139
// FCL provides various different implementations of CollisionManager.
138140
// Generally, the DynamicAABBTreeCollisionManager would provide the best performance.
139-
BroadPhaseCollisionManager* manager1 = new DynamicAABBTreeCollisionManager();
141+
BroadPhaseCollisionManagerf* manager1 = new DynamicAABBTreeCollisionManagerf();
140142
// Initialize the collision manager for the second group of objects.
141-
BroadPhaseCollisionManager* manager2 = new DynamicAABBTreeCollisionManager();
143+
BroadPhaseCollisionManagerf* manager2 = new DynamicAABBTreeCollisionManagerf();
142144
// To add objects into the collision manager, using BroadPhaseCollisionManager::registerObject() function to add one object
143-
std::vector<CollisionObject*> objects1 = ...
145+
std::vector<CollisionObjectf*> objects1 = ...
144146
for(std::size_t i = 0; i < objects1.size(); ++i)
145147
manager1->registerObject(objects1[i]);
146148
// Another choose is to use BroadPhaseCollisionManager::registerObjects() function to add a set of objects
147-
std::vector<CollisionObject*> objects2 = ...
149+
std::vector<CollisionObjectf*> objects2 = ...
148150
manager2->registerObjects(objects2);
149151
// In order to collect the information during broadphase, CollisionManager requires two settings:
150152
// a) a callback to collision or distance;
151153
// b) an intermediate data to store the information generated during the broadphase computation
152-
// For a), FCL provides the default callbacks for both collision and distance.
153-
// For b), FCL uses the CollisionData structure for collision and DistanceData structure for distance. CollisionData/DistanceData is just a container including both the CollisionRequest/DistanceRequest and CollisionResult/DistanceResult structures mentioned above.
154+
// For a), FCL's test framework provides default callbacks for both collision and distance.
155+
// For b), FCL uses the CollisionData structure for collision and DistanceData structure for distance.
156+
// CollisionData/DistanceData is just a container from the test framework including both the
157+
// CollisionRequest/DistanceRequest and CollisionResult/DistanceResult structures mentioned above.
154158
CollisionData collision_data;
155159
DistanceData distance_data;
156160
// Setup the managers, which is related with initializing the broadphase acceleration structure according to objects input
157161
manager1->setup();
158162
manager2->setup();
159163
// Examples for various queries
160164
// 1. Collision query between two object groups and get collision numbers
161-
manager2->collide(manager1, &collision_data, defaultCollisionFunction);
165+
manager2->collide(manager1, &collision_data, test::defaultCollisionFunction);
162166
int n_contact_num = collision_data.result.numContacts();
163167
// 2. Distance query between two object groups and get the minimum distance
164-
manager2->distance(manager1, &distance_data, defaultDistanceFunction);
168+
manager2->distance(manager1, &distance_data, test::defaultDistanceFunction);
165169
double min_distance = distance_data.result.min_distance;
166170
// 3. Self collision query for group 1
167-
manager1->collide(&collision_data, defaultCollisionFunction);
171+
manager1->collide(&collision_data, test::defaultCollisionFunction);
168172
// 4. Self distance query for group 1
169-
manager1->distance(&distance_data, defaultDistanceFunction);
173+
manager1->distance(&distance_data, test::defaultDistanceFunction);
170174
// 5. Collision query between one object in group 1 and the entire group 2
171-
manager2->collide(objects1[0], &collision_data, defaultCollisionFunction);
175+
manager2->collide(objects1[0], &collision_data, test::defaultCollisionFunction);
172176
// 6. Distance query between one object in group 1 and the entire group 2
173-
manager2->distance(objects1[0], &distance_data, defaultDistanceFunction);
177+
manager2->distance(objects1[0], &distance_data, test::defaultDistanceFunction);
174178
```
175179

176180

0 commit comments

Comments
 (0)