Verified Commit 6ea12e45 authored by Justin Carpentier's avatar Justin Carpentier
Browse files

collision: remove deprecated fields

parent fb517960
//
// Copyright (c) 2015-2020 CNRS INRIA
// Copyright (c) 2015-2021 CNRS INRIA
//
#ifndef __pinocchio_multibody_geometry_hpp__
......@@ -189,19 +189,6 @@ namespace pinocchio
std::vector<bool> activeCollisionPairs;
#ifdef PINOCCHIO_WITH_HPP_FCL
///
/// \brief Collision objects (ie a fcl placed geometry).
///
/// The object contains a pointer on the collision geometries contained in geomModel.geometryObjects.
/// \sa GeometryModel::geometryObjects and GeometryObjects
///
PINOCCHIO_DEPRECATED std::vector<fcl::CollisionObject> collisionObjects;
///
/// \brief Defines what information should be computed by distance computation.
///
/// \deprecated use \ref distanceRequests instead
PINOCCHIO_DEPRECATED fcl::DistanceRequest distanceRequest;
///
/// \brief Defines what information should be computed by distance computation.
......@@ -213,12 +200,6 @@ namespace pinocchio
///
std::vector<fcl::DistanceResult> distanceResults;
///
/// \brief Defines what information should be computed by collision test.
///
/// \deprecated use \ref collisionRequests instead
PINOCCHIO_DEPRECATED fcl::CollisionRequest collisionRequest;
///
/// \brief Defines what information should be computed by collision test.
/// There is one request per pair of geometries.
......
//
// Copyright (c) 2015-2020 CNRS INRIA
// Copyright (c) 2015-2021 CNRS INRIA
//
#ifndef __pinocchio_multibody_geometry_hxx__
......@@ -18,17 +18,13 @@
namespace pinocchio
{
// Avoid deprecated warning of collisionObjects
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
inline GeometryData::GeometryData(const GeometryModel & geom_model)
: oMg(geom_model.ngeoms)
, activeCollisionPairs(geom_model.collisionPairs.size(), true)
#ifdef PINOCCHIO_WITH_HPP_FCL
, distanceRequest(true)
, distanceRequests(geom_model.collisionPairs.size(), hpp::fcl::DistanceRequest(true))
, distanceResults(geom_model.collisionPairs.size())
, collisionRequest(::hpp::fcl::NO_REQUEST,1)
, collisionRequests(geom_model.collisionPairs.size(), hpp::fcl::CollisionRequest(::hpp::fcl::NO_REQUEST,1))
, collisionResults(geom_model.collisionPairs.size())
, radius()
......@@ -38,11 +34,6 @@ PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
, outerObjects()
{
#ifdef PINOCCHIO_WITH_HPP_FCL
collisionObjects.reserve(geom_model.geometryObjects.size());
BOOST_FOREACH(const GeometryObject & geom_object, geom_model.geometryObjects)
{
collisionObjects.push_back(fcl::CollisionObject(geom_object.geometry));
}
BOOST_FOREACH(hpp::fcl::CollisionRequest & creq, collisionRequests)
{
creq.enable_cached_gjk_guess = true;
......@@ -61,11 +52,8 @@ PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
: oMg (other.oMg)
, activeCollisionPairs (other.activeCollisionPairs)
#ifdef PINOCCHIO_WITH_HPP_FCL
, collisionObjects (other.collisionObjects)
, distanceRequest (other.distanceRequest)
, distanceRequests (other.distanceRequests)
, distanceResults (other.distanceResults)
, collisionRequest (other.collisionRequest)
, collisionRequests (other.collisionRequests)
, collisionResults (other.collisionResults)
, radius (other.radius)
......@@ -76,7 +64,6 @@ PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
{}
inline GeometryData::~GeometryData() {}
PINOCCHIO_COMPILER_DIAGNOSTIC_POP
template<typename S2, int O2, template<typename,int> class JointCollectionTpl>
GeomIndex GeometryModel::addGeometryObject(const GeometryObject & object,
......
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment