This class represents a basic "linear" implementation of DistanceAndInterpolationProvider.
#include <drake/planning/linear_distance_and_interpolation_provider.h>
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.