expose-regressor.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018-2020 CNRS INRIA
3 //
4 
7 
8 namespace pinocchio
9 {
10  namespace python
11  {
12 
14  {
15  return bodyRegressor(v, a);
16  }
17 
19  const context::Model & model, context::Data & data, const JointIndex jointId)
20  {
21  return jointBodyRegressor(model, data, jointId);
22  }
23 
25  const context::Model & model, context::Data & data, const FrameIndex frameId)
26  {
27  return frameBodyRegressor(model, data, frameId);
28  }
29 
31  {
32  typedef context::Scalar Scalar;
34  enum
35  {
37  };
38 
39  bp::def(
40  "computeStaticRegressor",
41  &computeStaticRegressor<Scalar, Options, JointCollectionDefaultTpl, VectorXs>,
42  bp::args("model", "data", "q"),
43  "Compute the static regressor that links the inertia parameters of the system to its "
44  "center of mass position,\n"
45  "store the result in context::Data and return it.\n\n"
46  "Parameters:\n"
47  "\tmodel: model of the kinematic tree\n"
48  "\tdata: data related to the model\n"
49  "\tq: the joint configuration vector (size model.nq)\n",
50  bp::return_value_policy<bp::return_by_value>());
51 
52  bp::def(
53  "bodyRegressor", &bodyRegressor_proxy, bp::args("velocity", "acceleration"),
54  "Computes the regressor for the dynamic parameters of a single rigid body.\n"
55  "The result is such that "
56  "Ia + v x Iv = bodyRegressor(v,a) * I.toDynamicParameters()\n\n"
57  "Parameters:\n"
58  "\tvelocity: spatial velocity of the rigid body\n"
59  "\tacceleration: spatial acceleration of the rigid body\n");
60 
61  bp::def(
62  "jointBodyRegressor", &jointBodyRegressor_proxy, bp::args("model", "data", "joint_id"),
63  "Compute the regressor for the dynamic parameters of a rigid body attached to a "
64  "given joint.\n"
65  "This algorithm assumes RNEA has been run to compute the acceleration and "
66  "gravitational effects.\n\n"
67  "Parameters:\n"
68  "\tmodel: model of the kinematic tree\n"
69  "\tdata: data related to the model\n"
70  "\tjoint_id: index of the joint\n");
71 
72  bp::def(
73  "frameBodyRegressor", &frameBodyRegressor_proxy, bp::args("model", "data", "frame_id"),
74  "Computes the regressor for the dynamic parameters of a rigid body attached to a "
75  "given frame.\n"
76  "This algorithm assumes RNEA has been run to compute the acceleration and "
77  "gravitational effects.\n\n"
78  "Parameters:\n"
79  "\tmodel: model of the kinematic tree\n"
80  "\tdata: data related to the model\n"
81  "\tframe_id: index of the frame\n");
82 
83  bp::def(
84  "computeJointTorqueRegressor",
87  bp::args("model", "data", "q", "v", "a"),
88  "Compute the joint torque regressor that links the joint torque "
89  "to the dynamic parameters of each link according to the current the robot motion,\n"
90  "store the result in context::Data and return it.\n\n"
91  "Parameters:\n"
92  "\tmodel: model of the kinematic tree\n"
93  "\tdata: data related to the model\n"
94  "\tq: the joint configuration vector (size model.nq)\n"
95  "\tv: the joint velocity vector (size model.nv)\n"
96  "\ta: the joint acceleration vector (size model.nv)\n",
97  bp::return_value_policy<bp::return_by_value>());
98  }
99 
100  } // namespace python
101 } // namespace pinocchio
pinocchio::python::jointBodyRegressor_proxy
context::MatrixXs jointBodyRegressor_proxy(const context::Model &model, context::Data &data, const JointIndex jointId)
Definition: expose-regressor.cpp:18
pinocchio::FrameIndex
Index FrameIndex
Definition: multibody/fwd.hpp:28
pinocchio::python::frameBodyRegressor_proxy
context::MatrixXs frameBodyRegressor_proxy(const context::Model &model, context::Data &data, const FrameIndex frameId)
Definition: expose-regressor.cpp:24
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::computeJointTorqueRegressor
DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & computeJointTorqueRegressor(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 the joint torque regressor that links the joint torque to the dynamic parameters of each lin...
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
pinocchio::frameBodyRegressor
DataTpl< Scalar, Options, JointCollectionTpl >::BodyRegressorType & frameBodyRegressor(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, FrameIndex frameId)
Computes the regressor for the dynamic parameters of a rigid body attached to a given frame,...
pinocchio::python::VectorXs
context::VectorXs VectorXs
Definition: admm-solver.cpp:30
pinocchio::python::Options
@ Options
Definition: expose-contact-inverse-dynamics.cpp:22
pinocchio::context::VectorXs
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
Definition: context/generic.hpp:47
pinocchio::python::bodyRegressor_proxy
context::MatrixXs bodyRegressor_proxy(const context::Motion &v, const context::Motion &a)
Definition: expose-regressor.cpp:13
algorithms.hpp
pinocchio::context::MatrixXs
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
Definition: context/generic.hpp:49
regressor.hpp
python
pinocchio::python::v
const Vector3Like & v
Definition: bindings/python/spatial/explog.hpp:66
pinocchio::python::context::Options
@ Options
Definition: bindings/python/context/generic.hpp:40
a
Vec3f a
pinocchio::bodyRegressor
void bodyRegressor(const MotionDense< MotionVelocity > &v, const MotionDense< MotionAcceleration > &a, const Eigen::MatrixBase< OutputType > &regressor)
Computes the regressor for the dynamic parameters of a single rigid body.
pinocchio::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:26
pinocchio::JointCollectionDefaultTpl
Definition: context/generic.hpp:15
pinocchio::MotionTpl< Scalar, Options >
pinocchio::ModelTpl
Definition: context/generic.hpp:20
pinocchio::python::exposeRegressor
void exposeRegressor()
Definition: expose-regressor.cpp:30
pinocchio::jointBodyRegressor
DataTpl< Scalar, Options, JointCollectionTpl >::BodyRegressorType & jointBodyRegressor(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, JointIndex jointId)
Computes the regressor for the dynamic parameters of a rigid body attached to a given joint,...
pinocchio::python::context::Scalar
PINOCCHIO_PYTHON_SCALAR_TYPE Scalar
Definition: bindings/python/context/generic.hpp:37
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Tue May 28 2024 02:41:40