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
fa57d90f
Verified
Commit
fa57d90f
authored
Feb 01, 2020
by
Justin Carpentier
Browse files
python: rework a bit the skew exposure and add skewSquare
parent
bf4aaf02
Changes
2
Show whitespace changes
Inline
Side-by-side
bindings/python/spatial/expose-skew.cpp
View file @
fa57d90f
//
// Copyright (c) 2015-20
19
CNRS INRIA
// Copyright (c) 20
15
Wandercraft
, 86 rue de Paris 91400 Orsay, France.
// Copyright (c) 2015-20
20
CNRS INRIA
// Copyright (c) 20
20
Wandercraft
//
#include "pinocchio/bindings/python/fwd.hpp"
#include <boost/python.hpp>
#include "pinocchio/bindings/python/fwd.hpp"
#include "pinocchio/spatial/se3.hpp"
#include "pinocchio/spatial/skew.hpp"
namespace
pinocchio
...
...
@@ -13,29 +15,40 @@ namespace pinocchio
{
namespace
bp
=
boost
::
python
;
Eigen
::
Matrix3d
skew_proxy
(
const
Eigen
::
Vector3d
&
v
)
{
return
pinocchio
::
skew
(
v
);
}
Eigen
::
Vector3d
unSkew_proxy
(
const
Eigen
::
Matrix3d
&
M
)
// We need to resort to another call, because it seems that Boost.Python is not aligning the Eigen::MatrixBase. TODO: fix it!
template
<
typename
Matrix3
>
Eigen
::
Matrix
<
typename
Matrix3
::
Scalar
,
3
,
1
,
Matrix3
::
Options
>
unSkew
(
const
Matrix3
&
mat
)
{
return
pinocchio
::
unSkew
(
M
);
return
pinocchio
::
unSkew
(
mat
);
}
void
exposeSkew
()
{
bp
::
def
(
"skew"
,
&
skew_proxy
,
bp
::
arg
(
"Angular velocity (vector of size 3)"
),
"Computes the skew representation of a given 3D vector, "
"i.e. the antisymmetric matrix representation of the cross product operator."
);
bp
::
def
(
"unSkew"
,
&
unSkew_proxy
,
bp
::
arg
(
"M: a 3x3 matrix."
),
"Inverse of skew operator. From a given skew-symmetric matrix M "
"of dimension 3x3, it extracts the supporting vector, i.e. the entries of M."
"Mathematically speacking, it computes v such that M x = cross(x, v)."
);
typedef
SE3
::
Matrix3
Matrix3
;
typedef
SE3
::
Vector3
Vector3
;
bp
::
def
(
"skew"
,
&
skew
<
Vector3
>
,
bp
::
arg
(
"u"
),
"Computes the skew representation of a given 3d vector, "
"i.e. the antisymmetric matrix representation of the cross product operator, aka U = [u]x.
\n
"
"Parameters:
\n
"
"
\t
u: the input vector of dimension 3"
);
bp
::
def
(
"skewSquare"
,
&
skewSquare
<
Vector3
,
Vector3
>
,
bp
::
args
(
"u"
,
"v"
),
"Computes the skew square representation of two given 3d vectors, "
"i.e. the antisymmetric matrix representation of the chained cross product operator, u x (v x w), where w is another 3d vector.
\n
"
"Parameters:
\n
"
"
\t
u: the first input vector of dimension 3
\n
"
"
\t
v: the second input vector of dimension 3"
);
bp
::
def
(
"unSkew"
,
&
unSkew
<
Matrix3
>
,
bp
::
arg
(
"U"
),
"Inverse of skew operator. From a given skew symmetric matrix U (i.e U = -U.T)"
"of dimension 3x3, it extracts the supporting vector, i.e. the entries of U.
\n
"
"Mathematically speacking, it computes v such that U.dot(x) = cross(u, x).
\n
"
"Parameters:
\n
"
"
\t
U: the input skew symmetric matrix of dimension 3x3."
);
}
}
// namespace python
...
...
src/spatial/skew.hpp
View file @
fa57d90f
...
...
@@ -185,7 +185,7 @@ namespace pinocchio
/// \param[in] u A 3 dimensional vector.
/// \param[in] v A 3 dimensional vector.
///
/// \return The square cross product matrix
C
.
/// \return The square cross product matrix
skew[u] * skew[v]
.
///
template
<
typename
V1
,
typename
V2
>
inline
Eigen
::
Matrix
<
typename
V1
::
Scalar
,
3
,
3
,
PINOCCHIO_EIGEN_PLAIN_TYPE
(
V1
)
::
Options
>
...
...
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