Skip to content

Commit

Permalink
doc(lanelet2_utils): fix invalid drawio link and update image
Browse files Browse the repository at this point in the history
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
  • Loading branch information
soblin committed Mar 10, 2025
1 parent ba30ae2 commit fddfaf4
Show file tree
Hide file tree
Showing 26 changed files with 295 additions and 170 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,13 @@ class InterpolatedArray
return interpolator_->build(bases_, values_);
}

bool build(std::vector<double> && bases, std::vector<T> && values)
{
bases_ = std::move(bases);
values_ = std::move(values);
return interpolator_->build(bases_, values_);
}

/**
* @brief Move constructor.
* @param other The InterpolatedArray to move from.
Expand Down Expand Up @@ -99,22 +106,22 @@ class InterpolatedArray
* @brief Get the start value of the base.
* @return The start value.
*/
[[nodiscard]] double start() const { return bases_.front(); }
double start() const { return bases_.front(); }

/**
* @brief Get the end value of the base.
* @return The end value.
*/
[[nodiscard]] double end() const { return bases_.at(bases_.size() - 1); }
double end() const { return bases_.at(bases_.size() - 1); }

class Segment
{
friend class InterpolatedArray;

double start_;
double end_;
const double start_;
const double end_;
InterpolatedArray<T> & parent_;
Segment(InterpolatedArray<T> & parent, double start, double end)
Segment(InterpolatedArray<T> & parent, const double start, const double end)
: start_(start), end_(end), parent_(parent)
{
}
Expand All @@ -125,7 +132,7 @@ class InterpolatedArray
std::vector<double> & bases = parent_.bases_;
std::vector<T> & values = parent_.values_;

auto insert_if_not_present = [&](double val) -> size_t {
auto insert_if_not_present = [&](const double val) -> size_t {
auto it = std::lower_bound(bases.begin(), bases.end(), val);
size_t index = std::distance(bases.begin(), it);

Expand Down Expand Up @@ -200,16 +207,13 @@ class InterpolatedArray
* @param x The position to compute the value at.
* @return The interpolated value.
*/
[[nodiscard]] T compute(const double & x) const { return interpolator_->compute(x); }
T compute(const double x) const { return interpolator_->compute(x); }

/**
* @brief Get the underlying data of the array.
* @return A pair containing the axis and values.
*/
[[nodiscard]] std::pair<std::vector<double>, std::vector<T>> get_data() const
{
return {bases_, values_};
}
std::pair<std::vector<double>, std::vector<T>> get_data() const { return {bases_, values_}; }
};

} // namespace autoware::trajectory::detail
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,31 +52,41 @@ class AkimaSpline : public detail::InterpolatorMixin<AkimaSpline, double>
* @param bases The bases values.
* @param values The values to interpolate.
*/
void build_impl(const std::vector<double> & bases, const std::vector<double> & values) override;
[[nodiscard]] bool build_impl(
const std::vector<double> & bases, const std::vector<double> & values) override;

/**
* @brief Build the interpolator with the given values.
*
* @param bases The bases values.
* @param values The values to interpolate.
*/
[[nodiscard]] bool build_impl(
std::vector<double> && bases, std::vector<double> && values) override;

/**
* @brief Compute the interpolated value at the given point.
*
* @param s The point at which to compute the interpolated value.
* @return The interpolated value.
*/
[[nodiscard]] double compute_impl(const double & s) const override;
double compute_impl(const double s) const override;

/**
* @brief Compute the first derivative at the given point.
*
* @param s The point at which to compute the first derivative.
* @return The first derivative.
*/
[[nodiscard]] double compute_first_derivative_impl(const double & s) const override;
double compute_first_derivative_impl(const double s) const override;

/**
* @brief Compute the second derivative at the given point.
*
* @param s The point at which to compute the second derivative.
* @return The second derivative.
*/
[[nodiscard]] double compute_second_derivative_impl(const double & s) const override;
double compute_second_derivative_impl(const double s) const override;

public:
AkimaSpline() = default;
Expand All @@ -86,7 +96,7 @@ class AkimaSpline : public detail::InterpolatorMixin<AkimaSpline, double>
*
* @return The minimum number of required points.
*/
[[nodiscard]] size_t minimum_required_points() const override { return 5; }
size_t minimum_required_points() const override { return 5; }
};

} // namespace autoware::trajectory::interpolator
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,31 +54,42 @@ class CubicSpline : public detail::InterpolatorMixin<CubicSpline, double>
* @param values The values to interpolate.
* @return True if the interpolator was built successfully, false otherwise.
*/
void build_impl(const std::vector<double> & bases, const std::vector<double> & values) override;
[[nodiscard]] bool build_impl(
const std::vector<double> & bases, const std::vector<double> & values) override;

/**
* @brief Build the interpolator with the given values.
*
* @param bases The bases values.
* @param values The values to interpolate.
* @return True if the interpolator was built successfully, false otherwise.
*/
[[nodiscard]] bool build_impl(
std::vector<double> && bases, std::vector<double> && values) override;

/**
* @brief Compute the interpolated value at the given point.
*
* @param s The point at which to compute the interpolated value.
* @return The interpolated value.
*/
[[nodiscard]] double compute_impl(const double & s) const override;
double compute_impl(const double s) const override;

/**
* @brief Compute the first derivative at the given point.
*
* @param s The point at which to compute the first derivative.
* @return The first derivative.
*/
[[nodiscard]] double compute_first_derivative_impl(const double & s) const override;
double compute_first_derivative_impl(const double s) const override;

/**
* @brief Compute the second derivative at the given point.
*
* @param s The point at which to compute the second derivative.
* @return The second derivative.
*/
[[nodiscard]] double compute_second_derivative_impl(const double & s) const override;
double compute_second_derivative_impl(const double s) const override;

public:
CubicSpline() = default;
Expand All @@ -88,7 +99,7 @@ class CubicSpline : public detail::InterpolatorMixin<CubicSpline, double>
*
* @return The minimum number of required points.
*/
[[nodiscard]] size_t minimum_required_points() const override { return 4; }
size_t minimum_required_points() const override { return 4; }
};

} // namespace autoware::trajectory::interpolator
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,17 +35,16 @@ class InterpolatorCommonInterface
{
protected:
std::vector<double> bases_; ///< bases values for the interpolation.
bool is_built_{false}; ///< flag indicating whether the interpolator has been built.

/**
* @brief Get the start of the interpolation range.
*/
[[nodiscard]] double start() const { return bases_.front(); }
double start() const { return bases_.front(); }

/**
* @brief Get the end of the interpolation range.
*/
[[nodiscard]] double end() const { return bases_.back(); }
double end() const { return bases_.back(); }

/**
* @brief Compute the interpolated value at the given point.
Expand All @@ -55,7 +54,7 @@ class InterpolatorCommonInterface
* @param s The point at which to compute the interpolated value.
* @return The interpolated value.
*/
[[nodiscard]] virtual T compute_impl(const double & s) const = 0;
virtual T compute_impl(const double s) const = 0;

/**
* @brief Build the interpolator with the given values.
Expand All @@ -65,7 +64,18 @@ class InterpolatorCommonInterface
* @param bases The bases values.
* @param values The values to interpolate.
*/
virtual void build_impl(const std::vector<double> & bases, const std::vector<T> & values) = 0;
[[nodiscard]] virtual bool build_impl(
const std::vector<double> & bases, const std::vector<T> & values) = 0;

/**
* @brief Build the interpolator with the given values.
*
* This method should be overridden by subclasses to provide the specific build logic.
*
* @param bases The bases values.
* @param values The values to interpolate.
*/
[[nodiscard]] virtual bool build_impl(std::vector<double> && bases, std::vector<T> && values) = 0;

/**
* @brief Validate the input to the compute method.
Expand All @@ -75,7 +85,7 @@ class InterpolatorCommonInterface
* @param s The input value.
* @return The input value, clamped to the range of the interpolator.
*/
[[nodiscard]] double validate_compute_input(const double & s) const
double validate_compute_input(const double s) const
{
if (s < start() || s > end()) {
RCLCPP_WARN(
Expand All @@ -100,7 +110,7 @@ class InterpolatorCommonInterface
*
* @throw std::out_of_range if the input value is outside the range of the bases array.
*/
[[nodiscard]] int32_t get_index(const double & s, bool end_inclusive = true) const
int32_t get_index(const double s, bool end_inclusive = true) const
{
if (end_inclusive && s == end()) {
return static_cast<int32_t>(bases_.size()) - 2;
Expand All @@ -125,34 +135,32 @@ class InterpolatorCommonInterface
* @param values The values to interpolate.
* @return True if the interpolator was built successfully, false otherwise.
*/
[[nodiscard]] bool build(const std::vector<double> & bases, const std::vector<T> & values)
template <typename BaseVectorT, typename ValueVectorT>
[[nodiscard]] auto build(BaseVectorT && bases, ValueVectorT && values) -> std::enable_if_t<
std::conjunction_v<
std::is_same<std::decay_t<BaseVectorT>, std::vector<double>>,
std::is_same<std::decay_t<ValueVectorT>, std::vector<T>>>,
bool>
{
if (bases.size() != values.size()) {
return false;
}
if (bases.size() < minimum_required_points()) {
return false;
}
build_impl(bases, values);
is_built_ = true;
return true;
return build_impl(
std::forward<std::decay_t<BaseVectorT>>(bases),
std::forward<std::decay_t<ValueVectorT>>(values));
}

/**
* @brief Check if the interpolator has been built.
*
* @return True if the interpolator has been built, false otherwise.
*/
[[nodiscard]] bool is_built() const { return is_built_; }

/**
* @brief Get the minimum number of required points for the interpolator.
*
* This method should be overridden by subclasses to return the specific requirement.
*
* @return The minimum number of required points.
*/
[[nodiscard]] virtual size_t minimum_required_points() const = 0;
virtual size_t minimum_required_points() const = 0;

/**
* @brief Compute the interpolated value at the given point.
Expand All @@ -161,12 +169,8 @@ class InterpolatorCommonInterface
* @return The interpolated value.
* @throw std::runtime_error if the interpolator has not been built.
*/
[[nodiscard]] T compute(const double & s) const
T compute(const double s) const
{
if (!is_built_) {
throw std::runtime_error(
"Interpolator has not been built."); // This Exception should not be thrown.
}
const double clamped_s = validate_compute_input(s);
return compute_impl(clamped_s);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ namespace autoware::trajectory::interpolator::detail
template <class InterpolatorType, class T>
struct InterpolatorMixin : public InterpolatorInterface<T>
{
[[nodiscard]] std::shared_ptr<InterpolatorInterface<T>> clone() const override
std::shared_ptr<InterpolatorInterface<T>> clone() const override
{
return std::make_shared<InterpolatorType>(static_cast<const InterpolatorType &>(*this));
}
Expand All @@ -62,17 +62,29 @@ struct InterpolatorMixin : public InterpolatorInterface<T>
return *this;
}

[[nodiscard]] Builder & set_bases(std::vector<double> && bases)
{
bases_ = std::move(bases);
return *this;
}

[[nodiscard]] Builder & set_values(const std::vector<T> & values)
{
values_ = values;
return *this;
}

[[nodiscard]] Builder & set_values(std::vector<T> && values)
{
values_ = std::move(values);
return *this;
}

template <typename... Args>
[[nodiscard]] std::optional<InterpolatorType> build(Args &&... args)
{
auto interpolator = InterpolatorType(std::forward<Args>(args)...);
const bool success = interpolator.build(bases_, values_);
const bool success = interpolator.build(std::move(bases_), std::move(values_));
if (!success) {
return std::nullopt;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class NearestNeighborCommonImpl : public detail::InterpolatorMixin<NearestNeighb
* @param s The point at which to compute the interpolated value.
* @return The interpolated value.
*/
[[nodiscard]] T compute_impl(const double & s) const override
T compute_impl(const double s) const override
{
const int32_t idx = this->get_index(s);
return (std::abs(s - this->bases_[idx]) <= std::abs(s - this->bases_[idx + 1]))
Expand All @@ -61,10 +61,26 @@ class NearestNeighborCommonImpl : public detail::InterpolatorMixin<NearestNeighb
* @param values The values to interpolate.
* @return True if the interpolator was built successfully, false otherwise.
*/
void build_impl(const std::vector<double> & bases, const std::vector<T> & values) override
[[nodiscard]] bool build_impl(
const std::vector<double> & bases, const std::vector<T> & values) override
{
this->bases_ = bases;
this->values_ = values;
return true;
}

/**
* @brief Build the interpolator with the given values.
*
* @param bases The bases values.
* @param values The values to interpolate.
* @return True if the interpolator was built successfully, false otherwise.
*/
[[nodiscard]] bool build_impl(std::vector<double> && bases, std::vector<T> && values) override
{
this->bases_ = std::move(bases);
this->values_ = std::move(values);
return true;
}

public:
Expand All @@ -73,7 +89,7 @@ class NearestNeighborCommonImpl : public detail::InterpolatorMixin<NearestNeighb
*
* @return The minimum number of required points.
*/
[[nodiscard]] size_t minimum_required_points() const override { return 1; }
size_t minimum_required_points() const override { return 1; }
};

} // namespace detail
Expand Down
Loading

0 comments on commit fddfaf4

Please sign in to comment.