14 using namespace Eigen;
20 colorMessage.r = colorVector(0);
21 colorMessage.g = colorVector(1);
22 colorMessage.b = colorVector(2);
23 if (resetTransparency) colorMessage.a = 1.0;
28 colorVector << colorMessage.r, colorMessage.g, colorMessage.b;
39 const double upperValueBound,
const bool invert,
const double colorChannelLowerValue,
40 const double colorChannelUpperValue)
42 float tempColorChannelLowerValue = colorChannelLowerValue;
43 float tempColorChannelUpperValue = colorChannelUpperValue;
47 tempColorChannelLowerValue = colorChannelUpperValue;
48 tempColorChannelUpperValue = colorChannelLowerValue;
51 colorChannel =
static_cast<float>(
computeLinearMapping(value, lowerValueBound, upperValueBound, tempColorChannelLowerValue, tempColorChannelUpperValue));
55 const std_msgs::ColorRGBA& colorForUpperValue,
const double value,
56 const double lowerValueBound,
const double upperValueBound)
58 setColorChannelFromValue(color.r, value, lowerValueBound, upperValueBound,
false, colorForLowerValue.r, colorForUpperValue.r);
59 setColorChannelFromValue(color.g, value, lowerValueBound, upperValueBound,
false, colorForLowerValue.g, colorForUpperValue.g);
60 setColorChannelFromValue(color.b, value, lowerValueBound, upperValueBound,
false, colorForLowerValue.b, colorForUpperValue.b);
64 const double upperValueBound,
const double maxSaturation,
const double minSaturation)
67 const Eigen::Array3f HspFactors(.299, .587, .114);
68 float saturationChange =
static_cast<float>(
computeLinearMapping(value, value, upperValueBound, maxSaturation, minSaturation));
71 float perceivedBrightness = sqrt((colorVector.array().square() * HspFactors).sum());
72 colorVector = perceivedBrightness + saturationChange * (colorVector.array() - perceivedBrightness);
73 colorVector = (colorVector.array().min(Array3f::Ones())).matrix();
77 void setColorFromValue(std_msgs::ColorRGBA& color,
const double value,
const double lowerValueBound,
const double upperValueBound)
82 hsl[0] =
static_cast<float>(
computeLinearMapping(value, lowerValueBound, upperValueBound, 0.0, 2.0 * M_PI));
86 float offset = 2.0 / 3.0 * M_PI;
87 Array3f rgbOffset(0, -offset, offset);
88 rgb = ((rgbOffset + hsl[0]).cos() + 0.5).min(Array3f::Ones()).max(Array3f::Zero()) * hsl[2];
89 float white = Vector3f(0.3, 0.59, 0.11).transpose() * rgb;
90 float saturation = 1.0 - hsl[1];
91 rgb = rgb + ((-rgb.array() + white) * saturation).matrix();
97 const double& sourceValue,
const double& sourceLowerValue,
const double& sourceUpperValue,
98 const double& mapLowerValue,
const double& mapUpperValue)
100 double m = (mapLowerValue - mapUpperValue) / (sourceLowerValue - sourceUpperValue);
101 double b = mapUpperValue - m * sourceUpperValue;
102 double mapValue = m * sourceValue + b;
103 if (mapLowerValue < mapUpperValue)
105 mapValue = std::max(mapValue, mapLowerValue);
106 mapValue = std::min(mapValue, mapUpperValue);
110 mapValue = std::min(mapValue, mapLowerValue);
111 mapValue = std::max(mapValue, mapUpperValue);
void interpolateBetweenColors(std_msgs::ColorRGBA &color, const std_msgs::ColorRGBA &colorForLowerValue, const std_msgs::ColorRGBA &colorForUpperValue, const double value, const double lowerValueBound, const double upperValueBound)
void setSaturationFromValue(std_msgs::ColorRGBA &color, const double value, const double lowerValueBound, const double upperValueBound, const double maxSaturation, const double minSaturation)
void setColorFromValue(std_msgs::ColorRGBA &color, const double value, const double lowerValueBound, const double upperValueBound)
void setColorChannelFromValue(float &colorChannel, const double value, const double lowerValueBound, const double upperValueBound, const bool invert=false, const double colorChannelLowerValue=0.0, const double colorChannelUpperValue=1.0)
void getColorVectorFromColorMessage(Eigen::Vector3f &colorVector, const std_msgs::ColorRGBA &colorMessage)
void setColorFromColorValue(std_msgs::ColorRGBA &color, const unsigned long &colorValue, bool resetTransparency=true)
bool colorValueToVector(const unsigned long &colorValue, Eigen::Vector3i &colorVector)
void getColorMessageFromColorVector(std_msgs::ColorRGBA &colorMessage, const Eigen::Vector3f &colorVector, bool resetTransparency=true)
double computeLinearMapping(const double &sourceValue, const double &sourceLowerValue, const double &sourceUpperValue, const double &mapLowerValue, const double &mapUpperValue)