Drake
Drake C++ Documentation
LinearDistanceAndInterpolationProvider Class Referencefinal

Detailed Description

This class represents a basic "linear" implementation of DistanceAndInterpolationProvider.

  • Configuration distance is computed as difference.cwiseProduct(weights).norm(), where difference is computed as the angle between quaternion DoF and difference between all other positions. Default weights are (1, 0, 0, 0) for quaternion DoF and 1 for all other positions.
  • Configuration interpolation is performed using slerp for quaternion DoF and linear interpolation for all other positions.

#include <drake/planning/linear_distance_and_interpolation_provider.h>

Public Member Functions

 LinearDistanceAndInterpolationProvider (const multibody::MultibodyPlant< double > &plant, const std::map< multibody::JointIndex, Eigen::VectorXd > &joint_distance_weights)
 Constructs a LinearDistanceAndInterpolationProvider for the specified plant using the provided map of distance weights joint_distance_weights and default weights (i.e. More...
 
 LinearDistanceAndInterpolationProvider (const multibody::MultibodyPlant< double > &plant, const Eigen::VectorXd &distance_weights)
 Constructs a LinearDistanceAndInterpolationProvider for the specified plant with the provided distance weights distance_weights. More...
 
 LinearDistanceAndInterpolationProvider (const multibody::MultibodyPlant< double > &plant)
 Constructs a LinearDistanceAndInterpolationProvider for the specified plant with default distance weights (i.e. More...
 
 ~LinearDistanceAndInterpolationProvider () final
 
const Eigen::VectorXd & distance_weights () const
 Gets the distance weights. More...
 
const std::vector< int > & quaternion_dof_start_indices () const
 Gets the start indices for quaternion DoF in the position vector. More...
 
Does not allow copy, move, or assignment
 LinearDistanceAndInterpolationProvider (const LinearDistanceAndInterpolationProvider &)=delete
 
LinearDistanceAndInterpolationProvideroperator= (const LinearDistanceAndInterpolationProvider &)=delete
 
 LinearDistanceAndInterpolationProvider (LinearDistanceAndInterpolationProvider &&)=delete
 
LinearDistanceAndInterpolationProvideroperator= (LinearDistanceAndInterpolationProvider &&)=delete
 
- Public Member Functions inherited from DistanceAndInterpolationProvider
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...
 
 DistanceAndInterpolationProvider (const DistanceAndInterpolationProvider &)=delete
 
DistanceAndInterpolationProvideroperator= (const DistanceAndInterpolationProvider &)=delete
 
 DistanceAndInterpolationProvider (DistanceAndInterpolationProvider &&)=delete
 
DistanceAndInterpolationProvideroperator= (DistanceAndInterpolationProvider &&)=delete
 

Additional Inherited Members

- Protected Member Functions inherited from DistanceAndInterpolationProvider
 DistanceAndInterpolationProvider ()
 

Constructor & Destructor Documentation

◆ LinearDistanceAndInterpolationProvider() [1/5]

◆ LinearDistanceAndInterpolationProvider() [2/5]

◆ LinearDistanceAndInterpolationProvider() [3/5]

LinearDistanceAndInterpolationProvider ( const multibody::MultibodyPlant< double > &  plant,
const std::map< multibody::JointIndex, Eigen::VectorXd > &  joint_distance_weights 
)

Constructs a LinearDistanceAndInterpolationProvider for the specified plant using the provided map of distance weights joint_distance_weights and default weights (i.e.

1) for all other positions.

Precondition
all distance weights must be non-negative and finite.

◆ LinearDistanceAndInterpolationProvider() [4/5]

LinearDistanceAndInterpolationProvider ( const multibody::MultibodyPlant< double > &  plant,
const Eigen::VectorXd &  distance_weights 
)

Constructs a LinearDistanceAndInterpolationProvider for the specified plant with the provided distance weights distance_weights.

Precondition
distance_weights must be the same size as plant.num_positions(), all weights must be non-negative and finite, and weights for quaternion DoF must be of the form (weight, 0, 0, 0).

◆ LinearDistanceAndInterpolationProvider() [5/5]

Constructs a LinearDistanceAndInterpolationProvider for the specified plant with default distance weights (i.e.

1) for all positions. Equivalent to constructing with an empty map of named joint distance weights.

◆ ~LinearDistanceAndInterpolationProvider()

Member Function Documentation

◆ distance_weights()

const Eigen::VectorXd& distance_weights ( ) const

Gets the distance weights.

◆ operator=() [1/2]

◆ operator=() [2/2]

◆ quaternion_dof_start_indices()

const std::vector<int>& quaternion_dof_start_indices ( ) const

Gets the start indices for quaternion DoF in the position vector.


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