Skip to content
Snippets Groups Projects
Commit 5c809477 authored by Nicolas Mansard's avatar Nicolas Mansard Committed by Nicolas Mansard
Browse files

[C++][Minor] Removed the appendGeometryModel methods that was partially updating geomData.

parent 0eef8bf1
No related branches found
No related tags found
No related merge requests found
...@@ -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
......
...@@ -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__
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment