Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009 #pragma once
00010
00011
00012 #include <ros/ros.h>
00013 #include <visualization_msgs/MarkerArray.h>
00014 #include <std_msgs/ColorRGBA.h>
00015
00016
00017 #include <Eigen/Core>
00018
00019 namespace grid_map_visualization {
00020
00027 void getColorMessageFromColorVector(std_msgs::ColorRGBA& colorMessage, const Eigen::Vector3f& colorVector, bool resetTransparency = true);
00028
00034 void getColorVectorFromColorMessage(Eigen::Vector3f& colorVector, const std_msgs::ColorRGBA& colorMessage);
00035
00042 void setColorFromColorValue(std_msgs::ColorRGBA& color, const unsigned long& colorValue, bool resetTransparency = true);
00043
00054 void setColorChannelFromValue(float& colorChannel, const double value, const double lowerValueBound,
00055 const double upperValueBound, const bool invert = false, const double colorChannelLowerValue = 0.0,
00056 const double colorChannelUpperValue = 1.0);
00057
00067 void interpolateBetweenColors(std_msgs::ColorRGBA& color, const std_msgs::ColorRGBA& colorForLowerValue,
00068 const std_msgs::ColorRGBA& colorForUpperValue, const double value,
00069 const double lowerValueBound, const double upperValueBound);
00070
00080 void setSaturationFromValue(std_msgs::ColorRGBA& color, const double value, const double lowerValueBound,
00081 const double upperValueBound, const double maxSaturation, const double minSaturation);
00082
00090 void setColorFromValue(std_msgs::ColorRGBA& color, const double value, const double lowerValueBound,
00091 const double upperValueBound);
00092
00102 double computeLinearMapping(
00103 const double& sourceValue, const double& sourceLowerValue, const double& sourceUpperValue,
00104 const double& mapLowerValue, const double& mapUpperValue);
00105
00106 }