Go to the documentation of this file.
160 "updateFramePlacements", &updateFramePlacements<Scalar, Options, JointCollectionDefaultTpl>,
161 bp::args(
"model",
"data"),
162 "Computes the placements of all the operational frames according to the current "
163 "joint placement stored in data"
164 "and puts the results in data.");
167 "updateFramePlacement", &updateFramePlacement<Scalar, Options, JointCollectionDefaultTpl>,
168 bp::args(
"model",
"data",
"frame_id"),
169 "Computes the placement of the given operational frame (frame_id) according to the "
170 "current joint placement stored in data, stores the results in data and returns it.",
171 bp::return_value_policy<bp::return_by_value>());
175 (bp::arg(
"model"), bp::arg(
"data"), bp::arg(
"frame_id"),
176 bp::arg(
"reference_frame") =
LOCAL),
177 "Returns the spatial velocity of the frame expressed in the coordinate system given "
178 "by reference_frame.\n"
179 "forwardKinematics(model,data,q,v[,a]) should be called first to compute the joint "
180 "spatial velocity stored in data.v");
184 (bp::arg(
"model"), bp::arg(
"data"), bp::arg(
"joint_id"), bp::arg(
"placement"),
185 bp::arg(
"reference_frame") =
LOCAL),
186 "Returns the spatial velocity of the frame expressed in the coordinate system given "
187 "by reference_frame.\n"
188 "forwardKinematics(model,data,q,v[,a]) should be called first to compute the joint "
189 "spatial velocity stored in data.v");
193 (bp::arg(
"model"), bp::arg(
"data"), bp::arg(
"frame_id"),
194 bp::arg(
"reference_frame") =
LOCAL),
195 "Returns the spatial acceleration of the frame expressed in the coordinate system "
196 "given by reference_frame.\n"
197 "forwardKinematics(model,data,q,v,a) should be called first to compute the joint "
198 "spatial acceleration stored in data.a .");
202 (bp::arg(
"model"), bp::arg(
"data"), bp::arg(
"joint_id"), bp::arg(
"placement"),
203 bp::arg(
"reference_frame") =
LOCAL),
204 "Returns the spatial acceleration of the frame expressed in the coordinate system "
205 "given by reference_frame.\n"
206 "forwardKinematics(model,data,q,v,a) should be called first to compute the joint "
207 "spatial acceleration stored in data.a .");
211 (bp::arg(
"model"), bp::arg(
"data"), bp::arg(
"frame_id"),
212 bp::arg(
"reference_frame") =
LOCAL),
213 "Returns the \"classical\" acceleration of the frame expressed in the coordinate "
214 "system given by reference_frame.\n"
215 "forwardKinematics(model,data,q,v,a) should be called first to compute the joint "
216 "spatial acceleration stored in data.a .");
220 (bp::arg(
"model"), bp::arg(
"data"), bp::arg(
"joint_id"), bp::arg(
"placement"),
221 bp::arg(
"reference_frame") =
LOCAL),
222 "Returns the \"classical\" acceleration of the frame expressed in the coordinate "
223 "system given by reference_frame.\n"
224 "forwardKinematics(model,data,q,v,a) should be called first to compute the joint "
225 "spatial acceleration stored in data.a .");
228 "framesForwardKinematics",
229 &framesForwardKinematics<Scalar, Options, JointCollectionDefaultTpl, VectorXs>,
230 bp::args(
"model",
"data",
"q"),
231 "Calls first the forwardKinematics(model,data,q) and then update the Frame placement "
232 "quantities (data.oMf).");
235 "computeFrameJacobian",
239 bp::args(
"model",
"data",
"q",
"frame_id",
"reference_frame"),
240 "Computes the Jacobian of the frame given by its frame_id in the coordinate system "
241 "given by reference_frame.\n");
244 "computeFrameJacobian",
248 bp::args(
"model",
"data",
"q",
"frame_id"),
249 "Computes the Jacobian of the frame given by its frame_id.\n"
250 "The columns of the Jacobian are expressed in the coordinates system of the Frame itself.\n"
251 "In other words, the velocity of the frame vF expressed in the local coordinate is given "
253 "where v is the joint velocity.");
257 bp::args(
"model",
"data",
"frame_id",
"reference_frame"),
258 "Computes the Jacobian of the frame given by its ID either in the LOCAL, "
259 "LOCAL_WORLD_ALIGNED or the WORLD coordinates systems.\n"
260 "In other words, the velocity of the frame vF expressed in the reference frame is "
262 "where v is the joint velocity vector.\n"
263 "remarks: computeJointJacobians(model,data,q) must have been called first.");
267 bp::args(
"model",
"data",
"joint_id",
"placement",
"reference_frame"),
268 "Computes the Jacobian of the frame given by its placement with respect to the Joint "
269 "frame and expressed the solution either in the LOCAL, LOCAL_WORLD_ALIGNED or the "
270 "WORLD coordinates systems.\n"
271 "In other words, the velocity of the frame vF expressed in the reference frame is "
273 "where v is the joint velocity vector.\n\n"
274 "remarks: computeJointJacobians(model,data,q) must have been called first.");
278 bp::args(
"model",
"data",
"q",
"v",
"frame_id",
"reference_frame"),
279 "Computes the Jacobian Time Variation of the frame given by its frame_id either in "
280 "the reference frame provided by reference_frame.\n");
284 bp::args(
"model",
"data",
"frame_id",
"reference_frame"),
285 "Returns the Jacobian time variation of the frame given by its frame_id either in "
286 "the reference frame provided by reference_frame.\n"
287 "You have to call computeJointJacobiansTimeVariation(model,data,q,v) and "
288 "updateFramePlacements(model,data) first.");
291 "computeSupportedInertiaByFrame",
292 &computeSupportedInertiaByFrame<double, 0, JointCollectionDefaultTpl>,
293 bp::args(
"model",
"data",
"frame_id",
"with_subtree"),
294 "Computes the supported inertia by the frame (given by frame_id) and returns it.\n"
295 "The supported inertia corresponds to the sum of the inertias of all the child frames "
296 "(that belongs to the same joint body) and the child joints, if with_subtree=True.\n"
297 "You must first call pinocchio::forwardKinematics to update placement values in data "
301 "computeSupportedForceByFrame",
302 &computeSupportedForceByFrame<double, 0, JointCollectionDefaultTpl>,
303 bp::args(
"model",
"data",
"frame_id"),
304 "Computes the supported force of the frame (given by frame_id) and returns it.\n"
305 "The supported force corresponds to the sum of all the forces experienced after the "
307 "You must first call pinocchio::rnea to update placement values in data structure.");
static context::Data::Matrix6x get_frame_jacobian_time_variation_proxy(const context::Model &model, context::Data &data, context::Data::FrameIndex jointId, ReferenceFrame rf)
static context::Data::Matrix6x frame_jacobian_time_variation_proxy(const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, const context::Data::FrameIndex frame_id, const ReferenceFrame rf)
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,...
pinocchio::JointIndex JointIndex
static context::Data::Matrix6x get_frame_jacobian_proxy1(const context::Model &model, context::Data &data, const context::Data::FrameIndex frame_id, ReferenceFrame rf=LOCAL)
static context::Data::Motion get_frame_acceleration_proxy2(const context::Model &model, context::Data &data, const context::Data::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf=LOCAL)
ReferenceFrame
Various conventions to express the velocity of a moving 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....
static context::Data::Motion get_frame_velocity_proxy1(const context::Model &model, context::Data &data, const context::Data::FrameIndex frame_id, ReferenceFrame rf=LOCAL)
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....
pinocchio::FrameIndex FrameIndex
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobiansTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the full model Jacobian variations with respect to time. It corresponds to dJ/dt which depen...
static context::Data::Matrix6x get_frame_jacobian_proxy2(const context::Model &model, context::Data &data, const context::Data::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf=LOCAL)
context::VectorXs VectorXs
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.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
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.
static context::Data::Motion get_frame_classical_acceleration_proxy1(const context::Model &model, context::Data &data, const context::Data::FrameIndex frame_id, ReferenceFrame rf=LOCAL)
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
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 ...
static context::Data::Motion get_frame_velocity_proxy2(const context::Model &model, context::Data &data, const context::Data::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf=LOCAL)
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
static context::Data::Motion get_frame_classical_acceleration_proxy2(const context::Model &model, context::Data &data, const context::Data::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf=LOCAL)
static context::Data::Motion get_frame_acceleration_proxy1(const context::Model &model, context::Data &data, const context::Data::FrameIndex frame_id, ReferenceFrame rf=LOCAL)
static context::Data::Matrix6x compute_frame_jacobian_proxy(const context::Model &model, context::Data &data, const context::VectorXs &q, context::Data::FrameIndex frame_id)
PINOCCHIO_PYTHON_SCALAR_TYPE Scalar
JointCollectionTpl & model
Main pinocchio namespace.
pinocchio
Author(s):
autogenerated on Sun Dec 22 2024 03:41:09