VisualizationBase.cpp
Go to the documentation of this file.
1 /*
2  * VisualizationBase.cpp
3  *
4  * Created on: Mar 20, 2015
5  * Author: Péter Fankhauser
6  * Institute: ETH Zurich, ANYbotics
7  */
8 
10 
11 namespace grid_map_visualization {
12 
13 VisualizationBase::VisualizationBase(ros::NodeHandle& nodeHandle, const std::string& name)
14  : nodeHandle_(nodeHandle),
15  name_(name)
16 {
17 }
18 
20 {
21 }
22 
24 {
25  if (publisher_.getNumSubscribers() > 0) return true;
26  return false;
27 }
28 
30 {
31  if (config.getType() != XmlRpc::XmlRpcValue::TypeStruct) {
32  ROS_ERROR("A filter configuration must be a map with fields name, type, and params.");
33  return false;
34  }
35 
36  // Check to see if we have parameters in our list.
37  if (config.hasMember("params")) {
38  XmlRpc::XmlRpcValue params = config["params"];
39  if (params.getType() != XmlRpc::XmlRpcValue::TypeStruct) {
40  ROS_ERROR("Params must be a map.");
41  return false;
42  } else {
43  for (XmlRpc::XmlRpcValue::iterator it = params.begin(); it != params.end(); ++it) {
44  ROS_DEBUG("Loading param %s\n", it->first.c_str());
45  parameters_[it->first] = it->second;
46  }
47  }
48  }
49 
50  return true;
51 }
52 
53 bool VisualizationBase::getParam(const std::string& name, std::string& value)
54 {
55  StringMap::iterator it = parameters_.find(name);
56  if (it == parameters_.end()) return false;
57  if (it->second.getType() != XmlRpc::XmlRpcValue::TypeString) return false;
58  value = std::string(it->second);
59  return true;
60 }
61 
62 bool VisualizationBase::getParam(const std::string& name, double& value)
63 {
64  StringMap::iterator it = parameters_.find(name);
65  if (it == parameters_.end()) return false;
66  if (it->second.getType() != XmlRpc::XmlRpcValue::TypeDouble
67  && it->second.getType() != XmlRpc::XmlRpcValue::TypeInt) return false;
68  value = it->second.getType() == XmlRpc::XmlRpcValue::TypeInt ?
69  (int) (it->second) : (double) (it->second);
70  return true;
71 }
72 
73 bool VisualizationBase::getParam(const std::string& name, float& value)
74 {
75  double valueDouble;
76  bool isSuccess = getParam(name, valueDouble);
77  if (isSuccess) value = static_cast<float>(valueDouble);
78  return isSuccess;
79 }
80 
81 bool VisualizationBase::getParam(const std::string& name, bool& value)
82 {
83  StringMap::iterator it = parameters_.find(name);
84  if (it == parameters_.end()) return false;
85  if (it->second.getType() != XmlRpc::XmlRpcValue::TypeBoolean) return false;
86  value = it->second;
87  return true;
88 }
89 
90 bool VisualizationBase::getParam(const std::string&name, int& value)
91 {
92  StringMap::iterator it = parameters_.find(name);
93  if (it == parameters_.end()) return false;
94  if(it->second.getType() != XmlRpc::XmlRpcValue::TypeInt) return false;
95  value = it->second;
96  return true;
97 }
98 
99 } /* namespace */
ValueStruct::iterator iterator
Type const & getType() const
bool getParam(const std::string &name, std::string &value)
bool hasMember(const std::string &name) const
StringMap parameters_
Storage of the parsed XML parameters.
uint32_t getNumSubscribers() const
ros::Publisher publisher_
ROS publisher of the occupancy grid.
virtual bool readParameters(XmlRpc::XmlRpcValue &config)
#define ROS_ERROR(...)
VisualizationBase(ros::NodeHandle &nodeHandle, const std::string &name)
#define ROS_DEBUG(...)


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