Commit 5e4ca72a authored by jcarpent's avatar jcarpent
Browse files

[Python] Expose the algo for derivation of the centroidal momentum matrix

parent 50fcc77f
......@@ -47,6 +47,13 @@ namespace se3
"Computes the centroidal mapping, the centroidal momentum and the Centroidal Composite Rigid Body Inertia, puts the result in Data and returns the centroidal mapping.",
bp::return_value_policy<bp::return_by_value>());
bp::def("dccrba",dccrba,
bp::args("Model","Data",
"Joint configuration q (size Model::nq)",
"Joint velocity v (size Model::nv)"),
"Computes the time derivative of the centroidal momentum matrix Ag in terms of q and v. It computes also the same information than ccrtba for the same price.",
bp::return_value_policy<bp::return_by_value>());
}
} // namespace python
......
......@@ -88,6 +88,8 @@ namespace se3
.ADD_DATA_PROPERTY_READONLY_BYVALUE(Matrix6x,Ag,
"Centroidal matrix which maps from joint velocity to the centroidal momentum.")
.ADD_DATA_PROPERTY_READONLY_BYVALUE(Matrix6x,dAg,
"Time derivative of the centroidal momentum matrix Ag.")
.ADD_DATA_PROPERTY_READONLY(Force,hg,
"Centroidal momentum (expressed in the frame centered at the CoM and aligned with the inertial frame).")
.ADD_DATA_PROPERTY_READONLY(Inertia,Ig,
......
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment