Skip to content

Commit

Permalink
Add Heightmap integration test (#785)
Browse files Browse the repository at this point in the history
This PR adds a heightmap test.

Almost all issues in #546 are covered.

Only Thermal Camera is not covered.

Fixes #332 (again) for macOS and possibly any OS/HW/Driver combination.
Fixes #369

Signed-off-by: Matias N. Goldberg <[email protected]>
Co-authored-by: Ian Chen <[email protected]>
  • Loading branch information
darksylinc and iche033 authored Dec 28, 2022
1 parent bf15100 commit 4de8d1e
Show file tree
Hide file tree
Showing 11 changed files with 804 additions and 42 deletions.
2 changes: 1 addition & 1 deletion ogre2/src/Ogre2DepthCamera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -909,7 +909,7 @@ void Ogre2DepthCamera::CreateDepthTexture()
this->ImageWidth(), this->ImageHeight());
this->dataPtr->ogreDepthTexture[i]->setNumMipmaps(1u);
this->dataPtr->ogreDepthTexture[i]->setPixelFormat(
Ogre::PFG_RGBA32_FLOAT);
Ogre::PFG_RGBA32_UINT);

this->dataPtr->ogreDepthTexture[i]->scheduleTransitionTo(
Ogre::GpuResidency::Resident);
Expand Down
2 changes: 1 addition & 1 deletion ogre2/src/media/Hlms/Terra/Metal/VertexShader_vs.metal
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ struct PS_INPUT
@insertpiece( Terra_VStoPS_block )
float4 gl_Position [[position]];
@foreach( hlms_pso_clip_distances, n )
float gl_ClipDistance@n [[clip_distance]];
float gl_ClipDistance [[clip_distance]] [@value( hlms_pso_clip_distances )];
@end
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,11 +23,10 @@ in block
vec2 uv0;
} inPs;

vulkan_layout( ogre_t0 ) uniform texture2D inputTexture;
vulkan( layout( ogre_s0 ) uniform sampler texSampler );
vulkan_layout( ogre_t0 ) uniform utexture2D inputTexture;

vulkan_layout( location = 0 )
out vec4 fragColor;
out uvec4 fragColor;

vulkan( layout( ogre_P0 ) uniform Params { )
uniform float near;
Expand All @@ -42,14 +41,14 @@ void main()
{
float tolerance = 1e-6;

// Note: We use texelFetch because p.a contains an uint32 and sampling
// Note: We use PFG_RGBA32_UINT because p.a contains an uint32 and sampling
// (even w/ point filtering) causes p.a to loss information (e.g.
// values close to 0 get rounded to 0)
//
// See https://github.com/gazebosim/gz-rendering/issues/332
vec4 p = texelFetch(vkSampler2D(inputTexture,texSampler), ivec2(inPs.uv0 *texResolution.xy), 0);
uvec4 p = texelFetch(inputTexture, ivec2(inPs.uv0 *texResolution.xy), 0);

vec3 point = p.xyz;
vec3 point = uintBitsToFloat(p.xyz);

// Clamp again in case render passes changed depth values
// to be outside of min/max range
Expand Down Expand Up @@ -78,5 +77,5 @@ void main()
}
}

fragColor = vec4(point, p.a);
fragColor = uvec4(floatBitsToUint(point), p.a);
}
17 changes: 8 additions & 9 deletions ogre2/src/media/materials/programs/GLSL/depth_camera_fs.glsl
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ vulkan_layout( ogre_t3 ) uniform texture2D particleDepthTexture;
vulkan( layout( ogre_s0 ) uniform sampler texSampler );

vulkan_layout( location = 0 )
out vec4 fragColor;
out uvec4 fragColor;

vulkan( layout( ogre_P0 ) uniform Params { )
uniform vec2 projectionParams;
Expand All @@ -49,13 +49,13 @@ vulkan( layout( ogre_P0 ) uniform Params { )
uniform float rnd;
vulkan( }; )

float packFloat(vec4 color)
uint packUnorm4x8Gz(vec4 color)
{
int rgba = (int(round(color.x * 255.0)) << 24) +
(int(round(color.y * 255.0)) << 16) +
(int(round(color.z * 255.0)) << 8) +
int(round(color.w * 255.0));
return intBitsToFloat(rgba);
uint rgba = (uint(round(color.x * 255.0)) << 24u) +
(uint(round(color.y * 255.0)) << 16u) +
(uint(round(color.z * 255.0)) << 8u) +
uint(round(color.w * 255.0));
return rgba;
}

float toSRGB( float x )
Expand Down Expand Up @@ -199,6 +199,5 @@ void main()
// gamma correct
color = toSRGB(color);

float rgba = packFloat(color);
fragColor = vec4(point, rgba);
fragColor = uvec4(floatBitsToUint(point), packUnorm4x8Gz(color));
}
Original file line number Diff line number Diff line change
Expand Up @@ -34,27 +34,24 @@ struct Params
float4 texResolution;
};

fragment float4 main_metal
fragment uint4 main_metal
(
PS_INPUT inPs [[stage_in]],
texture2d<float> inputTexture [[texture(0)]],
sampler inputSampler [[sampler(0)]],
texture2d<uint> inputTexture [[texture(0)]],
constant Params &params [[buffer(PARAMETER_SLOT)]]
)
{
float tolerance = 1e-6;

// Note: We use texelFetch because p.a contains an uint32 and sampling
// Note: We use PFG_RGBA32_UINT because p.a contains an uint32 and sampling
// (even w/ point filtering) causes p.a to loss information (e.g.
// values close to 0 get rounded to 0)
//
// See https://github.com/gazebosim/gz-rendering/issues/332
// Either: Metal equivalent of texelFetch
float4 p = inputTexture.read(uint2(inPs.uv0 * params.texResolution.xy), 0);
// Or: Use standard sampler
// float4 p = inputTexture.sample(inputSampler, inPs.uv0);
uint4 p = inputTexture.read(uint2(inPs.uv0 * params.texResolution.xy), 0);

float3 point = p.xyz;
float3 point = as_type<float3>(p.xyz);

// Clamp again in case render passes changed depth values
// to be outside of min/max range
Expand Down Expand Up @@ -83,6 +80,6 @@ fragment float4 main_metal
}
}

float4 fragColor(point, p.a);
uint4 fragColor(as_type<uint3>(point), p.a);
return fragColor;
}
17 changes: 8 additions & 9 deletions ogre2/src/media/materials/programs/Metal/depth_camera_fs.metal
Original file line number Diff line number Diff line change
Expand Up @@ -42,13 +42,13 @@ struct Params
float rnd;
};

float packFloat(float4 color)
uint packUnorm4x8Gz(float4 color)
{
int rgba = (int(round(color.x * 255.0)) << 24) +
(int(round(color.y * 255.0)) << 16) +
(int(round(color.z * 255.0)) << 8) +
int(round(color.w * 255.0));
return as_type<float>(rgba);
uint rgba = (uint(round(color.x * 255.0)) << 24u) +
(uint(round(color.y * 255.0)) << 16u) +
(uint(round(color.z * 255.0)) << 8u) +
uint(round(color.w * 255.0));
return rgba;
}

inline float toSRGB( float x )
Expand Down Expand Up @@ -89,7 +89,7 @@ float4 gaussrand(float2 co, float3 offsets, float mean, float stddev)
return float4(Z, Z, Z, 0.0);
}

fragment float4 main_metal
fragment uint4 main_metal
(
PS_INPUT inPs [[stage_in]],
texture2d<float> depthTexture [[texture(0)]],
Expand Down Expand Up @@ -204,7 +204,6 @@ fragment float4 main_metal
// gamma correct
color = toSRGB(color);

float rgba = packFloat(color);
float4 fragColor(point, rgba);
uint4 fragColor(as_type<uint3>(point), packUnorm4x8Gz(color));
return fragColor;
}
1 change: 1 addition & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ set(tests
camera
depth_camera
gpu_rays
heightmap
lidar_visual
render_pass
scene
Expand Down
23 changes: 23 additions & 0 deletions test/integration/base64.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
//
// base64 encoding and decoding with C++.
// Version: 1.01.00
//
// Copyright (C) 2004-2017 René Nyffenegger
//

#pragma once

#include <string>
#include <vector>

/// \brief Takes a binary input and outputs a string in base64
/// \param[in] _bytesToEncode binary data to encode
/// \param[in] _len length in bytes of _bytesToEncode
/// \param[out] _outBase64 String with base64-encoded of input
void Base64Encode(const void *_bytesToEncode, size_t _len,
std::string &_outBase64);

/// \brief Takes a base64-encoded string and turns it back into binary
/// \param _s base64-encoded string
/// \return Decoded binary data
std::vector<uint8_t> Base64Decode(const std::string &_s);
156 changes: 156 additions & 0 deletions test/integration/base64.inl
Original file line number Diff line number Diff line change
@@ -0,0 +1,156 @@
/*
base64.cpp and base64.h
base64 encoding and decoding with C++.
Version: 1.01.00
Copyright (C) 2004-2017 René Nyffenegger
This source code is provided 'as-is', without any express or implied
warranty. In no event will the author be held liable for any damages
arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it
freely, subject to the following restrictions:
1. The origin of this source code must not be misrepresented; you must not
claim that you wrote the original source code. If you use this source code
in a product, an acknowledgment in the product documentation would be
appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be
misrepresented as being the original source code.
3. This notice may not be removed or altered from any source distribution.
René Nyffenegger [email protected]
*/

#include "base64.hh"

#include <iostream>

static const std::string kBase64Chars = // NOLINT
"ABCDEFGHIJKLMNOPQRSTUVWXYZ"
"abcdefghijklmnopqrstuvwxyz"
"0123456789+/";

static inline bool is_base64(char c)
{
return (isalnum(c) || (c == '+') || (c == '/'));
}

void Base64Encode(const void *_bytesToEncode, size_t _len,
std::string &_outBase64)
{
uint8_t const *bytesToEncode =
reinterpret_cast<uint8_t const *>(_bytesToEncode);

int i = 0;
unsigned char char_array_3[3];
unsigned char char_array_4[4];

while (_len--)
{
char_array_3[i++] = *(bytesToEncode++);
if (i == 3)
{
char_array_4[0] = (char_array_3[0] & 0xfc) >> 2;
char_array_4[1] = static_cast<uint8_t>(((char_array_3[0] & 0x03) << 4) +
((char_array_3[1] & 0xf0) >> 4));
char_array_4[2] = static_cast<uint8_t>(((char_array_3[1] & 0x0f) << 2) +
((char_array_3[2] & 0xc0) >> 6));
char_array_4[3] = char_array_3[2] & 0x3f;

for (i = 0; (i < 4); i++)
{
_outBase64.push_back(kBase64Chars[char_array_4[i]]);
}
i = 0;
}
}

if (i)
{
int j = 0;
for (j = i; j < 3; j++)
char_array_3[j] = '\0';

char_array_4[0] = (char_array_3[0] & 0xfc) >> 2;
char_array_4[1] = static_cast<uint8_t>(((char_array_3[0] & 0x03) << 4) +
((char_array_3[1] & 0xf0) >> 4));
char_array_4[2] = static_cast<uint8_t>(((char_array_3[1] & 0x0f) << 2) +
((char_array_3[2] & 0xc0) >> 6));

for (j = 0; (j < i + 1); j++)
{
_outBase64.push_back(kBase64Chars[char_array_4[j]]);
}

while ((i++ < 3))
{
_outBase64.push_back('=');
}
}
}

std::vector<uint8_t> Base64Decode(const std::string &_s)
{
int in_len = static_cast<int>(_s.size());
int i = 0;
size_t in_ = 0u;
uint8_t char_array_4[4], char_array_3[3];
std::vector<uint8_t> ret;

while (in_len-- && (_s[in_] != '=') && is_base64(_s[in_]))
{
char_array_4[i++] = static_cast<uint8_t>(_s[in_]);
in_++;
if (i == 4)
{
for (i = 0; i < 4; i++)
{
char_array_4[i] = static_cast<uint8_t>(
kBase64Chars.find(static_cast<char>(char_array_4[i])));
}

char_array_3[0] = static_cast<uint8_t>((char_array_4[0] << 2) +
((char_array_4[1] & 0x30) >> 4));
char_array_3[1] = static_cast<uint8_t>(((char_array_4[1] & 0xf) << 4) +
((char_array_4[2] & 0x3c) >> 2));
char_array_3[2] =
static_cast<uint8_t>(((char_array_4[2] & 0x3) << 6) + char_array_4[3]);

for (i = 0; (i < 3); i++)
{
ret.push_back(char_array_3[i]);
}
i = 0;
}
}

if (i)
{
int j = 0;
for (j = 0; j < i; j++)
{
char_array_4[j] = static_cast<uint8_t>(static_cast<char>(
kBase64Chars.find(static_cast<char>(char_array_4[j]))));
}

char_array_3[0] = static_cast<uint8_t>((char_array_4[0] << 2) +
((char_array_4[1] & 0x30) >> 4));
char_array_3[1] = static_cast<uint8_t>(((char_array_4[1] & 0xf) << 4) +
((char_array_4[2] & 0x3c) >> 2));

for (j = 0; (j < i - 1); j++)
{
ret.push_back(char_array_3[j]);
}
}

return ret;
}
6 changes: 0 additions & 6 deletions test/integration/depth_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -237,10 +237,7 @@ TEST_F(DepthCameraTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(DepthCameraBoxes))
unsigned int ma = *mrgba >> 0 & 0xFF;
EXPECT_EQ(0u, mr);
EXPECT_EQ(0u, mg);
#ifndef __APPLE__
// https://github.com/gazebosim/gz-rendering/issues/332
EXPECT_GT(mb, 0u);
#endif

// Far left and right points should be red (background color)
float lc = pointCloudData[pcLeft + 3];
Expand Down Expand Up @@ -442,11 +439,8 @@ TEST_F(DepthCameraTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(DepthCameraBoxes))
unsigned int a = *rgba >> 0 & 0xFF;
EXPECT_EQ(0u, r);
EXPECT_EQ(0u, g);
#ifndef __APPLE__
// https://github.com/gazebosim/gz-rendering/issues/332
EXPECT_GT(b, 0u);
EXPECT_EQ(255u, a);
#endif
}
}
}
Expand Down
Loading

0 comments on commit 4de8d1e

Please sign in to comment.