aligator  0.14.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
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>;
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)
34 , pin_model_(model)
35 , p_ref_(frame)
36 , p_ref_inverse_(frame.inverse()) {
37 pin_frame_id_ = frame_id;
38 }
39
40 const SE3 &getReference() const { return p_ref_; }
41 void setReference(const SE3 &p_new) {
42 p_ref_ = p_new;
43 p_ref_inverse_ = p_new.inverse();
44 }
45
46 void evaluate(const ConstVectorRef &x, BaseData &data) const;
47
48 void computeJacobians(const ConstVectorRef &x, BaseData &data) const;
49
50 shared_ptr<BaseData> createData() const {
51 return std::make_shared<Data>(*this);
52 }
53
54protected:
57};
58
59template <typename Scalar>
61 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
63 using PinData = pinocchio::DataTpl<Scalar>;
64 using SE3 = pinocchio::SE3Tpl<Scalar>;
65
74
76};
77
78} // namespace aligator
79
80#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
81#include "aligator/modelling/multibody/frame-placement.txx"
82#endif
Main package namespace.
pinocchio::DataTpl< Scalar > PinData
FramePlacementDataTpl(const FramePlacementResidualTpl< Scalar > &model)
StageFunctionDataTpl< Scalar > Base
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
StageFunctionDataTpl< Scalar > BaseData
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
FramePlacementDataTpl< Scalar > Data
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.
StageFunctionDataTpl(const int ndx, const int nu, const int nr)
const int nu
Control dimension.
Represents unary functions of the form , with no control (or next-state) arguments.
StageFunctionTpl< Scalar > Base
pinocchio::FrameIndex pin_frame_id_
Definition fwd.hpp:12
Typedefs for math (Eigen vectors, matrices) depending on scalar type.
Definition math.hpp:100