Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
P
pinocchio
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Container Registry
Model registry
Operate
Environments
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Stack Of Tasks
pinocchio
Commits
c81cc2dc
Commit
c81cc2dc
authored
10 years ago
by
Nicolas Mansard
Committed by
Valenza Florian
9 years ago
Browse files
Options
Downloads
Patches
Plain Diff
Python: corrected a bug in data bindings with Eigen members.
parent
c8c9862d
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
src/python/data.hpp
+27
-23
27 additions, 23 deletions
src/python/data.hpp
with
27 additions
and
23 deletions
src/python/data.hpp
+
27
−
23
View file @
c81cc2dc
...
...
@@ -34,12 +34,16 @@ namespace se3
bp::make_function(&DataPythonVisitor::NAME, \
bp::return_internal_reference<>()), \
DOC)
//add_property(#NAME,&DataPythonVisitor::NAME,DOC)
//bp::make_function(&ModelPythonVisitor::inertias,
// bp::return_internal_reference<>()) )
#define ADD_DATA_PROPERTY_CONST(TYPE,NAME,DOC) \
add_property(#NAME, \
bp::make_function(&DataPythonVisitor::NAME), \
DOC)
#define IMPL_DATA_PROPERTY(TYPE,NAME,DOC) \
static TYPE & NAME( DataHandler & d ) { return d->NAME; }
#define IMPL_DATA_PROPERTY_CONST(TYPE,NAME,DOC) \
static TYPE NAME( DataHandler & d ) { return d->NAME; }
/* --- Exposing C++ API to python through the handler ----------------- */
template
<
class
PyClass
>
...
...
@@ -51,21 +55,21 @@ namespace se3
.
ADD_DATA_PROPERTY
(
std
::
vector
<
Force
>
,
f
,
"Body force"
)
.
ADD_DATA_PROPERTY
(
std
::
vector
<
SE3
>
,
oMi
,
"Body absolute placement (wrt world)"
)
.
ADD_DATA_PROPERTY
(
std
::
vector
<
SE3
>
,
liMi
,
"Body relative placement (wrt parent)"
)
.
ADD_DATA_PROPERTY
(
Eigen
::
VectorXd
,
tau
,
"Joint forces"
)
.
ADD_DATA_PROPERTY
_CONST
(
Eigen
::
VectorXd
,
tau
,
"Joint forces"
)
.
ADD_DATA_PROPERTY
(
std
::
vector
<
Inertia
>
,
Ycrb
,
"Inertia of the sub-tree composit rigid body"
)
.
ADD_DATA_PROPERTY
(
Eigen
::
MatrixXd
,
M
,
"Joint Inertia"
)
.
ADD_DATA_PROPERTY
(
std
::
vector
<
Matrix6x
>
,
Fcrb
,
"Spatial forces set, used in CRBA"
)
.
ADD_DATA_PROPERTY
_CONST
(
Eigen
::
MatrixXd
,
M
,
"Joint Inertia"
)
.
ADD_DATA_PROPERTY
_CONST
(
std
::
vector
<
Matrix6x
>
,
Fcrb
,
"Spatial forces set, used in CRBA"
)
.
ADD_DATA_PROPERTY
(
std
::
vector
<
Model
::
Index
>
,
lastChild
,
"Index of the last child (for CRBA)"
)
.
ADD_DATA_PROPERTY
(
std
::
vector
<
int
>
,
nvSubtree
,
"Dimension of the subtree motion space (for CRBA)"
)
.
ADD_DATA_PROPERTY
(
Eigen
::
MatrixXd
,
U
,
"Joint Inertia square root (upper triangle)"
)
.
ADD_DATA_PROPERTY
(
Eigen
::
VectorXd
,
D
,
"Diagonal of UDUT inertia decomposition"
)
.
ADD_DATA_PROPERTY
_CONST
(
Eigen
::
MatrixXd
,
U
,
"Joint Inertia square root (upper triangle)"
)
.
ADD_DATA_PROPERTY
_CONST
(
Eigen
::
VectorXd
,
D
,
"Diagonal of UDUT inertia decomposition"
)
.
ADD_DATA_PROPERTY
(
std
::
vector
<
int
>
,
parents_fromRow
,
"First previous non-zero row in M (used in Cholesky)"
)
.
ADD_DATA_PROPERTY
(
std
::
vector
<
int
>
,
nvSubtree_fromRow
,
""
)
.
ADD_DATA_PROPERTY
(
Eigen
::
MatrixXd
,
J
,
"Jacobian of joint placement"
)
.
ADD_DATA_PROPERTY
_CONST
(
Eigen
::
MatrixXd
,
J
,
"Jacobian of joint placement"
)
.
ADD_DATA_PROPERTY
(
std
::
vector
<
SE3
>
,
iMf
,
"Body placement wrt to algorithm end effector."
)
.
ADD_DATA_PROPERTY
(
std
::
vector
<
Eigen
::
Vector3d
>
,
com
,
"Subtree com position."
)
.
ADD_DATA_PROPERTY
_CONST
(
std
::
vector
<
Eigen
::
Vector3d
>
,
com
,
"Subtree com position."
)
.
ADD_DATA_PROPERTY
(
std
::
vector
<
double
>
,
mass
,
"Subtree total mass."
)
.
ADD_DATA_PROPERTY
(
Matrix3x
,
Jcom
,
"Jacobian of center of mass."
)
.
ADD_DATA_PROPERTY
_CONST
(
Matrix3x
,
Jcom
,
"Jacobian of center of mass."
)
;
}
...
...
@@ -74,24 +78,24 @@ namespace se3
IMPL_DATA_PROPERTY
(
std
::
vector
<
Force
>
,
f
,
"Body force"
)
IMPL_DATA_PROPERTY
(
std
::
vector
<
SE3
>
,
oMi
,
"Body absolute placement (wrt world)"
)
IMPL_DATA_PROPERTY
(
std
::
vector
<
SE3
>
,
liMi
,
"Body relative placement (wrt parent)"
)
IMPL_DATA_PROPERTY
(
Eigen
::
VectorXd
,
tau
,
"Joint forces"
)
IMPL_DATA_PROPERTY
_CONST
(
Eigen
::
VectorXd
,
tau
,
"Joint forces"
)
IMPL_DATA_PROPERTY
(
std
::
vector
<
Inertia
>
,
Ycrb
,
"Inertia of the sub-tree composit rigid body"
)
IMPL_DATA_PROPERTY
(
Eigen
::
MatrixXd
,
M
,
"Joint Inertia"
)
IMPL_DATA_PROPERTY
(
std
::
vector
<
Matrix6x
>
,
Fcrb
,
"Spatial forces set, used in CRBA"
)
IMPL_DATA_PROPERTY
_CONST
(
Eigen
::
MatrixXd
,
M
,
"Joint Inertia"
)
IMPL_DATA_PROPERTY
_CONST
(
std
::
vector
<
Matrix6x
>
,
Fcrb
,
"Spatial forces set, used in CRBA"
)
IMPL_DATA_PROPERTY
(
std
::
vector
<
Model
::
Index
>
,
lastChild
,
"Index of the last child (for CRBA)"
)
IMPL_DATA_PROPERTY
(
std
::
vector
<
int
>
,
nvSubtree
,
"Dimension of the subtree motion space (for CRBA)"
)
IMPL_DATA_PROPERTY
(
Eigen
::
MatrixXd
,
U
,
"Joint Inertia square root (upper triangle)"
)
IMPL_DATA_PROPERTY
(
Eigen
::
VectorXd
,
D
,
"Diagonal of UDUT inertia decomposition"
)
IMPL_DATA_PROPERTY
_CONST
(
Eigen
::
MatrixXd
,
U
,
"Joint Inertia square root (upper triangle)"
)
IMPL_DATA_PROPERTY
_CONST
(
Eigen
::
VectorXd
,
D
,
"Diagonal of UDUT inertia decomposition"
)
IMPL_DATA_PROPERTY
(
std
::
vector
<
int
>
,
parents_fromRow
,
"First previous non-zero row in M (used in Cholesky)"
)
IMPL_DATA_PROPERTY
(
std
::
vector
<
int
>
,
nvSubtree_fromRow
,
""
)
IMPL_DATA_PROPERTY
(
Eigen
::
MatrixXd
,
J
,
"Jacobian of joint placement"
)
IMPL_DATA_PROPERTY
_CONST
(
Eigen
::
MatrixXd
,
J
,
"Jacobian of joint placement"
)
IMPL_DATA_PROPERTY
(
std
::
vector
<
SE3
>
,
iMf
,
"Body placement wrt to algorithm end effector."
)
IMPL_DATA_PROPERTY
(
std
::
vector
<
Eigen
::
Vector3d
>
,
com
,
"Subtree com position."
)
IMPL_DATA_PROPERTY
_CONST
(
std
::
vector
<
Eigen
::
Vector3d
>
,
com
,
"Subtree com position."
)
IMPL_DATA_PROPERTY
(
std
::
vector
<
double
>
,
mass
,
"Subtree total mass."
)
IMPL_DATA_PROPERTY
(
Matrix3x
,
Jcom
,
"Jacobian of center of mass."
)
/* --- Expose --------------------------------------------------------- */
static
void
expose
()
IMPL_DATA_PROPERTY
_CONST
(
Matrix3x
,
Jcom
,
"Jacobian of center of mass."
)
/* --- Expose --------------------------------------------------------- */
static
void
expose
()
{
bp
::
class_
<
DataHandler
>
(
"Data"
,
"Articulated rigid body data (const)"
,
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment