.. _program_listing_file__tmp_ws_src_grid_map_grid_map_visualization_include_grid_map_visualization_GridMapVisualizationHelpers.hpp: Program Listing for File GridMapVisualizationHelpers.hpp ======================================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/grid_map/grid_map_visualization/include/grid_map_visualization/GridMapVisualizationHelpers.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp /* * GridMapVisualizationHelpers.hpp * * Created on: Jun 24, 2014 * Author: Péter Fankhauser * Institute: ETH Zurich, ANYbotics */ #ifndef GRID_MAP_VISUALIZATION__GRIDMAPVISUALIZATIONHELPERS_HPP_ #define GRID_MAP_VISUALIZATION__GRIDMAPVISUALIZATIONHELPERS_HPP_ // ROS #include #include #include // Eigen #include namespace grid_map_visualization { void getColorMessageFromColorVector( std_msgs::msg::ColorRGBA & colorMessage, const Eigen::Vector3f & colorVector, bool resetTransparency = true); void getColorVectorFromColorMessage( Eigen::Vector3f & colorVector, const std_msgs::msg::ColorRGBA & colorMessage); void setColorFromColorValue( std_msgs::msg::ColorRGBA & color, const uint64_t & colorValue, bool resetTransparency = true); 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 interpolateBetweenColors( std_msgs::msg::ColorRGBA & color, const std_msgs::msg::ColorRGBA & colorForLowerValue, const std_msgs::msg::ColorRGBA & colorForUpperValue, const double value, const double lowerValueBound, const double upperValueBound); void setSaturationFromValue( std_msgs::msg::ColorRGBA & color, const double value, const double lowerValueBound, const double upperValueBound, const double maxSaturation, const double minSaturation); void setColorFromValue( std_msgs::msg::ColorRGBA & color, const double value, const double lowerValueBound, const double upperValueBound); double computeLinearMapping( const double & sourceValue, const double & sourceLowerValue, const double & sourceUpperValue, const double & mapLowerValue, const double & mapUpperValue); } // namespace grid_map_visualization #endif // GRID_MAP_VISUALIZATION__GRIDMAPVISUALIZATIONHELPERS_HPP_