ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
p_map_provider.h
Go to the documentation of this file.
1 /********************************************************************************
2  * Copyright (C) 2017-2020 German Aerospace Center (DLR).
3  * Eclipse ADORe, Automated Driving Open Research https://eclipse.org/adore
4  *
5  * This program and the accompanying materials are made available under the
6  * terms of the Eclipse Public License 2.0 which is available at
7  * http://www.eclipse.org/legal/epl-2.0.
8  *
9  * SPDX-License-Identifier: EPL-2.0
10  *
11  * Contributors:
12  * Jan Lauermann - initial API and implementation
13  ********************************************************************************/
14 
15 #pragma once
16 
17 #include <ros/ros.h>
20 
21 namespace adore
22 {
23  namespace if_ROS
24  {
25  namespace params
26  {
28  {
29  public:
30  PMapProvider(ros::NodeHandle n,std::string prefix)
31  :ROSParam(n,prefix + "map_provider/")
32  {
33  }
34  //visibility radius of the map provider
35  virtual double getVisibiltyRadius()const override
36  {
37  double value = 200;
38  static const std::string name = prefix_ + "r";
39  get(name,value);
40  return value;
41  }
42  virtual bool getActivatePlotting()const override
43  {
44  bool value = false;
45  static const std::string name = prefix_ + "activate_plotting";
46  get(name,value);
47  return value;
48  }
49  virtual bool getPlotCompleteMapInLocalView()const override
50  {
51  bool value = false;
52  static const std::string name = prefix_ + "plot_complete_map_in_local_view";
53  get(name,value);
54  return value;
55  }
56  virtual bool useScenarioManagerMap()const override
57  {
58  bool value = false;
59  static const std::string name = prefix_ + "use_scenario_manager_map";
60  get(name,value);
61  return value;
62  }
63  virtual int getXODRLoaderPointsPerBorder()const override
64  {
65  int value = 128;
66  static const std::string name = prefix_ + "XODRLoaderPointsPerBorder";
67  get(name,value);
68  return value;
69  }
70  };
71  }
72  }
73 }
Definition: ros_com_patterns.h:179
std::string prefix_
Definition: ros_com_patterns.h:181
void get(const std::string &name, T &result) const
Definition: ros_com_patterns.h:186
Definition: p_map_provider.h:28
virtual bool getActivatePlotting() const override
Definition: p_map_provider.h:42
virtual double getVisibiltyRadius() const override
Definition: p_map_provider.h:35
virtual bool useScenarioManagerMap() const override
Definition: p_map_provider.h:56
virtual bool getPlotCompleteMapInLocalView() const override
Definition: p_map_provider.h:49
virtual int getXODRLoaderPointsPerBorder() const override
Definition: p_map_provider.h:63
PMapProvider(ros::NodeHandle n, std::string prefix)
Definition: p_map_provider.h:30
abstract class containing parameters to configure aspects of the map provider
Definition: ap_map_provider.h:25
Definition: areaofeffectconverter.h:20