 |
pinocchio
2.6.0
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
|
|
5 #ifndef __pinocchio_serialization_multibody_geometry_hpp__
6 #define __pinocchio_serialization_multibody_geometry_hpp__
8 #include <boost/serialization/vector.hpp>
9 #include <boost/serialization/map.hpp>
11 #ifdef PINOCCHIO_WITH_HPP_FCL
12 #define HPP_FCL_SKIP_EIGEN_BOOST_SERIALIZATION
13 #include <hpp/fcl/serialization/collision_data.h>
14 #undef HPP_FCL_SKIP_EIGEN_BOOST_SERIALIZATION
15 #endif // PINOCCHIO_WITH_HPP_FCL
17 #include "pinocchio/multibody/geometry.hpp"
18 #include "pinocchio/serialization/aligned-vector.hpp"
19 #include "pinocchio/serialization/spatial.hpp"
23 namespace serialization
25 template<
class Archive>
26 void serialize(Archive & ar,
30 ar & make_nvp(
"pair",base_object<pinocchio::CollisionPair::Base>(collision_pair));
33 template<
class Archive>
34 void serialize(Archive & ar,
38 ar & make_nvp(
"oMg",geom_data.oMg);
42 #ifdef PINOCCHIO_WITH_HPP_FCL
48 ar & make_nvp(
"radius",geom_data.
radius);
51 #endif // PINOCCHIO_WITH_HPP_FCL
60 #endif // ifndef __pinocchio_serialization_multibody_geometry_hpp__
std::vector< fcl::DistanceRequest > distanceRequests
Defines what information should be computed by distance computation. There is one request per pair of...
std::vector< bool > activeCollisionPairs
Vector of collision pairs.
PairIndex collisionPairIndex
Index of the collision pair.
std::vector< fcl::DistanceResult > distanceResults
Vector gathering the result of the distance computation for all the collision pairs.
std::vector< fcl::CollisionRequest > collisionRequests
Defines what information should be computed by collision test. There is one request per pair of geome...
std::vector< Scalar > radius
Radius of the bodies, i.e. distance of the further point of the geometry model attached to the body f...
std::map< JointIndex, GeomIndexList > outerObjects
A list of associated collision GeometryObjects to a given joint Id.
std::map< JointIndex, GeomIndexList > innerObjects
Map over vector GeomModel::geometryObjects, indexed by joints.
std::vector< fcl::CollisionResult > collisionResults
Vector gathering the result of the collision computation for all the collision pairs.