hpp-core  4.9.0
Implement basic classes for canonical path planning for kinematic chains.
hpp::core::CollisionValidation Class Reference

#include <hpp/core/collision-validation.hh>

Inheritance diagram for hpp::core::CollisionValidation:
Collaboration diagram for hpp::core::CollisionValidation:

Public Member Functions

virtual bool validate (const Configuration_t &config, ValidationReportPtr_t &validationReport)
 
void checkParameterized (bool active)
 
void computeAllContacts (bool computeAllContacts)
 
bool checkParameterized () const
 
- Public Member Functions inherited from hpp::core::ConfigValidation
virtual ~ConfigValidation ()
 
- Public Member Functions inherited from hpp::core::ObstacleUser
virtual ~ObstacleUser ()
 
const CollisionPairs_tpairs () const
 
CollisionPairs_tpairs ()
 
const CollisionRequests_trequests () const
 
CollisionRequests_trequests ()
 
fcl::CollisionRequestdefaultRequest ()
 
void setRequests (const fcl::CollisionRequest &r)
 
virtual void addObstacle (const CollisionObjectConstPtr_t &object)
 
virtual void addObstacleToJoint (const CollisionObjectConstPtr_t &object, const JointPtr_t &joint, const bool includeChildren)
 
virtual void removeObstacleFromJoint (const JointPtr_t &joint, const CollisionObjectConstPtr_t &object)
 
virtual void filterCollisionPairs (const RelativeMotion::matrix_type &relMotion)
 
virtual void setSecurityMargins (const matrix_t &securityMatrix)
 
- Public Member Functions inherited from hpp::core::ObstacleUserInterface
virtual ~ObstacleUserInterface ()
 

Static Public Member Functions

static CollisionValidationPtr_t create (const DevicePtr_t &robot)
 
- Static Public Member Functions inherited from hpp::core::ObstacleUser
static bool collide (const CollisionPairs_t &pairs, const CollisionRequests_t &reqs, fcl::CollisionResult &res, std::size_t &i, pinocchio::DeviceData &data)
 

Protected Member Functions

 CollisionValidation (const DevicePtr_t &robot)
 
- Protected Member Functions inherited from hpp::core::ConfigValidation
 ConfigValidation ()
 
- Protected Member Functions inherited from hpp::core::ObstacleUser
 ObstacleUser (DevicePtr_t robot)
 Constructor of body pair collision. More...
 
 ObstacleUser (const ObstacleUser &other)
 Copy constructor. More...
 
void addRobotCollisionPairs ()
 

Protected Attributes

DevicePtr_t robot_
 
- Protected Attributes inherited from hpp::core::ObstacleUser
DevicePtr_t robot_
 
fcl::CollisionRequest defaultRequest_
 
CollisionPairs_t cPairs_
 
CollisionPairs_t pPairs_
 Active collision pairs. More...
 
CollisionPairs_t dPairs_
 Parameterized collision pairs. More...
 
CollisionRequests_t cRequests_
 Disabled collision pairs. More...
 
CollisionRequests_t pRequests_
 Active collision requests. More...
 
CollisionRequests_t dRequests_
 Parameterized collision requests. More...
 

Additional Inherited Members

- Public Types inherited from hpp::core::ObstacleUser
typedef std::pair< CollisionObjectConstPtr_t, CollisionObjectConstPtr_tCollisionPair_t
 
typedef std::vector< CollisionPair_tCollisionPairs_t
 
typedef std::vector< fcl::CollisionRequestCollisionRequests_t
 

Detailed Description

Validate a configuration with respect to collision

Constructor & Destructor Documentation

◆ CollisionValidation()

hpp::core::CollisionValidation::CollisionValidation ( const DevicePtr_t robot)
protected

Member Function Documentation

◆ checkParameterized() [1/2]

void hpp::core::CollisionValidation::checkParameterized ( bool  active)
inline

◆ checkParameterized() [2/2]

bool hpp::core::CollisionValidation::checkParameterized ( ) const
inline

◆ computeAllContacts()

void hpp::core::CollisionValidation::computeAllContacts ( bool  computeAllContacts)
inline

◆ create()

static CollisionValidationPtr_t hpp::core::CollisionValidation::create ( const DevicePtr_t robot)
static

◆ validate()

virtual bool hpp::core::CollisionValidation::validate ( const Configuration_t config,
ValidationReportPtr_t validationReport 
)
virtual

Compute whether the configuration is valid

Parameters
configthe config to check for validity,
Return values
validationReportreport on validation. If non valid, a validation report will be allocated and returned via this shared pointer.
Returns
whether the whole config is valid.

Implements hpp::core::ConfigValidation.

Member Data Documentation

◆ robot_

DevicePtr_t hpp::core::CollisionValidation::robot_
protected

The documentation for this class was generated from the following file: