aligator  0.6.1
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
9namespace aligator {
10
11template <typename Scalar> struct FramePlacementDataTpl;
12
13template <typename _Scalar>
15public:
16 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
17 using Scalar = _Scalar;
20 using BaseData = StageFunctionDataTpl<Scalar>;
21 using Model = pinocchio::ModelTpl<Scalar>;
22 using ManifoldPtr = shared_ptr<ManifoldAbstractTpl<Scalar>>;
23 using SE3 = pinocchio::SE3Tpl<Scalar>;
24 using Data = FramePlacementDataTpl<Scalar>;
25
26 shared_ptr<Model> pin_model_;
27
28 FramePlacementResidualTpl(const int ndx, const int nu,
29 const shared_ptr<Model> &model, const SE3 &frame,
30 const pinocchio::FrameIndex frame_id)
31 : Base(ndx, nu, 6), pin_model_(model), p_ref_(frame),
32 p_ref_inverse_(frame.inverse()) {
33 pin_frame_id_ = frame_id;
34 }
35
36 const SE3 &getReference() const { return p_ref_; }
37 void setReference(const SE3 &p_new) {
38 p_ref_ = p_new;
39 p_ref_inverse_ = p_new.inverse();
40 }
41
42 void evaluate(const ConstVectorRef &x, BaseData &data) const;
43
44 void computeJacobians(const ConstVectorRef &x, BaseData &data) const;
45
46 shared_ptr<BaseData> createData() const {
47 return allocate_shared_eigen_aligned<Data>(*this);
48 }
49
50protected:
53};
54
55template <typename Scalar>
57 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
58 using Base = StageFunctionDataTpl<Scalar>;
59 using PinData = pinocchio::DataTpl<Scalar>;
60 using SE3 = pinocchio::SE3Tpl<Scalar>;
61
67 typename math_types<Scalar>::Matrix6s rJf_;
69 typename math_types<Scalar>::Matrix6Xs fJf_;
70
71 FramePlacementDataTpl(const FramePlacementResidualTpl<Scalar> &model);
72};
73
74} // namespace aligator
75
76#include "aligator/modelling/multibody/frame-placement.hxx"
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
void evaluate(const ConstVectorRef &x, BaseData &data) const
void computeJacobians(const ConstVectorRef &x, BaseData &data) const
FramePlacementDataTpl< Scalar > Data
shared_ptr< ManifoldAbstractTpl< Scalar > > ManifoldPtr
pinocchio::ModelTpl< Scalar > Model
shared_ptr< BaseData > createData() const
Instantiate a Data object.
FramePlacementResidualTpl(const int ndx, const int nu, const shared_ptr< Model > &model, const SE3 &frame, const pinocchio::FrameIndex frame_id)
pinocchio::SE3Tpl< Scalar > SE3
const int nu
Control dimension.
Represents unary functions of the form , with no control (or next-state) arguments.
pinocchio::FrameIndex pin_frame_id_
Definition fwd.hpp:12