diff --git a/demo/custom_vector_demo.cpp b/demo/custom_vector_demo.cpp index 8919c06..2c39967 100644 --- a/demo/custom_vector_demo.cpp +++ b/demo/custom_vector_demo.cpp @@ -132,7 +132,7 @@ namespace unc::robotics::nigh::metric { // This required method computes and returns the distance // between two points. The computation must match the metric - // a specified by the second template parameter. Note: Nigh + // as specified by the second template parameter. Note: Nigh // could implement this function based upon dimensions(), and // coeff(), however it is likely that a custom data type can // have a much faster implementation (e.g., based upon SIMD diff --git a/src/nigh/impl/non_atomic.hpp b/src/nigh/impl/non_atomic.hpp index d033ab9..4d9f00f 100644 --- a/src/nigh/impl/non_atomic.hpp +++ b/src/nigh/impl/non_atomic.hpp @@ -37,7 +37,7 @@ #ifndef NIGH_IMPL_NON_ATOMIC_HPP #define NIGH_IMPL_NON_ATOMIC_HPP -#include +#include namespace unc::robotics::nigh::impl { // Non-atomic class to mimic std::atomic, but ignore memory diff --git a/src/nigh/impl/region_lp.hpp b/src/nigh/impl/region_lp.hpp index 65f141e..5624174 100644 --- a/src/nigh/impl/region_lp.hpp +++ b/src/nigh/impl/region_lp.hpp @@ -285,9 +285,9 @@ namespace unc::robotics::nigh::impl { Distance distTo(const Key& key) const { std::size_t dimensions = min_.size(); - impl::LPSum sum(std::max({Distance(0), min(0) - key[0], key[0] - max(0)})); + impl::LPSum sum(std::max({Distance(0), min(0) - Space::coeff(key, 0), Space::coeff(key, 0) - max(0)})); for (std::size_t i=1 ; i