5 #ifndef __pinocchio_algorithm_model_hpp__ 6 #define __pinocchio_algorithm_model_hpp__ 8 #include "pinocchio/multibody/model.hpp" 9 #include "pinocchio/multibody/geometry.hpp" 23 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
25 appendModel(
const ModelTpl<Scalar,Options,JointCollectionTpl> & modelA,
26 const ModelTpl<Scalar,Options,JointCollectionTpl> & modelB,
28 const SE3Tpl<Scalar,Options> & aMb,
29 ModelTpl<Scalar,Options,JointCollectionTpl> &
model);
42 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
43 ModelTpl<Scalar,Options,JointCollectionTpl>
64 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
90 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType>
110 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType>
113 const std::vector<JointIndex> & list_of_joints_to_lock,
114 const Eigen::MatrixBase<ConfigVectorType> & reference_configuration)
119 buildReducedModel(model,list_of_joints_to_lock,reference_configuration,reduced_model);
121 return reduced_model;
138 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType>
142 const std::vector<JointIndex> & list_of_joints_to_lock,
143 const Eigen::MatrixBase<ConfigVectorType> & reference_configuration,
162 template <
typename,
int>
class JointCollectionTpl,
163 typename GeometryModelAllocator,
164 typename ConfigVectorType>
168 const std::vector<JointIndex> &list_of_joints_to_lock,
169 const Eigen::MatrixBase<ConfigVectorType> &reference_configuration,
171 std::vector<GeometryModel,GeometryModelAllocator> &list_of_reduced_geom_models);
175 #include "pinocchio/algorithm/model.hxx" 177 #endif // ifndef __pinocchio_algorithm_model_hpp__
void appendModel(const ModelTpl< Scalar, Options, JointCollectionTpl > &modelA, const ModelTpl< Scalar, Options, JointCollectionTpl > &modelB, const FrameIndex frameInModelA, const SE3Tpl< Scalar, Options > &aMb, ModelTpl< Scalar, Options, JointCollectionTpl > &model)
Append a child model into a parent model, after a specific frame given by its index.
Main pinocchio namespace.
JointCollectionTpl & model
void buildReducedModel(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, std::vector< JointIndex > list_of_joints_to_lock, const Eigen::MatrixBase< ConfigVectorType > &reference_configuration, ModelTpl< Scalar, Options, JointCollectionTpl > &reduced_model)
Build a reduced model from a given input model and a list of joint to lock.