Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

distTo() of LPRegion<Key, -1, p, Concurrent> now does not require Key elements to be accessible as key[i] but uses Space::coeff(key, i) instead #5

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion demo/custom_vector_demo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion src/nigh/impl/non_atomic.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
#ifndef NIGH_IMPL_NON_ATOMIC_HPP
#define NIGH_IMPL_NON_ATOMIC_HPP

#include <atomic>
#include <utility>

namespace unc::robotics::nigh::impl {
// Non-atomic class to mimic std::atomic, but ignore memory
Expand Down
4 changes: 2 additions & 2 deletions src/nigh/impl/region_lp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -285,9 +285,9 @@ namespace unc::robotics::nigh::impl {

Distance distTo(const Key& key) const {
std::size_t dimensions = min_.size();
impl::LPSum<p, Distance> sum(std::max({Distance(0), min(0) - key[0], key[0] - max(0)}));
impl::LPSum<p, Distance> sum(std::max({Distance(0), min(0) - Space::coeff(key, 0), Space::coeff(key, 0) - max(0)}));
for (std::size_t i=1 ; i<dimensions ; ++i)
sum += std::max({Distance(0), min(i) - key[i], key[i] - max(i)});
sum += std::max({Distance(0), min(i) - Space::coeff(key, i), Space::coeff(key, i) - max(i)});
return sum;
}
};
Expand Down