test/serialization.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021-2023 INRIA.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #define BOOST_TEST_MODULE COAL_SERIALIZATION
36 #include <fstream>
37 #include <boost/test/included/unit_test.hpp>
38 
39 #include "coal/fwd.hh"
40 
43 
44 #include "coal/collision.h"
45 
46 #include "coal/contact_patch.h"
47 #include "coal/distance.h"
48 #include "coal/BV/OBBRSS.h"
49 #include "coal/BVH/BVH_model.h"
50 
61 
62 #ifdef COAL_HAS_OCTOMAP
64 #endif
65 
66 #include "utility.h"
67 #include "fcl_resources/config.h"
68 
69 #include <boost/archive/tmpdir.hpp>
70 #include <boost/filesystem.hpp>
71 
72 namespace utf = boost::unit_test::framework;
73 
74 using namespace coal;
75 
76 template <typename T>
77 bool check(const T& value, const T& other) {
78  return value == other;
79 }
80 
81 template <typename T>
82 bool check_ptr(const T* value, const T* other) {
83  return *value == *other;
84 }
85 
86 enum SerializationMode { TXT = 1, XML = 2, BIN = 4, STREAM = 8 };
87 
88 template <typename T>
89 void test_serialization(const T* value, T& other_value,
90  const int mode = TXT | XML | BIN | STREAM) {
91  test_serialization(*value, other_value, mode);
92 }
93 
94 template <typename T,
95  bool is_base = std::is_base_of<T, CollisionGeometry>::value>
97  static void run(const T&, T&, const int) {}
98 };
99 
100 template <typename T>
102  static void run(const T& value, T& other_value, const int mode) {
103  const CollisionGeometry* ptr = &value;
104  CollisionGeometry* other_ptr = &other_value;
105 
106  const boost::filesystem::path tmp_path(boost::archive::tmpdir());
107  const boost::filesystem::path txt_path("file.txt");
108  const boost::filesystem::path txt_ptr_path("ptr_file.txt");
109  const boost::filesystem::path xml_path("file.xml");
110  const boost::filesystem::path bin_path("file.bin");
111  const boost::filesystem::path txt_filename(tmp_path / txt_path);
112  const boost::filesystem::path xml_filename(tmp_path / xml_path);
113  const boost::filesystem::path bin_filename(tmp_path / bin_path);
114 
115  // TXT
116  if (mode & 0x1) {
117  {
118  std::ofstream ofs(txt_filename.c_str());
119 
120  boost::archive::text_oarchive oa(ofs);
121  oa << ptr;
122  }
123  BOOST_CHECK(check(*reinterpret_cast<const CollisionGeometry*>(ptr),
124  *reinterpret_cast<const CollisionGeometry*>(ptr)));
125 
126  {
127  std::ifstream ifs(txt_filename.c_str());
128  boost::archive::text_iarchive ia(ifs);
129 
130  ia >> other_ptr;
131  }
132  BOOST_CHECK(
133  check(*reinterpret_cast<const CollisionGeometry*>(ptr),
134  *reinterpret_cast<const CollisionGeometry*>(other_ptr)));
135  }
136  }
137 };
138 
139 template <typename T>
140 void test_pointer_serialization(const T& value, T& other_value,
141  const int mode = TXT | XML | BIN | STREAM) {
143 }
144 
145 template <typename T>
146 void test_serialization(const T& value, T& other_value,
147  const int mode = TXT | XML | BIN | STREAM) {
148  const boost::filesystem::path tmp_path(boost::archive::tmpdir());
149  const boost::filesystem::path txt_path("file.txt");
150  const boost::filesystem::path txt_ptr_path("ptr_file.txt");
151  const boost::filesystem::path xml_path("file.xml");
152  const boost::filesystem::path bin_path("file.bin");
153  const boost::filesystem::path txt_filename(tmp_path / txt_path);
154  const boost::filesystem::path xml_filename(tmp_path / xml_path);
155  const boost::filesystem::path bin_filename(tmp_path / bin_path);
156 
157  // TXT
158  if (mode & 0x1) {
159  // -- TXT
160  {
161  const std::string filename = txt_filename.string();
163  BOOST_CHECK(check(value, value));
164 
166  BOOST_CHECK(check(value, other_value));
167  }
168 
169  // -- String stream (TXT format)
170  {
171  std::stringstream ss_out;
173  BOOST_CHECK(check(value, value));
174 
175  std::istringstream ss_in(ss_out.str());
176  coal::serialization::loadFromStringStream(other_value, ss_in);
177  BOOST_CHECK(check(value, other_value));
178  }
179 
180  // -- String
181  {
182  const std::string str_out = coal::serialization::saveToString(value);
183  BOOST_CHECK(check(value, value));
184 
185  const std::string str_in(str_out);
186  coal::serialization::loadFromString(other_value, str_in);
187  BOOST_CHECK(check(value, other_value));
188  }
189  }
190 
191  // XML
192  if (mode & 0x2) {
193  {
194  const std::string filename = xml_filename.string();
195  const std::string xml_tag = "value";
197  BOOST_CHECK(check(value, value));
198 
199  coal::serialization::loadFromXML(other_value, filename, xml_tag);
200  BOOST_CHECK(check(value, other_value));
201  }
202  }
203 
204  // BIN
205  if (mode & 0x4) {
206  {
207  const std::string filename = bin_filename.string();
209  BOOST_CHECK(check(value, value));
210 
212  BOOST_CHECK(check(value, other_value));
213  }
214  }
215 
216  // Stream Buffer
217  if (mode & 0x8) {
218  {
219  boost::asio::streambuf buffer;
221  BOOST_CHECK(check(value, value));
222 
223  coal::serialization::loadFromBuffer(other_value, buffer);
224  BOOST_CHECK(check(value, other_value));
225  }
226  }
227 
228  // Test std::shared_ptr<T>
229  {
230  const boost::filesystem::path txt_ptr_filename(tmp_path / txt_ptr_path);
231  std::shared_ptr<T> ptr = std::make_shared<T>(value);
232 
233  const std::string filename = txt_ptr_filename.string();
235  BOOST_CHECK(check_ptr(ptr.get(), ptr.get()));
236 
237  std::shared_ptr<T> other_ptr = nullptr;
239  BOOST_CHECK(check_ptr(ptr.get(), other_ptr.get()));
240  }
241 
242  test_pointer_serialization(value, other_value);
243 }
244 
245 template <typename T>
246 void test_serialization(const T& value,
247  const int mode = TXT | XML | BIN | STREAM) {
248  T other_value;
249  test_serialization(value, other_value, mode);
250 }
251 
253  AABB aabb(-Vec3s::Ones(), Vec3s::Ones());
254  test_serialization(aabb);
255 }
256 
257 BOOST_AUTO_TEST_CASE(test_collision_data) {
258  Contact contact(NULL, NULL, 1, 2, Vec3s::Ones(), Vec3s::Zero(), -10.);
259  test_serialization(contact);
260 
261  CollisionRequest collision_request(CONTACT, 10);
262  test_serialization(collision_request);
263 
264  CollisionResult collision_result;
265  collision_result.addContact(contact);
266  collision_result.addContact(contact);
267  collision_result.distance_lower_bound = 0.1;
268  collision_result.normal.setOnes();
269  collision_result.nearest_points[0].setRandom();
270  collision_result.nearest_points[1].setRandom();
271  test_serialization(collision_result);
272 
273  DistanceRequest distance_request(true, 1., 2.);
274  test_serialization(distance_request);
275 
276  DistanceResult distance_result;
277  distance_result.normal.setOnes();
278  distance_result.nearest_points[0].setRandom();
279  distance_result.nearest_points[1].setRandom();
280  test_serialization(distance_result);
281 
282  {
283  // Serializing contact patches.
284  const Halfspace hspace(0, 0, 1, 0);
285  const CoalScalar radius = 0.25;
286  const CoalScalar height = 1.;
287  const Cylinder cylinder(radius, height);
288 
289  const Transform3s tf1;
291  // set translation to have a collision
292  const CoalScalar offset = 0.001;
293  tf2.setTranslation(Vec3s(0, 0, height / 2 - offset));
294 
295  const size_t num_max_contact = 1;
297  num_max_contact);
298  CollisionResult col_res;
299  coal::collide(&hspace, tf1, &cylinder, tf2, col_req, col_res);
300  BOOST_CHECK(col_res.isCollision());
301  if (col_res.isCollision()) {
302  ContactPatchRequest patch_req;
303  ContactPatchResult patch_res(patch_req);
304  coal::computeContactPatch(&hspace, tf1, &cylinder, tf2, col_res,
305  patch_req, patch_res);
306  BOOST_CHECK(patch_res.numContactPatches() == 1);
307 
308  // Serialize patch request, result and the patch itself
309  test_serialization(patch_req);
310  test_serialization(patch_res);
311  if (patch_res.numContactPatches() > 0) {
312  test_serialization(patch_res.getContactPatch(0));
313  }
314  }
315  }
316 }
317 
318 template <typename T>
319 void checkEqualStdVector(const std::vector<T>& v1, const std::vector<T>& v2) {
320  BOOST_CHECK(v1.size() == v2.size());
321  if (v1.size() == v2.size()) {
322  for (size_t i = 0; i < v1.size(); i++) {
323  BOOST_CHECK(v1[i] == v2[i]);
324  }
325  }
326 }
327 
328 BOOST_AUTO_TEST_CASE(test_BVHModel) {
329  std::vector<Vec3s> p1, p2;
330  std::vector<Triangle> t1, t2;
331  boost::filesystem::path path(TEST_RESOURCES_DIR);
332 
333  loadOBJFile((path / "env.obj").string().c_str(), p1, t1);
334  loadOBJFile((path / "rob.obj").string().c_str(), p2, t2);
335 
336  BVHModel<OBBRSS> m1, m2;
337 
338  m1.beginModel();
339  m1.addSubModel(p1, t1);
340  m1.endModel();
341  BOOST_CHECK(m1.num_vertices == p1.size());
342  BOOST_CHECK(m1.num_tris == t1.size());
345  BOOST_CHECK(m1 == m1);
346 
347  m2.beginModel();
348  m2.addSubModel(p2, t2);
349  m2.endModel();
350  BOOST_CHECK(m2.num_vertices == p2.size());
351  BOOST_CHECK(m2.num_tris == t2.size());
352  checkEqualStdVector(*m2.vertices, p2);
354  BOOST_CHECK(m2 == m2);
355  BOOST_CHECK(m1 != m2);
356 
357  // Test BVHModel
358  {
359  BVHModel<OBBRSS> m1_copy;
360  test_serialization(m1, m1_copy);
361  }
362  {
363  BVHModel<OBBRSS> m1_copy;
364  test_serialization(m1, m1_copy, STREAM);
365  }
366 }
367 
368 #ifdef COAL_HAS_QHULL
369 BOOST_AUTO_TEST_CASE(test_Convex) {
370  std::vector<Vec3s> p1;
371  std::vector<Triangle> t1;
372  boost::filesystem::path path(TEST_RESOURCES_DIR);
373 
374  loadOBJFile((path / "env.obj").string().c_str(), p1, t1);
375 
376  BVHModel<OBBRSS> m1;
377 
378  m1.beginModel();
379  m1.addSubModel(p1, t1);
380  m1.endModel();
381 
382  m1.buildConvexHull(true);
383 
384  Convex<Triangle>& convex = static_cast<Convex<Triangle>&>(*m1.convex.get());
385 
386  // Test Convex
387  {
388  Convex<Triangle> convex_copy;
389  test_serialization(convex, convex_copy);
390  }
391 
392  // Test std::shared_ptr<CollisionGeometry>
393  {
394  const boost::filesystem::path tmp_dir(boost::archive::tmpdir());
395  // TODO(louis): understand why serializing a shared_ptr<CollisionGeometry>
396  // in TXT format fails only on MacOS + -O0.
397  // const boost::filesystem::path txt_filename = tmp_dir / "file.txt";
398  // const boost::filesystem::path bin_filename = tmp_dir / "file.bin";
399  const boost::filesystem::path xml_filename = tmp_dir / "file.xml";
400  Convex<Triangle> convex_copy;
401 
402  std::shared_ptr<CollisionGeometry> ptr =
403  std::make_shared<Convex<Triangle>>(convex);
404  BOOST_CHECK(ptr.get());
405  const std::string filename = xml_filename.string();
406  const std::string tag_name = "CollisionGeometry";
408  BOOST_CHECK(check(*reinterpret_cast<Convex<Triangle>*>(ptr.get()), convex));
409 
410  std::shared_ptr<CollisionGeometry> other_ptr = nullptr;
411  BOOST_CHECK(!other_ptr.get());
412  coal::serialization::loadFromXML(other_ptr, filename, tag_name);
413  BOOST_CHECK(
414  check(convex, *reinterpret_cast<Convex<Triangle>*>(other_ptr.get())));
415  }
416 }
417 #endif
418 
419 BOOST_AUTO_TEST_CASE(test_HeightField) {
420  const CoalScalar min_altitude = -1.;
421  const CoalScalar x_dim = 1., y_dim = 2.;
422  const Eigen::DenseIndex nx = 100, ny = 200;
423  const MatrixXs heights = MatrixXs::Random(ny, nx);
424 
425  HeightField<OBBRSS> hfield(x_dim, y_dim, heights, min_altitude);
426 
427  // Test HeightField
428  {
429  HeightField<OBBRSS> hfield_copy;
430  test_serialization(hfield, hfield_copy);
431  }
432  {
433  HeightField<OBBRSS> hfield_copy;
434  test_serialization(hfield, hfield_copy, STREAM);
435  }
436 }
437 
438 BOOST_AUTO_TEST_CASE(test_transform) {
439  Transform3s T;
440  T.setQuatRotation(Quaternion3f::UnitRandom());
441  T.setTranslation(Vec3s::Random());
442 
443  Transform3s T_copy;
444  test_serialization(T, T_copy);
445 }
446 
447 BOOST_AUTO_TEST_CASE(test_shapes) {
448  {
450  triangle.setSweptSphereRadius(1.);
451  triangle.computeLocalAABB();
452  TriangleP triangle_copy(Vec3s::Random(), Vec3s::Random(), Vec3s::Random());
453  test_serialization(triangle, triangle_copy);
454  }
455 
456  {
457  Box box(Vec3s::UnitX()), box_copy(Vec3s::Random());
458  box.setSweptSphereRadius(1.);
459  box.computeLocalAABB();
460  test_serialization(box, box_copy);
461  }
462 
463  {
464  Sphere sphere(1.), sphere_copy(2.);
465  sphere.setSweptSphereRadius(1.);
466  sphere.computeLocalAABB();
467  test_serialization(sphere, sphere_copy);
468  }
469 
470  {
471  Ellipsoid ellipsoid(1., 2., 3.), ellipsoid_copy(0., 0., 0.);
472  ellipsoid.setSweptSphereRadius(1.);
473  ellipsoid.computeLocalAABB();
474  test_serialization(ellipsoid, ellipsoid_copy);
475  }
476 
477  {
478  Capsule capsule(1., 2.), capsule_copy(10., 10.);
479  capsule.setSweptSphereRadius(1.);
480  capsule.computeLocalAABB();
481  test_serialization(capsule, capsule_copy);
482  }
483 
484  {
485  Cone cone(1., 2.), cone_copy(10., 10.);
486  cone.setSweptSphereRadius(1.);
487  cone.computeLocalAABB();
488  test_serialization(cone, cone_copy);
489  }
490 
491  {
492  Cylinder cylinder(1., 2.), cylinder_copy(10., 10.);
493  cylinder.setSweptSphereRadius(1.);
494  cylinder.computeLocalAABB();
495  test_serialization(cylinder, cylinder_copy);
496  }
497 
498  {
499  Halfspace hs(Vec3s::Random(), 1.), hs_copy(Vec3s::Zero(), 0.);
500  hs.setSweptSphereRadius(1.);
501  hs.computeLocalAABB();
502  test_serialization(hs, hs_copy);
503  }
504 
505  {
506  Plane plane(Vec3s::Random(), 1.), plane_copy(Vec3s::Zero(), 0.);
507  plane.setSweptSphereRadius(1.);
508  plane.computeLocalAABB();
509  test_serialization(plane, plane_copy);
510  }
511 
512 #ifdef HPP_FCL_HAS_QHULL
513  {
514  const size_t num_points = 500;
515  std::shared_ptr<std::vector<Vec3s>> points =
516  std::make_shared<std::vector<Vec3s>>();
517  points->reserve(num_points);
518  for (size_t i = 0; i < num_points; i++) {
519  points->emplace_back(Vec3s::Random());
520  }
521  using Convex = Convex<Triangle>;
522  std::unique_ptr<Convex> convex =
523  std::unique_ptr<Convex>(static_cast<Convex*>(ConvexBase::convexHull(
524  points, static_cast<unsigned int>(points->size()), true)));
525  convex->setSweptSphereRadius(1.);
526  convex->computeLocalAABB();
527 
528  Convex convex_copy;
529  test_serialization(*convex, convex_copy);
530  }
531 #endif
532 }
533 
534 #ifdef COAL_HAS_OCTOMAP
535 BOOST_AUTO_TEST_CASE(test_octree) {
536  const CoalScalar resolution = 1e-2;
537  const MatrixX3s points = MatrixX3s::Random(1000, 3);
538  OcTreePtr_t octree_ptr = makeOctree(points, resolution);
539  const OcTree& octree = *octree_ptr.get();
540 
541  const boost::filesystem::path tmp_dir(boost::archive::tmpdir());
542  const boost::filesystem::path txt_filename = tmp_dir / "file.txt";
543  const boost::filesystem::path bin_filename = tmp_dir / "file.bin";
544 
545  {
546  std::ofstream ofs(bin_filename.c_str(), std::ios::binary);
547  boost::archive::binary_oarchive oa(ofs);
548  oa << octree;
549  }
550 
551  OcTree octree_value(1.);
552  {
553  std::ifstream ifs(bin_filename.c_str(),
554  std::fstream::binary | std::fstream::in);
555  boost::archive::binary_iarchive ia(ifs);
556 
557  ia >> octree_value;
558  }
559 
560  BOOST_CHECK(octree.getTree() == octree.getTree());
561  BOOST_CHECK(octree_value.getTree() == octree_value.getTree());
562  // BOOST_CHECK(octree.getTree() == octree_value.getTree());
563  BOOST_CHECK(octree.getResolution() == octree_value.getResolution());
564  BOOST_CHECK(octree.getTree()->size() == octree_value.getTree()->size());
565  BOOST_CHECK(octree.toBoxes().size() == octree_value.toBoxes().size());
566  BOOST_CHECK(octree == octree_value);
567 
568  OcTree octree_copy(1.);
569  test_serialization(octree, octree_copy);
570 }
571 #endif
572 
573 BOOST_AUTO_TEST_CASE(test_memory_footprint) {
574  Sphere sphere(1.);
575  BOOST_CHECK(sizeof(Sphere) == computeMemoryFootprint(sphere));
576 
577  std::vector<Vec3s> p1;
578  std::vector<Triangle> t1;
579  boost::filesystem::path path(TEST_RESOURCES_DIR);
580 
581  loadOBJFile((path / "env.obj").string().c_str(), p1, t1);
582 
583  BVHModel<OBBRSS> m1;
584 
585  m1.beginModel();
586  m1.addSubModel(p1, t1);
587  m1.endModel();
588 
589  std::cout << "computeMemoryFootprint(m1): " << computeMemoryFootprint(m1)
590  << std::endl;
591  BOOST_CHECK(sizeof(BVHModel<OBBRSS>) < computeMemoryFootprint(m1));
592  BOOST_CHECK(static_cast<size_t>(m1.memUsage(false)) ==
594 }
595 
octree.h
STREAM
@ STREAM
Definition: test/serialization.cpp:86
memory.h
collision.h
coal::BVHModelBase::beginModel
int beginModel(unsigned int num_tris=0, unsigned int num_vertices=0)
Begin a new BVH model.
Definition: BVH_model.cpp:179
coal::CONTACT
@ CONTACT
Definition: coal/collision_data.h:305
coal::serialization::loadFromBinary
void loadFromBinary(T &object, const std::string &filename)
Loads an object from a binary file.
Definition: coal/serialization/archive.h:228
TXT
@ TXT
Definition: test/serialization.cpp:86
coal::serialization::loadFromString
void loadFromString(T &object, const std::string &str)
Loads an object from a std::string.
Definition: coal/serialization/archive.h:141
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
SerializationMode
SerializationMode
Definition: test/serialization.cpp:86
collision_manager.box
box
Definition: collision_manager.py:11
coal::BVHModelBase::vertices
std::shared_ptr< std::vector< Vec3s > > vertices
Geometry point data.
Definition: coal/BVH/BVH_model.h:68
coal::BVHModelBase::endModel
int endModel()
End BVH model construction, will build the bounding volume hierarchy.
Definition: BVH_model.cpp:507
coal::BVHModel::memUsage
int memUsage(const bool msg) const
Check the number of memory used.
Definition: BVH_model.cpp:840
hfield.h
COAL_COMPILER_DIAGNOSTIC_PUSH
#define COAL_COMPILER_DIAGNOSTIC_PUSH
Definition: include/coal/fwd.hh:120
coal::CollisionResult::isCollision
bool isCollision() const
return binary collision result
Definition: coal/collision_data.h:443
collision_manager.sphere
sphere
Definition: collision_manager.py:4
coal::Halfspace
Half Space: this is equivalent to the Plane in ODE. A Half space has a priviledged direction: the dir...
Definition: coal/shape/geometric_shapes.h:892
gjk.tf1
tuple tf1
Definition: test/scripts/gjk.py:27
test_pointer_serialization
void test_pointer_serialization(const T &value, T &other_value, const int mode=TXT|XML|BIN|STREAM)
Definition: test/serialization.cpp:140
AABB.h
coal::Capsule
Capsule It is where is the distance between the point x and the capsule segment AB,...
Definition: coal/shape/geometric_shapes.h:383
BVH_model.h
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
test_pointer_serialization_impl< T, true >::run
static void run(const T &value, T &other_value, const int mode)
Definition: test/serialization.cpp:102
coal::DistanceResult::normal
Vec3s normal
normal.
Definition: coal/collision_data.h:1061
coal::ContactPatchResult::numContactPatches
size_t numContactPatches() const
Number of contact patches in the result.
Definition: coal/collision_data.h:859
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(test_aabb)
Definition: test/serialization.cpp:252
utility.h
test_serialization
void test_serialization(const T *value, T &other_value, const int mode=TXT|XML|BIN|STREAM)
Definition: test/serialization.cpp:89
coal::CollisionResult::nearest_points
std::array< Vec3s, 2 > nearest_points
nearest points. A CollisionResult can have multiple contacts. The nearest points in CollisionResults ...
Definition: coal/collision_data.h:414
check_ptr
bool check_ptr(const T *value, const T *other)
Definition: test/serialization.cpp:82
coal::ContactPatchResult::getContactPatch
const ContactPatch & getContactPatch(const size_t i) const
Const getter for the i-th contact patch of the result.
Definition: coal/collision_data.h:882
octree
Definition: octree.py:1
coal::makeOctree
COAL_DLLAPI OcTreePtr_t makeOctree(const Eigen::Matrix< CoalScalar, Eigen::Dynamic, 3 > &point_cloud, const CoalScalar resolution)
Build an OcTree from a point cloud and a given resolution.
Definition: src/octree.cpp:188
coal::Ellipsoid
Ellipsoid centered at point zero.
Definition: coal/shape/geometric_shapes.h:305
coal::BVHModelBase::addSubModel
int addSubModel(const std::vector< Vec3s > &ps, const std::vector< Triangle > &ts)
Add a set of triangles in the new BVH model.
Definition: BVH_model.cpp:439
coal::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: coal/collision_object.h:94
check
bool check(const T &value, const T &other)
Definition: test/serialization.cpp:77
coal::AABB
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Definition: coal/BV/AABB.h:55
coal::Plane
Infinite plane. A plane can be viewed as two half spaces; it has no priviledged direction....
Definition: coal/shape/geometric_shapes.h:983
coal::CollisionResult::distance_lower_bound
CoalScalar distance_lower_bound
Definition: coal/collision_data.h:401
coal::Box
Center at zero point, axis aligned box.
Definition: coal/shape/geometric_shapes.h:166
coal::Sphere
Center at zero point sphere.
Definition: coal/shape/geometric_shapes.h:240
coal::serialization::loadFromText
void loadFromText(T &object, const std::string &filename)
Loads an object from a TXT file.
Definition: coal/serialization/archive.h:63
coal::Transform3s
Simple transform class used locally by InterpMotion.
Definition: coal/math/transform.h:55
coal::Transform3s::setQuatRotation
void setQuatRotation(const Quatf &q_)
set transform from rotation
Definition: coal/math/transform.h:148
coal::Transform3s::setTranslation
void setTranslation(const Eigen::MatrixBase< Derived > &T_)
set transform from translation
Definition: coal/math/transform.h:143
coal::serialization::saveToXML
void saveToXML(const T &object, const std::string &filename, const std::string &tag_name)
Saves an object inside a XML file.
Definition: coal/serialization/archive.h:202
coal::UnitZ
const Vec3s UnitZ
Definition: utility.cpp:90
contact_patch.h
BVH_model.h
coal::DistanceRequest
request to the distance computation
Definition: coal/collision_data.h:985
XML
@ XML
Definition: test/serialization.cpp:86
t2
dictionary t2
collision-bench.filename
filename
Definition: collision-bench.py:6
fwd.hh
coal::CollisionResult::addContact
void addContact(const Contact &c)
add one contact into result structure
Definition: coal/collision_data.h:431
coal::ConvexBase::convexHull
static ConvexBase * convexHull(std::shared_ptr< std::vector< Vec3s >> &points, unsigned int num_points, bool keepTriangles, const char *qhullCommand=NULL)
Build a convex hull based on Qhull library and store the vertices and optionally the triangles.
Definition: src/shape/convex.cpp:44
coal::BVHModelBase::convex
shared_ptr< ConvexBase > convex
Convex<Triangle> representation of this object.
Definition: coal/BVH/BVH_model.h:86
coal::CollisionResult
collision result
Definition: coal/collision_data.h:390
test_pointer_serialization_impl
Definition: test/serialization.cpp:96
coal::computeContactPatch
COAL_DLLAPI void computeContactPatch(const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const CollisionResult &collision_result, const ContactPatchRequest &request, ContactPatchResult &result)
Main contact patch computation interface.
Definition: src/contact_patch.cpp:47
coal::CollisionRequest
request to the collision algorithm
Definition: coal/collision_data.h:311
value
float value
archive.h
distance.h
coal::DistanceResult
distance result
Definition: coal/collision_data.h:1051
gjk.tf2
tuple tf2
Definition: test/scripts/gjk.py:36
coal::Convex
Convex polytope.
Definition: coal/serialization/collision_object.h:51
coal::UnitX
const Vec3s UnitX
Definition: utility.cpp:88
coal::Cylinder
Cylinder along Z axis. The cylinder is defined at its centroid.
Definition: coal/shape/geometric_shapes.h:560
coal::ContactPatchResult
Result for a contact patch computation.
Definition: coal/collision_data.h:822
coal::Contact
Contact information returned by collision.
Definition: coal/collision_data.h:58
coal::ContactPatchRequest
Request for a contact patch computation.
Definition: coal/collision_data.h:724
coal::MatrixX3s
Eigen::Matrix< CoalScalar, Eigen::Dynamic, 3, Eigen::RowMajor > MatrixX3s
Definition: coal/data_types.h:82
collision.path
path
Definition: scripts/collision.py:6
coal::HeightField
Data structure depicting a height field given by the base grid dimensions and the elevation along the...
Definition: coal/hfield.h:202
coal::TriangleP::computeLocalAABB
void computeLocalAABB()
virtual function of compute AABB in local coordinate
Definition: src/shape/geometric_shapes.cpp:243
octree.p1
tuple p1
Definition: octree.py:54
coal::TriangleP
Triangle stores the points instead of only indices of points.
Definition: coal/shape/geometric_shapes.h:110
coal::serialization::saveToText
void saveToText(const T &object, const std::string &filename)
Saves an object inside a TXT file.
Definition: coal/serialization/archive.h:87
coal::BVHModelBase::buildConvexHull
bool buildConvexHull(bool keepTriangle, const char *qhullCommand=NULL)
Build a convex hull and store it in attribute convex.
Definition: BVH_model.cpp:154
coal::MatrixXs
Eigen::Matrix< CoalScalar, Eigen::Dynamic, Eigen::Dynamic > MatrixXs
Definition: coal/data_types.h:86
coal::OcTreePtr_t
shared_ptr< OcTree > OcTreePtr_t
Definition: include/coal/fwd.hh:144
coal::Cone
Cone The base of the cone is at and the top is at .
Definition: coal/shape/geometric_shapes.h:467
collision_data.h
coal::BVHModelBase::tri_indices
std::shared_ptr< std::vector< Triangle > > tri_indices
Geometry triangle index data, will be NULL for point clouds.
Definition: coal/BVH/BVH_model.h:71
coal::BVHModel
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: coal/BVH/BVH_model.h:314
coal::OcTree
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
Definition: coal/octree.h:53
coal::serialization::saveToStringStream
void saveToStringStream(const T &object, std::stringstream &ss)
Saves an object inside a std::stringstream.
Definition: coal/serialization/archive.h:127
convex.h
x1
x1
contact_patch.h
coal::CollisionResult::normal
Vec3s normal
normal associated to nearest_points. Same as CollisionResult::nearest_points but for the normal.
Definition: coal/collision_data.h:405
coal::serialization::saveToBinary
void saveToBinary(const T &object, const std::string &filename)
Saves an object inside a binary file.
Definition: coal/serialization/archive.h:249
BIN
@ BIN
Definition: test/serialization.cpp:86
coal::ShapeBase::setSweptSphereRadius
void setSweptSphereRadius(CoalScalar radius)
Set radius of sphere swept around the shape. Must be >= 0.
Definition: coal/shape/geometric_shapes.h:76
COAL_COMPILER_DIAGNOSTIC_POP
#define COAL_COMPILER_DIAGNOSTIC_POP
Definition: include/coal/fwd.hh:121
OBBRSS.h
coal::serialization::loadFromStringStream
void loadFromStringStream(T &object, std::istringstream &is)
Loads an object from a std::stringstream.
Definition: coal/serialization/archive.h:109
COAL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
#define COAL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
Definition: include/coal/fwd.hh:122
coal::BVHModelBase::num_vertices
unsigned int num_vertices
Number of points.
Definition: coal/BVH/BVH_model.h:80
test_pointer_serialization_impl::run
static void run(const T &, T &, const int)
Definition: test/serialization.cpp:97
coal::UnitY
const Vec3s UnitY
Definition: utility.cpp:89
coal::serialization::saveToString
std::string saveToString(const T &object)
Saves an object inside a std::string.
Definition: coal/serialization/archive.h:156
coal::computeMemoryFootprint
size_t computeMemoryFootprint(const T &object)
Returns the memory footpring of the input object. For POD objects, this function returns the result o...
Definition: coal/serialization/memory.h:24
coal::collide
COAL_DLLAPI std::size_t collide(const CollisionObject *o1, const CollisionObject *o2, const CollisionRequest &request, CollisionResult &result)
Main collision interface: given two collision objects, and the requirements for contacts,...
Definition: src/collision.cpp:61
geometric_shapes.h
transform.h
coal::BVHModelBase::num_tris
unsigned int num_tris
Number of triangles.
Definition: coal/BVH/BVH_model.h:77
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::serialization::loadFromXML
void loadFromXML(T &object, const std::string &filename, const std::string &tag_name)
Loads an object from a XML file.
Definition: coal/serialization/archive.h:172
checkEqualStdVector
void checkEqualStdVector(const std::vector< T > &v1, const std::vector< T > &v2)
Definition: test/serialization.cpp:319
coal::DistanceResult::nearest_points
std::array< Vec3s, 2 > nearest_points
nearest points. See CollisionResult::nearest_points.
Definition: coal/collision_data.h:1065
coal::serialization::saveToBuffer
void saveToBuffer(const T &object, boost::asio::streambuf &buffer)
Saves an object to a binary buffer.
Definition: coal/serialization/archive.h:284
coal::serialization::loadFromBuffer
void loadFromBuffer(T &object, boost::asio::streambuf &buffer)
Loads an object from a binary buffer.
Definition: coal/serialization/archive.h:270
coal::loadOBJFile
void loadOBJFile(const char *filename, std::vector< Vec3s > &points, std::vector< Triangle > &triangles)
Load an obj mesh file.
Definition: utility.cpp:97


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:59