Go to the documentation of this file.
9 #include <boost/python/tuple.hpp>
30 return bp::make_tuple(partial_dq, partial_dv);
47 return bp::make_tuple(v_partial_dq, v_partial_dv);
64 model,
data, jointId, rf, v_partial_dq, a_partial_dq, a_partial_dv, a_partial_da);
66 return bp::make_tuple(v_partial_dq, a_partial_dq, a_partial_dv, a_partial_da);
87 return bp::make_tuple(v_partial_dq, a_partial_dq, a_partial_dv, a_partial_da);
109 "computeForwardKinematicsDerivatives",
112 bp::args(
"model",
"data",
"q",
"v",
"a"),
113 "Computes all the terms required to compute the derivatives of the placement, "
114 "spatial velocity and acceleration\n"
115 "for any joint of the model.\n"
116 "The results are stored in data.\n\n"
118 "\tmodel: model of the kinematic tree\n"
119 "\tdata: data related to the model\n"
120 "\tq: the joint configuration vector (size model.nq)\n"
121 "\tv: the joint velocity vector (size model.nv)\n"
122 "\ta: the joint acceleration vector (size model.nv)\n");
126 bp::args(
"model",
"data",
"joint_id",
"reference_frame"),
127 "Computes the partial derivatives of the spatial velocity of a given joint with respect "
129 "the joint configuration and velocity and returns them as a tuple.\n"
130 "The partial derivatives can be either expressed in the LOCAL frame of the joint, in the "
131 "LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of "
133 "You must first call computeForwardKinematicsDerivatives before calling this function.\n\n"
135 "\tmodel: model of the kinematic tree\n"
136 "\tdata: data related to the model\n"
137 "\tjoint_id: index of the joint\n"
138 "\treference_frame: reference frame in which the resulting derivatives are expressed\n");
142 bp::args(
"model",
"data",
"joint_id",
"placement",
"reference_frame"),
143 "Computes the partial derivatives of the velocity of a point given by its placement "
144 "information w.r.t. the joint frame and returns them as a tuple.\n"
145 "The partial derivatives can be either expressed in the LOCAL frame of the joint, in the "
146 "LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of "
148 "You must first call computeForwardKinematicsDerivatives before calling this function.\n\n"
150 "\tmodel: model of the kinematic tree\n"
151 "\tdata: data related to the model\n"
152 "\tjoint_id: index of the joint\n"
153 "\tplacement: relative placement of the point w.r.t. the joint frame\n"
154 "\treference_frame: reference frame in which the resulting derivatives are expressed\n");
158 bp::args(
"model",
"data",
"joint_id",
"placement",
"reference_frame"),
159 "Computes the partial derivatives of the classic acceleration of a point given by its "
160 "placement information w.r.t. the joint frame and returns them as a tuple.\n"
161 "The partial derivatives can be either expressed in the LOCAL frame of the joint, in the "
162 "LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of "
164 "You must first call computeForwardKinematicsDerivatives before calling this function.\n\n"
166 "\tmodel: model of the kinematic tree\n"
167 "\tdata: data related to the model\n"
168 "\tjoint_id: index of the joint\n"
169 "\tplacement: relative placement of the point w.r.t. the joint frame\n"
170 "\treference_frame: reference frame in which the resulting derivatives are expressed\n");
174 bp::args(
"model",
"data",
"joint_id",
"reference_frame"),
175 "Computes the partial derivatives of the spatial acceleration of a given joint with "
177 "the joint configuration, velocity and acceleration and returns them as a tuple.\n"
178 "The partial derivatives can be either expressed in the LOCAL frame of the joint, in the "
179 "LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of "
181 "You must first call computeForwardKinematicsDerivatives before calling this function.\n\n"
183 "\tmodel: model of the kinematic tree\n"
184 "\tdata: data related to the model\n"
185 "\tjoint_id: index of the joint\n"
186 "\treference_frame: reference frame in which the resulting derivatives are expressed\n");
190 bp::args(
"model",
"data"),
191 "Computes the partial derivaties of the center of mass velocity with respect to\n"
192 "the joint configuration.\n"
193 "You must first call computeAllTerms(model,data,q,v) or centerOfMass(model,data,q,v) "
194 "before calling this function.\n\n"
196 "\tmodel: model of the kinematic tree\n"
197 "\tdata: data related to the model\n");
ReferenceFrame
Various conventions to express the velocity of a moving frame.
void getPointClassicAccelerationDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix3xOut1 > &v_point_partial_dq, const Eigen::MatrixBase< Matrix3xOut2 > &a_point_partial_dq, const Eigen::MatrixBase< Matrix3xOut3 > &a_point_partial_dv, const Eigen::MatrixBase< Matrix3xOut4 > &a_point_partial_da)
Computes the partial derivatives of the classic acceleration of a point given by its placement inform...
context::Data::Matrix3x getCoMVelocityDerivatives_proxy(const context::Model &model, context::Data &data)
bp::tuple getPointClassicAccelerationDerivatives_proxy(const context::Model &model, context::Data &data, const JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf)
context::VectorXs VectorXs
void getJointAccelerationDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &a_partial_dq, const Eigen::MatrixBase< Matrix6xOut3 > &a_partial_dv, const Eigen::MatrixBase< Matrix6xOut4 > &a_partial_da)
Computes the partial derivaties of the spatial acceleration of a given with respect to the joint conf...
void computeForwardKinematicsDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a)
Computes all the terms required to compute the derivatives of the placement, spatial velocity and acc...
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
const MotionDense< Motion2 > const SE3Tpl< SE3Scalar, SE3Options > & placement
Eigen::Matrix< Scalar, 3, Eigen::Dynamic, Options > Matrix3x
The 3d jacobian type (temporary)
void getJointVelocityDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &v_partial_dv)
Computes the partial derivaties of the spatial velocity of a given with respect to the joint configur...
bp::tuple getPointVelocityDerivatives_proxy(const context::Model &model, context::Data &data, const JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf)
void getCenterOfMassVelocityDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Matrix3xOut > &vcom_partial_dq)
Computes the partial derivatie of the center-of-mass velocity with respect to the joint configuration...
bp::tuple getJointVelocityDerivatives_proxy(const context::Model &model, context::Data &data, const JointIndex jointId, ReferenceFrame rf)
Eigen::Matrix< double, 6, Eigen::Dynamic > Matrix6x
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
void getPointVelocityDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix3xOut1 > &v_point_partial_dq, const Eigen::MatrixBase< Matrix3xOut2 > &v_point_partial_dv)
Computes the partial derivatives of the velocity of a point given by its placement information w....
Eigen::Matrix< Scalar, 3, Eigen::Dynamic, Options > Matrix3x
void exposeKinematicsDerivatives()
bp::tuple getJointAccelerationDerivatives_proxy(const context::Model &model, context::Data &data, const JointIndex jointId, ReferenceFrame rf)
PINOCCHIO_PYTHON_SCALAR_TYPE Scalar
JointCollectionTpl & model
Main pinocchio namespace.
pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:29