pinocchio  3.7.0
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
 
Loading...
Searching...
No Matches
frames.hpp
1//
2// Copyright (c) 2015-2020 CNRS INRIA
3//
4
5#ifndef __pinocchio_algorithm_frames_hpp__
6#define __pinocchio_algorithm_frames_hpp__
7
8#include "pinocchio/multibody/model.hpp"
9#include "pinocchio/multibody/data.hpp"
10
11namespace pinocchio
12{
13
24 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
28
40 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
44 const FrameIndex frame_id);
45
57 template<
58 typename Scalar,
59 int Options,
60 template<typename, int> class JointCollectionTpl,
61 typename ConfigVectorType>
65 const Eigen::MatrixBase<ConfigVectorType> & q);
66
83 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
87 const JointIndex joint_id,
88 const SE3Tpl<Scalar, Options> & placement,
89 const ReferenceFrame rf = LOCAL);
90
106 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
110 const FrameIndex frame_id,
111 const ReferenceFrame rf = LOCAL)
112 {
114 const typename Model::Frame & frame = model.frames[frame_id];
115
116 return getFrameVelocity(model, data, frame.parentJoint, frame.placement, rf);
117 }
118
135 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
139 const JointIndex joint_id,
140 const SE3Tpl<Scalar, Options> & placement,
141 const ReferenceFrame rf = LOCAL);
142
164 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
168 const FrameIndex frame_id,
169 const ReferenceFrame rf = LOCAL)
170 {
172 const typename Model::Frame & frame = model.frames[frame_id];
173 return getFrameAcceleration(model, data, frame.parentJoint, frame.placement, rf);
174 }
175
193 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
197 const JointIndex joint_id,
198 const SE3Tpl<Scalar, Options> & placement,
199 const ReferenceFrame rf = LOCAL);
200
224 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
228 const FrameIndex frame_id,
229 const ReferenceFrame rf = LOCAL)
230 {
232 const typename Model::Frame & frame = model.frames[frame_id];
233 return getFrameClassicalAcceleration(model, data, frame.parentJoint, frame.placement, rf);
234 }
235
264 template<
265 typename Scalar,
266 int Options,
267 template<typename, int> class JointCollectionTpl,
268 typename Matrix6xLike>
272 const JointIndex joint_id,
273 const SE3Tpl<Scalar, Options> & placement,
275 const Eigen::MatrixBase<Matrix6xLike> & J);
276
301 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
302 Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options> getFrameJacobian(
305 const JointIndex joint_id,
306 const SE3Tpl<Scalar, Options> & placement,
308 {
309 typedef Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options> Matrix6x;
310 Matrix6x res(Matrix6x::Zero(6, model.nv));
311
312 getFrameJacobian(model, data, joint_id, placement, reference_frame, res);
313 return res;
314 }
315
343 template<
344 typename Scalar,
345 int Options,
346 template<typename, int> class JointCollectionTpl,
347 typename Matrix6xLike>
348 inline void getFrameJacobian(
351 const FrameIndex frame_id,
353 const Eigen::MatrixBase<Matrix6xLike> & J)
354 {
355 PINOCCHIO_CHECK_INPUT_ARGUMENT(
356 frame_id < (FrameIndex)model.nframes, "The index of the Frame is outside the bounds.");
357
359 typedef typename Model::Frame Frame;
360
361 const Frame & frame = model.frames[frame_id];
362 data.oMf[frame_id] = data.oMi[frame.parentJoint] * frame.placement;
363
365 model, data, frame.parentJoint, frame.placement, reference_frame,
366 PINOCCHIO_EIGEN_CONST_CAST(Matrix6xLike, J));
367 }
368
393 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
394 Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options> getFrameJacobian(
397 const FrameIndex frame_id,
399 {
400 typedef Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options> Matrix6x;
401 Matrix6x res(Matrix6x::Zero(6, model.nv));
402
403 getFrameJacobian(model, data, frame_id, reference_frame, res);
404 return res;
405 }
406
431 template<
432 typename Scalar,
433 int Options,
434 template<typename, int> class JointCollectionTpl,
435 typename ConfigVectorType,
436 typename Matrix6xLike>
440 const Eigen::MatrixBase<ConfigVectorType> & q,
441 const FrameIndex frame_id,
443 const Eigen::MatrixBase<Matrix6xLike> & J);
444
469 template<
470 typename Scalar,
471 int Options,
472 template<typename, int> class JointCollectionTpl,
473 typename ConfigVectorType,
474 typename Matrix6xLike>
478 const Eigen::MatrixBase<ConfigVectorType> & q,
479 const FrameIndex frame_id,
480 const Eigen::MatrixBase<Matrix6xLike> & J)
481 {
483 model, data, q.derived(), frame_id, LOCAL, PINOCCHIO_EIGEN_CONST_CAST(Matrix6xLike, J));
484 }
485
504 template<
505 typename Scalar,
506 int Options,
507 template<typename, int> class JointCollectionTpl,
508 typename Matrix6xLike>
512 const FrameIndex frame_id,
513 const ReferenceFrame rf,
514 const Eigen::MatrixBase<Matrix6xLike> & dJ);
515
549 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
553 const FrameIndex frame_id,
554 bool with_subtree);
555
589 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
593 const FrameIndex frame_id);
594
595} // namespace pinocchio
596
597/* --- Details -------------------------------------------------------------------- */
598#include "pinocchio/algorithm/frames.hxx"
599
600#if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
601 #include "pinocchio/algorithm/frames.txx"
602#endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
603
604#endif // ifndef __pinocchio_algorithm_frames_hpp__
ReferenceFrame
Various conventions to express the velocity of a moving frame.
Definition fwd.hpp:47
@ LOCAL
Definition fwd.hpp:50
Main pinocchio namespace.
Definition treeview.dox:11
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.
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 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,...
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 ...
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....
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....
void updateFramePlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Updates the position of each frame contained in the model.
void computeFrameJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const FrameIndex frame_id, 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.
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....
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....
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....