ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
p_local_road_map.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  PLocalRoadMap(ros::NodeHandle n,std::string prefix)
31  :ROSParam(n,prefix + "local_road_map/")
32  {
33  }
34  virtual double getDiscardRadius()const override
35  {
36  double value = 200.0;
37  static const std::string name = prefix_ + "discard_radius";
38  get(name,value);
39  return value;
40  }
41  virtual bool isNavigationActive()const override
42  {
43  bool value = false;
44  static const std::string name = prefix_ + "navigation_active";
45  get(name,value);
46  return value;
47  }
48  virtual double getBorderTraceLength()const override
49  {
50  double value = 50.0;
51  static const std::string name = prefix_ + "border_trace_length";
52  get(name,value);
53  return value;
54  }
55  };
56  }
57  }
58 }
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_local_road_map.h:28
PLocalRoadMap(ros::NodeHandle n, std::string prefix)
Definition: p_local_road_map.h:30
virtual bool isNavigationActive() const override
Definition: p_local_road_map.h:41
virtual double getBorderTraceLength() const override
Definition: p_local_road_map.h:48
virtual double getDiscardRadius() const override
Definition: p_local_road_map.h:34
abstract class to configure the local view of the road map
Definition: ap_local_road_map.h:26
Definition: areaofeffectconverter.h:20