5 #ifndef __pinocchio_algorithm_frames_hpp__ 6 #define __pinocchio_algorithm_frames_hpp__ 8 #include "pinocchio/multibody/model.hpp" 9 #include "pinocchio/multibody/data.hpp" 24 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
26 DataTpl<Scalar,Options,JointCollectionTpl> & data);
39 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
42 DataTpl<Scalar,Options,JointCollectionTpl> & data,
57 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType>
59 DataTpl<Scalar,Options,JointCollectionTpl> & data,
60 const Eigen::MatrixBase<ConfigVectorType> &
q);
74 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
96 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
116 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
137 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
164 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename Matrix6xLike>
169 const Eigen::MatrixBase<Matrix6xLike> &
J);
190 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType,
typename Matrix6xLike>
193 const Eigen::MatrixBase<ConfigVectorType> &
q,
196 const Eigen::MatrixBase<Matrix6xLike> & J);
217 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType,
typename Matrix6xLike>
220 const Eigen::MatrixBase<ConfigVectorType> & q,
222 const Eigen::MatrixBase<Matrix6xLike> & J)
233 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType,
typename Matrix6xLike>
237 const Eigen::MatrixBase<ConfigVectorType> & q,
239 const Eigen::MatrixBase<Matrix6xLike> & J)
259 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename Matrix6xLike>
264 const Eigen::MatrixBase<Matrix6xLike> & dJ);
269 #include "pinocchio/algorithm/frames.hxx" 271 #endif // ifndef __pinocchio_algorithm_frames_hpp__
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...
ReferenceFrame
List of Reference Frames supported by Pinocchio.
MotionTpl< Scalar, Options > getFrameVelocity(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf=LOCAL)
Returns the spatial velocity of the Frame expressed in the desired reference frame. You must first call pinocchio::forwardKinematics to update placement and velocity values in data structure.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
MotionTpl< Scalar, Options > getFrameAcceleration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf=LOCAL)
Returns the spatial acceleration of the Frame expressed in the desired reference frame. You must first call pinocchio::forwardKinematics to update placement, velocity and acceleration values in data structure.
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.
The LOCAL frame convention corresponds to the frame directly attached to the moving part (Joint...
Main pinocchio namespace.
PINOCCHIO_DEPRECATED void frameJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const FrameIndex frameId, const Eigen::MatrixBase< Matrix6xLike > &J)
This function is now deprecated and has been renamed computeFrameJacobian. This signature will be rem...
void updateFramePlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Updates the position of each frame contained in the model.
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 ...
void getFrameJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xLike > &J)
Returns the jacobian of the frame expressed either expressed in the LOCAL frame coordinate system or ...
JointCollectionTpl & model
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...
SE3Tpl< Scalar, Options > SE3
MotionTpl< Scalar, Options > getFrameClassicalAcceleration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf=LOCAL)
Returns the "classical" acceleration of the Frame expressed in the desired reference frame...