Merge pull request #24459 from savuor:tri_rasterize

Triangle rasterization function #24459

#24065 reopened since the previous one was automatically closed after rebase
Connected PR with ground truth data: [#1113@extra](https://github.com/opencv/opencv_extra/pull/1113)

### Pull Request Readiness Checklist

See details at https://github.com/opencv/opencv/wiki/How_to_contribute#making-a-good-pull-request

- [x] I agree to contribute to the project under Apache 2 License.
- [x] To the best of my knowledge, the proposed patch is not based on a code under GPL or another license that is incompatible with OpenCV
- [x] The PR is proposed to the proper branch
- [x] There is a reference to the original bug report and related work
- [x] There is accuracy test, performance test and test data in opencv_extra repository, if applicable
      Patch to opencv_extra has the same branch name.
- [x] The feature is well documented and sample code can be built with the project CMake
pull/25080/head
Rostislav Vasilikhin 10 months ago committed by GitHub
parent f084a229b4
commit fa745553bf
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
  1. 130
      modules/3d/include/opencv2/3d.hpp
  2. 113
      modules/3d/misc/python/test/test_raster.py
  3. 344
      modules/3d/perf/perf_rendering.cpp
  4. 402
      modules/3d/src/rendering.cpp
  5. 948
      modules/3d/test/test_rendering.cpp
  6. 1
      samples/opengl/CMakeLists.txt
  7. 460
      samples/opengl/opengl_testdata_generator.cpp

@ -2848,6 +2848,136 @@ CV_EXPORTS_W void loadMesh(const String &filename, OutputArray vertices, OutputA
CV_EXPORTS_W void saveMesh(const String &filename, InputArray vertices, InputArrayOfArrays indices,
InputArray normals = noArray(), InputArray colors = noArray());
//! Triangle fill settings
enum TriangleShadingType
{
RASTERIZE_SHADING_WHITE = 0, //!< a white color is used for the whole triangle
RASTERIZE_SHADING_FLAT = 1, //!< a color of 1st vertex of each triangle is used
RASTERIZE_SHADING_SHADED = 2 //!< a color is interpolated between 3 vertices with perspective correction
};
//! Face culling settings: what faces are drawn after face culling
enum TriangleCullingMode
{
RASTERIZE_CULLING_NONE = 0, //!< all faces are drawn, no culling is actually performed
RASTERIZE_CULLING_CW = 1, //!< triangles which vertices are given in clockwork order are drawn
RASTERIZE_CULLING_CCW = 2 //!< triangles which vertices are given in counterclockwork order are drawn
};
//! GL compatibility settings
enum TriangleGlCompatibleMode
{
RASTERIZE_COMPAT_DISABLED = 0, //!< Color and depth have their natural values and converted to internal formats if needed
RASTERIZE_COMPAT_INVDEPTH = 1 //!< Color is natural, Depth is transformed from [-zNear; -zFar] to [0; 1]
//!< by the following formula: \f$ \frac{z_{far} \left(z + z_{near}\right)}{z \left(z_{far} - z_{near}\right)} \f$ \n
//!< In this mode the input/output depthBuf is considered to be in this format,
//!< therefore it's faster since there're no conversions performed
};
/**
* @brief Structure to keep settings for rasterization
*/
struct CV_EXPORTS_W_SIMPLE TriangleRasterizeSettings
{
TriangleRasterizeSettings();
CV_WRAP TriangleRasterizeSettings& setShadingType(TriangleShadingType st) { shadingType = st; return *this; }
CV_WRAP TriangleRasterizeSettings& setCullingMode(TriangleCullingMode cm) { cullingMode = cm; return *this; }
CV_WRAP TriangleRasterizeSettings& setGlCompatibleMode(TriangleGlCompatibleMode gm) { glCompatibleMode = gm; return *this; }
TriangleShadingType shadingType;
TriangleCullingMode cullingMode;
TriangleGlCompatibleMode glCompatibleMode;
};
/** @brief Renders a set of triangles on a depth and color image
Triangles can be drawn white (1.0, 1.0, 1.0), flat-shaded or with a color interpolation between vertices.
In flat-shaded mode the 1st vertex color of each triangle is used to fill the whole triangle.
The world2cam is an inverted camera pose matrix in fact. It transforms vertices from world to
camera coordinate system.
The camera coordinate system emulates the OpenGL's coordinate system having coordinate origin in a screen center,
X axis pointing right, Y axis pointing up and Z axis pointing towards the viewer
except that image is vertically flipped after the render.
This means that all visible objects are placed in z-negative area, or exactly in -zNear > z > -zFar since
zNear and zFar are positive.
For example, at fovY = PI/2 the point (0, 1, -1) will be projected to (width/2, 0) screen point,
(1, 0, -1) to (width/2 + height/2, height/2). Increasing fovY makes projection smaller and vice versa.
The function does not create or clear output images before the rendering. This means that it can be used
for drawing over an existing image or for rendering a model into a 3D scene using pre-filled Z-buffer.
Empty scene results in a depth buffer filled by the maximum value since every pixel is infinitely far from the camera.
Therefore, before rendering anything from scratch the depthBuf should be filled by zFar values (or by ones in INVDEPTH mode).
There are special versions of this function named triangleRasterizeDepth and triangleRasterizeColor
for cases if a user needs a color image or a depth image alone; they may run slightly faster.
@param vertices vertices coordinates array. Should contain values of CV_32FC3 type or a compatible one (e.g. cv::Vec3f, etc.)
@param indices triangle vertices index array, 3 per triangle. Each index indicates a vertex in a vertices array.
Should contain CV_32SC3 values or compatible
@param colors per-vertex colors of CV_32FC3 type or compatible. Can be empty or the same size as vertices array.
If the values are out of [0; 1] range, the result correctness is not guaranteed
@param colorBuf an array representing the final rendered image. Should containt CV_32FC3 values and be the same size as depthBuf.
Not cleared before rendering, i.e. the content is reused as there is some pre-rendered scene.
@param depthBuf an array of floats containing resulting Z buffer. Should contain float values and be the same size as colorBuf.
Not cleared before rendering, i.e. the content is reused as there is some pre-rendered scene.
Empty scene corresponds to all values set to zFar (or to 1.0 in INVDEPTH mode)
@param world2cam a 4x3 or 4x4 float or double matrix containing inverted (sic!) camera pose
@param fovY field of view in vertical direction, given in radians
@param zNear minimum Z value to render, everything closer is clipped
@param zFar maximum Z value to render, everything farther is clipped
@param settings see TriangleRasterizeSettings. By default the smooth shading is on,
with CW culling and with disabled GL compatibility
*/
CV_EXPORTS_W void triangleRasterize(InputArray vertices, InputArray indices, InputArray colors,
InputOutputArray colorBuf, InputOutputArray depthBuf,
InputArray world2cam, double fovY, double zNear, double zFar,
const TriangleRasterizeSettings& settings = TriangleRasterizeSettings());
/** @brief Overloaded version of triangleRasterize() with depth-only rendering
@param vertices vertices coordinates array. Should contain values of CV_32FC3 type or a compatible one (e.g. cv::Vec3f, etc.)
@param indices triangle vertices index array, 3 per triangle. Each index indicates a vertex in a vertices array.
Should contain CV_32SC3 values or compatible
@param depthBuf an array of floats containing resulting Z buffer. Should contain float values and be the same size as colorBuf.
Not cleared before rendering, i.e. the content is reused as there is some pre-rendered scene.
Empty scene corresponds to all values set to zFar (or to 1.0 in INVDEPTH mode)
@param world2cam a 4x3 or 4x4 float or double matrix containing inverted (sic!) camera pose
@param fovY field of view in vertical direction, given in radians
@param zNear minimum Z value to render, everything closer is clipped
@param zFar maximum Z value to render, everything farther is clipped
@param settings see TriangleRasterizeSettings. By default the smooth shading is on,
with CW culling and with disabled GL compatibility
*/
CV_EXPORTS_W void triangleRasterizeDepth(InputArray vertices, InputArray indices, InputOutputArray depthBuf,
InputArray world2cam, double fovY, double zNear, double zFar,
const TriangleRasterizeSettings& settings = TriangleRasterizeSettings());
/** @brief Overloaded version of triangleRasterize() with color-only rendering
@param vertices vertices coordinates array. Should contain values of CV_32FC3 type or a compatible one (e.g. cv::Vec3f, etc.)
@param indices triangle vertices index array, 3 per triangle. Each index indicates a vertex in a vertices array.
Should contain CV_32SC3 values or compatible
@param colors per-vertex colors of CV_32FC3 type or compatible. Can be empty or the same size as vertices array.
If the values are out of [0; 1] range, the result correctness is not guaranteed
@param colorBuf an array representing the final rendered image. Should containt CV_32FC3 values and be the same size as depthBuf.
Not cleared before rendering, i.e. the content is reused as there is some pre-rendered scene.
@param world2cam a 4x3 or 4x4 float or double matrix containing inverted (sic!) camera pose
@param fovY field of view in vertical direction, given in radians
@param zNear minimum Z value to render, everything closer is clipped
@param zFar maximum Z value to render, everything farther is clipped
@param settings see TriangleRasterizeSettings. By default the smooth shading is on,
with CW culling and with disabled GL compatibility
*/
CV_EXPORTS_W void triangleRasterizeColor(InputArray vertices, InputArray indices, InputArray colors, InputOutputArray colorBuf,
InputArray world2cam, double fovY, double zNear, double zFar,
const TriangleRasterizeSettings& settings = TriangleRasterizeSettings());
//! @} _3d
} //end namespace cv

@ -0,0 +1,113 @@
#!/usr/bin/env python
# Python 2/3 compatibility
from __future__ import print_function
import os, numpy
import math
import unittest
import cv2 as cv
from tests_common import NewOpenCVTests
def lookAtMatrixCal(position, lookat, upVector):
tmp = position - lookat
norm = numpy.linalg.norm(tmp)
w = tmp / norm
tmp = numpy.cross(upVector, w)
norm = numpy.linalg.norm(tmp)
u = tmp / norm
v = numpy.cross(w, u)
res = numpy.array([
[u[0], u[1], u[2], 0],
[v[0], v[1], v[2], 0],
[w[0], w[1], w[2], 0],
[0, 0, 0, 1.0]
], dtype=numpy.float32)
translate = numpy.array([
[1.0, 0, 0, -position[0]],
[0, 1.0, 0, -position[1]],
[0, 0, 1.0, -position[2]],
[0, 0, 0, 1.0]
], dtype=numpy.float32)
res = numpy.matmul(res, translate)
return res
class raster_test(NewOpenCVTests):
def prepareData(self):
self.vertices = numpy.array([
[ 2.0, 0.0, -2.0],
[ 0.0, -6.0, -2.0],
[-2.0, 0.0, -2.0],
[ 3.5, -1.0, -5.0],
[ 2.5, -2.5, -5.0],
[-1.0, 1.0, -5.0],
[-6.5, -1.0, -3.0],
[-2.5, -2.0, -3.0],
[ 1.0, 1.0, -5.0],
], dtype=numpy.float32)
self.indices = numpy.array([ [0, 1, 2], [3, 4, 5], [6, 7, 8]], dtype=int)
col1 = [ 185.0, 238.0, 217.0 ]
col2 = [ 238.0, 217.0, 185.0 ]
col3 = [ 238.0, 10.0, 150.0 ]
self.colors = numpy.array([
col1, col2, col3,
col2, col3, col1,
col3, col1, col2,
], dtype=numpy.float32)
self.colors = self.colors / 255.0
self.zNear = 0.1
self.zFar = 50.0
self.fovy = 45.0 * math.pi / 180.0
position = numpy.array([0.0, 0.0, 5.0], dtype=numpy.float32)
lookat = numpy.array([0.0, 0.0, 0.0], dtype=numpy.float32)
upVector = numpy.array([0.0, 1.0, 0.0], dtype=numpy.float32)
self.cameraPose = lookAtMatrixCal(position, lookat, upVector)
self.depth_buf = numpy.ones((240, 320), dtype=numpy.float32) * self.zFar
self.color_buf = numpy.zeros((240, 320, 3), dtype=numpy.float32)
self.settings = cv.TriangleRasterizeSettings().setShadingType(cv.RASTERIZE_SHADING_SHADED)
self.settings = self.settings.setCullingMode(cv.RASTERIZE_CULLING_NONE)
def compareResults(self, needRgb, needDepth):
if needDepth:
depth = self.get_sample('rendering/depth_image_Clipping_320x240_CullNone.png', cv.IMREAD_ANYDEPTH).astype(numpy.float32)
depthFactor = 1000.0
diff = depth/depthFactor - self.depth_buf
norm = numpy.linalg.norm(diff)
self.assertLessEqual(norm, 356.0)
if needRgb:
rgb = self.get_sample('rendering/example_image_Clipping_320x240_CullNone_Shaded.png', cv.IMREAD_ANYCOLOR)
diff = rgb/255.0 - self.color_buf
norm = numpy.linalg.norm(diff)
self.assertLessEqual(norm, 11.62)
def test_rasterizeBoth(self):
self.prepareData()
self.color_buf, self.depth_buf = cv.triangleRasterize(self.vertices, self.indices, self.colors, self.color_buf, self.depth_buf,
self.cameraPose, self.fovy, self.zNear, self.zFar, self.settings)
self.compareResults(needRgb=True, needDepth=True)
def test_rasterizeDepth(self):
self.prepareData()
self.depth_buf = cv.triangleRasterizeDepth(self.vertices, self.indices, self.depth_buf,
self.cameraPose, self.fovy, self.zNear, self.zFar, self.settings)
self.compareResults(needRgb=False, needDepth=True)
def test_rasterizeColor(self):
self.prepareData()
self.color_buf = cv.triangleRasterizeColor(self.vertices, self.indices, self.colors, self.color_buf,
self.cameraPose, self.fovy, self.zNear, self.zFar, self.settings)
self.compareResults(needRgb=True, needDepth=False)
if __name__ == '__main__':
NewOpenCVTests.bootstrap()

@ -0,0 +1,344 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#include "perf_precomp.hpp"
namespace opencv_test
{
// that was easier than using CV_ENUM() macro
namespace
{
using namespace cv;
struct ShadingTypeEnum
{
static const std::array<TriangleShadingType, 3> vals;
static const std::array<std::string, 3> svals;
ShadingTypeEnum(TriangleShadingType v = RASTERIZE_SHADING_WHITE) : val(v) {}
operator TriangleShadingType() const { return val; }
void PrintTo(std::ostream *os) const
{
int v = int(val);
if (v >= 0 && v < (int)vals.size())
{
*os << svals[v];
}
else
{
*os << "UNKNOWN";
}
}
static ::testing::internal::ParamGenerator<ShadingTypeEnum> all()
{
return ::testing::Values(ShadingTypeEnum(vals[0]),
ShadingTypeEnum(vals[1]),
ShadingTypeEnum(vals[2]));
}
private:
TriangleShadingType val;
};
const std::array<TriangleShadingType, 3> ShadingTypeEnum::vals
{
RASTERIZE_SHADING_WHITE,
RASTERIZE_SHADING_FLAT,
RASTERIZE_SHADING_SHADED
};
const std::array<std::string, 3> ShadingTypeEnum::svals
{
std::string("White"),
std::string("Flat"),
std::string("Shaded")
};
static inline void PrintTo(const ShadingTypeEnum &t, std::ostream *os) { t.PrintTo(os); }
using namespace cv;
struct GlCompatibleModeEnum
{
static const std::array<TriangleGlCompatibleMode, 2> vals;
static const std::array<std::string, 2> svals;
GlCompatibleModeEnum(TriangleGlCompatibleMode v = RASTERIZE_COMPAT_DISABLED) : val(v) {}
operator TriangleGlCompatibleMode() const { return val; }
void PrintTo(std::ostream *os) const
{
int v = int(val);
if (v >= 0 && v < (int)vals.size())
{
*os << svals[v];
}
else
{
*os << "UNKNOWN";
}
}
static ::testing::internal::ParamGenerator<GlCompatibleModeEnum> all()
{
return ::testing::Values(GlCompatibleModeEnum(vals[0]),
GlCompatibleModeEnum(vals[1]));
}
private:
TriangleGlCompatibleMode val;
};
const std::array<TriangleGlCompatibleMode, 2> GlCompatibleModeEnum::vals
{
RASTERIZE_COMPAT_DISABLED,
RASTERIZE_COMPAT_INVDEPTH,
};
const std::array<std::string, 2> GlCompatibleModeEnum::svals
{
std::string("Disabled"),
std::string("InvertedDepth"),
};
static inline void PrintTo(const GlCompatibleModeEnum &t, std::ostream *os) { t.PrintTo(os); }
}
enum class Outputs
{
DepthOnly = 0,
ColorOnly = 1,
DepthColor = 2,
};
// that was easier than using CV_ENUM() macro
namespace
{
using namespace cv;
struct OutputsEnum
{
static const std::array<Outputs, 3> vals;
static const std::array<std::string, 3> svals;
OutputsEnum(Outputs v = Outputs::DepthColor) : val(v) {}
operator Outputs() const { return val; }
void PrintTo(std::ostream *os) const
{
int v = int(val);
if (v >= 0 && v < (int)vals.size())
{
*os << svals[v];
}
else
{
*os << "UNKNOWN";
}
}
static ::testing::internal::ParamGenerator<OutputsEnum> all()
{
return ::testing::Values(OutputsEnum(vals[0]),
OutputsEnum(vals[1]),
OutputsEnum(vals[2]));
}
private:
Outputs val;
};
const std::array<Outputs, 3> OutputsEnum::vals
{
Outputs::DepthOnly,
Outputs::ColorOnly,
Outputs::DepthColor
};
const std::array<std::string, 3> OutputsEnum::svals
{
std::string("DepthOnly"),
std::string("ColorOnly"),
std::string("DepthColor")
};
static inline void PrintTo(const OutputsEnum &t, std::ostream *os) { t.PrintTo(os); }
}
static Matx44d lookAtMatrixCal(const Vec3d& position, const Vec3d& lookat, const Vec3d& upVector)
{
Vec3d w = cv::normalize(position - lookat);
Vec3d u = cv::normalize(upVector.cross(w));
Vec3d v = w.cross(u);
Matx44d res(u[0], u[1], u[2], 0,
v[0], v[1], v[2], 0,
w[0], w[1], w[2], 0,
0, 0, 0, 1.0);
Matx44d translate(1.0, 0, 0, -position[0],
0, 1.0, 0, -position[1],
0, 0, 1.0, -position[2],
0, 0, 0, 1.0);
res = res * translate;
return res;
}
static void generateNormals(const std::vector<Vec3f>& points, const std::vector<std::vector<int>>& indices,
std::vector<Vec3f>& normals)
{
std::vector<std::vector<Vec3f>> preNormals(points.size(), std::vector<Vec3f>());
for (const auto& tri : indices)
{
Vec3f p0 = points[tri[0]];
Vec3f p1 = points[tri[1]];
Vec3f p2 = points[tri[2]];
Vec3f cross = cv::normalize((p1 - p0).cross(p2 - p0));
for (int i = 0; i < 3; i++)
{
preNormals[tri[i]].push_back(cross);
}
}
normals.reserve(points.size());
for (const auto& pn : preNormals)
{
Vec3f sum { };
for (const auto& n : pn)
{
sum += n;
}
normals.push_back(cv::normalize(sum));
}
}
// load model once and keep it in static memory
static void getModelOnce(const std::string& objectPath, std::vector<Vec3f>& vertices,
std::vector<Vec3i>& indices, std::vector<Vec3f>& colors)
{
static bool load = false;
static std::vector<Vec3f> vert, col;
static std::vector<Vec3i> ind;
if (!load)
{
std::vector<vector<int>> indvec;
// using per-vertex normals as colors
loadMesh(objectPath, vert, indvec);
generateNormals(vert, indvec, col);
for (const auto &vec : indvec)
{
ind.push_back({vec[0], vec[1], vec[2]});
}
for (auto &color : col)
{
color = Vec3f(abs(color[0]), abs(color[1]), abs(color[2]));
}
load = true;
}
vertices = vert;
colors = col;
indices = ind;
}
template<typename T>
std::string printEnum(T v)
{
std::ostringstream ss;
v.PrintTo(&ss);
return ss.str();
}
// resolution, shading type, outputs needed
typedef perf::TestBaseWithParam<std::tuple<std::tuple<int, int>, ShadingTypeEnum, OutputsEnum, GlCompatibleModeEnum>> RenderingTest;
PERF_TEST_P(RenderingTest, rasterizeTriangles, ::testing::Combine(
::testing::Values(std::make_tuple(1920, 1080), std::make_tuple(1024, 768), std::make_tuple(640, 480)),
ShadingTypeEnum::all(),
OutputsEnum::all(),
GlCompatibleModeEnum::all()
))
{
auto t = GetParam();
auto wh = std::get<0>(t);
int width = std::get<0>(wh);
int height = std::get<1>(wh);
auto shadingType = std::get<1>(t);
auto outputs = std::get<2>(t);
auto glCompatibleMode = std::get<3>(t);
string objectPath = findDataFile("viz/dragon.ply");
Vec3f position = Vec3d( 1.9, 0.4, 1.3);
Vec3f lookat = Vec3d( 0.0, 0.0, 0.0);
Vec3f upVector = Vec3d( 0.0, 1.0, 0.0);
double fovy = 45.0;
std::vector<Vec3f> vertices;
std::vector<Vec3i> indices;
std::vector<Vec3f> colors;
getModelOnce(objectPath, vertices, indices, colors);
if (shadingType != RASTERIZE_SHADING_WHITE)
{
// let vertices be in BGR format to avoid later color conversions
// cvtColor does not work with 1d Mats
std::vector<Mat> xyz;
cv::split(colors, xyz);
cv::merge(std::vector<Mat>{xyz[2], xyz[1], xyz[0]}, colors);
}
double zNear = 0.1, zFar = 50.0;
Matx44d cameraPose = lookAtMatrixCal(position, lookat, upVector);
double fovYradians = fovy * (CV_PI / 180.0);
TriangleRasterizeSettings settings;
settings.setCullingMode(RASTERIZE_CULLING_CW)
.setShadingType(shadingType)
.setGlCompatibleMode(glCompatibleMode);
Mat depth_buf, color_buf;
while (next())
{
// Prefilled to measure pure rendering time w/o allocation and clear
float zMax = (glCompatibleMode == RASTERIZE_COMPAT_INVDEPTH) ? 1.f : (float)zFar;
depth_buf = Mat(height, width, CV_32F, zMax);
color_buf = Mat(height, width, CV_32FC3, Scalar::all(0));
startTimer();
if (outputs == Outputs::ColorOnly)
{
cv::triangleRasterizeColor(vertices, indices, colors, color_buf, cameraPose,
fovYradians, zNear, zFar, settings);
}
else if (outputs == Outputs::DepthOnly)
{
cv::triangleRasterizeDepth(vertices, indices, depth_buf, cameraPose,
fovYradians, zNear, zFar, settings);
}
else // Outputs::DepthColor
{
cv::triangleRasterize(vertices, indices, colors, color_buf, depth_buf,
cameraPose, fovYradians, zNear, zFar, settings);
}
stopTimer();
}
if (debugLevel > 0)
{
depth_buf.convertTo(depth_buf, CV_16U, 1000.0);
std::string shadingName = printEnum(shadingType);
std::string suffix = cv::format("%dx%d_%s", width, height, shadingName.c_str());
imwrite("perf_color_image_" + suffix + ".png", color_buf * 255.f);
imwrite("perf_depth_image_" + suffix + ".png", depth_buf);
}
SANITY_CHECK_NOTHING();
}
} // namespace

@ -0,0 +1,402 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#include "precomp.hpp"
namespace cv {
TriangleRasterizeSettings::TriangleRasterizeSettings()
{
shadingType = RASTERIZE_SHADING_SHADED;
cullingMode = RASTERIZE_CULLING_CW;
glCompatibleMode = RASTERIZE_COMPAT_DISABLED;
}
static void drawTriangle(Vec4f verts[3], Vec3f colors[3], Mat& depthBuf, Mat& colorBuf,
TriangleRasterizeSettings settings)
{
// this will be useful during refactoring
// if there's gonna be more supported data types
CV_DbgAssert(depthBuf.empty() || depthBuf.type() == CV_32FC1);
CV_DbgAssert(colorBuf.empty() || colorBuf.type() == CV_32FC3);
// any of buffers can be empty
int width = std::max(colorBuf.cols, depthBuf.cols);
int height = std::max(colorBuf.rows, depthBuf.rows);
Point minPt(width, height), maxPt(0, 0);
for (int i = 0; i < 3; i++)
{
// round down to cover the whole pixel
int x = (int)(verts[i][0]), y = (int)(verts[i][1]);
minPt.x = std::min( x, minPt.x);
minPt.y = std::min( y, minPt.y);
maxPt.x = std::max(x + 1, maxPt.x);
maxPt.y = std::max(y + 1, maxPt.y);
}
minPt.x = std::max(minPt.x, 0); maxPt.x = std::min(maxPt.x, width);
minPt.y = std::max(minPt.y, 0); maxPt.y = std::min(maxPt.y, height);
Point2f a(verts[0][0], verts[0][1]), b(verts[1][0], verts[1][1]), c(verts[2][0], verts[2][1]);
Point2f bc = b - c, ac = a - c;
float d = ac.x*bc.y - ac.y*bc.x;
// culling and degenerated triangle removal
if ((settings.cullingMode == RASTERIZE_CULLING_CW && d <= 0) ||
(settings.cullingMode == RASTERIZE_CULLING_CCW && d >= 0) ||
(abs(d) < 1e-6))
{
return;
}
float invd = 1.f / d;
Vec3f zinv { verts[0][2], verts[1][2], verts[2][2] };
Vec3f w { verts[0][3], verts[1][3], verts[2][3] };
for (int y = minPt.y; y < maxPt.y; y++)
{
for (int x = minPt.x; x < maxPt.x; x++)
{
Point2f p(x + 0.5f, y + 0.5f), pc = p - c;
// barycentric coordinates
Vec3f f;
f[0] = ( pc.x * bc.y - pc.y * bc.x) * invd;
f[1] = ( pc.y * ac.x - pc.x * ac.y) * invd;
f[2] = 1.f - f[0] - f[1];
// if inside the triangle
if ((f[0] >= 0) && (f[1] >= 0) && (f[2] >= 0))
{
bool update = false;
if (!depthBuf.empty())
{
float zCurrent = depthBuf.at<float>(height - 1 - y, x);
float zNew = f[0] * zinv[0] + f[1] * zinv[1] + f[2] * zinv[2];
if (zNew < zCurrent)
{
update = true;
depthBuf.at<float>(height - 1 - y, x) = zNew;
}
}
else // RASTERIZE_SHADING_WHITE
{
update = true;
}
if (!colorBuf.empty() && update)
{
Vec3f color;
if (settings.shadingType == RASTERIZE_SHADING_WHITE)
{
color = { 1.f, 1.f, 1.f };
}
else if (settings.shadingType == RASTERIZE_SHADING_FLAT)
{
color = colors[0];
}
else // TriangleShadingType::Shaded
{
float zInter = 1.0f / (f[0] * w[0] + f[1] * w[1] + f[2] * w[2]);
color = { 0, 0, 0 };
for (int j = 0; j < 3; j++)
{
color += (f[j] * w[j]) * colors[j];
}
color *= zInter;
}
colorBuf.at<Vec3f>(height - 1 - y, x) = color;
}
}
}
}
}
// values outside of [zNear, zFar] have to be restored
// [0, 1] -> [zNear, zFar]
static void linearizeDepth(const Mat& inbuf, const Mat& validMask, Mat outbuf, double zFar, double zNear)
{
CV_Assert(inbuf.type() == CV_32FC1);
CV_Assert(validMask.type() == CV_8UC1);
CV_Assert(outbuf.type() == CV_32FC1);
CV_Assert(outbuf.size() == inbuf.size());
float scaleNear = (float)(1.0 / zNear);
float scaleFar = (float)(1.0 / zFar);
for (int y = 0; y < inbuf.rows; y++)
{
const float* inp = inbuf.ptr<float>(y);
const uchar * validPtr = validMask.ptr<uchar>(y);
float * outp = outbuf.ptr<float>(y);
for (int x = 0; x < inbuf.cols; x++)
{
if (validPtr[x])
{
float d = inp[x];
// precision-optimized version of this:
//float z = - zFar * zNear / (d * (zFar - zNear) - zFar);
float z = 1.f / ((1.f - d) * scaleNear + d * scaleFar );
outp[x] = z;
}
}
}
}
// [zNear, zFar] -> [0, 1]
static void invertDepth(const Mat& inbuf, Mat& outbuf, Mat& validMask, double zNear, double zFar)
{
CV_Assert(inbuf.type() == CV_32FC1);
outbuf.create(inbuf.size(), CV_32FC1);
validMask.create(inbuf.size(), CV_8UC1);
float fNear = (float)zNear, fFar = (float)zFar;
float zadd = (float)(zFar / (zFar - zNear));
float zmul = (float)(-zNear * zFar / (zFar - zNear));
for (int y = 0; y < inbuf.rows; y++)
{
const float * inp = inbuf.ptr<float>(y);
float * outp = outbuf.ptr<float>(y);
uchar * validPtr = validMask.ptr<uchar>(y);
for (int x = 0; x < inbuf.cols; x++)
{
float z = inp[x];
uchar m = (z >= fNear) && (z <= fFar);
z = std::max(std::min(z, fFar), fNear);
// precision-optimized version of this:
// outp[x] = (z - zNear) / z * zFar / (zFar - zNear);
outp[x] = zadd + zmul / z;
validPtr[x] = m;
}
}
}
static void triangleRasterizeInternal(InputArray _vertices, InputArray _indices, InputArray _colors,
Mat& colorBuf, Mat& depthBuf,
InputArray world2cam, double fovyRadians, double zNear, double zFar,
const TriangleRasterizeSettings& settings)
{
CV_Assert(world2cam.type() == CV_32FC1 || world2cam.type() == CV_64FC1);
CV_Assert((world2cam.size() == Size {4, 3}) || (world2cam.size() == Size {4, 4}));
CV_Assert((fovyRadians > 0) && (fovyRadians < CV_PI));
CV_Assert(zNear > 0);
CV_Assert(zFar > zNear);
Mat cpMat;
world2cam.getMat().convertTo(cpMat, CV_64FC1);
Matx44d camPoseMat = Matx44d::eye();
for (int i = 0; i < 3; i++)
{
for (int j = 0; j < 4; j++)
{
camPoseMat(i, j) = cpMat.at<double>(i, j);
}
}
if(_indices.empty())
{
return;
}
CV_CheckFalse(_vertices.empty(), "No vertices provided along with indices array");
Mat vertices, colors, triangles;
int nVerts = 0, nColors = 0, nTriangles = 0;
int vertexType = _vertices.type();
CV_Assert(vertexType == CV_32FC1 || vertexType == CV_32FC3);
vertices = _vertices.getMat();
// transform 3xN matrix to Nx3, except 3x3
if ((_vertices.channels() == 1) && (_vertices.rows() == 3) && (_vertices.cols() != 3))
{
vertices = vertices.t();
}
// This transposition is performed on 1xN matrix so it's almost free in terms of performance
vertices = vertices.reshape(3, 1).t();
nVerts = (int)vertices.total();
int indexType = _indices.type();
CV_Assert(indexType == CV_32SC1 || indexType == CV_32SC3);
triangles = _indices.getMat();
// transform 3xN matrix to Nx3, except 3x3
if ((_indices.channels() == 1) && (_indices.rows() == 3) && (_indices.cols() != 3))
{
triangles = triangles.t();
}
// This transposition is performed on 1xN matrix so it's almost free in terms of performance
triangles = triangles.reshape(3, 1).t();
nTriangles = (int)triangles.total();
if (!_colors.empty())
{
int colorType = _colors.type();
CV_Assert(colorType == CV_32FC1 || colorType == CV_32FC3);
colors = _colors.getMat();
// transform 3xN matrix to Nx3, except 3x3
if ((_colors.channels() == 1) && (_colors.rows() == 3) && (_colors.cols() != 3))
{
colors = colors.t();
}
colors = colors.reshape(3, 1).t();
nColors = (int)colors.total();
CV_Assert(nColors == nVerts);
}
// any of buffers can be empty
Size imgSize {std::max(colorBuf.cols, depthBuf.cols), std::max(colorBuf.rows, depthBuf.rows)};
// world-to-camera coord system
Matx44d lookAtMatrix = camPoseMat;
double ys = 1.0 / std::tan(fovyRadians / 2);
double xs = ys / (double)imgSize.width * (double)imgSize.height;
double zz = (zNear + zFar) / (zNear - zFar);
double zw = 2.0 * zFar * zNear / (zNear - zFar);
// camera to NDC: [-1, 1]^3
Matx44d perspectMatrix (xs, 0, 0, 0,
0, ys, 0, 0,
0, 0, zz, zw,
0, 0, -1, 0);
Matx44f mvpMatrix = perspectMatrix * lookAtMatrix;
// vertex transform stage
Mat screenVertices(vertices.size(), CV_32FC4);
for (int i = 0; i < nVerts; i++)
{
Vec3f vglobal = vertices.at<Vec3f>(i);
Vec4f vndc = mvpMatrix * Vec4f(vglobal[0], vglobal[1], vglobal[2], 1.f);
float invw = 1.f / vndc[3];
Vec4f vdiv = {vndc[0] * invw, vndc[1] * invw, vndc[2] * invw, invw};
// [-1, 1]^3 => [0, width] x [0, height] x [0, 1]
Vec4f vscreen = {
(vdiv[0] + 1.f) * 0.5f * (float)imgSize.width,
(vdiv[1] + 1.f) * 0.5f * (float)imgSize.height,
(vdiv[2] + 1.f) * 0.5f,
vdiv[3]
};
screenVertices.at<Vec4f>(i) = vscreen;
}
// draw stage
for (int t = 0; t < nTriangles; t++)
{
Vec3i tri = triangles.at<Vec3i>(t);
Vec3f col[3];
Vec4f ver[3];
for (int i = 0; i < 3; i++)
{
int idx = tri[i];
CV_DbgAssert(idx >= 0 && idx < nVerts);
col[i] = colors.empty() ? Vec3f::all(0) : colors.at<Vec3f>(idx);
ver[i] = screenVertices.at<Vec4f>(idx);
}
drawTriangle(ver, col, depthBuf, colorBuf, settings);
}
}
void triangleRasterizeDepth(InputArray _vertices, InputArray _indices, InputOutputArray _depthBuf,
InputArray world2cam, double fovY, double zNear, double zFar,
const TriangleRasterizeSettings& settings)
{
CV_Assert(!_depthBuf.empty());
CV_Assert(_depthBuf.type() == CV_32FC1);
Mat emptyColorBuf;
// out-of-range values from user-provided depthBuf should not be altered, let's mark them
Mat_<uchar> validMask;
Mat depthBuf;
if (settings.glCompatibleMode == RASTERIZE_COMPAT_INVDEPTH)
{
depthBuf = _depthBuf.getMat();
}
else // RASTERIZE_COMPAT_DISABLED
{
invertDepth(_depthBuf.getMat(), depthBuf, validMask, zNear, zFar);
}
triangleRasterizeInternal(_vertices, _indices, noArray(), emptyColorBuf, depthBuf, world2cam, fovY, zNear, zFar, settings);
if (settings.glCompatibleMode == RASTERIZE_COMPAT_DISABLED)
{
linearizeDepth(depthBuf, validMask, _depthBuf.getMat(), zFar, zNear);
}
}
void triangleRasterizeColor(InputArray _vertices, InputArray _indices, InputArray _colors, InputOutputArray _colorBuf,
InputArray world2cam, double fovY, double zNear, double zFar,
const TriangleRasterizeSettings& settings)
{
CV_Assert(!_colorBuf.empty());
CV_Assert(_colorBuf.type() == CV_32FC3);
Mat colorBuf = _colorBuf.getMat();
Mat depthBuf;
if (_colors.empty())
{
// full white shading does not require depth test
CV_Assert(settings.shadingType == RASTERIZE_SHADING_WHITE);
}
else
{
// internal depth buffer is not exposed outside
depthBuf.create(_colorBuf.size(), CV_32FC1);
depthBuf.setTo(1.0);
}
triangleRasterizeInternal(_vertices, _indices, _colors, colorBuf, depthBuf, world2cam, fovY, zNear, zFar, settings);
}
void triangleRasterize(InputArray _vertices, InputArray _indices, InputArray _colors,
InputOutputArray _colorBuffer, InputOutputArray _depthBuffer,
InputArray world2cam, double fovyRadians, double zNear, double zFar,
const TriangleRasterizeSettings& settings)
{
if (_colors.empty())
{
CV_Assert(settings.shadingType == RASTERIZE_SHADING_WHITE);
}
CV_Assert(!_colorBuffer.empty());
CV_Assert(_colorBuffer.type() == CV_32FC3);
CV_Assert(!_depthBuffer.empty());
CV_Assert(_depthBuffer.type() == CV_32FC1);
CV_Assert(_depthBuffer.size() == _colorBuffer.size());
Mat colorBuf = _colorBuffer.getMat();
// out-of-range values from user-provided depthBuf should not be altered, let's mark them
Mat_<uchar> validMask;
Mat depthBuf;
if (settings.glCompatibleMode == RASTERIZE_COMPAT_INVDEPTH)
{
depthBuf = _depthBuffer.getMat();
}
else // RASTERIZE_COMPAT_DISABLED
{
invertDepth(_depthBuffer.getMat(), depthBuf, validMask, zNear, zFar);
}
triangleRasterizeInternal(_vertices, _indices, _colors, colorBuf, depthBuf, world2cam, fovyRadians, zNear, zFar, settings);
if (settings.glCompatibleMode == RASTERIZE_COMPAT_DISABLED)
{
linearizeDepth(depthBuf, validMask, _depthBuffer.getMat(), zFar, zNear);
}
}
} // namespace cv

@ -0,0 +1,948 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#include "test_precomp.hpp"
namespace opencv_test { namespace {
using namespace cv;
// that was easier than using CV_ENUM() macro
namespace
{
using namespace cv;
struct CullingModeEnum
{
static const std::array<TriangleCullingMode, 3> vals;
static const std::array<std::string, 3> svals;
CullingModeEnum(TriangleCullingMode v = RASTERIZE_CULLING_NONE) : val(v) {}
operator TriangleCullingMode() const { return val; }
void PrintTo(std::ostream *os) const
{
int v = int(val);
if (v >= 0 && v < (int)vals.size())
{
*os << svals[v];
}
else
{
*os << "UNKNOWN";
}
}
static ::testing::internal::ParamGenerator<CullingModeEnum> all()
{
return ::testing::Values(CullingModeEnum(vals[0]),
CullingModeEnum(vals[1]),
CullingModeEnum(vals[2]));
}
private:
TriangleCullingMode val;
};
const std::array<TriangleCullingMode, 3> CullingModeEnum::vals
{
RASTERIZE_CULLING_NONE,
RASTERIZE_CULLING_CW,
RASTERIZE_CULLING_CCW
};
const std::array<std::string, 3> CullingModeEnum::svals
{
std::string("None"),
std::string("CW"),
std::string("CCW")
};
static inline void PrintTo(const CullingModeEnum &t, std::ostream *os) { t.PrintTo(os); }
}
// that was easier than using CV_ENUM() macro
namespace
{
using namespace cv;
struct ShadingTypeEnum
{
static const std::array<TriangleShadingType, 3> vals;
static const std::array<std::string, 3> svals;
ShadingTypeEnum(TriangleShadingType v = RASTERIZE_SHADING_WHITE) : val(v) {}
operator TriangleShadingType() const { return val; }
void PrintTo(std::ostream *os) const
{
int v = int(val);
if (v >= 0 && v < (int)vals.size())
{
*os << svals[v];
}
else
{
*os << "UNKNOWN";
}
}
static ::testing::internal::ParamGenerator<ShadingTypeEnum> all()
{
return ::testing::Values(ShadingTypeEnum(vals[0]),
ShadingTypeEnum(vals[1]),
ShadingTypeEnum(vals[2]));
}
private:
TriangleShadingType val;
};
const std::array<TriangleShadingType, 3> ShadingTypeEnum::vals
{
RASTERIZE_SHADING_WHITE,
RASTERIZE_SHADING_FLAT,
RASTERIZE_SHADING_SHADED
};
const std::array<std::string, 3> ShadingTypeEnum::svals
{
std::string("White"),
std::string("Flat"),
std::string("Shaded")
};
static inline void PrintTo(const ShadingTypeEnum &t, std::ostream *os) { t.PrintTo(os); }
}
enum class ModelType
{
Empty = 0,
File = 1,
Clipping = 2,
Color = 3,
Centered = 4
};
// that was easier than using CV_ENUM() macro
namespace
{
using namespace cv;
struct ModelTypeEnum
{
static const std::array<ModelType, 5> vals;
static const std::array<std::string, 5> svals;
ModelTypeEnum(ModelType v = ModelType::Empty) : val(v) {}
operator ModelType() const { return val; }
void PrintTo(std::ostream *os) const
{
int v = int(val);
if (v >= 0 && v < (int)vals.size())
{
*os << svals[v];
}
else
{
*os << "UNKNOWN";
}
}
static ::testing::internal::ParamGenerator<ModelTypeEnum> all()
{
return ::testing::Values(ModelTypeEnum(vals[0]),
ModelTypeEnum(vals[1]),
ModelTypeEnum(vals[2]),
ModelTypeEnum(vals[3]),
ModelTypeEnum(vals[4]));
}
private:
ModelType val;
};
const std::array<ModelType, 5> ModelTypeEnum::vals
{
ModelType::Empty,
ModelType::File,
ModelType::Clipping,
ModelType::Color,
ModelType::Centered
};
const std::array<std::string, 5> ModelTypeEnum::svals
{
std::string("Empty"),
std::string("File"),
std::string("Clipping"),
std::string("Color"),
std::string("Centered")
};
static inline void PrintTo(const ModelTypeEnum &t, std::ostream *os) { t.PrintTo(os); }
}
template<typename T>
std::string printEnum(T v)
{
std::ostringstream ss;
v.PrintTo(&ss);
return ss.str();
}
static Matx44d lookAtMatrixCal(const Vec3d& position, const Vec3d& lookat, const Vec3d& upVector)
{
Vec3d w = cv::normalize(position - lookat);
Vec3d u = cv::normalize(upVector.cross(w));
Vec3d v = w.cross(u);
Matx44d res(u[0], u[1], u[2], 0,
v[0], v[1], v[2], 0,
w[0], w[1], w[2], 0,
0, 0, 0, 1.0);
Matx44d translate(1.0, 0, 0, -position[0],
0, 1.0, 0, -position[1],
0, 0, 1.0, -position[2],
0, 0, 0, 1.0);
res = res * translate;
return res;
}
static void generateNormals(const std::vector<Vec3f>& points, const std::vector<std::vector<int>>& indices,
std::vector<Vec3f>& normals)
{
std::vector<std::vector<Vec3f>> preNormals(points.size(), std::vector<Vec3f>());
for (const auto& tri : indices)
{
Vec3f p0 = points[tri[0]];
Vec3f p1 = points[tri[1]];
Vec3f p2 = points[tri[2]];
Vec3f cross = cv::normalize((p1 - p0).cross(p2 - p0));
for (int i = 0; i < 3; i++)
{
preNormals[tri[i]].push_back(cross);
}
}
normals.reserve(points.size());
for (const auto& pn : preNormals)
{
Vec3f sum { };
for (const auto& n : pn)
{
sum += n;
}
normals.push_back(cv::normalize(sum));
}
}
// load model once and keep it in static memory
static void getModelOnce(const std::string& objectPath, std::vector<Vec3f>& vertices,
std::vector<Vec3i>& indices, std::vector<Vec3f>& colors)
{
static bool load = false;
static std::vector<Vec3f> vert, col;
static std::vector<Vec3i> ind;
if (!load)
{
std::vector<vector<int>> indvec;
// using per-vertex normals as colors
loadMesh(objectPath, vert, indvec);
generateNormals(vert, indvec, col);
for (const auto &vec : indvec)
{
ind.push_back({vec[0], vec[1], vec[2]});
}
for (auto &color : col)
{
color = Vec3f(abs(color[0]), abs(color[1]), abs(color[2]));
}
load = true;
}
vertices = vert;
colors = col;
indices = ind;
}
class ModelData
{
public:
ModelData(ModelType type = ModelType::Empty)
{
switch (type)
{
case ModelType::Empty:
{
position = Vec3d(0.0, 0.0, 0.0);
lookat = Vec3d(0.0, 0.0, 0.0);
upVector = Vec3d(0.0, 1.0, 0.0);
fovy = 45.0;
vertices = std::vector<Vec3f>(4, {2.0f, 0, -2.0f});
colors = std::vector<Vec3f>(4, {0, 0, 1.0f});
indices = { };
}
break;
case ModelType::File:
{
string objectPath = findDataFile("viz/dragon.ply");
position = Vec3d( 1.9, 0.4, 1.3);
lookat = Vec3d( 0.0, 0.0, 0.0);
upVector = Vec3d( 0.0, 1.0, 0.0);
fovy = 45.0;
getModelOnce(objectPath, vertices, indices, colors);
}
break;
case ModelType::Clipping:
{
position = Vec3d(0.0, 0.0, 5.0);
lookat = Vec3d(0.0, 0.0, 0.0);
upVector = Vec3d(0.0, 1.0, 0.0);
fovy = 45.0;
vertices =
{
{ 2.0, 0.0, -2.0}, { 0.0, -6.0, -2.0}, {-2.0, 0.0, -2.0},
{ 3.5, -1.0, -5.0}, { 2.5, -2.5, -5.0}, {-1.0, 1.0, -5.0},
{-6.5, -1.0, -3.0}, {-2.5, -2.0, -3.0}, { 1.0, 1.0, -5.0},
};
indices = { {0, 1, 2}, {3, 4, 5}, {6, 7, 8} };
Vec3f col1(217.0, 238.0, 185.0);
Vec3f col2(185.0, 217.0, 238.0);
Vec3f col3(150.0, 10.0, 238.0);
col1 *= (1.f / 255.f);
col2 *= (1.f / 255.f);
col3 *= (1.f / 255.f);
colors =
{
col1, col2, col3,
col2, col3, col1,
col3, col1, col2,
};
}
break;
case ModelType::Centered:
{
position = Vec3d(0.0, 0.0, 5.0);
lookat = Vec3d(0.0, 0.0, 0.0);
upVector = Vec3d(0.0, 1.0, 0.0);
fovy = 45.0;
vertices =
{
{ 2.0, 0.0, -2.0}, { 0.0, -2.0, -2.0}, {-2.0, 0.0, -2.0},
{ 3.5, -1.0, -5.0}, { 2.5, -1.5, -5.0}, {-1.0, 0.5, -5.0},
};
indices = { {0, 1, 2}, {3, 4, 5} };
Vec3f col1(217.0, 238.0, 185.0);
Vec3f col2(185.0, 217.0, 238.0);
col1 *= (1.f / 255.f);
col2 *= (1.f / 255.f);
colors =
{
col1, col2, col1,
col2, col1, col2,
};
}
break;
case ModelType::Color:
{
position = Vec3d(0.0, 0.0, 5.0);
lookat = Vec3d(0.0, 0.0, 0.0);
upVector = Vec3d(0.0, 1.0, 0.0);
fovy = 60.0;
vertices =
{
{ 2.0, 0.0, -2.0},
{ 0.0, 2.0, -3.0},
{-2.0, 0.0, -2.0},
{ 0.0, -2.0, 1.0},
};
indices = { {0, 1, 2}, {0, 2, 3} };
colors =
{
{ 0.0f, 0.0f, 1.0f},
{ 0.0f, 1.0f, 0.0f},
{ 1.0f, 0.0f, 0.0f},
{ 0.0f, 1.0f, 0.0f},
};
}
break;
default:
CV_Error(Error::StsBadArg, "Unknown model type");
break;
}
}
Vec3d position;
Vec3d lookat;
Vec3d upVector;
double fovy;
std::vector<Vec3f> vertices;
std::vector<Vec3i> indices;
std::vector<Vec3f> colors;
};
void compareDepth(const cv::Mat& gt, const cv::Mat& mat, cv::Mat& diff, double zFar, double scale,
double maskThreshold, double normInfThreshold, double normL2Threshold)
{
ASSERT_EQ(CV_16UC1, gt.type());
ASSERT_EQ(CV_16UC1, mat.type());
ASSERT_EQ(gt.size(), mat.size());
Mat gtMask = gt < zFar*scale;
Mat matMask = mat < zFar*scale;
Mat diffMask = gtMask != matMask;
int nzDepthDiff = cv::countNonZero(diffMask);
EXPECT_LE(nzDepthDiff, maskThreshold);
Mat jointMask = gtMask & matMask;
int nzJointMask = cv::countNonZero(jointMask);
double normInfDepth = cv::norm(gt, mat, cv::NORM_INF, jointMask);
EXPECT_LE(normInfDepth, normInfThreshold);
double normL2Depth = nzJointMask ? (cv::norm(gt, mat, cv::NORM_L2, jointMask) / nzJointMask) : 0;
EXPECT_LE(normL2Depth, normL2Threshold);
// add --test_debug to output differences
if (debugLevel > 0)
{
std::cout << "nzDepthDiff: " << nzDepthDiff << " vs " << maskThreshold << std::endl;
std::cout << "normInfDepth: " << normInfDepth << " vs " << normInfThreshold << std::endl;
std::cout << "normL2Depth: " << normL2Depth << " vs " << normL2Threshold << std::endl;
}
diff = (gt - mat) + (1 << 15);
}
void compareRGB(const cv::Mat& gt, const cv::Mat& mat, cv::Mat& diff, double normInfThreshold, double normL2Threshold)
{
ASSERT_EQ(CV_32FC3, gt.type());
ASSERT_EQ(CV_32FC3, mat.type());
ASSERT_EQ(gt.size(), mat.size());
double normInfRgb = cv::norm(gt, mat, cv::NORM_INF);
EXPECT_LE(normInfRgb, normInfThreshold);
double normL2Rgb = cv::norm(gt, mat, cv::NORM_L2) / gt.total();
EXPECT_LE(normL2Rgb, normL2Threshold);
// add --test_debug to output differences
if (debugLevel > 0)
{
std::cout << "normInfRgb: " << normInfRgb << " vs " << normInfThreshold << std::endl;
std::cout << "normL2Rgb: " << normL2Rgb << " vs " << normL2Threshold << std::endl;
}
diff = (gt - mat) * 0.5 + 0.5;
}
struct RenderTestThresholds
{
RenderTestThresholds(
double _rgbInfThreshold,
double _rgbL2Threshold,
double _depthMaskThreshold,
double _depthInfThreshold,
double _depthL2Threshold) :
rgbInfThreshold(_rgbInfThreshold),
rgbL2Threshold(_rgbL2Threshold),
depthMaskThreshold(_depthMaskThreshold),
depthInfThreshold(_depthInfThreshold),
depthL2Threshold(_depthL2Threshold)
{ }
double rgbInfThreshold;
double rgbL2Threshold;
double depthMaskThreshold;
double depthInfThreshold;
double depthL2Threshold;
};
// resolution, shading type, culling mode, model type, float type, index type
typedef std::tuple<std::tuple<int, int>, ShadingTypeEnum, CullingModeEnum, ModelTypeEnum, MatDepth, MatDepth> RenderTestParamType;
class RenderingTest : public ::testing::TestWithParam<RenderTestParamType>
{
protected:
void SetUp() override
{
params = GetParam();
auto wh = std::get<0>(params);
width = std::get<0>(wh);
height = std::get<1>(wh);
shadingType = std::get<1>(params);
cullingMode = std::get<2>(params);
modelType = std::get<3>(params);
modelData = ModelData(modelType);
ftype = std::get<4>(params);
itype = std::get<5>(params);
zNear = 0.1, zFar = 50.0;
depthScale = 1000.0;
depth_buf = Mat(height, width, ftype, zFar);
color_buf = Mat(height, width, CV_MAKETYPE(ftype, 3), Scalar::all(0));
cameraPose = lookAtMatrixCal(modelData.position, modelData.lookat, modelData.upVector);
fovYradians = modelData.fovy * (CV_PI / 180.0);
verts = Mat(modelData.vertices);
verts.convertTo(verts, ftype);
if (shadingType != RASTERIZE_SHADING_WHITE)
{
colors = Mat(modelData.colors);
colors.convertTo(colors, ftype);
// let vertices be in BGR format to avoid later color conversions
// cvtColor does not work with 1d Mats
std::vector<Mat> xyz;
cv::split(colors, xyz);
cv::merge(std::vector<Mat>{xyz[2], xyz[1], xyz[0]}, colors);
}
indices = Mat(modelData.indices);
if (itype != CV_32S)
{
indices.convertTo(indices, itype);
}
settings = TriangleRasterizeSettings().setCullingMode(cullingMode).setShadingType(shadingType);
triangleRasterize(verts, indices, colors, color_buf, depth_buf,
cameraPose, fovYradians, zNear, zFar, settings);
}
public:
RenderTestParamType params;
int width, height;
double zNear, zFar, depthScale;
Mat depth_buf, color_buf;
Mat verts, colors, indices;
Matx44d cameraPose;
double fovYradians;
TriangleRasterizeSettings settings;
ModelData modelData;
ModelTypeEnum modelType;
ShadingTypeEnum shadingType;
CullingModeEnum cullingMode;
int ftype, itype;
};
// depth-only or RGB-only rendering should produce the same result as usual rendering
TEST_P(RenderingTest, noArrays)
{
Mat depthOnly(height, width, ftype, zFar);
Mat colorOnly(height, width, CV_MAKETYPE(ftype, 3), Scalar::all(0));
triangleRasterizeDepth(verts, indices, depthOnly, cameraPose, fovYradians, zNear, zFar, settings);
triangleRasterizeColor(verts, indices, colors, colorOnly, cameraPose, fovYradians, zNear, zFar, settings);
Mat rgbDiff, depthDiff;
compareRGB(color_buf, colorOnly, rgbDiff, 0, 0);
depth_buf.convertTo(depth_buf, CV_16U, depthScale);
depthOnly.convertTo(depthOnly, CV_16U, depthScale);
compareDepth(depth_buf, depthOnly, depthDiff, zFar, depthScale, 0, 0, 0);
// add --test_debug to output resulting images
if (debugLevel > 0)
{
std::string modelName = printEnum(modelType);
std::string shadingName = printEnum(shadingType);
std::string cullingName = printEnum(cullingMode);
std::string suffix = cv::format("%s_%dx%d_Cull%s", modelName.c_str(), width, height, cullingName.c_str());
std::string outColorPath = "noarray_color_image_" + suffix + "_" + shadingName + ".png";
std::string outDepthPath = "noarray_depth_image_" + suffix + "_" + shadingName + ".png";
imwrite(outColorPath, color_buf * 255.f);
imwrite(outDepthPath, depth_buf);
imwrite("diff_" + outColorPath, rgbDiff * 255.f);
imwrite("diff_" + outDepthPath, depthDiff);
}
}
// passing the same parameters in float should give the same result
TEST_P(RenderingTest, floatParams)
{
Mat depth_buf2(height, width, ftype, zFar);
Mat color_buf2(height, width, CV_MAKETYPE(ftype, 3), Scalar::all(0));
// cameraPose can also be float, checking it
triangleRasterize(verts, indices, colors, color_buf2, depth_buf2,
Matx44f(cameraPose), (float)fovYradians, (float)zNear, (float)zFar, settings);
RenderTestThresholds thr(0, 0, 0, 0, 0);
switch (modelType)
{
case ModelType::Empty: break;
case ModelType::Color: break;
case ModelType::Clipping:
if (width == 320 && height == 240 && shadingType == RASTERIZE_SHADING_FLAT && cullingMode == RASTERIZE_CULLING_CW)
{
thr.depthInfThreshold = 1;
thr.depthL2Threshold = 0.00127;
}
else if (width == 320 && height == 240 && shadingType == RASTERIZE_SHADING_SHADED && cullingMode == RASTERIZE_CULLING_NONE)
{
thr.rgbInfThreshold = 3e-7;
thr.rgbL2Threshold = 1.86e-10;
thr.depthInfThreshold = 1;
thr.depthL2Threshold = 0.000406;
}
else if (width == 256 && height == 256 && shadingType == RASTERIZE_SHADING_SHADED && cullingMode == RASTERIZE_CULLING_CW)
{
thr.rgbInfThreshold = 2.39e-07;
thr.rgbL2Threshold = 1.86e-10;
thr.depthInfThreshold = 1;
thr.depthL2Threshold = 0.0016;
}
else if (width == 256 && height == 256 && shadingType == RASTERIZE_SHADING_FLAT && cullingMode == RASTERIZE_CULLING_CCW)
{
thr.rgbInfThreshold = 0.934;
thr.rgbL2Threshold = 0.000102;
thr.depthMaskThreshold = 21;
}
else if (width == 640 && height == 480 && shadingType == RASTERIZE_SHADING_WHITE && cullingMode == RASTERIZE_CULLING_NONE)
{
thr.rgbL2Threshold = 1;
thr.depthInfThreshold = 1;
thr.depthL2Threshold = 0.000248;
}
else if (width == 700 && height == 700 && shadingType == RASTERIZE_SHADING_FLAT && cullingMode == RASTERIZE_CULLING_CCW)
{
thr.rgbInfThreshold = 0.934;
thr.rgbL2Threshold = 3.18e-5;
thr.depthMaskThreshold = 114;
}
break;
case ModelType::File:
thr.depthInfThreshold = 1;
if (width == 320 && height == 240 && shadingType == RASTERIZE_SHADING_SHADED && cullingMode == RASTERIZE_CULLING_CCW)
{
thr.rgbInfThreshold = 0.000157;
thr.rgbL2Threshold = 6e-09;
thr.depthL2Threshold = 0.000413;
}
else if (width == 700 && height == 700 && shadingType == RASTERIZE_SHADING_SHADED && cullingMode == RASTERIZE_CULLING_CW)
{
thr.rgbInfThreshold = 0.000303;
thr.rgbL2Threshold = 1.9e-09;
thr.depthL2Threshold = 0.00012;
}
else if (width == 700 && height == 700 && shadingType == RASTERIZE_SHADING_WHITE && cullingMode == RASTERIZE_CULLING_NONE)
{
thr.depthL2Threshold = 0.00012;
}
break;
case ModelType::Centered:
if (shadingType == RASTERIZE_SHADING_SHADED && cullingMode != RASTERIZE_CULLING_CW)
{
thr.rgbInfThreshold = 3.58e-07;
thr.rgbL2Threshold = 1.51e-10;
}
break;
}
Mat rgbDiff, depthDiff;
compareRGB(color_buf, color_buf2, rgbDiff, thr.rgbInfThreshold, thr.rgbL2Threshold);
depth_buf.convertTo(depth_buf, CV_16U, depthScale);
depth_buf2.convertTo(depth_buf2, CV_16U, depthScale);
compareDepth(depth_buf, depth_buf2, depthDiff, zFar, depthScale, thr.depthMaskThreshold, thr.depthInfThreshold, thr.depthL2Threshold);
// add --test_debug to output resulting images
if (debugLevel > 0)
{
std::string modelName = printEnum(modelType);
std::string shadingName = printEnum(shadingType);
std::string cullingName = printEnum(cullingMode);
std::string suffix = cv::format("%s_%dx%d_Cull%s", modelName.c_str(), width, height, cullingName.c_str());
std::string outColorPath = "float_color_image_" + suffix + "_" + shadingName + ".png";
std::string outDepthPath = "float_depth_image_" + suffix + "_" + shadingName + ".png";
imwrite(outColorPath, color_buf * 255.f);
imwrite(outDepthPath, depth_buf);
imwrite("diff_" + outColorPath, rgbDiff * 255.f);
imwrite("diff_" + outDepthPath, depthDiff);
}
}
// some culling options produce the same pictures, let's join them
TriangleCullingMode findSameCulling(ModelType modelType, TriangleShadingType shadingType, TriangleCullingMode cullingMode, bool forRgb)
{
TriangleCullingMode sameCullingMode = cullingMode;
if ((modelType == ModelType::Centered && cullingMode == RASTERIZE_CULLING_CCW) ||
(modelType == ModelType::Color && cullingMode == RASTERIZE_CULLING_CW) ||
(modelType == ModelType::File && shadingType == RASTERIZE_SHADING_WHITE && forRgb) ||
(modelType == ModelType::File && cullingMode == RASTERIZE_CULLING_CW))
{
sameCullingMode = RASTERIZE_CULLING_NONE;
}
return sameCullingMode;
}
// compare rendering results to the ones produced by samples/opengl/opengl_testdata_generator app
TEST_P(RenderingTest, accuracy)
{
depth_buf.convertTo(depth_buf, CV_16U, depthScale);
if (modelType == ModelType::Empty ||
(modelType == ModelType::Centered && cullingMode == RASTERIZE_CULLING_CW) ||
(modelType == ModelType::Color && cullingMode == RASTERIZE_CULLING_CCW))
{
// empty image case
EXPECT_EQ(0, cv::norm(color_buf, NORM_INF));
Mat depthDiff;
absdiff(depth_buf, Scalar(zFar * depthScale), depthDiff);
EXPECT_EQ(0, cv::norm(depthDiff, cv::NORM_INF));
}
else
{
RenderTestThresholds thr(0, 0, 0, 0, 0);
switch (modelType)
{
case ModelType::Centered:
if (shadingType == RASTERIZE_SHADING_SHADED)
{
thr.rgbInfThreshold = 0.00218;
thr.rgbL2Threshold = 2.85e-06;
}
break;
case ModelType::Clipping:
if (width == 320 && height == 240 && shadingType == RASTERIZE_SHADING_FLAT && cullingMode == RASTERIZE_CULLING_CW)
{
thr.depthInfThreshold = 1;
thr.depthL2Threshold = 0.0016;
}
else if (width == 320 && height == 240 && shadingType == RASTERIZE_SHADING_SHADED && cullingMode == RASTERIZE_CULLING_NONE)
{
thr.rgbInfThreshold = 0.934;
thr.rgbL2Threshold = 8.03E-05;
thr.depthMaskThreshold = 23;
thr.depthInfThreshold = 1;
thr.depthL2Threshold = 0.000544;
}
else if (width == 256 && height == 256 && shadingType == RASTERIZE_SHADING_SHADED && cullingMode == RASTERIZE_CULLING_CW)
{
thr.rgbInfThreshold = 0.0022;
thr.rgbL2Threshold = 2.54E-06;
thr.depthInfThreshold = 1;
thr.depthL2Threshold = 0.00175;
}
else if (width == 256 && height == 256 && shadingType == RASTERIZE_SHADING_FLAT && cullingMode == RASTERIZE_CULLING_CCW)
{
thr.rgbInfThreshold = 0.934;
thr.rgbL2Threshold = 0.000102;
thr.depthMaskThreshold = 21;
}
else if (width == 640 && height == 480 && shadingType == RASTERIZE_SHADING_WHITE && cullingMode == RASTERIZE_CULLING_NONE)
{
thr.rgbInfThreshold = 1;
thr.rgbL2Threshold = 3.95E-05;
thr.depthMaskThreshold = 49;
thr.depthInfThreshold = 1;
thr.depthL2Threshold = 0.000269;
}
else if (width == 700 && height == 700 && shadingType == RASTERIZE_SHADING_FLAT && cullingMode == RASTERIZE_CULLING_CCW)
{
thr.rgbInfThreshold = 0.934;
thr.rgbL2Threshold = 3.27e-5;
thr.depthMaskThreshold = 121;
}
break;
case ModelType::Color:
thr.depthInfThreshold = 1;
if (width == 320 && height == 240)
{
thr.depthL2Threshold = 0.000989;
}
else if (width == 256 && height == 256)
{
thr.depthL2Threshold = 0.000785;
}
if (shadingType == RASTERIZE_SHADING_SHADED)
{
thr.rgbInfThreshold = 0.0022;
thr.rgbL2Threshold = 3.13e-06;
}
break;
case ModelType::File:
if (width == 320 && height == 240 && shadingType == RASTERIZE_SHADING_SHADED && cullingMode == RASTERIZE_CULLING_CCW)
{
thr.rgbInfThreshold = 0.93;
thr.rgbL2Threshold = 2.45E-05;
thr.depthMaskThreshold = 2;
thr.depthInfThreshold = 99;
thr.depthL2Threshold = 0.00544;
}
else if (width == 700 && height == 700 && shadingType == RASTERIZE_SHADING_SHADED && cullingMode == RASTERIZE_CULLING_CW)
{
thr.rgbInfThreshold = 0.973;
thr.rgbL2Threshold = 4.46E-06;
thr.depthMaskThreshold = 3;
thr.depthInfThreshold = 258;
thr.depthL2Threshold = 0.00142;
}
else if (width == 700 && height == 700 && shadingType == RASTERIZE_SHADING_WHITE && cullingMode == RASTERIZE_CULLING_NONE)
{
thr.rgbInfThreshold = 1;
thr.rgbL2Threshold = 6.13E-06;
thr.depthMaskThreshold = 3;
thr.depthInfThreshold = 258;
thr.depthL2Threshold = 0.00142;
}
break;
default:
break;
}
CullingModeEnum cullingModeRgb = findSameCulling(modelType, shadingType, cullingMode, true);
CullingModeEnum cullingModeDepth = findSameCulling(modelType, shadingType, cullingMode, false);
std::string modelName = printEnum(modelType);
std::string shadingName = printEnum(shadingType);
std::string cullingName = printEnum(cullingMode);
std::string cullingRgbName = printEnum(cullingModeRgb);
std::string cullingDepthName = printEnum(cullingModeDepth);
std::string path = findDataDirectory("rendering");
std::string suffix = cv::format("%s_%dx%d_Cull%s", modelName.c_str(), width, height, cullingName.c_str());
std::string suffixRgb = cv::format("%s_%dx%d_Cull%s", modelName.c_str(), width, height, cullingRgbName.c_str());
std::string suffixDepth = cv::format("%s_%dx%d_Cull%s", modelName.c_str(), width, height, cullingDepthName.c_str());
std::string gtPathColor = path + "/example_image_" + suffixRgb + "_" + shadingName + ".png";
std::string gtPathDepth = path + "/depth_image_" + suffixDepth + ".png";
Mat rgbDiff, depthDiff;
Mat groundTruthColor = imread(gtPathColor);
groundTruthColor.convertTo(groundTruthColor, CV_32F, (1.f / 255.f));
compareRGB(groundTruthColor, color_buf, rgbDiff, thr.rgbInfThreshold, thr.rgbL2Threshold);
Mat groundTruthDepth = imread(gtPathDepth, cv::IMREAD_GRAYSCALE | cv::IMREAD_ANYDEPTH);
compareDepth(groundTruthDepth, depth_buf, depthDiff, zFar, depthScale, thr.depthMaskThreshold, thr.depthInfThreshold, thr.depthL2Threshold);
// add --test_debug to output resulting images
if (debugLevel > 0)
{
std::string outColorPath = "color_image_" + suffix + "_" + shadingName + ".png";
std::string outDepthPath = "depth_image_" + suffix + "_" + shadingName + ".png";
imwrite(outColorPath, color_buf * 255.f);
imwrite(outDepthPath, depth_buf);
imwrite("diff_" + outColorPath, rgbDiff * 255.f);
imwrite("diff_" + outDepthPath, depthDiff);
}
}
}
// drawing model as a whole or as two halves should give the same result
TEST_P(RenderingTest, keepDrawnData)
{
if (modelType != ModelType::Empty)
{
Mat depth_buf2(height, width, ftype, zFar);
Mat color_buf2(height, width, CV_MAKETYPE(ftype, 3), Scalar::all(0));
Mat idx1, idx2;
int nTriangles = (int)indices.total();
idx1 = indices.reshape(3, 1)(Range::all(), Range(0, nTriangles / 2));
idx2 = indices.reshape(3, 1)(Range::all(), Range(nTriangles / 2, nTriangles));
triangleRasterize(verts, idx1, colors, color_buf2, depth_buf2, cameraPose, fovYradians, zNear, zFar, settings);
triangleRasterize(verts, idx2, colors, color_buf2, depth_buf2, cameraPose, fovYradians, zNear, zFar, settings);
Mat rgbDiff, depthDiff;
compareRGB(color_buf, color_buf2, rgbDiff, 0, 0);
depth_buf.convertTo(depth_buf, CV_16U, depthScale);
depth_buf2.convertTo(depth_buf2, CV_16U, depthScale);
compareDepth(depth_buf, depth_buf2, depthDiff, zFar, depthScale, 0, 0, 0);
}
}
TEST_P(RenderingTest, glCompatibleDepth)
{
Mat depth_buf2(height, width, ftype, 1.0);
triangleRasterizeDepth(verts, indices, depth_buf2, cameraPose, fovYradians, zNear, zFar,
settings.setGlCompatibleMode(RASTERIZE_COMPAT_INVDEPTH));
Mat convertedDepth(height, width, ftype);
// map from [0, 1] to [zNear, zFar]
double scaleNear = (1.0 / zNear);
double scaleFar = (1.0 / zFar);
for (int y = 0; y < height; y++)
{
for (int x = 0; x < width; x++)
{
double z = (double)depth_buf2.at<float>(y, x);
convertedDepth.at<float>(y, x) = (float)(1.0 / ((1.0 - z) * scaleNear + z * scaleFar ));
}
}
double normL2Diff = cv::norm(depth_buf, convertedDepth, cv::NORM_L2) / (height * width);
const double normL2Threshold = 1.e-9;
EXPECT_LE(normL2Diff, normL2Threshold);
// add --test_debug to output differences
if (debugLevel > 0)
{
std::cout << "normL2Diff: " << normL2Diff << " vs " << normL2Threshold << std::endl;
}
}
INSTANTIATE_TEST_CASE_P(Rendering, RenderingTest, ::testing::Values(
RenderTestParamType { std::make_tuple(320, 240), RASTERIZE_SHADING_SHADED, RASTERIZE_CULLING_NONE, ModelType::Centered, CV_32F, CV_32S },
RenderTestParamType { std::make_tuple(256, 256), RASTERIZE_SHADING_SHADED, RASTERIZE_CULLING_NONE, ModelType::Centered, CV_32F, CV_32S },
RenderTestParamType { std::make_tuple(256, 256), RASTERIZE_SHADING_WHITE, RASTERIZE_CULLING_NONE, ModelType::Centered, CV_32F, CV_32S },
RenderTestParamType { std::make_tuple(640, 480), RASTERIZE_SHADING_FLAT, RASTERIZE_CULLING_NONE, ModelType::Centered, CV_32F, CV_32S },
RenderTestParamType { std::make_tuple(320, 240), RASTERIZE_SHADING_FLAT, RASTERIZE_CULLING_CW, ModelType::Color, CV_32F, CV_32S },
RenderTestParamType { std::make_tuple(320, 240), RASTERIZE_SHADING_SHADED, RASTERIZE_CULLING_NONE, ModelType::Color, CV_32F, CV_32S },
RenderTestParamType { std::make_tuple(256, 256), RASTERIZE_SHADING_SHADED, RASTERIZE_CULLING_NONE, ModelType::Color, CV_32F, CV_32S },
RenderTestParamType { std::make_tuple(256, 256), RASTERIZE_SHADING_WHITE, RASTERIZE_CULLING_NONE, ModelType::Color, CV_32F, CV_32S },
RenderTestParamType { std::make_tuple(320, 240), RASTERIZE_SHADING_FLAT, RASTERIZE_CULLING_CW, ModelType::Clipping, CV_32F, CV_32S },
RenderTestParamType { std::make_tuple(320, 240), RASTERIZE_SHADING_SHADED, RASTERIZE_CULLING_NONE, ModelType::Clipping, CV_32F, CV_32S },
RenderTestParamType { std::make_tuple(256, 256), RASTERIZE_SHADING_FLAT, RASTERIZE_CULLING_CCW, ModelType::Clipping, CV_32F, CV_32S },
RenderTestParamType { std::make_tuple(256, 256), RASTERIZE_SHADING_SHADED, RASTERIZE_CULLING_CW, ModelType::Clipping, CV_32F, CV_32S },
RenderTestParamType { std::make_tuple(640, 480), RASTERIZE_SHADING_WHITE, RASTERIZE_CULLING_NONE, ModelType::Clipping, CV_32F, CV_32S },
RenderTestParamType { std::make_tuple(700, 700), RASTERIZE_SHADING_FLAT, RASTERIZE_CULLING_CCW, ModelType::Clipping, CV_32F, CV_32S },
RenderTestParamType { std::make_tuple(320, 240), RASTERIZE_SHADING_SHADED, RASTERIZE_CULLING_CCW, ModelType::File, CV_32F, CV_32S },
RenderTestParamType { std::make_tuple(700, 700), RASTERIZE_SHADING_SHADED, RASTERIZE_CULLING_CW, ModelType::File, CV_32F, CV_32S },
RenderTestParamType { std::make_tuple(700, 700), RASTERIZE_SHADING_WHITE, RASTERIZE_CULLING_NONE, ModelType::File, CV_32F, CV_32S }
));
} // namespace ::
} // namespace opencv_test

@ -10,6 +10,7 @@ SET(OPENCV_OPENGL_SAMPLES_REQUIRED_DEPS
opencv_core
opencv_imgproc
opencv_imgcodecs
opencv_3d
opencv_videoio
opencv_highgui)
ocv_check_dependencies(${OPENCV_OPENGL_SAMPLES_REQUIRED_DEPS})

@ -0,0 +1,460 @@
#include <iostream>
#ifdef _WIN32
#define WIN32_LEAN_AND_MEAN 1
#define NOMINMAX 1
#include <windows.h>
#endif
#if defined(__APPLE__)
#include <OpenGL/gl.h>
#include <OpenGL/glu.h>
#else
#include <GL/gl.h>
#include <GL/glu.h>
#endif
#include "opencv2/core.hpp"
#include "opencv2/core/opengl.hpp"
#include "opencv2/3d.hpp"
#include "opencv2/imgproc.hpp"
#include "opencv2/highgui.hpp"
using namespace std;
using namespace cv;
using namespace cv::cuda;
// model data should be identical to the code from tests
enum class ModelType
{
Empty = 0,
File = 1,
Clipping = 2,
Color = 3,
Centered = 4
};
static void generateNormals(const std::vector<Vec3f>& points, const std::vector<std::vector<int>>& indices,
std::vector<Vec3f>& normals)
{
std::vector<std::vector<Vec3f>> preNormals(points.size(), std::vector<Vec3f>());
for (const auto& tri : indices)
{
Vec3f p0 = points[tri[0]];
Vec3f p1 = points[tri[1]];
Vec3f p2 = points[tri[2]];
Vec3f cross = cv::normalize((p1 - p0).cross(p2 - p0));
for (int i = 0; i < 3; i++)
{
preNormals[tri[i]].push_back(cross);
}
}
normals.reserve(points.size());
for (const auto& pn : preNormals)
{
Vec3f sum { };
for (const auto& n : pn)
{
sum += n;
}
normals.push_back(cv::normalize(sum));
}
}
class ModelData
{
public:
ModelData(ModelType type = ModelType::Empty, std::string objPath = { })
{
switch (type)
{
case ModelType::Empty:
{
position = Vec3d(0.0, 0.0, 0.0);
lookat = Vec3d(0.0, 0.0, 0.0);
upVector = Vec3d(0.0, 1.0, 0.0);
fovy = 45.0;
vertices = std::vector<Vec3f>(4, {2.0f, 0, -2.0f});
colors = std::vector<Vec3f>(4, {0, 0, 1.0f});
indices = { };
}
break;
case ModelType::File:
{
position = Vec3d( 1.9, 0.4, 1.3);
lookat = Vec3d( 0.0, 0.0, 0.0);
upVector = Vec3d( 0.0, 1.0, 0.0);
fovy = 45.0;
objectPath = objPath;
std::vector<vector<int>> indvec;
loadMesh(objectPath, vertices, indvec);
// using per-vertex normals as colors
generateNormals(vertices, indvec, colors);
if (vertices.size() != colors.size())
{
std::runtime_error("Model should contain normals for each vertex");
}
for (const auto &vec : indvec)
{
indices.push_back({vec[0], vec[1], vec[2]});
}
for (auto &color : colors)
{
color = Vec3f(abs(color[0]), abs(color[1]), abs(color[2]));
}
}
break;
case ModelType::Clipping:
{
position = Vec3d(0.0, 0.0, 5.0);
lookat = Vec3d(0.0, 0.0, 0.0);
upVector = Vec3d(0.0, 1.0, 0.0);
fovy = 45.0;
vertices =
{
{ 2.0, 0.0, -2.0}, { 0.0, -6.0, -2.0}, {-2.0, 0.0, -2.0},
{ 3.5, -1.0, -5.0}, { 2.5, -2.5, -5.0}, {-1.0, 1.0, -5.0},
{-6.5, -1.0, -3.0}, {-2.5, -2.0, -3.0}, { 1.0, 1.0, -5.0},
};
indices = { {0, 1, 2}, {3, 4, 5}, {6, 7, 8} };
Vec3f col1(217.0, 238.0, 185.0);
Vec3f col2(185.0, 217.0, 238.0);
Vec3f col3(150.0, 10.0, 238.0);
col1 *= (1.f / 255.f);
col2 *= (1.f / 255.f);
col3 *= (1.f / 255.f);
colors =
{
col1, col2, col3,
col2, col3, col1,
col3, col1, col2,
};
}
break;
case ModelType::Centered:
{
position = Vec3d(0.0, 0.0, 5.0);
lookat = Vec3d(0.0, 0.0, 0.0);
upVector = Vec3d(0.0, 1.0, 0.0);
fovy = 45.0;
vertices =
{
{ 2.0, 0.0, -2.0}, { 0.0, -2.0, -2.0}, {-2.0, 0.0, -2.0},
{ 3.5, -1.0, -5.0}, { 2.5, -1.5, -5.0}, {-1.0, 0.5, -5.0},
};
indices = { {0, 1, 2}, {3, 4, 5} };
Vec3f col1(217.0, 238.0, 185.0);
Vec3f col2(185.0, 217.0, 238.0);
col1 *= (1.f / 255.f);
col2 *= (1.f / 255.f);
colors =
{
col1, col2, col1,
col2, col1, col2,
};
}
break;
case ModelType::Color:
{
position = Vec3d(0.0, 0.0, 5.0);
lookat = Vec3d(0.0, 0.0, 0.0);
upVector = Vec3d(0.0, 1.0, 0.0);
fovy = 60.0;
vertices =
{
{ 2.0, 0.0, -2.0},
{ 0.0, 2.0, -3.0},
{-2.0, 0.0, -2.0},
{ 0.0, -2.0, 1.0},
};
indices = { {0, 1, 2}, {0, 2, 3} };
colors =
{
{ 0.0f, 0.0f, 1.0f},
{ 0.0f, 1.0f, 0.0f},
{ 1.0f, 0.0f, 0.0f},
{ 0.0f, 1.0f, 0.0f},
};
}
break;
default:
CV_Error(Error::StsBadArg, "Unknown model type");
break;
}
}
Vec3d position;
Vec3d lookat;
Vec3d upVector;
double fovy;
std::vector<Vec3f> vertices;
std::vector<Vec3i> indices;
std::vector<Vec3f> colors;
string objectPath;
};
struct DrawData
{
ogl::Arrays arr;
ogl::Buffer indices;
};
void draw(void* userdata);
void draw(void* userdata)
{
DrawData* data = static_cast<DrawData*>(userdata);
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
ogl::render(data->arr, data->indices, ogl::TRIANGLES);
}
static void generateImage(cv::Size imgSz, TriangleShadingType shadingType, TriangleCullingMode cullingMode,
ModelType modelType, std::string modelPath, cv::Mat& colorImage, cv::Mat& depthImage)
{
namedWindow("OpenGL", WINDOW_OPENGL);
resizeWindow("OpenGL", imgSz.width, imgSz.height);
ModelData modelData(modelType, modelPath);
DrawData data;
std::vector<Vec3f> vertices;
std::vector<Vec4f> colors4f;
std::vector<int> idxLinear;
if (shadingType == RASTERIZE_SHADING_FLAT)
{
// rearrange vertices and colors for flat shading
int ctr = 0;
for (const auto& idx : modelData.indices)
{
for (int i = 0; i < 3; i++)
{
vertices.push_back(modelData.vertices[idx[i]]);
idxLinear.push_back(ctr++);
}
Vec3f ci = modelData.colors[idx[0]];
for (int i = 0; i < 3; i++)
{
colors4f.emplace_back(ci[0], ci[1], ci[2], 1.f);
}
}
}
else
{
vertices = modelData.vertices;
for (const auto& c : modelData.colors)
{
Vec3f ci = (shadingType == RASTERIZE_SHADING_SHADED) ? c: cv::Vec3f::all(1.f);
colors4f.emplace_back(ci[0], ci[1], ci[2], 1.0);
}
for (const auto& idx : modelData.indices)
{
for (int i = 0; i < 3; i++)
{
idxLinear.push_back(idx[i]);
}
}
}
data.arr.setVertexArray(vertices);
data.arr.setColorArray(colors4f);
data.indices.copyFrom(idxLinear);
double zNear = 0.1, zFar = 50;
glMatrixMode(GL_PROJECTION);
glLoadIdentity();
gluPerspective(modelData.fovy, (double)imgSz.width / imgSz.height, zNear, zFar);
glMatrixMode(GL_MODELVIEW);
glLoadIdentity();
//gluLookAt(0, 0, 5, 0, 0, 0, 0, 1, 0);
gluLookAt(modelData.position[0], modelData.position[1], modelData.position[2],
modelData.lookat [0], modelData.lookat [1], modelData.lookat [2],
modelData.upVector[0], modelData.upVector[1], modelData.upVector[2]);
if (cullingMode == RASTERIZE_CULLING_NONE)
{
glDisable(GL_CULL_FACE);
}
else
{
glEnable(GL_CULL_FACE);
glCullFace(GL_FRONT);
if (cullingMode == RASTERIZE_CULLING_CW)
{
glFrontFace(GL_CW);
}
else
{
glFrontFace(GL_CCW);
}
}
glEnable(GL_DEPTH_TEST);
cv::setOpenGlDrawCallback("OpenGL", draw, &data);
const int framesToSkip = 10;
for (int f = 0; f < framesToSkip; f++)
{
updateWindow("OpenGL");
colorImage = cv::Mat(imgSz.height, imgSz.width, CV_8UC3);
glReadPixels(0, 0, imgSz.width, imgSz.height, GL_RGB, GL_UNSIGNED_BYTE, colorImage.data);
cv::cvtColor(colorImage, colorImage, cv::COLOR_RGB2BGR);
cv::flip(colorImage, colorImage, 0);
depthImage = cv::Mat(imgSz.height, imgSz.width, CV_32F);
glReadPixels(0, 0, imgSz.width, imgSz.height, GL_DEPTH_COMPONENT, GL_FLOAT, depthImage.data);
// map from [0, 1] to [zNear, zFar]
for (auto it = depthImage.begin<float>(); it != depthImage.end<float>(); ++it)
{
*it = (float)(zNear * zFar / (double(*it) * (zNear - zFar) + zFar));
}
cv::flip(depthImage, depthImage, 0);
depthImage.convertTo(depthImage, CV_16U, 1000.0);
char key = (char)waitKey(40);
if (key == 27)
break;
}
cv::setOpenGlDrawCallback("OpenGL", 0, 0);
cv::destroyAllWindows();
}
int main(int argc, char* argv[])
{
cv::CommandLineParser parser(argc, argv,
"{ help h usage ? | | show this message }"
"{ outPath | | output path for generated images }"
"{ modelPath | | path to 3d model to render }"
);
parser.about("This app is used to generate test data for triangleRasterize() function");
if (parser.has("help"))
{
parser.printMessage();
return 0;
}
std::string modelPath = parser.get<std::string>("modelPath");
if (modelPath.empty())
{
std::cout << "No model path given" << std::endl;
return -1;
}
std::string outPath = parser.get<std::string>("outPath");
if (outPath.empty())
{
std::cout << "No output path given" << std::endl;
return -1;
}
std::array<cv::Size, 4> resolutions = { cv::Size {700, 700}, cv::Size {640, 480}, cv::Size(256, 256), cv::Size(320, 240) };
for (const auto& res : resolutions)
{
for (const auto shadingType : {
RASTERIZE_SHADING_WHITE,
RASTERIZE_SHADING_FLAT,
RASTERIZE_SHADING_SHADED
})
{
std::string shadingName;
switch (shadingType)
{
case RASTERIZE_SHADING_WHITE: shadingName = "White"; break;
case RASTERIZE_SHADING_FLAT: shadingName = "Flat"; break;
case RASTERIZE_SHADING_SHADED: shadingName = "Shaded"; break;
default:
break;
}
for (const auto cullingMode : {
RASTERIZE_CULLING_NONE,
RASTERIZE_CULLING_CW,
RASTERIZE_CULLING_CCW
})
{
std::string cullingName;
switch (cullingMode)
{
case RASTERIZE_CULLING_NONE: cullingName = "None"; break;
case RASTERIZE_CULLING_CW: cullingName = "CW"; break;
case RASTERIZE_CULLING_CCW: cullingName = "CCW"; break;
default: break;
}
for (const auto modelType : {
ModelType::File,
ModelType::Clipping,
ModelType::Color,
ModelType::Centered,
})
{
std::string modelName;
switch (modelType)
{
case ModelType::File: modelName = "File"; break;
case ModelType::Clipping: modelName = "Clipping"; break;
case ModelType::Color: modelName = "Color"; break;
case ModelType::Centered: modelName = "Centered"; break;
default:
break;
}
std::string suffix = cv::format("%s_%dx%d_Cull%s", modelName.c_str(), res.width, res.height, cullingName.c_str());
std::cout << suffix + "_" + shadingName << "..." << std::endl;
cv::Mat colorImage, depthImage;
generateImage(res, shadingType, cullingMode, modelType, modelPath, colorImage, depthImage);
std::string gtPathColor = outPath + "/example_image_" + suffix + "_" + shadingName + ".png";
std::string gtPathDepth = outPath + "/depth_image_" + suffix + ".png";
cv::imwrite(gtPathColor, colorImage);
cv::imwrite(gtPathDepth, depthImage);
}
}
}
}
return 0;
}
Loading…
Cancel
Save