Skip to content

Commit

Permalink
Merge pull request #4640 from kunaltyagi/shot.static_init
Browse files Browse the repository at this point in the history
  • Loading branch information
kunaltyagi authored Apr 9, 2021
2 parents e1664a4 + 400a4ec commit 203067d
Show file tree
Hide file tree
Showing 4 changed files with 122 additions and 81 deletions.
85 changes: 84 additions & 1 deletion common/include/pcl/common/colors.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@
#include <pcl/pcl_macros.h>
#include <pcl/point_types.h>

#include <type_traits> // for is_floating_point

namespace pcl
{

Expand Down Expand Up @@ -83,4 +85,85 @@ namespace pcl
using GlasbeyLUT = ColorLUT<pcl::LUT_GLASBEY>;
using ViridisLUT = ColorLUT<pcl::LUT_VIRIDIS>;

}
/**
* @brief Returns a Look-Up Table useful in converting RGB to sRGB
* @tparam T floating point type with resultant value
* @tparam bits depth of RGB
* @return 1-D LUT for converting R, G or B into Rs, Gs or Bs
* @remarks sRGB was proposed by Stokes et al. as a uniform default color
* space for the internet
* M. Stokes, M. Anderson, S. Chandrasekar, and R. Motta: A standard default colorspace for the internet - sRGB (Nov 1996)
* IEC 61966-2.1 Default RGB Colour Space - sRGB (International Electrotechnical Commission, Geneva, Switzerland, 1999)
* www.srgb.com, www.color.org/srgb.html
*/
template <typename T, std::uint8_t bits = 8>
PCL_EXPORTS inline std::array<T, 1 << bits>
RGB2sRGB_LUT() noexcept
{
static_assert(std::is_floating_point<T>::value, "LUT value must be a floating point");

constexpr const std::size_t size = 1 << bits;

static const auto sRGB_LUT = [&]() {
// MSVC wouldn't take `size` here instead of the expression
std::array<T, 1 << bits> LUT;
for (std::size_t i = 0; i < size; ++i) {
T f = static_cast<T>(i) / static_cast<T>(size - 1);
if (f > 0.04045) {
// ((f + 0.055)/1.055)^2.4
LUT[i] = static_cast<T>(
std::pow((f + static_cast<T>(0.055)) / static_cast<T>(1.055),
static_cast<T>(2.4)));
}
else {
// f / 12.92
LUT[i] = f / static_cast<T>(12.92);
}
}
return LUT;
}();
return sRGB_LUT;
}

/**
* @brief Returns a Look-Up Table useful in converting scaled CIE XYZ into CIE L*a*b*
* @details The function assumes that the XYZ values are
* * not normalized using reference illuminant
* * scaled such that reference illuminant has Xn = Yn = Zn = discretizations
* @tparam T floating point type with resultant value
* @tparam discretizations number of levels for the LUT
* @return 1-D LUT with results of f(X/Xn)
* @note This function doesn't convert from CIE XYZ to CIE L*a*b*. The actual conversion
* is as follows:
* L* = 116 * [f(Y/Yn) - 16/116]
* a* = 500 * [f(X/Xn) - f(Y/Yn)]
* b* = 200 * [f(Y/Yn) - f(Z/Zn)]
* Where, Xn, Yn and Zn are values of the reference illuminant (at prescribed angle)
* f is appropriate function such that L* = 100, a* = b* = 0 for white color
* Reference: Billmeyer and Saltzman’s Principles of Color Technology
*/
template <typename T, std::size_t discretizations = 4000>
PCL_EXPORTS inline const std::array<T, discretizations>&
XYZ2LAB_LUT() noexcept
{
static_assert(std::is_floating_point<T>::value, "LUT value must be a floating point");

static const auto f_LUT = [&]() {
std::array<T, discretizations> LUT;
for (std::size_t i = 0; i < discretizations; ++i) {
T f = static_cast<T>(i) / static_cast<T>(discretizations);
if (f > static_cast<T>(0.008856)) {
// f^(1/3)
LUT[i] = static_cast<T>(std::pow(f, (static_cast<T>(1) / static_cast<T>(3))));
}
else {
// 7.87 * f + 16/116
LUT[i] =
static_cast<T>(7.87) * f + (static_cast<T>(16) / static_cast<T>(116));
}
}
return LUT;
}();
return f_LUT;
}
} // namespace pcl
34 changes: 8 additions & 26 deletions features/include/pcl/features/impl/shot.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@
#include <pcl/features/shot.h>
#include <pcl/features/shot_lrf.h>

#include <pcl/common/colors.h> // for RGB2sRGB_LUT, XYZ2LAB_LUT

// Useful constants.
#define PST_PI 3.1415926535897932384626433832795
#define PST_RAD_45 0.78539816339744830961566084581988
Expand Down Expand Up @@ -84,41 +86,21 @@ areEquals (float val1, float val2, float zeroFloatEps = zeroFloatEps8)
}

//////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> float
pcl::SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::sRGB_LUT[256] = {- 1};
template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT>
std::array<float, 256>
pcl::SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::sRGB_LUT = pcl::RGB2sRGB_LUT<float, 8>();

//////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> float
pcl::SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::sXYZ_LUT[4000] = {- 1};
template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT>
std::array<float, 4000>
pcl::SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::sXYZ_LUT = pcl::XYZ2LAB_LUT<float, 4000>();

//////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
pcl::SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::RGB2CIELAB (unsigned char R, unsigned char G,
unsigned char B, float &L, float &A,
float &B2)
{
// @TODO: C++17 supports constexpr lambda for compile time init
if (sRGB_LUT[0] < 0)
{
for (int i = 0; i < 256; i++)
{
float f = static_cast<float> (i) / 255.0f;
if (f > 0.04045)
sRGB_LUT[i] = powf ((f + 0.055f) / 1.055f, 2.4f);
else
sRGB_LUT[i] = f / 12.92f;
}

for (int i = 0; i < 4000; i++)
{
float f = static_cast<float> (i) / 4000.0f;
if (f > 0.008856)
sXYZ_LUT[i] = static_cast<float> (powf (f, 0.3333f));
else
sXYZ_LUT[i] = static_cast<float>((7.787 * f) + (16.0 / 116.0));
}
}

float fr = sRGB_LUT[R];
float fg = sRGB_LUT[G];
float fb = sRGB_LUT[B];
Expand Down
7 changes: 4 additions & 3 deletions features/include/pcl/features/shot.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,8 @@
#include <pcl/point_types.h>
#include <pcl/features/feature.h>

#include <array> // for sRGB_LUT, sXYZ_LUT

namespace pcl
{
/** \brief SHOTEstimation estimates the Signature of Histograms of OrienTations (SHOT) descriptor for
Expand Down Expand Up @@ -98,7 +100,6 @@ namespace pcl
{
feature_name_ = "SHOTEstimation";
};


public:

Expand Down Expand Up @@ -400,8 +401,8 @@ namespace pcl
static void
RGB2CIELAB (unsigned char R, unsigned char G, unsigned char B, float &L, float &A, float &B2);

static float sRGB_LUT[256];
static float sXYZ_LUT[4000];
static std::array<float, 256> sRGB_LUT;
static std::array<float, 4000> sXYZ_LUT;
};
}

Expand Down
77 changes: 26 additions & 51 deletions registration/src/gicp6d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
*
*/

#include <pcl/common/colors.h> // for RGB2sRGB_LUT, XYZ2LAB_LUT
#include <pcl/registration/gicp6d.h>
#include <pcl/memory.h> // for pcl::make_shared

Expand All @@ -46,65 +47,39 @@ RGB2Lab(const Eigen::Vector3i& colorRGB)
{
// for sRGB -> CIEXYZ see http://www.easyrgb.com/index.php?X=MATH&H=02#text2
// for CIEXYZ -> CIELAB see http://www.easyrgb.com/index.php?X=MATH&H=07#text7
// an overview at: https://www.comp.nus.edu.sg/~leowwk/papers/colordiff.pdf

double R, G, B, X, Y, Z;
const auto& sRGB_LUT = RGB2sRGB_LUT<double, 8>();

// map sRGB values to [0, 1]
R = colorRGB[0] / 255.0;
G = colorRGB[1] / 255.0;
B = colorRGB[2] / 255.0;
const double R = sRGB_LUT[colorRGB[0]];
const double G = sRGB_LUT[colorRGB[1]];
const double B = sRGB_LUT[colorRGB[2]];

// linearize sRGB values
if (R > 0.04045)
R = pow((R + 0.055) / 1.055, 2.4);
else
R /= 12.92;
// linear sRGB -> CIEXYZ, D65 illuminant, observer at 2 degrees
const double X = R * 0.4124 + G * 0.3576 + B * 0.1805;
const double Y = R * 0.2126 + G * 0.7152 + B * 0.0722;
const double Z = R * 0.0193 + G * 0.1192 + B * 0.9505;

if (G > 0.04045)
G = pow((G + 0.055) / 1.055, 2.4);
else
G /= 12.92;

if (B > 0.04045)
B = pow((B + 0.055) / 1.055, 2.4);
else
B /= 12.92;

// postponed:
// R *= 100.0;
// G *= 100.0;
// B *= 100.0;

// linear sRGB -> CIEXYZ
X = R * 0.4124 + G * 0.3576 + B * 0.1805;
Y = R * 0.2126 + G * 0.7152 + B * 0.0722;
Z = R * 0.0193 + G * 0.1192 + B * 0.9505;

// *= 100.0 including:
X /= 0.95047; // 95.047;
// Y /= 1;//100.000;
Z /= 1.08883; // 108.883;
// normalize X, Y, Z with tristimulus values for Xn, Yn, Zn
float f[3] = {static_cast<float>(X), static_cast<float>(Y), static_cast<float>(Z)};
f[0] /= 0.95047;
f[1] /= 1;
f[2] /= 1.08883;

// CIEXYZ -> CIELAB
if (X > 0.008856)
X = pow(X, 1.0 / 3.0);
else
X = 7.787 * X + 16.0 / 116.0;

if (Y > 0.008856)
Y = pow(Y, 1.0 / 3.0);
else
Y = 7.787 * Y + 16.0 / 116.0;

if (Z > 0.008856)
Z = pow(Z, 1.0 / 3.0);
else
Z = 7.787 * Z + 16.0 / 116.0;
for (int i = 0; i < 3; ++i) {
if (f[i] > 0.008856) {
f[i] = std::pow(f[i], 1.0 / 3.0);
}
else {
f[i] = 7.787 * f[i] + 16.0 / 116.0;
}
}

Eigen::Vector3f colorLab;
colorLab[0] = static_cast<float>(116.0 * Y - 16.0);
colorLab[1] = static_cast<float>(500.0 * (X - Y));
colorLab[2] = static_cast<float>(200.0 * (Y - Z));
colorLab[0] = 116.0f * f[1] - 16.0f;
colorLab[1] = 500.0f * (f[0] - f[1]);
colorLab[2] = 200.0f * (f[1] - f[2]);

return colorLab;
}
Expand Down

0 comments on commit 203067d

Please sign in to comment.