This class represents a basic "linear" implementation of DistanceAndInterpolationProvider.
#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. | |
| 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. | |
| LinearDistanceAndInterpolationProvider (const multibody::MultibodyPlant< double > &plant) | |
| Constructs a LinearDistanceAndInterpolationProvider for the specified plant with default distance weights (i.e. | |
| ~LinearDistanceAndInterpolationProvider () final | |
| const Eigen::VectorXd & | distance_weights () const |
| Gets the distance weights. | |
| const std::vector< int > & | quaternion_dof_start_indices () const |
| Gets the start indices for quaternion DoF in the position vector. | |
Does not allow copy, move, or assignment | |
| LinearDistanceAndInterpolationProvider (const LinearDistanceAndInterpolationProvider &)=delete | |
| LinearDistanceAndInterpolationProvider & | operator= (const LinearDistanceAndInterpolationProvider &)=delete |
| LinearDistanceAndInterpolationProvider (LinearDistanceAndInterpolationProvider &&)=delete | |
| LinearDistanceAndInterpolationProvider & | operator= (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. | |
| Eigen::VectorXd | InterpolateBetweenConfigurations (const Eigen::VectorXd &from, const Eigen::VectorXd &to, double ratio) const |
| Returns the interpolated configuration between from and to at ratio. | |
| DistanceAndInterpolationProvider (const DistanceAndInterpolationProvider &)=delete | |
| DistanceAndInterpolationProvider & | operator= (const DistanceAndInterpolationProvider &)=delete |
| DistanceAndInterpolationProvider (DistanceAndInterpolationProvider &&)=delete | |
| DistanceAndInterpolationProvider & | operator= (DistanceAndInterpolationProvider &&)=delete |
Additional Inherited Members | |
| Protected Member Functions inherited from DistanceAndInterpolationProvider | |
| DistanceAndInterpolationProvider () | |
|
delete |
| 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.
| 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.
|
explicit |
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.
|
final |
| const Eigen::VectorXd & distance_weights | ( | ) | const |
Gets the distance weights.
|
delete |
|
delete |
| const std::vector< int > & quaternion_dof_start_indices | ( | ) | const |
Gets the start indices for quaternion DoF in the position vector.