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
5c809477
Commit
5c809477
authored
8 years ago
by
Nicolas Mansard
Committed by
Nicolas Mansard
8 years ago
Browse files
Options
Downloads
Patches
Plain Diff
[C++][Minor] Removed the appendGeometryModel methods that was partially updating geomData.
parent
0eef8bf1
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
+4
-10
4 additions, 10 deletions
src/algorithm/geometry.hpp
src/algorithm/geometry.hxx
+0
-35
0 additions, 35 deletions
src/algorithm/geometry.hxx
with
4 additions
and
45 deletions
src/algorithm/geometry.hpp
+
4
−
10
View file @
5c809477
...
@@ -146,22 +146,16 @@ namespace se3
...
@@ -146,22 +146,16 @@ namespace se3
/// \li add GeometryObject of geomModel2 to geomModel1,
/// \li add GeometryObject of geomModel2 to geomModel1,
/// \li add the collision pairs of geomModel2 into geomModel1 (indexes are updated)
/// \li add the collision pairs of geomModel2 into geomModel1 (indexes are updated)
/// \li add all the collision pairs between geometry objects of geomModel1 and geomModel2.
/// \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
/// It is possible to ommit both data (an additional function signature is available which makes
/// them optionnal), then inner/outer objects are not updated.
/// them optionnal), then inner/outer objects are not updated.
///
///
/// \param[out] geomModel1 geometry model where the data is added
/// \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[in] geomModel2 geometry model from which new geometries are taken
/// \param[out] geomData2 geometry data corresponding to geomModel2.
/// \note Of course, the geomData corresponding to geomModel1 will not be valid anymore,
/// \warning Radius should be recomputed.
/// and should be updated (or more simply, re-created from the new setting of geomModel1).
/// \todo The geometry objects of geomModel2 should be added as outerObjects
/// \todo This function is not asserted in unittest.
/// of the joints originating from model1 but I do not know how to do it.
inline
void
appendGeometryModel
(
GeometryModel
&
geomModel1
,
inline
void
appendGeometryModel
(
GeometryModel
&
geomModel1
,
GeometryData
&
geomData1
,
GeometryData
&
geomData1
);
const
GeometryModel
&
geomModel2
,
const
GeometryData
&
geomData2
);
}
// namespace se3
}
// namespace se3
...
...
This diff is collapsed.
Click to expand it.
src/algorithm/geometry.hxx
+
0
−
35
View file @
5c809477
...
@@ -273,41 +273,6 @@ namespace se3
...
@@ -273,41 +273,6 @@ namespace se3
}
}
}
}
inline
void
appendGeometryModel
(
GeometryModel
&
geomModel1
,
GeometryData
&
geomData1
,
const
GeometryModel
&
geomModel2
,
const
GeometryData
&
geomData2
)
{
/// 1&2. Call previous function.
appendGeometryModel
(
geomModel1
,
geomModel2
);
/// 3. Update the inner/outer objects
Index
nGeom1
=
geomModel1
.
geometryObjects
.
size
();
typedef
GeometryData
::
GeomIndexList
GeomIndexList
;
typedef
std
::
map
<
JointIndex
,
GeomIndexList
>
Map_t
;
BOOST_FOREACH
(
const
Map_t
::
value_type
&
innerObject
,
geomData2
.
innerObjects
)
{
GeomIndexList
&
innerGeoms
=
geomData1
.
innerObjects
[
innerObject
.
first
];
innerGeoms
.
reserve
(
innerGeoms
.
size
()
+
innerObject
.
second
.
size
());
BOOST_FOREACH
(
const
GeomIndex
&
gid
,
innerObject
.
second
)
{
innerGeoms
.
push_back
(
nGeom1
+
gid
);
}
}
BOOST_FOREACH
(
const
Map_t
::
value_type
&
outerObject
,
geomData2
.
outerObjects
)
{
GeomIndexList
&
outerGeoms
=
geomData1
.
outerObjects
[
outerObject
.
first
];
outerGeoms
.
reserve
(
outerGeoms
.
size
()
+
outerObject
.
second
.
size
());
BOOST_FOREACH
(
const
GeomIndex
&
gid
,
outerObject
.
second
)
{
outerGeoms
.
push_back
(
nGeom1
+
gid
);
}
}
// FIXME: I copy here the previous algo. Maybe it would be safer to simply use the
// fillInnerOuterObjectMaps() method (however marginally less efficient: is it important?).
}
}
// namespace se3
}
// namespace se3
#endif // ifnded __se3_algo_geometry_hxx__
#endif // ifnded __se3_algo_geometry_hxx__
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