4#include <pinocchio/multibody/model.hpp>
5#include <pinocchio/algorithm/joint-configuration.hpp>
17template <
typename _Scalar,
int _Options = 0>
24 using ModelType = pinocchio::ModelTpl<Scalar, Options>;
36 VectorXs
rand()
const {
return pinocchio::randomConfiguration(
model_); }
38 return pinocchio::isNormalized(
model_, x);
45 VectorRef xout)
const {
46 pinocchio::integrate(
model_, x, v, xout);
50 MatrixRef Jout,
int arg)
const {
53 pinocchio::dIntegrate(
model_, x, v, Jout, pinocchio::ARG0);
56 pinocchio::dIntegrate(
model_, x, v, Jout, pinocchio::ARG1);
62 MatrixRef Jout,
int arg)
const {
65 pinocchio::dIntegrateTransport(
model_, x, v, Jout, pinocchio::ARG0);
68 pinocchio::dIntegrateTransport(
model_, x, v, Jout, pinocchio::ARG1);
76 VectorRef vout)
const {
77 pinocchio::difference(
model_, x0, x1, vout);
81 MatrixRef Jout,
int arg)
const {
84 pinocchio::dDifference(
model_, x0, x1, Jout, pinocchio::ARG0);
87 pinocchio::dDifference(
model_, x0, x1, Jout, pinocchio::ARG1);
93 const Scalar &u, VectorRef out)
const {
94 pinocchio::interpolate(
model_, x0, x1, u, out);
112template <
typename Scalar,
int Options = 0>
131#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION
132#include "proxsuite-nlp/modelling/spaces/multibody.txx"
#define PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar)
Multibody configuration group , defined using the Pinocchio library.
MultibodyConfiguration(const MultibodyConfiguration &)=default
int ndx() const
Get manifold tangent space dimension.
static constexpr int Options
VectorXs neutral() const
Get the neutral element from the manifold (if this makes sense).
const ModelType & getModel() const
void interpolate_impl(const ConstVectorRef &x0, const ConstVectorRef &x1, const Scalar &u, VectorRef out) const
Interpolation operation.
void Jdifference_impl(const ConstVectorRef &x0, const ConstVectorRef &x1, MatrixRef Jout, int arg) const
MultibodyConfiguration & operator=(const MultibodyConfiguration &)=default
void integrate_impl(const ConstVectorRef &x, const ConstVectorRef &v, VectorRef xout) const
Perform the manifold integration operation.
void JintegrateTransport(const ConstVectorRef &x, const ConstVectorRef &v, MatrixRef Jout, int arg) const
Perform the parallel transport operation.
MultibodyConfiguration(const ModelType &model)
bool isNormalized(const ConstVectorRef &x) const
Check if the input vector x is a viable element of the manifold.
void Jintegrate_impl(const ConstVectorRef &x, const ConstVectorRef &v, MatrixRef Jout, int arg) const
MultibodyConfiguration(MultibodyConfiguration &&)=default
VectorXs rand() const
Sample a random point on the manifold.
void difference_impl(const ConstVectorRef &x0, const ConstVectorRef &x1, VectorRef vout) const
Implementation of the manifold retraction operation.
pinocchio::ModelTpl< Scalar, Options > ModelType
int nx() const
Get manifold representation dimension.
MultibodyConfiguration & operator=(MultibodyConfiguration &&)=default
The tangent bundle of a multibody configuration group.
MultibodyPhaseSpace & operator=(MultibodyPhaseSpace &&)=default
MultibodyPhaseSpace(MultibodyPhaseSpace &&)=default
MultibodyPhaseSpace(const ModelType &model)
const ModelType & getModel() const
MultibodyPhaseSpace & operator=(const MultibodyPhaseSpace &)=default
MultibodyPhaseSpace(const MultibodyPhaseSpace &)=default
typename ConfigSpace::ModelType ModelType
Tangent bundle of a base manifold M.
MultibodyConfiguration< Scalar, 0 > base_