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
9f107b57
Commit
9f107b57
authored
Jan 14, 2018
by
jcarpent
Browse files
[Data] Remove data.dtau_da reference on data.M
It seems that Python does not support at the alignment level such reference.
parent
17b856fa
Changes
4
Hide whitespace changes
Inline
Side-by-side
src/algorithm/rnea-derivatives.hpp
View file @
9f107b57
...
...
@@ -54,7 +54,7 @@ namespace se3
/// \param[out] rnea_partial_dv Partial derivative of the generalized torque vector with respect to the joint velocity.
/// \param[out] rnea_partial_da Partial derivative of the generalized torque vector with respect to the joint acceleration.
///
/// \remark rnea_partial_dq, rnea_partial_dv and rnea_partial_da must be first initialized with zeros (
gravity
_partial_dq.setZero).
/// \remark rnea_partial_dq, rnea_partial_dv and rnea_partial_da must be first initialized with zeros (
rnea
_partial_dq.setZero
(),etc
).
/// As for se3::crba, only the upper triangular part of rnea_partial_da is filled.
///
/// \sa se3::rnea
...
...
@@ -78,11 +78,9 @@ namespace se3
/// \param[in] v The joint velocity vector (dim model.nv).
/// \param[in] a The joint acceleration vector (dim model.nv).
///
/// \returns The results are stored in data.dtau_dq, data.
tau_dv
and data.dtau_da which respectively correspond
/// \returns The results are stored in data.dtau_dq, data.
M
and data.dtau_da which respectively correspond
/// to the partial derivatives of the joint torque vector with respect to the joint configuration, velocity and acceleration.
/// data.dtau_da is a reference on data.M. And as for se3::crba, only the upper triangular part of data.M is filled.
///
/// \remark rnea_partial_dq and rnea_partial_dv must be first initialized with zeros (gravity_partial_dq.setZero).
/// And as for se3::crba, only the upper triangular part of data.M is filled.
///
/// \sa se3::rnea, se3::crba, se3::cholesky::decompose
///
...
...
@@ -93,7 +91,7 @@ namespace se3
const
Eigen
::
VectorXd
&
a
)
{
computeRNEADerivatives
(
model
,
data
,
q
,
v
,
a
,
data
.
dtau_dq
,
data
.
dtau_dv
,
data
.
dtau_da
);
data
.
dtau_dq
,
data
.
dtau_dv
,
data
.
M
);
}
...
...
src/multibody/model.hpp
View file @
9f107b57
...
...
@@ -522,9 +522,6 @@ namespace se3
/// \brief Variation of the joint torque vector with respect to the joint velocity.
Eigen
::
MatrixXd
dtau_dv
;
/// \brief Variation of the joint torque vector with respect to the joint acceleration. This is only a reference on data.M.
Eigen
::
MatrixXd
&
dtau_da
;
/// \brief Vector of joint placements wrt to algorithm end effector.
container
::
aligned_vector
<
SE3
>
iMf
;
...
...
src/multibody/model.hxx
View file @
9f107b57
...
...
@@ -278,7 +278,6 @@ namespace se3
,
dAdv
(
6
,
model
.
nv
)
,
dtau_dq
(
Eigen
::
MatrixXd
::
Zero
(
model
.
nv
,
model
.
nv
))
,
dtau_dv
(
Eigen
::
MatrixXd
::
Zero
(
model
.
nv
,
model
.
nv
))
,
dtau_da
(
M
)
,
iMf
((
std
::
size_t
)
model
.
njoints
)
,
com
((
std
::
size_t
)
model
.
njoints
)
,
vcom
((
std
::
size_t
)
model
.
njoints
)
...
...
unittest/rnea-derivatives.cpp
View file @
9f107b57
...
...
@@ -256,7 +256,7 @@ BOOST_AUTO_TEST_CASE(test_rnea_derivatives)
BOOST_CHECK
(
rnea_partial_dq
.
isApprox
(
data2
.
dtau_dq
));
BOOST_CHECK
(
rnea_partial_dv
.
isApprox
(
data2
.
dtau_dv
));
BOOST_CHECK
(
rnea_partial_da
.
isApprox
(
data2
.
dtau_da
));
BOOST_CHECK
(
rnea_partial_da
.
isApprox
(
data2
.
M
));
}
...
...
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