expose-frames-derivatives.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2020 INRIA
3 //
4 
7 
8 #include <boost/python/tuple.hpp>
9 
10 namespace pinocchio
11 {
12  namespace python
13  {
14  namespace bp = boost::python;
15 
17  Data & data,
19  ReferenceFrame rf)
20  {
21  typedef Data::Matrix6x Matrix6x;
22 
23  Matrix6x partial_dq(Matrix6x::Zero(6,model.nv));
24  Matrix6x partial_dv(Matrix6x::Zero(6,model.nv));
25 
27  partial_dq,partial_dv);
28 
29  return bp::make_tuple(partial_dq,partial_dv);
30  }
31 
33  Data & data,
35  ReferenceFrame rf)
36  {
37  typedef Data::Matrix6x Matrix6x;
38 
39  Matrix6x v_partial_dq(Matrix6x::Zero(6,model.nv));
40  Matrix6x a_partial_dq(Matrix6x::Zero(6,model.nv));
41  Matrix6x a_partial_dv(Matrix6x::Zero(6,model.nv));
42  Matrix6x a_partial_da(Matrix6x::Zero(6,model.nv));
43 
45  v_partial_dq,a_partial_dq,
46  a_partial_dv,a_partial_da);
47 
48  return bp::make_tuple(v_partial_dq,a_partial_dq,a_partial_dv,a_partial_da);
49  }
50 
52  {
53  using namespace Eigen;
54 
55  bp::def("getFrameVelocityDerivatives",
57  bp::args("model","data","frame_id","reference_frame"),
58  "Computes the partial derivatives of the spatial velocity of a given frame with respect to\n"
59  "the joint configuration and velocity and returns them as a tuple.\n"
60  "The Jacobians can be either expressed in the LOCAL frame of the joint, in the LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of reference_frame.\n"
61  "You must first call computeForwardKinematicsDerivatives before calling this function.\n\n"
62  "Parameters:\n"
63  "\tmodel: model of the kinematic tree\n"
64  "\tdata: data related to the model\n"
65  "\tframe_id: index of the frame\n"
66  "\treference_frame: reference frame in which the resulting derivatives are expressed\n");
67 
68  bp::def("getFrameAccelerationDerivatives",
70  bp::args("model","data","frame_id","reference_frame"),
71  "Computes the partial derivatives of the spatial acceleration of a given frame with respect to\n"
72  "the joint configuration, velocity and acceleration and returns them as a tuple.\n"
73  "The Jacobians can be either expressed in the LOCAL frame of the joint, in the LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of reference_frame.\n"
74  "You must first call computeForwardKinematicsDerivatives before calling this function.\n\n"
75  "Parameters:\n"
76  "\tmodel: model of the kinematic tree\n"
77  "\tdata: data related to the model\n"
78  "\tframe_id: index of the frame\n"
79  "\treference_frame: reference frame in which the resulting derivatives are expressed\n");
80 
81  }
82 
83  } // namespace python
84 } // namespace pinocchio
pinocchio::getFrameVelocityDerivatives
void getFrameVelocityDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &v_partial_dv)
Computes the partial derivatives of the frame velocity quantity with respect to q and v....
boost::python
Eigen
pinocchio::DataTpl
Definition: multibody/data.hpp:29
pinocchio::python::getFrameVelocityDerivatives_proxy
bp::tuple getFrameVelocityDerivatives_proxy(const Model &model, Data &data, const Model::FrameIndex frame_id, ReferenceFrame rf)
Definition: expose-frames-derivatives.cpp:16
pinocchio::ReferenceFrame
ReferenceFrame
List of Reference Frames supported by Pinocchio.
Definition: multibody/fwd.hpp:44
setup.data
data
Definition: cmake/cython/setup.in.py:48
meshcat-viewer.frame_id
frame_id
Definition: meshcat-viewer.py:93
algorithms.hpp
pinocchio::DataTpl::Matrix6x
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
Definition: multibody/data.hpp:73
python
pinocchio::python::getFrameAccelerationDerivatives_proxy
bp::tuple getFrameAccelerationDerivatives_proxy(const Model &model, Data &data, const Model::FrameIndex frame_id, ReferenceFrame rf)
Definition: expose-frames-derivatives.cpp:32
pinocchio::ModelTpl::FrameIndex
pinocchio::FrameIndex FrameIndex
Definition: multibody/model.hpp:51
pinocchio::getFrameAccelerationDerivatives
void getFrameAccelerationDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, 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 frame acceleration quantity with respect to q,...
pinocchio::python::exposeFramesDerivatives
void exposeFramesDerivatives()
Definition: expose-frames-derivatives.cpp:51
pinocchio::ModelTpl
Definition: multibody/fwd.hpp:23
Matrix6x
Eigen::Matrix< double, 6, Eigen::Dynamic > Matrix6x
Definition: joint-mimic.cpp:15
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:746
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:28
frames-derivatives.hpp


pinocchio
Author(s):
autogenerated on Tue Feb 13 2024 03:43:58