-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
distance_and_interpolation_provider.cc
37 lines (29 loc) · 1.18 KB
/
distance_and_interpolation_provider.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
#include "drake/planning/distance_and_interpolation_provider.h"
#include <cmath>
#include "drake/common/drake_throw.h"
namespace drake {
namespace planning {
DistanceAndInterpolationProvider::~DistanceAndInterpolationProvider() = default;
double DistanceAndInterpolationProvider::ComputeConfigurationDistance(
const Eigen::VectorXd& from, const Eigen::VectorXd& to) const {
DRAKE_THROW_UNLESS(from.size() == to.size());
const double distance = DoComputeConfigurationDistance(from, to);
DRAKE_THROW_UNLESS(distance >= 0.0);
DRAKE_THROW_UNLESS(std::isfinite(distance));
return distance;
}
Eigen::VectorXd
DistanceAndInterpolationProvider::InterpolateBetweenConfigurations(
const Eigen::VectorXd& from, const Eigen::VectorXd& to,
const double ratio) const {
DRAKE_THROW_UNLESS(from.size() == to.size());
DRAKE_THROW_UNLESS(ratio >= 0.0);
DRAKE_THROW_UNLESS(ratio <= 1.0);
Eigen::VectorXd interpolated =
DoInterpolateBetweenConfigurations(from, to, ratio);
DRAKE_THROW_UNLESS(from.size() == interpolated.size());
return interpolated;
}
DistanceAndInterpolationProvider::DistanceAndInterpolationProvider() = default;
} // namespace planning
} // namespace drake