GridMapVisualizationHelpers.hpp
Go to the documentation of this file.
1 /*
2  * GridMapVisualizationHelpers.hpp
3  *
4  * Created on: Jun 24, 2014
5  * Author: Péter Fankhauser
6  * Institute: ETH Zurich, ANYbotics
7  */
8 
9 #pragma once
10 
11 // ROS
12 #include <ros/ros.h>
13 #include <visualization_msgs/MarkerArray.h>
14 #include <std_msgs/ColorRGBA.h>
15 
16 // Eigen
17 #include <Eigen/Core>
18 
19 namespace grid_map_visualization {
20 
27 void getColorMessageFromColorVector(std_msgs::ColorRGBA& colorMessage, const Eigen::Vector3f& colorVector, bool resetTransparency = true);
28 
34 void getColorVectorFromColorMessage(Eigen::Vector3f& colorVector, const std_msgs::ColorRGBA& colorMessage);
35 
42 void setColorFromColorValue(std_msgs::ColorRGBA& color, const unsigned long& colorValue, bool resetTransparency = true);
43 
54 void setColorChannelFromValue(float& colorChannel, const double value, const double lowerValueBound,
55  const double upperValueBound, const bool invert = false, const double colorChannelLowerValue = 0.0,
56  const double colorChannelUpperValue = 1.0);
57 
67 void interpolateBetweenColors(std_msgs::ColorRGBA& color, const std_msgs::ColorRGBA& colorForLowerValue,
68  const std_msgs::ColorRGBA& colorForUpperValue, const double value,
69  const double lowerValueBound, const double upperValueBound);
70 
80 void setSaturationFromValue(std_msgs::ColorRGBA& color, const double value, const double lowerValueBound,
81  const double upperValueBound, const double maxSaturation, const double minSaturation);
82 
90 void setColorFromValue(std_msgs::ColorRGBA& color, const double value, const double lowerValueBound,
91  const double upperValueBound);
92 
102 double computeLinearMapping(
103  const double& sourceValue, const double& sourceLowerValue, const double& sourceUpperValue,
104  const double& mapLowerValue, const double& mapUpperValue);
105 
106 } /* namespace */
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)
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)


grid_map_visualization
Author(s): Péter Fankhauser
autogenerated on Tue Jun 25 2019 20:02:32