23 "rnea", &rnea<Scalar, Options, JointCollectionDefaultTpl, VectorXs, VectorXs, VectorXs>,
24 bp::args(
"model",
"data",
"q",
"v",
"a"),
25 "Compute the RNEA, store the result in Data and return it.\n\n"
27 "\tmodel: model of the kinematic tree\n"
28 "\tdata: data related to the model\n"
29 "\tq: the joint configuration vector (size model.nq)\n"
30 "\tv: the joint velocity vector (size model.nv)\n"
31 "\ta: the joint acceleration vector (size model.nv)\n",
32 bp::return_value_policy<bp::return_by_value>());
38 bp::args(
"model",
"data",
"q",
"v",
"a",
"fext"),
39 "Compute the RNEA with external forces, store the result in Data and return it.\n\n"
41 "\tmodel: model of the kinematic tree\n"
42 "\tdata: data related to the model\n"
43 "\tq: the joint configuration vector (size model.nq)\n"
44 "\tv: the joint velocity vector (size model.nv)\n"
45 "\ta: the joint acceleration vector (size model.nv)\n"
46 "\tfext: list of external forces expressed in the local frame of the joints (size "
48 bp::return_value_policy<bp::return_by_value>());
52 &nonLinearEffects<Scalar, Options, JointCollectionDefaultTpl, VectorXs, VectorXs>,
53 bp::args(
"model",
"data",
"q",
"v"),
54 "Compute the Non Linear Effects (coriolis, centrifugal and gravitational effects), "
55 "store the result in Data and return it.\n\n"
57 "\tmodel: model of the kinematic tree\n"
58 "\tdata: data related to the model\n"
59 "\tq: the joint configuration vector (size model.nq)\n"
60 "\tv: the joint velocity vector (size model.nv)\n",
61 bp::return_value_policy<bp::return_by_value>());
64 "computeGeneralizedGravity",
65 &computeGeneralizedGravity<Scalar, Options, JointCollectionDefaultTpl, VectorXs>,
66 bp::args(
"model",
"data",
"q"),
67 "Compute the generalized gravity contribution g(q) of the Lagrangian dynamics, store "
68 "the result in data.g and return it.\n\n"
70 "\tmodel: model of the kinematic tree\n"
71 "\tdata: data related to the model\n"
72 "\tq: the joint configuration vector (size model.nq)\n",
73 bp::return_value_policy<bp::return_by_value>());
76 "computeStaticTorque",
77 &computeStaticTorque<Scalar, Options, JointCollectionDefaultTpl, VectorXs>,
78 bp::args(
"model",
"data",
"q",
"fext"),
79 "Computes the generalized static torque contribution g(q) - J.T f_ext of the "
80 "Lagrangian dynamics, store the result in data.tau and return it.\n\n"
82 "\tmodel: model of the kinematic tree\n"
83 "\tdata: data related to the model\n"
84 "\tq: the joint configuration vector (size model.nq)\n"
85 "\tfext: list of external forces expressed in the local frame of the joints (size "
87 bp::return_value_policy<bp::return_by_value>());
90 "computeCoriolisMatrix",
91 &computeCoriolisMatrix<Scalar, Options, JointCollectionDefaultTpl, VectorXs, VectorXs>,
92 bp::args(
"model",
"data",
"q",
"v"),
93 "Compute the Coriolis Matrix C(q,v) of the Lagrangian dynamics, store the result in data.C "
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 bp::return_value_policy<bp::return_by_value>());
103 "getCoriolisMatrix", &getCoriolisMatrix<Scalar, Options, JointCollectionDefaultTpl>,
104 bp::args(
"model",
"data"),
105 "Retrives the Coriolis Matrix C(q,v) of the Lagrangian dynamics after calling one of "
106 "the derivative algorithms, store the result in data.C and return it.\n\n"
108 "\tmodel: model of the kinematic tree\n"
109 "\tdata: data related to the model\n",
110 bp::return_value_policy<bp::return_by_value>());