expose-frames-derivatives.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2020 INRIA
3 //
4 
5 #include <boost/python/tuple.hpp>
6 
9 
10 namespace pinocchio
11 {
12  namespace python
13  {
14  namespace bp = boost::python;
15 
17  const context::Model & model,
20  ReferenceFrame rf)
21  {
23 
24  Matrix6x partial_dq(Matrix6x::Zero(6, model.nv));
25  Matrix6x partial_dv(Matrix6x::Zero(6, model.nv));
26 
27  getFrameVelocityDerivatives(model, data, frame_id, rf, partial_dq, partial_dv);
28 
29  return bp::make_tuple(partial_dq, partial_dv);
30  }
31 
33  const context::Model & model,
36  const context::SE3 & placement,
37  ReferenceFrame rf)
38  {
40 
41  Matrix6x partial_dq(Matrix6x::Zero(6, model.nv));
42  Matrix6x partial_dv(Matrix6x::Zero(6, model.nv));
43 
44  getFrameVelocityDerivatives(model, data, joint_id, placement, rf, partial_dq, partial_dv);
45 
46  return bp::make_tuple(partial_dq, partial_dv);
47  }
48 
50  const context::Model & model,
53  ReferenceFrame rf)
54  {
56 
57  Matrix6x v_partial_dq(Matrix6x::Zero(6, model.nv));
58  Matrix6x a_partial_dq(Matrix6x::Zero(6, model.nv));
59  Matrix6x a_partial_dv(Matrix6x::Zero(6, model.nv));
60  Matrix6x a_partial_da(Matrix6x::Zero(6, model.nv));
61 
63  model, data, frame_id, rf, v_partial_dq, a_partial_dq, a_partial_dv, a_partial_da);
64 
65  return bp::make_tuple(v_partial_dq, a_partial_dq, a_partial_dv, a_partial_da);
66  }
67 
69  const context::Model & model,
72  const context::SE3 & placement,
73  ReferenceFrame rf)
74  {
76 
77  Matrix6x v_partial_dq(Matrix6x::Zero(6, model.nv));
78  Matrix6x a_partial_dq(Matrix6x::Zero(6, model.nv));
79  Matrix6x a_partial_dv(Matrix6x::Zero(6, model.nv));
80  Matrix6x a_partial_da(Matrix6x::Zero(6, model.nv));
81 
83  model, data, joint_id, placement, rf, v_partial_dq, a_partial_dq, a_partial_dv,
84  a_partial_da);
85 
86  return bp::make_tuple(v_partial_dq, a_partial_dq, a_partial_dv, a_partial_da);
87  }
88 
90  {
91  using namespace Eigen;
92 
93  bp::def(
94  "getFrameVelocityDerivatives", getFrameVelocityDerivatives_proxy1,
95  bp::args("model", "data", "frame_id", "reference_frame"),
96  "Computes the partial derivatives of the spatial velocity of a given frame with respect "
97  "to\n"
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 "
101  "reference_frame.\n"
102  "You must first call computeForwardKinematicsDerivatives before calling this function.\n\n"
103  "Parameters:\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");
108 
109  bp::def(
110  "getFrameVelocityDerivatives", getFrameVelocityDerivatives_proxy2,
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 "
117  "reference_frame.\n"
118  "You must first call computeForwardKinematicsDerivatives before calling this function.\n\n"
119  "Parameters:\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");
125 
126  bp::def(
127  "getFrameAccelerationDerivatives", getFrameAccelerationDerivatives_proxy1,
128  bp::args("model", "data", "frame_id", "reference_frame"),
129  "Computes the partial derivatives of the spatial acceleration of a given frame with "
130  "respect to\n"
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 "
134  "reference_frame.\n"
135  "You must first call computeForwardKinematicsDerivatives before calling this function.\n\n"
136  "Parameters:\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");
141 
142  bp::def(
143  "getFrameAccelerationDerivatives", getFrameAccelerationDerivatives_proxy2,
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 "
150  "reference_frame.\n"
151  "You must first call computeForwardKinematicsDerivatives before calling this function.\n\n"
152  "Parameters:\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");
158  }
159 
160  } // namespace python
161 } // namespace pinocchio
boost::python
Eigen
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::getFrameAccelerationDerivatives
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...
pinocchio::ReferenceFrame
ReferenceFrame
Various conventions to express the velocity of a moving frame.
Definition: multibody/fwd.hpp:46
pinocchio::SE3Tpl< Scalar, Options >
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::python::getFrameAccelerationDerivatives_proxy2
bp::tuple getFrameAccelerationDerivatives_proxy2(const context::Model &model, context::Data &data, const context::Model::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf)
Definition: expose-frames-derivatives.cpp:68
pinocchio::ModelTpl::JointIndex
pinocchio::JointIndex JointIndex
Definition: multibody/model.hpp:68
pinocchio::placement
const MotionDense< Motion2 > const SE3Tpl< SE3Scalar, SE3Options > & placement
Definition: spatial/classic-acceleration.hpp:122
algorithms.hpp
python
pinocchio::getFrameVelocityDerivatives
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::ModelTpl::FrameIndex
pinocchio::FrameIndex FrameIndex
Definition: multibody/model.hpp:70
pinocchio::python::getFrameAccelerationDerivatives_proxy1
bp::tuple getFrameAccelerationDerivatives_proxy1(const context::Model &model, context::Data &data, const context::Model::FrameIndex frame_id, ReferenceFrame rf)
Definition: expose-frames-derivatives.cpp:49
contact-cholesky.frame_id
frame_id
Definition: contact-cholesky.py:22
Matrix6x
Eigen::Matrix< double, 6, Eigen::Dynamic > Matrix6x
Definition: joint-mimic.cpp:15
pinocchio::python::exposeFramesDerivatives
void exposeFramesDerivatives()
Definition: expose-frames-derivatives.cpp:89
pinocchio::python::getFrameVelocityDerivatives_proxy1
bp::tuple getFrameVelocityDerivatives_proxy1(const context::Model &model, context::Data &data, const context::Model::FrameIndex frame_id, ReferenceFrame rf)
Definition: expose-frames-derivatives.cpp:16
pinocchio::DataTpl::Matrix6x
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
Definition: multibody/data.hpp:91
append-urdf-model-with-another-model.joint_id
joint_id
Definition: append-urdf-model-with-another-model.py:34
pinocchio::ModelTpl
Definition: context/generic.hpp:20
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
frames-derivatives.hpp
pinocchio::python::getFrameVelocityDerivatives_proxy2
bp::tuple getFrameVelocityDerivatives_proxy2(const context::Model &model, context::Data &data, const context::Model::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf)
Definition: expose-frames-derivatives.cpp:32


pinocchio
Author(s):
autogenerated on Sat Jun 1 2024 02:40:34