$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage, Inc. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 */ 00034 00039 #include <pcl_visualization/common/float_image_utils.h> 00040 #include <cmath> 00041 #include <pcl/win32_macros.h> 00042 00043 using std::cout; 00044 using std::cerr; 00045 using std::min; 00046 using std::max; 00047 00048 00049 void 00050 pcl_visualization::FloatImageUtils::getColorForFloat (float value, unsigned char& r, unsigned char& g, unsigned char& b) 00051 { 00052 if (pcl_isinf (value)) 00053 { 00054 if (value > 0.0f) 00055 { 00056 r = 150; g = 150; b = 200; // INFINITY 00057 return; 00058 } 00059 r = 150; g = 200; b = 150; // -INFINITY 00060 return; 00061 } 00062 if (!pcl_isfinite (value)) 00063 { 00064 r = 200; g = 150; b = 150; // -INFINITY 00065 return; 00066 } 00067 00068 r = g = b = 0; 00069 value *= 10; 00070 if (value <= 1.0) 00071 { // black -> purple 00072 b = lrint(value*200); 00073 r = lrint(value*120); 00074 } 00075 else if (value <= 2.0) 00076 { // purple -> blue 00077 b = 200 + lrint((value-1.0)*55); 00078 r = 120 - lrint((value-1.0)*120); 00079 } 00080 else if (value <= 3.0) 00081 { // blue -> turquoise 00082 b = 255 - lrint((value-2.0)*55); 00083 g = lrint((value-2.0)*200); 00084 } 00085 else if (value <= 4.0) 00086 { // turquoise -> green 00087 b = 200 - lrint((value-3.0)*200); 00088 g = 200 + lrint((value-3.0)*55); 00089 } 00090 else if (value <= 5.0) 00091 { // green -> greyish green 00092 g = 255 - lrint((value-4.0)*100); 00093 r = lrint((value-4.0)*120); 00094 } 00095 else if (value <= 6.0) 00096 { // greyish green -> red 00097 r = 100 + lrint((value-5.0)*155); 00098 g = 120 - lrint((value-5.0)*120); 00099 b = 120 - lrint((value-5.0)*120); 00100 } 00101 else if (value <= 7.0) 00102 { // red -> yellow 00103 r = 255; 00104 g = lrint((value-6.0)*255); 00105 } 00106 else 00107 { // yellow -> white 00108 r = 255; 00109 g = 255; 00110 b = lrint((value-7.0)*255.0/3.0); 00111 } 00112 } 00113 00114 void 00115 pcl_visualization::FloatImageUtils::getColorForAngle (float value, unsigned char& r, unsigned char& g, unsigned char& b) 00116 { 00117 if (pcl_isinf (value)) 00118 { 00119 if (value > 0.0f) 00120 { 00121 r = 150; g = 150; b = 200; // INFINITY 00122 return; 00123 } 00124 r = 150; g = 200; b = 150; // -INFINITY 00125 return; 00126 } 00127 if (!pcl_isfinite (value)) 00128 { 00129 r = 200; g = 150; b = 150; // -INFINITY 00130 return; 00131 } 00132 00133 r = g = b = 0; 00134 if (value < -M_PI/2.0f) 00135 { // black -> blue 00136 b = lrint(lrint(255*(value+float(M_PI))/(float(M_PI)/2.0f))); 00137 } 00138 else if (value <= 0.0f) 00139 { // blue -> white 00140 b = 255; 00141 r = g = lrint(lrint(255*(value+float(M_PI/2))/(float(M_PI)/2.0f))); 00142 } 00143 else if (value <= M_PI/2.0f) 00144 { // white -> green 00145 g = 255; 00146 r = b = lrint(255-lrint(255*(value)/(float(M_PI)/2.0f))); 00147 } 00148 else 00149 { // green -> black 00150 g = lrint(255-lrint(255*(value-M_PI/2.0f)/(float(M_PI)/2.0f))); 00151 } 00152 //cout << 180.0f*value/M_PI<<"deg => "<<(int)r<<", "<<(int)g<<", "<<(int)b<<"\n"; 00153 } 00154 00155 void 00156 pcl_visualization::FloatImageUtils::getColorForHalfAngle (float value, unsigned char& r, unsigned char& g, unsigned char& b) 00157 { 00158 getColorForAngle(2.0f*value, r, g, b); 00159 } 00160 00161 00162 00163 unsigned char* 00164 pcl_visualization::FloatImageUtils::getVisualImage (const float* floatImage, int width, int height, float minValue, float maxValue, bool grayScale) 00165 { 00166 //MEASURE_FUNCTION_TIME; 00167 00168 //cout << "Image is of size "<<width<<"x"<<height<<"\n"; 00169 int size = width*height; 00170 int arraySize = 3 * size; 00171 unsigned char* data = new unsigned char[arraySize]; 00172 unsigned char* dataPtr = data; 00173 00174 bool recalculateMinValue = pcl_isinf (minValue), 00175 recalculateMaxValue = pcl_isinf (maxValue); 00176 if (recalculateMinValue) minValue = std::numeric_limits<float>::infinity (); 00177 if (recalculateMaxValue) maxValue = -std::numeric_limits<float>::infinity (); 00178 00179 if (recalculateMinValue || recalculateMaxValue) 00180 { 00181 for (int i=0; i<size; ++i) 00182 { 00183 float value = floatImage[i]; 00184 if (!pcl_isfinite(value)) continue; 00185 if (recalculateMinValue) minValue=min(minValue, value); 00186 if (recalculateMaxValue) maxValue=max(maxValue, value); 00187 } 00188 } 00189 //cout << "minValue is "<<minValue<<" and maxValue is "<<maxValue<<".\n"; 00190 float factor = 1.0 / (maxValue-minValue), offset = -minValue; 00191 00192 for (int i=0; i<size; ++i) 00193 { 00194 unsigned char& r=*(dataPtr++), & g=*(dataPtr++), & b=*(dataPtr++); 00195 float value = floatImage[i]; 00196 00197 if (!pcl_isfinite(value)) 00198 { 00199 getColorForFloat(value, r, g, b); 00200 continue; 00201 } 00202 00203 // Normalize value to [0, 1] 00204 value = max(0.0f, min(1.0f, factor*(value + offset))); 00205 00206 // Get a color from the value in [0, 1] 00207 if (grayScale) 00208 { 00209 r = g = b = lrint(value*255); 00210 } 00211 else 00212 { 00213 getColorForFloat(value, r, g, b); 00214 } 00215 //cout << "Setting pixel "<<i<<" to "<<(int)r<<", "<<(int)g<<", "<<(int)b<<".\n"; 00216 } 00217 00218 return data; 00219 } 00220 00221 unsigned char* 00222 pcl_visualization::FloatImageUtils::getVisualAngleImage (const float* angle_image, int width, int height) 00223 { 00224 int size = width*height; 00225 int arraySize = 3 * size; 00226 unsigned char* data = new unsigned char[arraySize]; 00227 unsigned char* dataPtr = data; 00228 00229 for (int i=0; i<size; ++i) 00230 { 00231 unsigned char& r=*(dataPtr++), & g=*(dataPtr++), & b=*(dataPtr++); 00232 float angle = angle_image[i]; 00233 00234 getColorForAngle(angle, r, g, b); 00235 } 00236 00237 return data; 00238 } 00239 00240 unsigned char* 00241 pcl_visualization::FloatImageUtils::getVisualHalfAngleImage (const float* angle_image, int width, int height) 00242 { 00243 int size = width*height; 00244 int arraySize = 3 * size; 00245 unsigned char* data = new unsigned char[arraySize]; 00246 unsigned char* dataPtr = data; 00247 00248 for (int i=0; i<size; ++i) 00249 { 00250 unsigned char& r=*(dataPtr++), & g=*(dataPtr++), & b=*(dataPtr++); 00251 float angle = angle_image[i]; 00252 00253 getColorForHalfAngle(angle, r, g, b); 00254 } 00255 00256 return data; 00257 } 00258