expose-regressor.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018-2020 CNRS INRIA
3 //
4 
7 
9 
10 namespace pinocchio
11 {
12  namespace python
13  {
14 
15  context::MatrixXs bodyRegressor_proxy(const context::Motion & v, const context::Motion & a)
16  {
17  return bodyRegressor(v, a);
18  }
19 
20  context::MatrixXs jointBodyRegressor_proxy(
21  const context::Model & model, context::Data & data, const JointIndex jointId)
22  {
23  return jointBodyRegressor(model, data, jointId);
24  }
25 
26  context::MatrixXs frameBodyRegressor_proxy(
27  const context::Model & model, context::Data & data, const FrameIndex frameId)
28  {
29  return frameBodyRegressor(model, data, frameId);
30  }
31 
33  {
34  typedef context::Scalar Scalar;
36  enum
37  {
39  };
40 
41  bp::def(
42  "computeStaticRegressor",
43  &computeStaticRegressor<Scalar, Options, JointCollectionDefaultTpl, VectorXs>,
44  bp::args("model", "data", "q"),
45  "Compute the static regressor that links the inertia parameters of the system to its "
46  "center of mass position,\n"
47  "store the result in context::Data and return it.\n\n"
48  "Parameters:\n"
49  "\tmodel: model of the kinematic tree\n"
50  "\tdata: data related to the model\n"
51  "\tq: the joint configuration vector (size model.nq)\n",
52  mimic_not_supported_function<bp::return_value_policy<bp::return_by_value>>(0));
53 
54  bp::def(
55  "bodyRegressor", &bodyRegressor_proxy, bp::args("velocity", "acceleration"),
56  "Computes the regressor for the dynamic parameters of a single rigid body.\n"
57  "The result is such that "
58  "Ia + v x Iv = bodyRegressor(v,a) * I.toDynamicParameters()\n\n"
59  "Parameters:\n"
60  "\tvelocity: spatial velocity of the rigid body\n"
61  "\tacceleration: spatial acceleration of the rigid body\n");
62 
63  bp::def(
64  "jointBodyRegressor", &jointBodyRegressor_proxy, bp::args("model", "data", "joint_id"),
65  "Compute the regressor for the dynamic parameters of a rigid body attached to a "
66  "given joint.\n"
67  "This algorithm assumes RNEA has been run to compute the acceleration and "
68  "gravitational effects.\n\n"
69  "Parameters:\n"
70  "\tmodel: model of the kinematic tree\n"
71  "\tdata: data related to the model\n"
72  "\tjoint_id: index of the joint\n",
74 
75  bp::def(
76  "frameBodyRegressor", &frameBodyRegressor_proxy, bp::args("model", "data", "frame_id"),
77  "Computes the regressor for the dynamic parameters of a rigid body attached to a "
78  "given frame.\n"
79  "This algorithm assumes RNEA has been run to compute the acceleration and "
80  "gravitational effects.\n\n"
81  "Parameters:\n"
82  "\tmodel: model of the kinematic tree\n"
83  "\tdata: data related to the model\n"
84  "\tframe_id: index of the frame\n",
86 
87  bp::def(
88  "computeJointTorqueRegressor",
91  bp::args("model", "data", "q", "v", "a"),
92  "Compute the joint torque regressor that links the joint torque "
93  "to the dynamic parameters of each link according to the current the robot motion,\n"
94  "store the result in context::Data and return it.\n\n"
95  "Parameters:\n"
96  "\tmodel: model of the kinematic tree\n"
97  "\tdata: data related to the model\n"
98  "\tq: the joint configuration vector (size model.nq)\n"
99  "\tv: the joint velocity vector (size model.nv)\n"
100  "\ta: the joint acceleration vector (size model.nv)\n",
101  mimic_not_supported_function<bp::return_value_policy<bp::return_by_value>>(0));
102 
103  bp::def(
104  "computeKineticEnergyRegressor",
105  &computeKineticEnergyRegressor<
107  bp::args("model", "data", "q", "v"),
108  "Compute the kinetic energy regressor that links the kinetic energy"
109  "to the dynamic parameters of each link according to the current the robot motion,\n"
110  "store the result in context::Data and return it.\n\n"
111  "Parameters:\n"
112  "\tmodel: model of the kinematic tree\n"
113  "\tdata: data related to the model\n"
114  "\tq: the joint configuration vector (size model.nq)\n"
115  "\tv: the joint velocity vector (size model.nv)\n",
116  mimic_not_supported_function<bp::return_value_policy<bp::return_by_value>>(0));
117 
118  bp::def(
119  "computePotentialEnergyRegressor",
120  &computePotentialEnergyRegressor<Scalar, Options, JointCollectionDefaultTpl, VectorXs>,
121  bp::args("model", "data", "q"),
122  "Compute the potential energy regressor that links the potential energy"
123  "to the dynamic parameters of each link according to the current the robot motion,\n"
124  "store the result in context::Data and return it.\n\n"
125  "Parameters:\n"
126  "\tmodel: model of the kinematic tree\n"
127  "\tdata: data related to the model\n"
128  "\tq: the joint configuration vector (size model.nq)\n",
129  mimic_not_supported_function<bp::return_value_policy<bp::return_by_value>>(0));
130  }
131 
132  } // namespace python
133 } // namespace pinocchio
pinocchio::python::jointBodyRegressor_proxy
context::MatrixXs jointBodyRegressor_proxy(const context::Model &model, context::Data &data, const JointIndex jointId)
Definition: expose-regressor.cpp:20
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:26
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::python::Options
@ Options
Definition: expose-contact-inverse-dynamics.cpp:24
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 frame_id)
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::context::Options
@ Options
Definition: bindings/python/context/generic.hpp:40
pinocchio::python::bodyRegressor_proxy
context::MatrixXs bodyRegressor_proxy(const context::Motion &v, const context::Motion &a)
Definition: expose-regressor.cpp:15
algorithms.hpp
regressor.hpp
python
pinocchio::python::v
const Vector3Like & v
Definition: bindings/python/spatial/explog.hpp:66
pinocchio::jointBodyRegressor
DataTpl< Scalar, Options, JointCollectionTpl >::BodyRegressorType & jointBodyRegressor(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, JointIndex joint_id)
Computes the regressor for the dynamic parameters of a rigid body attached to a given joint,...
a
Vec3f a
pinocchio::python::mimic_not_supported_function
Definition: model-checker.hpp:22
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 >
model-checker.hpp
pinocchio::ModelTpl
Definition: context/generic.hpp:20
pinocchio::python::exposeRegressor
void exposeRegressor()
Definition: expose-regressor.cpp:32
pinocchio::python::context::Scalar
PINOCCHIO_PYTHON_SCALAR_TYPE Scalar
Definition: bindings/python/context/generic.hpp:37
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:33


pinocchio
Author(s):
autogenerated on Thu Apr 10 2025 02:42:18