Go to the documentation of this file.
5 #ifndef __pinocchio_algorithm_frames_hpp__
6 #define __pinocchio_algorithm_frames_hpp__
24 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
26 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
27 DataTpl<Scalar, Options, JointCollectionTpl> &
data);
40 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
42 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
43 DataTpl<Scalar, Options, JointCollectionTpl> &
data,
60 template<
typename,
int>
class JointCollectionTpl,
61 typename ConfigVectorType>
63 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
64 DataTpl<Scalar, Options, JointCollectionTpl> &
data,
65 const Eigen::MatrixBase<ConfigVectorType> &
q);
83 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
85 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
86 const DataTpl<Scalar, Options, JointCollectionTpl> &
data,
88 const SE3Tpl<Scalar, Options> &
placement,
106 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
135 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
137 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
138 const DataTpl<Scalar, Options, JointCollectionTpl> &
data,
140 const SE3Tpl<Scalar, Options> &
placement,
164 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
193 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
195 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
196 const DataTpl<Scalar, Options, JointCollectionTpl> &
data,
198 const SE3Tpl<Scalar, Options> &
placement,
224 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
267 template<
typename,
int>
class JointCollectionTpl,
268 typename Matrix6xLike>
270 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
271 DataTpl<Scalar, Options, JointCollectionTpl> &
data,
273 const SE3Tpl<Scalar, Options> &
placement,
275 const Eigen::MatrixBase<Matrix6xLike> &
J);
301 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
309 typedef Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options>
Matrix6x;
346 template<
typename,
int>
class JointCollectionTpl,
347 typename Matrix6xLike>
353 const Eigen::MatrixBase<Matrix6xLike> &
J)
393 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
400 typedef Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options>
Matrix6x;
435 template<
typename,
int>
class JointCollectionTpl,
436 typename ConfigVectorType,
437 typename Matrix6xLike>
439 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
440 DataTpl<Scalar, Options, JointCollectionTpl> &
data,
441 const Eigen::MatrixBase<ConfigVectorType> &
q,
444 const Eigen::MatrixBase<Matrix6xLike> &
J);
473 template<
typename,
int>
class JointCollectionTpl,
474 typename ConfigVectorType,
475 typename Matrix6xLike>
479 const Eigen::MatrixBase<ConfigVectorType> &
q,
481 const Eigen::MatrixBase<Matrix6xLike> &
J)
508 template<
typename,
int>
class JointCollectionTpl,
509 typename Matrix6xLike>
511 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
512 DataTpl<Scalar, Options, JointCollectionTpl> &
data,
515 const Eigen::MatrixBase<Matrix6xLike> & dJ);
550 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
552 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
553 const DataTpl<Scalar, Options, JointCollectionTpl> &
data,
590 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
592 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
593 const DataTpl<Scalar, Options, JointCollectionTpl> &
data,
599 #include "pinocchio/algorithm/frames.hxx"
601 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
602 #include "pinocchio/algorithm/frames.txx"
603 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
605 #endif // ifndef __pinocchio_algorithm_frames_hpp__
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
Macro to check an assert-like condition and throw a std::invalid_argument exception (with a message) ...
void getFrameJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6xLike > &J)
Returns the jacobian of the frame given by its relative placement w.r.t. a joint frame,...
ReferenceFrame
Various conventions to express the velocity of a moving frame.
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
MotionTpl< Scalar, Options > getFrameVelocity(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame rf=LOCAL)
Returns the spatial velocity of the Frame expressed in the desired reference frame....
MotionTpl< Scalar, Options > getFrameClassicalAcceleration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame rf=LOCAL)
Returns the "classical" acceleration of the Frame expressed in the desired reference frame....
ForceTpl< Scalar, Options > computeSupportedForceByFrame(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id)
Computes the force supported by a specific frame (given by frame_id) expressed in the LOCAL frame....
void computeFrameJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const FrameIndex frameId, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6xLike > &J)
Computes the Jacobian of a specific Frame expressed in the desired reference_frame given as argument.
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
const MotionDense< Motion2 > const SE3Tpl< SE3Scalar, SE3Options > & placement
void updateFramePlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Updates the position of each frame contained in the model.
InertiaTpl< Scalar, Options > computeSupportedInertiaByFrame(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, bool with_subtree)
Compute the inertia supported by a specific frame (given by frame_id) expressed in the LOCAL frame....
void framesForwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
First calls the forwardKinematics on the model, then computes the placement of each frame....
FrameTpl< context::Scalar, context::Options > Frame
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Eigen::Matrix< double, 6, Eigen::Dynamic > Matrix6x
MotionTpl< Scalar, Options > getFrameAcceleration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame rf=LOCAL)
Returns the spatial acceleration of the Frame expressed in the desired reference frame....
void getFrameJacobianTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xLike > &dJ)
Computes the Jacobian time variation of a specific frame (given by frame_id) expressed either in the ...
const DataTpl< Scalar, Options, JointCollectionTpl >::SE3 & updateFramePlacement(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id)
Updates the placement of the given frame.
SE3Tpl< Scalar, Options > SE3
ModelTpl< context::Scalar, context::Options > Model
JointCollectionTpl & model
Main pinocchio namespace.
pinocchio
Author(s):
autogenerated on Mon Dec 16 2024 03:41:01