Skip to content
Snippets Groups Projects
Unverified Commit 93c01405 authored by Justin Carpentier's avatar Justin Carpentier Committed by GitHub
Browse files

Merge pull request #704 from jcarpent/devel

bindings/python: correct bindings of contact dynamics
parents 0339723e ad791020
No related branches found
No related tags found
No related merge requests found
......@@ -10,17 +10,30 @@ namespace pinocchio
namespace python
{
BOOST_PYTHON_FUNCTION_OVERLOADS(forwardDynamics_overloads, forwardDynamics, 7, 9)
static const Eigen::VectorXd forwardDynamics_proxy(const Model & model,
Data & data,
const Eigen::VectorXd & q,
const Eigen::VectorXd & v,
const Eigen::VectorXd & tau,
const Eigen::MatrixXd & J,
const Eigen::VectorXd & gamma,
const double inv_damping = 0.0,
const bool updateKinematics = true)
{
return forwardDynamics(model, data, q, v, tau, J, gamma, inv_damping, updateKinematics);
}
BOOST_PYTHON_FUNCTION_OVERLOADS(forwardDynamics_overloads, forwardDynamics_proxy, 7, 9)
// TODO: overloading impulseDynamics directly, as done for forwardDynamics, was apparently not working (it crashed for 5 arguments)
// Therefore, it was necessary to resort to a proxy
static const Eigen::VectorXd & impulseDynamics_proxy(const Model & model,
Data & data,
const Eigen::VectorXd & q,
const Eigen::VectorXd & v_before,
const Eigen::MatrixXd & J,
const double r_coeff = 0.0,
const bool updateKinematics = true)
static const Eigen::VectorXd impulseDynamics_proxy(const Model & model,
Data & data,
const Eigen::VectorXd & q,
const Eigen::VectorXd & v_before,
const Eigen::MatrixXd & J,
const double r_coeff = 0.0,
const bool updateKinematics = true)
{
return impulseDynamics(model, data, q, v_before, J, r_coeff, updateKinematics);
}
......@@ -42,7 +55,7 @@ namespace pinocchio
using namespace Eigen;
bp::def("forwardDynamics",
&forwardDynamics<double,0,JointCollectionDefaultTpl,VectorXd,VectorXd,VectorXd,MatrixXd,VectorXd>,
&forwardDynamics_proxy,
forwardDynamics_overloads(
bp::args("Model","Data",
"Joint configuration q (size Model::nq)",
......@@ -53,7 +66,7 @@ namespace pinocchio
"(double) Damping factor for cholesky decomposition of JMinvJt. Set to zero if constraints are full rank.",
"Update kinematics (if true, it updates the dynamic variable according to the current state)"),
"Solves the forward dynamics problem with contacts, puts the result in Data::ddq and return it. The contact forces are stored in data.lambda_c"
)[bp::return_value_policy<bp::return_by_value>()]);
));
bp::def("impulseDynamics",
&impulseDynamics_proxy,
......@@ -65,7 +78,8 @@ namespace pinocchio
"Coefficient of restitution r_coeff (0 = rigid impact; 1 = fully elastic impact)",
"Update kinematics (if true, it updates only the joint space inertia matrix)"),
"Solve the impact dynamics problem with contacts, put the result in Data::dq_after and return it. The contact impulses are stored in data.impulse_c"
)[bp::return_value_policy<bp::return_by_value>()]);
));
bp::def("getKKTContactDynamicMatrixInverse",getKKTContactDynamicMatrixInverse_proxy,
bp::args("Model","Data",
"Contact Jacobian J(size nb_constraint * Model::nv)"),
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment