Skip to content
GitLab
Menu
Projects
Groups
Snippets
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
Stack Of Tasks
pinocchio
Commits
cccbb211
Commit
cccbb211
authored
Oct 03, 2019
by
Gabriele Buondonno
Browse files
[python] Expose forwardDynamics new signatures
parent
e1be67c9
Changes
2
Hide whitespace changes
Inline
Side-by-side
bindings/python/algorithm/expose-contact-dynamics.cpp
View file @
cccbb211
...
...
@@ -17,14 +17,25 @@ namespace pinocchio
const
Eigen
::
VectorXd
&
tau
,
const
Eigen
::
MatrixXd
&
J
,
const
Eigen
::
VectorXd
&
gamma
,
const
double
inv_damping
=
0.0
,
const
bool
updateKinematics
=
true
)
const
double
inv_damping
=
0.0
)
{
return
forwardDynamics
(
model
,
data
,
q
,
v
,
tau
,
J
,
gamma
,
inv_damping
,
updateKinematics
);
return
forwardDynamics
(
model
,
data
,
q
,
v
,
tau
,
J
,
gamma
,
inv_damping
);
}
BOOST_PYTHON_FUNCTION_OVERLOADS
(
forwardDynamics_overloads
,
forwardDynamics_proxy
,
7
,
9
)
BOOST_PYTHON_FUNCTION_OVERLOADS
(
forwardDynamics_overloads
,
forwardDynamics_proxy
,
7
,
8
)
static
const
Eigen
::
VectorXd
forwardDynamics_proxy_no_q
(
const
Model
&
model
,
Data
&
data
,
const
Eigen
::
VectorXd
&
tau
,
const
Eigen
::
MatrixXd
&
J
,
const
Eigen
::
VectorXd
&
gamma
,
const
double
inv_damping
=
0.0
)
{
return
forwardDynamics
(
model
,
data
,
tau
,
J
,
gamma
,
inv_damping
);
}
BOOST_PYTHON_FUNCTION_OVERLOADS
(
forwardDynamics_overloads_no_q
,
forwardDynamics_proxy_no_q
,
5
,
6
)
static
const
Eigen
::
VectorXd
impulseDynamics_proxy
(
const
Model
&
model
,
Data
&
data
,
const
Eigen
::
VectorXd
&
q
,
...
...
@@ -73,8 +84,18 @@ namespace pinocchio
"Joint torque tau (size Model::nv)"
,
"Contact Jacobian J (size nb_constraint * Model::nv)"
,
"Contact drift gamma (size nb_constraint)"
,
"(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)"
),
"(double) Damping factor for cholesky decomposition of JMinvJt. Set to zero if constraints are full rank."
),
"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
::
def
(
"forwardDynamics"
,
&
forwardDynamics_proxy_no_q
,
forwardDynamics_overloads_no_q
(
bp
::
args
(
"Model"
,
"Data"
,
"Joint torque tau (size Model::nv)"
,
"Contact Jacobian J (size nb_constraint * Model::nv)"
,
"Contact drift gamma (size nb_constraint)"
,
"(double) Damping factor for cholesky decomposition of JMinvJt. Set to zero if constraints are full rank."
),
"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"
));
...
...
bindings/python/pinocchio/deprecated.py
View file @
cccbb211
...
...
@@ -228,3 +228,31 @@ impulseDynamics.__doc__ = (
+
'
\n\n
impulseDynamics( (Model)Model, (Data)Data, (object)Joint configuration q (size Model::nq), (object)Joint velocity before impact v_before (size Model::nv), (object)Contact Jacobian J (size nb_constraint * Model::nv), (float)Coefficient of restitution r_coeff (0 = rigid impact; 1 = fully elastic impact), (bool)updateKinematics) -> object :'
+
'
\n
This function signature has been deprecated and will be removed in future releases of Pinocchio.'
)
# This function is only deprecated when using a specific signature. Therefore, it needs special care
# Marked as deprecated on 2 Oct 2019
def
forwardDynamics
(
model
,
data
,
*
args
):
if
len
(
args
)
==
7
and
type
(
args
[
6
])
is
bool
:
message
=
(
"This function signature has been deprecated and will be removed in future releases of Pinocchio. "
"Please change for the new signature of forwardDynamics(model,data[,q],v,tau,J,gamma[,inv_damping])."
)
_warnings
.
warn
(
message
,
category
=
DeprecatedWarning
,
stacklevel
=
2
)
q
=
args
[
0
]
v
=
args
[
1
]
tau
=
args
[
2
]
J
=
args
[
3
]
gamma
=
args
[
4
]
inv_damping
=
args
[
5
]
updateKinematics
=
args
[
6
]
if
updateKinematics
:
return
pin
.
forwardDynamics
(
model
,
data
,
q
,
v
,
tau
,
J
,
gamma
,
inv_damping
)
else
:
return
pin
.
forwardDynamics
(
model
,
data
,
tau
,
J
,
gamma
,
inv_damping
)
return
pin
.
forwardDynamics
(
model
,
data
,
*
args
)
forwardDynamics
.
__doc__
=
(
pin
.
forwardDynamics
.
__doc__
+
'
\n\n
forwardDynamics( (Model)Model, (Data)Data, (object)Joint configuration q (size Model::nq), (object)Joint velocity v (size Model::nv), (object)Joint torque tau (size Model::nv), (object)Contact Jacobian J (size nb_constraint * Model::nv), (object)Contact drift gamma (size nb_constraint), (float)(double) Damping factor for cholesky decomposition of JMinvJt. Set to zero if constraints are full rank, (bool)Update kinematics) -> object :'
+
'
\n
This function signature has been deprecated and will be removed in future releases of Pinocchio.'
)
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
.
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment