Go to the documentation of this file.
5 #include <boost/python/tuple.hpp>
29 return bp::make_tuple(partial_dq, partial_dv);
46 return bp::make_tuple(partial_dq, partial_dv);
63 model,
data,
frame_id, rf, v_partial_dq, a_partial_dq, a_partial_dv, a_partial_da);
65 return bp::make_tuple(v_partial_dq, a_partial_dq, a_partial_dv, a_partial_da);
86 return bp::make_tuple(v_partial_dq, a_partial_dq, a_partial_dv, a_partial_da);
91 using namespace Eigen;
95 bp::args(
"model",
"data",
"frame_id",
"reference_frame"),
96 "Computes the partial derivatives of the spatial velocity of a given frame with respect "
98 "the joint configuration and velocity and returns them as a tuple.\n"
99 "The partial derivatives can be either expressed in the LOCAL frame of the joint, in the "
100 "LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of "
102 "You must first call computeForwardKinematicsDerivatives before calling this function.\n\n"
104 "\tmodel: model of the kinematic tree\n"
105 "\tdata: data related to the model\n"
106 "\tframe_id: index of the frame\n"
107 "\treference_frame: reference frame in which the resulting derivatives are expressed\n");
111 bp::args(
"model",
"data",
"joint_id",
"placement",
"reference_frame"),
112 "Computes the partial derivatives of the spatial velocity of a frame given by its relative "
113 "placement, with respect to\n"
114 "the joint configuration and velocity and returns them as a tuple.\n"
115 "The partial derivatives can be either expressed in the LOCAL frame of the joint, in the "
116 "LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of "
118 "You must first call computeForwardKinematicsDerivatives before calling this function.\n\n"
120 "\tmodel: model of the kinematic tree\n"
121 "\tdata: data related to the model\n"
122 "\tjoint_id: index of the joint\n"
123 "\tplacement: placement of the Frame w.r.t. the joint frame.\n"
124 "\treference_frame: reference frame in which the resulting derivatives are expressed\n");
128 bp::args(
"model",
"data",
"frame_id",
"reference_frame"),
129 "Computes the partial derivatives of the spatial acceleration of a given frame with "
131 "the joint configuration, velocity and acceleration and returns them as a tuple.\n"
132 "The partial derivatives can be either expressed in the LOCAL frame of the joint, in the "
133 "LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of "
135 "You must first call computeForwardKinematicsDerivatives before calling this function.\n\n"
137 "\tmodel: model of the kinematic tree\n"
138 "\tdata: data related to the model\n"
139 "\tframe_id: index of the frame\n"
140 "\treference_frame: reference frame in which the resulting derivatives are expressed\n");
144 bp::args(
"model",
"data",
"joint_id",
"placement",
"reference_frame"),
145 "Computes the partial derivatives of the spatial acceleration of a frame given by its "
146 "relative placement, with respect to\n"
147 "the joint configuration, velocity and acceleration and returns them as a tuple.\n"
148 "The partial derivatives can be either expressed in the LOCAL frame of the joint, in the "
149 "LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of "
151 "You must first call computeForwardKinematicsDerivatives before calling this function.\n\n"
153 "\tmodel: model of the kinematic tree\n"
154 "\tdata: data related to the model\n"
155 "\tjoint_id: index of the joint\n"
156 "\tplacement: placement of the Frame w.r.t. the joint frame.\n"
157 "\treference_frame: reference frame in which the resulting derivatives are expressed\n");
void getFrameAccelerationDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, 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 derivatives of the spatial acceleration of a frame given by its relative placeme...
ReferenceFrame
Various conventions to express the velocity of a moving frame.
bp::tuple getFrameAccelerationDerivatives_proxy2(const context::Model &model, context::Data &data, const context::Model::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf)
pinocchio::JointIndex JointIndex
const MotionDense< Motion2 > const SE3Tpl< SE3Scalar, SE3Options > & placement
void getFrameVelocityDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &v_partial_dv)
Computes the partial derivatives of the spatial velocity of a frame given by its relative placement,...
pinocchio::FrameIndex FrameIndex
bp::tuple getFrameAccelerationDerivatives_proxy1(const context::Model &model, context::Data &data, const context::Model::FrameIndex frame_id, ReferenceFrame rf)
Eigen::Matrix< double, 6, Eigen::Dynamic > Matrix6x
void exposeFramesDerivatives()
bp::tuple getFrameVelocityDerivatives_proxy1(const context::Model &model, context::Data &data, const context::Model::FrameIndex frame_id, ReferenceFrame rf)
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
JointCollectionTpl & model
Main pinocchio namespace.
bp::tuple getFrameVelocityDerivatives_proxy2(const context::Model &model, context::Data &data, const context::Model::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf)
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:43