VisualizationBase.hpp
Go to the documentation of this file.
1 /*
2  * VisualizationBase.hpp
3  *
4  * Created on: Mar 20, 2015
5  * Author: Péter Fankhauser
6  * Institute: ETH Zurich, ANYbotics
7  */
8 
9 #pragma once
10 
12 
13 // ROS
14 #include <ros/ros.h>
15 
16 namespace grid_map_visualization {
17 
18 typedef std::map<std::string, XmlRpc::XmlRpcValue> StringMap;
19 
21 {
22  public:
23 
29  VisualizationBase(ros::NodeHandle& nodeHandle, const std::string& name);
30 
34  virtual ~VisualizationBase();
35 
41  virtual bool readParameters(XmlRpc::XmlRpcValue& config);
42 
46  virtual bool initialize() = 0;
47 
53  virtual bool visualize(const grid_map::GridMap& map) = 0;
54 
59  bool isActive() const;
60 
61  protected:
62 
69  bool getParam(const std::string& name, std::string& value);
70 
77  bool getParam(const std::string& name, double& value);
78 
85  bool getParam(const std::string& name, float& value);
86 
93  bool getParam(const std::string&name, int& value);
94 
101  bool getParam(const std::string& name, bool& value);
102 
105 
107  std::string name_;
108 
110  StringMap parameters_;
111 
114 };
115 
116 } /* namespace */
std::map< std::string, XmlRpc::XmlRpcValue > StringMap
bool getParam(const std::string &name, std::string &value)
StringMap parameters_
Storage of the parsed XML parameters.
ros::NodeHandle & nodeHandle_
ROS nodehandle.
std::string name_
Name of the visualization.
ros::Publisher publisher_
ROS publisher of the occupancy grid.
virtual bool readParameters(XmlRpc::XmlRpcValue &config)
virtual bool visualize(const grid_map::GridMap &map)=0
VisualizationBase(ros::NodeHandle &nodeHandle, const std::string &name)


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