Go to the documentation of this file.
   35 #define BOOST_TEST_MODULE COAL_SERIALIZATION 
   37 #include <boost/test/included/unit_test.hpp> 
   62 #ifdef COAL_HAS_OCTOMAP 
   67 #include "fcl_resources/config.h" 
   69 #include <boost/archive/tmpdir.hpp> 
   70 #include <boost/filesystem.hpp> 
   72 namespace utf = boost::unit_test::framework;
 
   77 bool check(
const T& value, 
const T& other) {
 
   78   return value == other;
 
   83   return *
value == *other;
 
   95           bool is_base = std::is_base_of<T, CollisionGeometry>::value>
 
   97   static void run(
const T&, T&, 
const int) {}
 
  100 template <
typename T>
 
  102   static void run(
const T& value, T& other_value, 
const int mode) {
 
  118         std::ofstream ofs(txt_filename.c_str());
 
  120         boost::archive::text_oarchive oa(ofs);
 
  127         std::ifstream ifs(txt_filename.c_str());
 
  128         boost::archive::text_iarchive ia(ifs);
 
  139 template <
typename T>
 
  145 template <
typename T>
 
  161       const std::string 
filename = txt_filename.string();
 
  171       std::stringstream ss_out;
 
  175       std::istringstream ss_in(ss_out.str());
 
  185       const std::string str_in(str_out);
 
  194       const std::string 
filename = xml_filename.string();
 
  195       const std::string xml_tag = 
"value";
 
  207       const std::string 
filename = bin_filename.string();
 
  219       boost::asio::streambuf buffer;
 
  231     std::shared_ptr<T> ptr = std::make_shared<T>(
value);
 
  233     const std::string 
filename = txt_ptr_filename.string();
 
  235     BOOST_CHECK(
check_ptr(ptr.get(), ptr.get()));
 
  237     std::shared_ptr<T> other_ptr = 
nullptr;
 
  239     BOOST_CHECK(
check_ptr(ptr.get(), other_ptr.get()));
 
  245 template <
typename T>
 
  253   AABB aabb(-Vec3s::Ones(), Vec3s::Ones());
 
  258   Contact contact(NULL, NULL, 1, 2, Vec3s::Ones(), Vec3s::Zero(), -10.);
 
  268   collision_result.
normal.setOnes();
 
  277   distance_result.
normal.setOnes();
 
  287     const Cylinder cylinder(radius, height);
 
  293     tf2.setTranslation(
Vec3s(0, 0, height / 2 - offset));
 
  295     const size_t num_max_contact = 1;
 
  305                                 patch_req, patch_res);
 
  318 template <
typename T>
 
  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]);
 
  329   std::vector<Vec3s> 
p1, p2;
 
  330   std::vector<Triangle> t1, 
t2;
 
  342   BOOST_CHECK(m1.
num_tris == t1.size());
 
  345   BOOST_CHECK(m1 == m1);
 
  354   BOOST_CHECK(m2 == m2);
 
  355   BOOST_CHECK(m1 != m2);
 
  368 #ifdef COAL_HAS_QHULL 
  370   std::vector<Vec3s> 
p1;
 
  371   std::vector<Triangle> t1;
 
  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";
 
  410     std::shared_ptr<CollisionGeometry> other_ptr = 
nullptr;
 
  411     BOOST_CHECK(!other_ptr.get());
 
  422   const Eigen::DenseIndex nx = 100, ny = 200;
 
  423   const MatrixXs heights = MatrixXs::Random(ny, nx);
 
  452     TriangleP triangle_copy(Vec3s::Random(), Vec3s::Random(), Vec3s::Random());
 
  458     box.setSweptSphereRadius(1.);
 
  459     box.computeLocalAABB();
 
  465     sphere.setSweptSphereRadius(1.);
 
  466     sphere.computeLocalAABB();
 
  471     Ellipsoid ellipsoid(1., 2., 3.), ellipsoid_copy(0., 0., 0.);
 
  472     ellipsoid.setSweptSphereRadius(1.);
 
  473     ellipsoid.computeLocalAABB();
 
  478     Capsule capsule(1., 2.), capsule_copy(10., 10.);
 
  479     capsule.setSweptSphereRadius(1.);
 
  480     capsule.computeLocalAABB();
 
  485     Cone cone(1., 2.), cone_copy(10., 10.);
 
  486     cone.setSweptSphereRadius(1.);
 
  487     cone.computeLocalAABB();
 
  492     Cylinder cylinder(1., 2.), cylinder_copy(10., 10.);
 
  493     cylinder.setSweptSphereRadius(1.);
 
  494     cylinder.computeLocalAABB();
 
  499     Halfspace hs(Vec3s::Random(), 1.), hs_copy(Vec3s::Zero(), 0.);
 
  500     hs.setSweptSphereRadius(1.);
 
  501     hs.computeLocalAABB();
 
  506     Plane plane(Vec3s::Random(), 1.), plane_copy(Vec3s::Zero(), 0.);
 
  507     plane.setSweptSphereRadius(1.);
 
  508     plane.computeLocalAABB();
 
  512 #ifdef HPP_FCL_HAS_QHULL 
  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());
 
  522     std::unique_ptr<Convex> convex =
 
  524             points, 
static_cast<unsigned int>(points->size()), 
true)));
 
  525     convex->setSweptSphereRadius(1.);
 
  526     convex->computeLocalAABB();
 
  534 #ifdef COAL_HAS_OCTOMAP 
  537   const MatrixX3s points = MatrixX3s::Random(1000, 3);
 
  546     std::ofstream ofs(bin_filename.c_str(), std::ios::binary);
 
  547     boost::archive::binary_oarchive oa(ofs);
 
  553     std::ifstream ifs(bin_filename.c_str(),
 
  554                       std::fstream::binary | std::fstream::in);
 
  555     boost::archive::binary_iarchive ia(ifs);
 
  561   BOOST_CHECK(octree_value.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);
 
  577   std::vector<Vec3s> 
p1;
 
  578   std::vector<Triangle> t1;
 
  592   BOOST_CHECK(
static_cast<size_t>(m1.
memUsage(
false)) ==
 
  
int beginModel(unsigned int num_tris=0, unsigned int num_vertices=0)
Begin a new BVH model.
void loadFromBinary(T &object, const std::string &filename)
Loads an object from a binary file.
void loadFromString(T &object, const std::string &str)
Loads an object from a std::string.
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
std::shared_ptr< std::vector< Vec3s > > vertices
Geometry point data.
int endModel()
End BVH model construction, will build the bounding volume hierarchy.
int memUsage(const bool msg) const
Check the number of memory used.
#define COAL_COMPILER_DIAGNOSTIC_PUSH
bool isCollision() const
return binary collision result
Half Space: this is equivalent to the Plane in ODE. A Half space has a priviledged direction: the dir...
void test_pointer_serialization(const T &value, T &other_value, const int mode=TXT|XML|BIN|STREAM)
Capsule It is  where  is the distance between the point x and the capsule segment AB,...
static void run(const T &value, T &other_value, const int mode)
BOOST_AUTO_TEST_CASE(test_aabb)
void test_serialization(const T *value, T &other_value, const int mode=TXT|XML|BIN|STREAM)
std::array< Vec3s, 2 > nearest_points
nearest points. A CollisionResult can have multiple contacts. The nearest points in CollisionResults ...
bool check_ptr(const T *value, const T *other)
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.
Ellipsoid centered at point zero.
int addSubModel(const std::vector< Vec3s > &ps, const std::vector< Triangle > &ts)
Add a set of triangles in the new BVH model.
The geometry for the object for collision or distance computation.
bool check(const T &value, const T &other)
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Infinite plane. A plane can be viewed as two half spaces; it has no priviledged direction....
CoalScalar distance_lower_bound
Center at zero point, axis aligned box.
Center at zero point sphere.
void loadFromText(T &object, const std::string &filename)
Loads an object from a TXT file.
void saveToXML(const T &object, const std::string &filename, const std::string &tag_name)
Saves an object inside a XML file.
request to the distance computation
void addContact(const Contact &c)
add one contact into result structure
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.
shared_ptr< ConvexBase > convex
Convex<Triangle> representation of this object.
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.
request to the collision algorithm
Cylinder along Z axis. The cylinder is defined at its centroid.
Eigen::Matrix< CoalScalar, Eigen::Dynamic, 3, Eigen::RowMajor > MatrixX3s
Data structure depicting a height field given by the base grid dimensions and the elevation along the...
void computeLocalAABB()
virtual function of compute AABB in local coordinate
Triangle stores the points instead of only indices of points.
void saveToText(const T &object, const std::string &filename)
Saves an object inside a TXT file.
bool buildConvexHull(bool keepTriangle, const char *qhullCommand=NULL)
Build a convex hull and store it in attribute convex.
Eigen::Matrix< CoalScalar, Eigen::Dynamic, Eigen::Dynamic > MatrixXs
shared_ptr< OcTree > OcTreePtr_t
Cone The base of the cone is at  and the top is at .
std::shared_ptr< std::vector< Triangle > > tri_indices
Geometry triangle index data, will be NULL for point clouds.
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
void saveToStringStream(const T &object, std::stringstream &ss)
Saves an object inside a std::stringstream.
Vec3s normal
normal associated to nearest_points. Same as CollisionResult::nearest_points but for the normal.
void saveToBinary(const T &object, const std::string &filename)
Saves an object inside a binary file.
void setSweptSphereRadius(CoalScalar radius)
Set radius of sphere swept around the shape. Must be >= 0.
#define COAL_COMPILER_DIAGNOSTIC_POP
void loadFromStringStream(T &object, std::istringstream &is)
Loads an object from a std::stringstream.
#define COAL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
unsigned int num_vertices
Number of points.
static void run(const T &, T &, const int)
std::string saveToString(const T &object)
Saves an object inside a std::string.
size_t computeMemoryFootprint(const T &object)
Returns the memory footpring of the input object. For POD objects, this function returns the result o...
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,...
unsigned int num_tris
Number of triangles.
void loadFromXML(T &object, const std::string &filename, const std::string &tag_name)
Loads an object from a XML file.
void checkEqualStdVector(const std::vector< T > &v1, const std::vector< T > &v2)
std::array< Vec3s, 2 > nearest_points
nearest points. See CollisionResult::nearest_points.
void saveToBuffer(const T &object, boost::asio::streambuf &buffer)
Saves an object to a binary buffer.
void loadFromBuffer(T &object, boost::asio::streambuf &buffer)
Loads an object from a binary buffer.
void loadOBJFile(const char *filename, std::vector< Vec3s > &points, std::vector< Triangle > &triangles)
Load an obj mesh file.
hpp-fcl
Author(s): 
autogenerated on Fri Feb 14 2025 03:45:51