Skip to content

Commit

Permalink
Create raster based on face interpolation. (#3161)
Browse files Browse the repository at this point in the history
* FaceRasterFilter.

* Link MathUtils so we don't need to export the symbols.

* Updates for change in Raster and review.

* Add test and fix small problems.

* Missed file.

* Actually test stuff.
  • Loading branch information
abellgithub committed Jul 10, 2020
1 parent 20b3983 commit 9f13fa0
Show file tree
Hide file tree
Showing 14 changed files with 750 additions and 76 deletions.
151 changes: 151 additions & 0 deletions filters/FaceRasterFilter.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,151 @@
/******************************************************************************
* Copyright (c) 2020, Hobu Inc.
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following
* conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Hobu, Inc. or Flaxen Geo Consulting nor the
* names of its contributors may be used to endorse or promote
* products derived from this software without specific prior
* written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
* OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
* OF SUCH DAMAGE.
****************************************************************************/

#include "FaceRasterFilter.hpp"

#include <pdal/util/Utils.hpp>
#include <pdal/private/MathUtils.hpp>

namespace pdal
{

static StaticPluginInfo const s_info
{
"filters.faceraster",
"Face Raster Filter",
"http://pdal.io/stages/filters.faceraster.html"
};

CREATE_STATIC_STAGE(FaceRasterFilter, s_info)

std::string FaceRasterFilter::getName() const
{
return s_info.name;
}


FaceRasterFilter::FaceRasterFilter()
{}


void FaceRasterFilter::addArgs(ProgramArgs& args)
{
m_limits.addArgs(args);
args.add("mesh", "Mesh name", m_meshName);
}

void FaceRasterFilter::prepared(PointTableRef)
{
int cnt = m_limits.checkArgs();
if (cnt != 0 && cnt != 4)
throwError("Must specify all or none of 'origin_x', 'origin_y', 'width' and 'height'.");
m_computeLimits = (cnt == 0);
}


void FaceRasterFilter::filter(PointView& v)
{
double halfEdge = m_limits.edgeLength / 2;
double edgeBit = m_limits.edgeLength * .000001;

// If the user hasn't set bounds, set them based on the data.
if (m_computeLimits)
{
BOX2D bounds;
v.calculateBounds(bounds);
m_limits.xOrigin = bounds.minx - halfEdge;
m_limits.yOrigin = bounds.miny - halfEdge;
m_limits.width = ((bounds.maxx - m_limits.xOrigin) / m_limits.edgeLength) + 1;
m_limits.height = ((bounds.maxy - m_limits.yOrigin) / m_limits.edgeLength) + 1;
}
Rasterd *raster = v.createRaster("faceraster", m_limits);
if (!raster)
throwError("Raster already exists");

TriangularMesh *m = v.mesh(m_meshName);
if (!m)
throwError("Mesh '" + m_meshName + "' does not exist.");

for (const Triangle& t : *m)
{
double x1 = v.getFieldAs<double>(Dimension::Id::X, t.m_a);
double y1 = v.getFieldAs<double>(Dimension::Id::Y, t.m_a);
double z1 = v.getFieldAs<double>(Dimension::Id::Z, t.m_a);

double x2 = v.getFieldAs<double>(Dimension::Id::X, t.m_b);
double y2 = v.getFieldAs<double>(Dimension::Id::Y, t.m_b);
double z2 = v.getFieldAs<double>(Dimension::Id::Z, t.m_b);

double x3 = v.getFieldAs<double>(Dimension::Id::X, t.m_c);
double y3 = v.getFieldAs<double>(Dimension::Id::Y, t.m_c);
double z3 = v.getFieldAs<double>(Dimension::Id::Z, t.m_c);

double xmax = (std::max)((std::max)(x1, x2), x3);
double xmin = (std::min)((std::min)(x1, x2), x3);
double ymax = (std::max)((std::max)(y1, y2), y3);
double ymin = (std::min)((std::min)(y1, y2), y3);

// Since we're checking cell centers, we add 1/2 the edge length to avoid testing cells
// where we know the limiting position can't intersect the cell center. The
// subtraction of edgeBit for the lower bound is to allow for the case where the
// minimum position is exactly aligned with a cell center (we could simply start one cell
// lower and to the left, but this small adjustment eliminates that extra row/col in most
// cases).
int ax = raster->xCell(xmin + halfEdge - edgeBit);
int ay = raster->yCell(ymin + halfEdge - edgeBit);

// edgeBit adjustment not necessary here since we're rounding up for exact values.
int bx = raster->xCell(xmax + halfEdge);
int by = raster->yCell(ymax + halfEdge);

ax = Utils::clamp(ax, 0, (int)m_limits.width);
bx = Utils::clamp(bx, 0, (int)m_limits.width);
ay = Utils::clamp(ay, 0, (int)m_limits.height);
by = Utils::clamp(by, 0, (int)m_limits.height);

for (int xi = ax; xi < bx; ++xi)
for (int yi = ay; yi < by; ++yi)
{
double x = raster->xCellPos(xi);
double y = raster->yCellPos(yi);

double val = math::barycentricInterpolation(x1, y1, z1,
x2, y2, z2, x3, y3, z3, x, y);
if (val != std::numeric_limits<double>::infinity())
raster->at(xi, yi) = val;
}
}
}

} // namespace pdal
65 changes: 65 additions & 0 deletions filters/FaceRasterFilter.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
/******************************************************************************
* Copyright (c) 2020, Hobu Inc.
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following
* conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Hobu, Inc. or Flaxen Geo Consulting nor the
* names of its contributors may be used to endorse or promote
* products derived from this software without specific prior
* written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
* OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
* OF SUCH DAMAGE.
****************************************************************************/

#pragma once

#include <pdal/Filter.hpp>
#include <pdal/private/Raster.hpp>

namespace pdal
{

template <typename T>
class Raster;

class PDAL_DLL FaceRasterFilter : public pdal::Filter
{
public:
FaceRasterFilter();
FaceRasterFilter& operator=(const FaceRasterFilter&) = delete;
FaceRasterFilter(const FaceRasterFilter&) = delete;

std::string getName() const;

private:
virtual void addArgs(ProgramArgs& args);
virtual void prepared(PointTableRef);
virtual void filter(PointView& view);

RasterLimits m_limits;
std::string m_meshName;
bool m_computeLimits;
};

} // namespace pdal
49 changes: 2 additions & 47 deletions filters/HagDelaunayFilter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
#include "HagDelaunayFilter.hpp"

#include <pdal/KDIndex.hpp>
#include <pdal/private/MathUtils.hpp>

#include "private/delaunator.hpp"

Expand All @@ -45,52 +46,6 @@ namespace pdal
namespace
{

// https://en.wikipedia.org/wiki/Barycentric_coordinate_system
// http://blackpawn.com/texts/pointinpoly/default.html
//
// If x/y is in the triangle, we'll return a valid distance.
// If not, we return infinity. If the determinant is 0, the input points
// aren't a triangle (they're collinear).
double distance_along_z(double x1, double y1, double z1,
double x2, double y2, double z2,
double x3, double y3, double z3,
double x, double y)
{
double z = std::numeric_limits<double>::infinity();

double detT = ((y2-y3) * (x1-x3)) + ((x3-x2) * (y1-y3));

//ABELL - should probably check something close to 0, rather than
// exactly 0.
if (detT != 0.0)
{
// Compute the barycentric coordinates of x,y (relative to
// x1/y1, x2/y2, x3/y3). Essentially the weight that each
// corner of the triangle contributes to the point in question.

// Another way to think about this is that we're making a basis
// for the system with the basis vectors being two sides of
// the triangle. You can rearrange the z calculation below in
// terms of lambda1 and lambda2 to see this. Also note that
// since lambda1 and lambda2 are coefficients of the basis vectors,
// any values outside of the range [0,1] are necessarily out of the
// triangle.
double lambda1 = ((y2-y3) * (x-x3) + (x3-x2) * (y-y3)) / detT;
double lambda2 = ((y3-y1) * (x-x3) + (x1-x3) * (y-y3)) / detT;
if (lambda1 >= 0 && lambda1 <= 1 && lambda2 >= 0 && lambda2 <= 1)
{
double sum = lambda1 + lambda2;
if (sum <= 1)
{
double lambda3 = 1 - sum;
z = (lambda1 * z1) + (lambda2 * z2) + (lambda3 * z3);
}
}
}
return z;
}


// The non-ground point (x0, y0) is in exactly 0 or 1 of the triangles of
// the ground triangulation, so when we find a triangle containing the point,
// return the interpolated z.
Expand Down Expand Up @@ -131,7 +86,7 @@ double delaunay_interp_ground(double x0, double y0, PointViewPtr gView,
double cz = gView->getFieldAs<double>(Id::Z, ids[ci]);

// Returns infinity unless the point x0/y0 is in the triangle.
double z1 = distance_along_z(ax, ay, az, bx, by, bz,
double z1 = math::barycentricInterpolation(ax, ay, az, bx, by, bz,
cx, cy, cz, x0, y0);
if (z1 != std::numeric_limits<double>::infinity())
return z1;
Expand Down
3 changes: 2 additions & 1 deletion io/private/GDALGrid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,8 @@ namespace pdal
GDALGrid::GDALGrid(size_t width, size_t height, double edgeLength,
double radius, int outputTypes, size_t windowSize, double power) :
m_width(width), m_height(height), m_windowSize(windowSize),
m_edgeLength(edgeLength), m_radius(radius), m_power(power), m_outputTypes(outputTypes)
m_edgeLength(edgeLength), m_radius(radius), m_power(power),
m_outputTypes(outputTypes)
{
if (width > (size_t)(std::numeric_limits<int>::max)() ||
height > (size_t)(std::numeric_limits<int>::max)())
Expand Down
3 changes: 2 additions & 1 deletion io/private/GDALGrid.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,8 @@ class GDALGrid

// Exported for testing.
PDAL_DLL GDALGrid(size_t width, size_t height,
double edgeLength, double radius, int outputTypes, size_t windowSize, double power);
double edgeLength, double radius, int outputTypes, size_t windowSize,
double power);

void expand(size_t width, size_t height, size_t xshift, size_t yshift);

Expand Down
23 changes: 23 additions & 0 deletions pdal/PointView.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,6 +180,29 @@ TriangularMesh *PointView::mesh(const std::string& name)
}


Rasterd *PointView::createRaster(const std::string& name, const RasterLimits& limits)
{
if (Utils::contains(m_rasters, name))
return nullptr;
auto res = m_rasters.insert(std::make_pair(name,
std::unique_ptr<Rasterd>(new Rasterd(limits))));
if (res.second)
return res.first->second.get();
return nullptr;
}


Rasterd *PointView::raster(const std::string& name)
{
auto it = m_rasters.find(name);
if (it != m_rasters.end())
return it->second.get();
if (name.empty() && m_rasters.size())
return m_rasters.begin()->second.get();
return nullptr;
}


void PointView::invalidateProducts()
{
m_index2.reset();
Expand Down
19 changes: 19 additions & 0 deletions pdal/PointView.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include <pdal/PointLayout.hpp>
#include <pdal/PointTable.hpp>
#include <pdal/PointRef.hpp>
#include <pdal/private/Raster.hpp>

#include <memory>
#include <queue>
Expand Down Expand Up @@ -287,6 +288,23 @@ class PDAL_DLL PointView : public PointContainer
*/
TriangularMesh *mesh(const std::string& name = "");

/**
Creates a raster with the specified name.
\param name Name of the raster.
\param limits Limits of the raster to create.
\return Pointer to the new raster. Null is returned if the raster already exists.
*/
Rasterd *createRaster(const std::string& name, const RasterLimits& limits);

/**
Get a pointer to a raster.
\param name Name of the raster.
\return Pointer to the New raster. Null
*/
Rasterd *raster(const std::string& name = "");

KD3Index& build3dIndex();
KD2Index& build2dIndex();

Expand All @@ -301,6 +319,7 @@ class PDAL_DLL PointView : public PointContainer
std::queue<PointId> m_temps;
SpatialReference m_spatialReference;
std::map<std::string, std::unique_ptr<TriangularMesh>> m_meshes;
std::map<std::string, std::unique_ptr<Rasterd>> m_rasters;
std::unique_ptr<KD3Index> m_index3;
std::unique_ptr<KD2Index> m_index2;

Expand Down

0 comments on commit 9f13fa0

Please sign in to comment.