.. _program_listing_file__tmp_ws_src_grid_map_grid_map_visualization_include_grid_map_visualization_visualizations_OccupancyGridVisualization.hpp: Program Listing for File OccupancyGridVisualization.hpp ======================================================= |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/grid_map/grid_map_visualization/include/grid_map_visualization/visualizations/OccupancyGridVisualization.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp /* * PointCloudOccupancyGrid.hpp * * Created on: Nov 3, 2014 * Author: Péter Fankhauser * Institute: ETH Zurich, ANYbotics */ #ifndef GRID_MAP_VISUALIZATION__VISUALIZATIONS__OCCUPANCYGRIDVISUALIZATION_HPP_ #define GRID_MAP_VISUALIZATION__VISUALIZATIONS__OCCUPANCYGRIDVISUALIZATION_HPP_ #include #include #include #include "grid_map_visualization/visualizations/VisualizationBase.hpp" namespace grid_map_visualization { class OccupancyGridVisualization : public VisualizationBase { public: explicit OccupancyGridVisualization(const std::string & name, rclcpp::Node::SharedPtr nodePtr); virtual ~OccupancyGridVisualization(); bool readParameters() override; bool initialize() override; bool visualize(const grid_map::GridMap & map) override; private: std::string layer_; // (used to normalize the cell data in [min, max]). float dataMin_, dataMax_; rclcpp::Publisher::SharedPtr publisher_; }; } // namespace grid_map_visualization #endif // GRID_MAP_VISUALIZATION__VISUALIZATIONS__OCCUPANCYGRIDVISUALIZATION_HPP_