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
70f4b363
Commit
70f4b363
authored
8 years ago
by
Nicolas Mansard
Committed by
Nicolas Mansard
8 years ago
Browse files
Options
Downloads
Patches
Plain Diff
[Doc] Modified the header of algo/geom to improve doc and readibility of API.
parent
cc68302d
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
src/algorithm/geometry.hpp
+35
-14
35 additions, 14 deletions
src/algorithm/geometry.hpp
src/algorithm/geometry.hxx
+23
-7
23 additions, 7 deletions
src/algorithm/geometry.hxx
with
58 additions
and
21 deletions
src/algorithm/geometry.hpp
+
35
−
14
View file @
70f4b363
...
...
@@ -27,7 +27,6 @@
namespace
se3
{
///
/// \brief Apply a forward kinematics and update the placement of the geometry objects.
///
...
...
@@ -57,7 +56,22 @@ namespace se3
const
GeometryModel
&
geom
,
GeometryData
&
geom_data
);
#ifdef WITH_HPP_FCL
/// Compute the forward kinematics, update the geometry placements and
/// calls computeCollision for every active pairs of GeometryData.
///
/// \param[in] model robot model (const)
/// \param[out] data corresponding data (nonconst) where FK results are stored
/// \param[in] model_geom geometry model (const)
/// \param[out] data_geom corresponding geometry data (nonconst) where distances are computed
/// \param[in] q robot configuration.
/// \param[in] stopAtFirstCollision if true, stop the loop on pairs after the first collision.
/// \return When ComputeShortest is true, the index of the collision pair which has the shortest distance.
/// When ComputeShortest is false, the number of collision pairs.
/// \warning if stopAtFirstcollision = true, then the collisions vector will
/// not be entirely fulfilled (of course).
inline
bool
computeCollisions
(
const
Model
&
model
,
Data
&
data
,
const
GeometryModel
&
model_geom
,
...
...
@@ -66,22 +80,18 @@ namespace se3
const
bool
stopAtFirstCollision
=
false
);
inline
bool
computeCollisions
(
GeometryData
&
data_geom
,
const
bool
stopAtFirstCollision
=
false
);
/// Compute the distances of all collision pairs
/// Compute the forward kinematics, update the geometry placements and
/// calls computeDistance for every active pairs of GeometryData.
///
/// \param ComputeShortest default to true.
/// \param data_geom
/// \param[in] ComputeShortest default to true.
/// \param[in][out] model: robot model (const)
/// \param[out] data: corresponding data (nonconst) where FK results are stored
/// \param[in] model_geom: geometry model (const)
/// \param[out] data_geom: corresponding geometry data (nonconst) where distances are computed
/// \param[in] q: robot configuration.
/// \return When ComputeShortest is true, the index of the collision pair which has the shortest distance.
/// When ComputeShortest is false, the number of collision pairs.
template
<
bool
ComputeShortest
>
inline
std
::
size_t
computeDistances
(
GeometryData
&
data_geom
);
/// Compute the forward kinematics, update the goemetry placements and
/// calls computeDistances(GeometryData&).
template
<
bool
ComputeShortest
>
inline
std
::
size_t
computeDistances
(
const
Model
&
model
,
Data
&
data
,
const
GeometryModel
&
model_geom
,
...
...
@@ -89,6 +99,8 @@ namespace se3
const
Eigen
::
VectorXd
&
q
);
/// Compute the radius of the geometry volumes attached to every joints.
/// \sa GeometryData::radius
inline
void
computeBodyRadius
(
const
Model
&
model
,
const
GeometryModel
&
geomModel
,
GeometryData
&
geomData
);
...
...
@@ -102,12 +114,21 @@ namespace se3
/// \li add all the collision pairs between geometry objects of geomModel1 and geomModel2.
/// \li update the inner objects of geomModel1 with the inner objects of geomModel2
/// \li update the outer objects (see TODO)
/// It is possible to ommit both data (an additional function signature is available which makes
/// them optionnal), then inner/outer objects are not updated.
///
/// \param[out] geomModel1 geometry model where the data is added
/// \param[out] geomData1 corresponding geometry data, where in/outer objects are updated
/// \param[in] geomModel2 geometry model from which new geometries are taken
/// \param[out] geomData2 geometry data corresponding to geomModel2.
/// \warning Radius should be recomputed.
/// \todo The geometry objects of geomModel2 should be added as outerObjects
/// of the joints originating from model1 but I do not know how to do it.
inline
void
appendGeometryModel
(
GeometryModel
&
geomModel1
,
const
GeometryModel
&
geomModel2
);
GeometryData
&
geomData1
,
const
GeometryModel
&
geomModel2
,
const
GeometryData
&
geomData2
);
}
// namespace se3
/* --- Details -------------------------------------------------------------------- */
...
...
This diff is collapsed.
Click to expand it.
src/algorithm/geometry.hxx
+
23
−
7
View file @
70f4b363
...
...
@@ -22,7 +22,9 @@
namespace
se3
{
/* --- GEOMETRY PLACEMENTS -------------------------------------------------------- */
/* --- GEOMETRY PLACEMENTS -------------------------------------------------------- */
/* --- GEOMETRY PLACEMENTS -------------------------------------------------------- */
inline
void
updateGeometryPlacements
(
const
Model
&
model
,
Data
&
data
,
const
GeometryModel
&
model_geom
,
...
...
@@ -51,6 +53,10 @@ namespace se3
}
}
#ifdef WITH_HPP_FCL
/* --- COLLISIONS ----------------------------------------------------------------- */
/* --- COLLISIONS ----------------------------------------------------------------- */
/* --- COLLISIONS ----------------------------------------------------------------- */
inline
bool
computeCollisions
(
GeometryData
&
data_geom
,
const
bool
stopAtFirstCollision
)
...
...
@@ -86,12 +92,10 @@ namespace se3
return
computeCollisions
(
data_geom
,
stopAtFirstCollision
);
}
// Required to have a default template argument on templated free function
inline
std
::
size_t
computeDistances
(
GeometryData
&
data_geom
)
{
return
computeDistances
<
true
>
(
data_geom
);
}
/* --- DISTANCES ----------------------------------------------------------------- */
/* --- DISTANCES ----------------------------------------------------------------- */
/* --- DISTANCES ----------------------------------------------------------------- */
template
<
bool
COMPUTE_SHORTEST
>
inline
std
::
size_t
computeDistances
(
GeometryData
&
data_geom
)
{
...
...
@@ -113,6 +117,12 @@ namespace se3
return
min_index
;
}
// Required to have a default template argument on templated free function
inline
std
::
size_t
computeDistances
(
GeometryData
&
data_geom
)
{
return
computeDistances
<
true
>
(
data_geom
);
}
// Required to have a default template argument on templated free function
inline
std
::
size_t
computeDistances
(
const
Model
&
model
,
Data
&
data
,
...
...
@@ -136,6 +146,10 @@ namespace se3
return
computeDistances
<
ComputeShortest
>
(
data_geom
);
}
/* --- RADIUS -------------------------------------------------------------------- */
/* --- RADIUS -------------------------------------------------------------------- */
/* --- RADIUS -------------------------------------------------------------------- */
/// Given p1..3 being either "min" or "max", return one of the corners of the
/// AABB cub of the FCL object.
#define SE3_GEOM_AABB(FCL,p1,p2,p3) \
...
...
@@ -181,6 +195,8 @@ namespace se3
#undef SE3_GEOM_AABB
#endif // WITH_HPP_FCL
/* --- APPEND GEOMETRY MODEL ----------------------------------------------------------- */
inline
void
appendGeometryModel
(
GeometryModel
&
geomModel1
,
const
GeometryModel
&
geomModel2
)
{
...
...
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