hpp::core::DiscretizedCollisionChecking Class Reference

Validation of path by collision checking at discretized parameter values. More...

#include <hpp/core/discretized-collision-checking.hh>

Inheritance diagram for hpp::core::DiscretizedCollisionChecking:
Collaboration diagram for hpp::core::DiscretizedCollisionChecking:

List of all members.

Public Member Functions

virtual bool validate (const PathPtr_t &path, bool reverse, PathPtr_t &validPart)
 Compute the largest valid interval starting from the path beginning.
virtual bool validate (const PathPtr_t &path, bool reverse, PathPtr_t &validPart, ValidationReport &validationReport)
 Compute the largest valid interval starting from the path beginning.
virtual void addObstacle (const CollisionObjectPtr_t &)
 Add an obstacle.
virtual void removeObstacleFromJoint (const JointPtr_t &joint, const CollisionObjectPtr_t &obstacle)
 Remove a collision pair between a joint and an obstacle.

Static Public Member Functions

static
DiscretizedCollisionCheckingPtr_t 
create (const DevicePtr_t &robot, const value_type &stepSize)

Protected Member Functions

 DiscretizedCollisionChecking (const DevicePtr_t &robot, const value_type &stepSize)

Detailed Description

Validation of path by collision checking at discretized parameter values.

Should be replaced soon by a better algorithm


Constructor & Destructor Documentation

hpp::core::DiscretizedCollisionChecking::DiscretizedCollisionChecking ( const DevicePtr_t robot,
const value_type stepSize 
) [protected]

Member Function Documentation

virtual void hpp::core::DiscretizedCollisionChecking::addObstacle ( const CollisionObjectPtr_t ) [virtual]

Add an obstacle.

Parameters:
objectobstacle added

Reimplemented from hpp::core::PathValidation.

static DiscretizedCollisionCheckingPtr_t hpp::core::DiscretizedCollisionChecking::create ( const DevicePtr_t robot,
const value_type stepSize 
) [static]
virtual void hpp::core::DiscretizedCollisionChecking::removeObstacleFromJoint ( const JointPtr_t joint,
const CollisionObjectPtr_t obstacle 
) [virtual]

Remove a collision pair between a joint and an obstacle.

Parameters:
jointthe joint that holds the inner objects,
obstaclethe obstacle to remove. collision configuration validation needs to know about obstacles. This virtual method does nothing for configuration validation methods that do not care about obstacles.

Reimplemented from hpp::core::PathValidation.

virtual bool hpp::core::DiscretizedCollisionChecking::validate ( const PathPtr_t path,
bool  reverse,
PathPtr_t validPart 
) [virtual]

Compute the largest valid interval starting from the path beginning.

Parameters:
paththe path to check for validity,
reverseif true check from the end,
Return values:
validPartthe extracted valid part of the path, pointer to path if path is valid.
reportinformation about the validation process. The type can be derived for specific implementation
Returns:
whether the whole path is valid.

Implements hpp::core::PathValidation.

virtual bool hpp::core::DiscretizedCollisionChecking::validate ( const PathPtr_t path,
bool  reverse,
PathPtr_t validPart,
ValidationReport validationReport 
) [virtual]

Compute the largest valid interval starting from the path beginning.

Parameters:
paththe path to check for validity,
reverseif true check from the end,
Return values:
validPartthe extracted valid part of the path, pointer to path if path is valid.
validationReportinformation about the validation process: which objects have been detected in collision and at which parameter along the path.
Precondition:
validationReport should be a of type CollisionPathValidationReport.
Returns:
whether the whole path is valid.

Implements hpp::core::PathValidation.