aligator  0.9.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
frame-placement.hpp
Go to the documentation of this file.
1#pragma once
2
4#include "./fwd.hpp"
5
6#include <pinocchio/multibody/model.hpp>
7#include <pinocchio/multibody/frame.hpp>
8
9#include <proxsuite-nlp/third-party/polymorphic_cxx14.hpp>
10
11namespace aligator {
12
13template <typename Scalar> struct FramePlacementDataTpl;
14
15template <typename _Scalar>
17public:
18 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
19 using Scalar = _Scalar;
23 using Model = pinocchio::ModelTpl<Scalar>;
24 using PolyManifold = xyz::polymorphic<ManifoldAbstractTpl<Scalar>>;
25 using SE3 = pinocchio::SE3Tpl<Scalar>;
27
29
30 FramePlacementResidualTpl(const int ndx, const int nu, const Model &model,
31 const SE3 &frame,
32 const pinocchio::FrameIndex frame_id)
33 : Base(ndx, nu, 6), pin_model_(model), p_ref_(frame),
34 p_ref_inverse_(frame.inverse()) {
35 pin_frame_id_ = frame_id;
36 }
37
38 const SE3 &getReference() const { return p_ref_; }
39 void setReference(const SE3 &p_new) {
40 p_ref_ = p_new;
41 p_ref_inverse_ = p_new.inverse();
42 }
43
44 void evaluate(const ConstVectorRef &x, BaseData &data) const;
45
46 void computeJacobians(const ConstVectorRef &x, BaseData &data) const;
47
48 shared_ptr<BaseData> createData() const {
49 return std::make_shared<Data>(*this);
50 }
51
52protected:
55};
56
57template <typename Scalar>
59 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
61 using PinData = pinocchio::DataTpl<Scalar>;
62 using SE3 = pinocchio::SE3Tpl<Scalar>;
63
69 typename math_types<Scalar>::Matrix6s rJf_;
71 typename math_types<Scalar>::Matrix6Xs fJf_;
72
74};
75
76} // namespace aligator
77
78#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
79#include "aligator/modelling/multibody/frame-placement.txx"
80#endif
Main package namespace.
pinocchio::DataTpl< Scalar > PinData
FramePlacementDataTpl(const FramePlacementResidualTpl< Scalar > &model)
math_types< Scalar >::Matrix6s rJf_
Jacobian of the error.
math_types< Scalar >::Matrix6Xs fJf_
Jacobian of the error, local frame.
SE3 rMf_
Placement error of the frame.
PinData pin_data_
Pinocchio data object.
pinocchio::SE3Tpl< Scalar > SE3
FramePlacementResidualTpl(const int ndx, const int nu, const Model &model, const SE3 &frame, const pinocchio::FrameIndex frame_id)
void evaluate(const ConstVectorRef &x, BaseData &data) const
void computeJacobians(const ConstVectorRef &x, BaseData &data) const
pinocchio::ModelTpl< Scalar > Model
xyz::polymorphic< ManifoldAbstractTpl< Scalar > > PolyManifold
shared_ptr< BaseData > createData() const
Instantiate a Data object.
pinocchio::SE3Tpl< Scalar > SE3
Base struct for function data.
Definition fwd.hpp:62
Represents unary functions of the form , with no control (or next-state) arguments.
Definition fwd.hpp:59
pinocchio::FrameIndex pin_frame_id_
Definition fwd.hpp:12