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

[core] Various cleanup and bug fixes of Perlin processes. #825

Merged
merged 1 commit into from
Jul 14, 2024
Merged
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
85 changes: 44 additions & 41 deletions core/include/jiminy/core/utilities/random.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
namespace jiminy
{
static inline constexpr double PERLIN_NOISE_PERSISTENCE{1.50};
static inline constexpr double PERLIN_NOISE_LACUNARITY{1.15};
static inline constexpr double PERLIN_NOISE_LACUNARITY{0.85};

// ***************************** Uniform random bit generators ***************************** //

Expand Down Expand Up @@ -230,8 +230,7 @@ namespace jiminy
{
JIMINY_THROW(std::invalid_argument, "'wavelength' must be strictly larger than 0.0.");
}
auto gen = uniform_random_bit_generator_ref<uint32_t>{std::random_device{}};
shift_ = uniform(N, 1, gen).cast<double>();
reset(std::random_device{});
}

template<template<unsigned int> class DerivedPerlinNoiseOctave, unsigned int N>
Expand Down Expand Up @@ -297,7 +296,7 @@ namespace jiminy
{
VectorN<int32_t> knot;
VectorN<double> delta;
const auto derived = static_cast<const DerivedPerlinNoiseOctave<N> &>(*this);
const auto & derived = static_cast<const DerivedPerlinNoiseOctave<N> &>(*this);
for (uint32_t k = 0; k < (1U << N); k++)
{
// Mapping from index to knot
Expand Down Expand Up @@ -398,7 +397,7 @@ namespace jiminy
RandomPerlinNoiseOctave<N>::RandomPerlinNoiseOctave(double wavelength) :
AbstractPerlinNoiseOctave<RandomPerlinNoiseOctave, N>(wavelength)
{
seed_ = std::random_device{}();
reset(std::random_device{});
}

template<unsigned int N>
Expand All @@ -408,7 +407,7 @@ namespace jiminy
// Call base implementation
AbstractPerlinNoiseOctave<RandomPerlinNoiseOctave, N>::reset(g);

// Sample new random seed for MurmurHash
// Sample new random seed
seed_ = g();
}

Expand Down Expand Up @@ -502,12 +501,6 @@ namespace jiminy
reset(std::random_device{});
}

template<unsigned int N>
double PeriodicPerlinNoiseOctave<N>::getPeriod() const noexcept
{
return period_;
}

template<unsigned int N>
void PeriodicPerlinNoiseOctave<N>::reset(
const uniform_random_bit_generator_ref<uint32_t> & g) noexcept
Expand All @@ -516,28 +509,25 @@ namespace jiminy
AbstractPerlinNoiseOctave<PeriodicPerlinNoiseOctave, N>::reset(g);

// Re-initialize the pre-computed hash table
std::generate(
grads_.begin(),
grads_.end(),
[&g]() -> VectorN<double>
for (auto & grad : grads_)
{
if constexpr (N == 1)
{
if constexpr (N == 1)
{
return VectorN<double>{uniform(g, -1.0F, 1.0F)};
}
else if constexpr (N == 2)
{
const double theta = 2 * M_PI * uniform(g);
const float radius = std::sqrt(uniform(g));
return VectorN<double>{radius * std::cos(theta), radius * std::sin(theta)};
}
else
{
const VectorN<double> dir = normal(N, 1, g).cast<double>().normalized();
const double radius = std::pow(uniform(g), 1.0 / N);
return radius * dir;
}
});
grad = VectorN<double>{uniform(g, -1.0F, 1.0F)};
}
else if constexpr (N == 2)
{
const double theta = 2 * M_PI * uniform(g);
const float radius = std::sqrt(uniform(g));
grad = VectorN<double>{radius * std::cos(theta), radius * std::sin(theta)};
}
else
{
const VectorN<double> dir = normal(N, 1, g).cast<double>().normalized();
const double radius = std::pow(uniform(g), 1.0 / N);
grad = radius * dir;
}
}
}

template<unsigned int N>
Expand All @@ -562,6 +552,12 @@ namespace jiminy
return grads_[index];
}

template<unsigned int N>
double PeriodicPerlinNoiseOctave<N>::getPeriod() const noexcept
{
return period_;
}

template<template<unsigned int> class DerivedPerlinNoiseOctave, unsigned int N>
AbstractPerlinProcess<DerivedPerlinNoiseOctave, N>::AbstractPerlinProcess(
std::vector<OctaveScalePair> && octaveScalePairs) noexcept :
Expand Down Expand Up @@ -643,19 +639,26 @@ namespace jiminy
static std::vector<std::pair<DerivedPerlinNoiseOctave<N>, const double>>
buildPerlinNoiseOctaves(double wavelength, std::size_t numOctaves, ExtraArgs &&... args)
{
// Make sure that at least one octave has been requested
if (numOctaves < 1)
{
JIMINY_THROW(std::invalid_argument, "'numOctaves' must at least 1.");
}

// Make sure that wavelength of all the octaves is consistent with period if application
if constexpr (std::is_base_of_v<PeriodicPerlinNoiseOctave<N>, DerivedPerlinNoiseOctave<N>>)
{
const double period = std::get<0>(std::tuple{std::forward<ExtraArgs>(args)...});
const double wavelengthMax =
std::pow(PERLIN_NOISE_LACUNARITY, numOctaves) * wavelength;
if (period < wavelengthMax)
const double wavelengthFinal =
wavelength / std::pow(PERLIN_NOISE_LACUNARITY, numOctaves - 1);
if (period < std::max(wavelength, wavelengthFinal))
{
JIMINY_THROW(std::invalid_argument,
"'period' must be larger than (",
"'period' must be larger than the wavelength of all the octaves (",
std::max(wavelength, wavelengthFinal),
"), ie 'wavelength' / ",
PERLIN_NOISE_LACUNARITY,
"^'numOctaves') * 'wavelength' (ie. ",
wavelengthMax,
").");
"^i for i in [1, ..., 'numOctaves'].");
}
}

Expand All @@ -665,7 +668,7 @@ namespace jiminy
for (std::size_t i = 0; i < numOctaves; ++i)
{
octaveScalePairs.emplace_back(DerivedPerlinNoiseOctave<N>(wavelength, args...), scale);
wavelength *= PERLIN_NOISE_LACUNARITY;
wavelength /= PERLIN_NOISE_LACUNARITY;
scale *= PERLIN_NOISE_PERSISTENCE;
}
return octaveScalePairs;
Expand Down
2 changes: 1 addition & 1 deletion core/src/utilities/geometry.cc
Original file line number Diff line number Diff line change
Expand Up @@ -902,7 +902,7 @@ namespace jiminy
const auto grad = fun.grad(pos);

// Compute the inverse of the normal's Euclidean norm
const double normInv = 1.0 / grad.norm();
const double normInv = 1.0 / std::sqrt(1.0 + grad.squaredNorm());

// Update normal vector
normal.value() << -normInv * grad.template head<2>(), normInv;
Expand Down
Loading