GridMapVisualizationHelpers.cpp
Go to the documentation of this file.
00001 /*
00002  * GridMapVisualizationHelpers.cpp
00003  *
00004  *  Created on: Jun 24, 2014
00005  *      Author: Péter Fankhauser
00006  *       Institute: ETH Zurich, Autonomous Systems Lab
00007  */
00008 
00009 #include "grid_map_visualization/GridMapVisualizationHelpers.hpp"
00010 
00011 #include <grid_map_ros/GridMapMsgHelpers.hpp>
00012 #include <grid_map_core/GridMapMath.hpp>
00013 
00014 using namespace Eigen;
00015 
00016 namespace grid_map_visualization {
00017 
00018 void getColorMessageFromColorVector(std_msgs::ColorRGBA& colorMessage, const Eigen::Vector3f& colorVector, bool resetTransparency)
00019 {
00020   colorMessage.r = colorVector(0);
00021   colorMessage.g = colorVector(1);
00022   colorMessage.b = colorVector(2);
00023   if (resetTransparency) colorMessage.a = 1.0;
00024 }
00025 
00026 void getColorVectorFromColorMessage(Eigen::Vector3f& colorVector, const std_msgs::ColorRGBA& colorMessage)
00027 {
00028   colorVector << colorMessage.r, colorMessage.g, colorMessage.b;
00029 }
00030 
00031 void setColorFromColorValue(std_msgs::ColorRGBA& color, const unsigned long& colorValue, bool resetTransparency)
00032 {
00033   Vector3f colorVector;
00034   grid_map::colorValueToVector(colorValue, colorVector);
00035   getColorMessageFromColorVector(color, colorVector, resetTransparency);
00036 }
00037 
00038 void setColorChannelFromValue(float& colorChannel, const double value, const double lowerValueBound,
00039                               const double upperValueBound, const bool invert, const double colorChannelLowerValue,
00040                               const double colorChannelUpperValue)
00041 {
00042   float tempColorChannelLowerValue = colorChannelLowerValue;
00043   float tempColorChannelUpperValue = colorChannelUpperValue;
00044 
00045   if (invert)
00046   {
00047     tempColorChannelLowerValue = colorChannelUpperValue;
00048     tempColorChannelUpperValue = colorChannelLowerValue;
00049   }
00050 
00051   colorChannel = static_cast<float>(computeLinearMapping(value, lowerValueBound, upperValueBound, tempColorChannelLowerValue, tempColorChannelUpperValue));
00052 }
00053 
00054 void interpolateBetweenColors(std_msgs::ColorRGBA& color, const std_msgs::ColorRGBA& colorForLowerValue,
00055                               const std_msgs::ColorRGBA& colorForUpperValue, const double value,
00056                               const double lowerValueBound, const double upperValueBound)
00057 {
00058   setColorChannelFromValue(color.r, value, lowerValueBound, upperValueBound, false, colorForLowerValue.r, colorForUpperValue.r);
00059   setColorChannelFromValue(color.g, value, lowerValueBound, upperValueBound, false, colorForLowerValue.g, colorForUpperValue.g);
00060   setColorChannelFromValue(color.b, value, lowerValueBound, upperValueBound, false, colorForLowerValue.b, colorForUpperValue.b);
00061 }
00062 
00063 void setSaturationFromValue(std_msgs::ColorRGBA& color, const double value, const double lowerValueBound,
00064                             const double upperValueBound, const double maxSaturation, const double minSaturation)
00065 {
00066   // Based on "changeSaturation" function by Darel Rex Finley.
00067   const Eigen::Array3f HspFactors(.299, .587, .114); // see http://alienryderflex.com/hsp.html
00068   float saturationChange = static_cast<float>(computeLinearMapping(value, value, upperValueBound, maxSaturation, minSaturation));
00069   Vector3f colorVector;
00070   getColorVectorFromColorMessage(colorVector, color);
00071   float perceivedBrightness = sqrt((colorVector.array().square() * HspFactors).sum());
00072   colorVector = perceivedBrightness + saturationChange * (colorVector.array() - perceivedBrightness);
00073   colorVector = (colorVector.array().min(Array3f::Ones())).matrix();
00074   getColorMessageFromColorVector(color, colorVector, false);
00075 }
00076 
00077 void setColorFromValue(std_msgs::ColorRGBA& color, const double value, const double lowerValueBound, const double upperValueBound)
00078 {
00079   Vector3f hsl; // Hue: [0, 2 Pi], Saturation and Lightness: [0, 1]
00080   Vector3f rgb;
00081 
00082   hsl[0] = static_cast<float>(computeLinearMapping(value, lowerValueBound, upperValueBound, 0.0, 2.0 * M_PI));
00083   hsl[1] = 1.0;
00084   hsl[2] = 1.0;
00085 
00086   float offset = 2.0 / 3.0 * M_PI;
00087   Array3f rgbOffset(0, -offset, offset);
00088   rgb = ((rgbOffset + hsl[0]).cos() + 0.5).min(Array3f::Ones()).max(Array3f::Zero()) * hsl[2];
00089   float white = Vector3f(0.3, 0.59, 0.11).transpose() * rgb;
00090   float saturation = 1.0 - hsl[1];
00091   rgb = rgb + ((-rgb.array() + white) * saturation).matrix();
00092 
00093   getColorMessageFromColorVector(color, rgb, false);
00094 }
00095 
00096 double computeLinearMapping(
00097     const double& sourceValue, const double& sourceLowerValue, const double& sourceUpperValue,
00098     const double& mapLowerValue, const double& mapUpperValue)
00099 {
00100   double m = (mapLowerValue - mapUpperValue) / (sourceLowerValue - sourceUpperValue);
00101   double b = mapUpperValue - m * sourceUpperValue;
00102   double mapValue = m * sourceValue + b;
00103   if (mapLowerValue < mapUpperValue)
00104   {
00105     mapValue = std::max(mapValue, mapLowerValue);
00106     mapValue = std::min(mapValue, mapUpperValue);
00107   }
00108   else
00109   {
00110     mapValue = std::min(mapValue, mapLowerValue);
00111     mapValue = std::max(mapValue, mapUpperValue);
00112   }
00113   return mapValue;
00114 }
00115 
00116 } /* namespace */


grid_map_visualization
Author(s): Péter Fankhauser
autogenerated on Mon Oct 9 2017 03:09:35