Drake
Drake C++ Documentation
DistanceAndInterpolationProvider Class Referenceabstract

Detailed Description

This class represents the base interface for performing configuration distance and interpolation operations, used by CollisionChecker.

See LinearDistanceAndInterpolationProvider for an implementation covering common "linear" distance and interpolation behavior.

Configuration distance and interpolation are necessary for a CollisionChecker to perform edge collision checks, and an essential part of many motion planning problems. The C-spaces for many planning problems combine joints with widely differing effects (e.g. for a given angular change, the shoulder joint of a robot arm results in much more significant motion than the same change on a finger joint) or units (e.g. a mobile robot with translation in meters and yaw in radians). As a result, it is often necessary to weight elements of the configuration differently when computing configuration distance.

Likewise, in more complex C-spaces, it may be necessary to perform more complex interpolation behavior (e.g. when planning for a mobile robot whose motion is modelled via Dubbins or Reeds-Shepp paths).

Configuration distance takes two configurations of the robot, from and to, both as Eigen::VectorXd, and returns (potentially weighted) C-space distance as a double. The returned distance will be strictly non-negative.

To be valid, distance must satisfy the following condition:

  • ComputeConfigurationDistance(q, q) ≡ 0

for values of q that are valid for the C-space in use.

Configuration interpolation takes two configurations of the robot, from and to, both as Eigen::VectorXd, plus a ratio in [0, 1] and returns the interpolated configuration.

To be valid, interpolation must satisfy the following conditions:

  • InterpolateBetweenConfigurations(from, to, 0) ≡ from
  • InterpolateBetweenConfigurations(from, to, 1) ≡ to
  • InterpolateBetweenConfigurations(q, q, ratio) ≡ q, for all ratio in [0, 1]

for values of q, from, and to that are valid for the C-space in use.

#include <drake/planning/distance_and_interpolation_provider.h>

Public Member Functions

virtual ~DistanceAndInterpolationProvider ()
 
double ComputeConfigurationDistance (const Eigen::VectorXd &from, const Eigen::VectorXd &to) const
 Computes the configuration distance from the provided configuration from to the provided configuration to. More...
 
Eigen::VectorXd InterpolateBetweenConfigurations (const Eigen::VectorXd &from, const Eigen::VectorXd &to, double ratio) const
 Returns the interpolated configuration between from and to at ratio. More...
 
Does not allow copy, move, or assignment
 DistanceAndInterpolationProvider (const DistanceAndInterpolationProvider &)=delete
 
DistanceAndInterpolationProvideroperator= (const DistanceAndInterpolationProvider &)=delete
 
 DistanceAndInterpolationProvider (DistanceAndInterpolationProvider &&)=delete
 
DistanceAndInterpolationProvideroperator= (DistanceAndInterpolationProvider &&)=delete
 

Protected Member Functions

 DistanceAndInterpolationProvider ()
 
virtual double DoComputeConfigurationDistance (const Eigen::VectorXd &from, const Eigen::VectorXd &to) const =0
 Derived distance and interpolation providers must implement distance computation. More...
 
virtual Eigen::VectorXd DoInterpolateBetweenConfigurations (const Eigen::VectorXd &from, const Eigen::VectorXd &to, double ratio) const =0
 Derived distance and interpolation providers must implement interpolation. More...
 

Constructor & Destructor Documentation

◆ DistanceAndInterpolationProvider() [1/3]

◆ DistanceAndInterpolationProvider() [2/3]

◆ ~DistanceAndInterpolationProvider()

virtual ~DistanceAndInterpolationProvider ( )
virtual

◆ DistanceAndInterpolationProvider() [3/3]

Member Function Documentation

◆ ComputeConfigurationDistance()

double ComputeConfigurationDistance ( const Eigen::VectorXd &  from,
const Eigen::VectorXd &  to 
) const

Computes the configuration distance from the provided configuration from to the provided configuration to.

The returned distance will be strictly non-negative.

Precondition
from.size() == to.size()

◆ DoComputeConfigurationDistance()

virtual double DoComputeConfigurationDistance ( const Eigen::VectorXd &  from,
const Eigen::VectorXd &  to 
) const
protectedpure virtual

Derived distance and interpolation providers must implement distance computation.

The returned distance must be non-negative. DistanceAndInterpolationProvider ensures that from and to are the same size.

◆ DoInterpolateBetweenConfigurations()

virtual Eigen::VectorXd DoInterpolateBetweenConfigurations ( const Eigen::VectorXd &  from,
const Eigen::VectorXd &  to,
double  ratio 
) const
protectedpure virtual

Derived distance and interpolation providers must implement interpolation.

The returned configuration must be the same size as from and to. DistanceAndInterpolationProvider ensures that from and to are the same size and that ratio is in [0, 1].

◆ InterpolateBetweenConfigurations()

Eigen::VectorXd InterpolateBetweenConfigurations ( const Eigen::VectorXd &  from,
const Eigen::VectorXd &  to,
double  ratio 
) const

Returns the interpolated configuration between from and to at ratio.

Precondition
from.size() == to.size()
ratio in [0, 1]

◆ operator=() [1/2]

◆ operator=() [2/2]


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