5 #ifndef __pinocchio_multibody_model_serialization_hpp__     6 #define __pinocchio_multibody_model_serialization_hpp__     8 #include <boost/serialization/string.hpp>     9 #include <boost/serialization/variant.hpp>    10 #include <boost/serialization/vector.hpp>    11 #include <boost/serialization/map.hpp>    13 #include "pinocchio/serialization/fwd.hpp"    14 #include "pinocchio/serialization/aligned-vector.hpp"    15 #include "pinocchio/serialization/spatial.hpp"    16 #include "pinocchio/serialization/joints.hpp"    17 #include "pinocchio/serialization/frame.hpp"    23     template<
class Archive, 
typename Scalar, 
int Options, 
template<
typename,
int> 
class JointCollectionTpl>
    54       ar & 
make_nvp(
"inertias",model.inertias);
    55       ar & 
make_nvp(
"jointPlacements",model.jointPlacements);
    64 #endif // ifndef __pinocchio_multibody_model_serialization_hpp__ 
JointModelVector joints
Model of joint i, encapsulated in a JointModelAccessor. 
int njoints
Number of joints. 
std::vector< std::string > names
Name of joint i 
ConfigVectorType lowerPositionLimit
Lower joint configuration limit. 
FrameVector frames
Vector of operational frames registered on the model. 
void serialize(Archive &ar, hpp::fcl::AABB &aabb, const unsigned int)
std::vector< int > nvs
Dimension of the joint i tangent subspace. 
TangentVectorType rotorInertia
Vector of rotor inertia parameters. 
std::vector< IndexVector > subtrees
Vector of joint subtrees. subtree[j] corresponds to the subtree supported by the joint j...
ConfigVectorMap referenceConfigurations
Map of reference configurations, indexed by user given names. 
int nframes
Number of operational frames. 
std::string name
Model name;. 
TangentVectorType rotorGearRatio
Vector of rotor gear ratio parameters. 
std::vector< int > nqs
Dimension of the joint i configuration subspace. 
TangentVectorType friction
Vector of joint friction parameters. 
std::vector< int > idx_qs
Starting index of the joint i in the configuration space. 
int nbodies
Number of bodies. 
Motion gravity
Spatial gravity of the model. 
const nvp< typename pinocchio::container::aligned_vector< T >::vector_base > make_nvp(const char *name, pinocchio::container::aligned_vector< T > &t)
std::vector< int > idx_vs
Starting index of the joint i in the tangent configuration space. 
TangentVectorType effortLimit
Vector of maximal joint torques. 
TangentVectorType damping
Vector of joint damping parameters. 
std::vector< JointIndex > parents
Joint parent of joint i, denoted li (li==parents[i]). 
int nv
Dimension of the velocity vector space. 
TangentVectorType velocityLimit
Vector of maximal joint velocities. 
ConfigVectorType upperPositionLimit
Upper joint configuration limit. 
std::vector< IndexVector > supports
Vector of joint supports. supports[j] corresponds to the collection of all joints located on the path...
int nq
Dimension of the configuration vector representation.