ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
p_vehicle.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  PVehicle(ros::NodeHandle n,std::string prefix)
31  :ROSParam(n,prefix + "Vehicle/")
32  {
33  }
34  //ID of current vehicle
35  virtual std::string get_vehicle_id()const override
36  {
37  std::string value = "default vehicle";
38  static const std::string name = prefix_ + "VehicleID";
39  get(name,value);
40  return value;
41  }
42  //front axle to cog
43  virtual double get_a()const override
44  {
45  double value = 1.014;
46  static const std::string name = prefix_ + "a";
47  get(name,value);
48  return value;
49  }
50  //rear axle to cog
51  virtual double get_b()const override
52  {
53  double value = 1.676;
54  static const std::string name = prefix_ + "b";
55  get(name,value);
56  return value;
57  }
58  //front axle to front border
59  virtual double get_c()const override
60  {
61  double value = 0.97;
62  static const std::string name = prefix_ + "c";
63  get(name,value);
64  return value;
65  }
66  //rear border to rear axle
67  virtual double get_d()const override
68  {
69  double value = 1.12;
70  static const std::string name = prefix_ + "d";
71  get(name,value);
72  return value;
73  }
74  //mass
75  virtual double get_m()const override
76  {
77  double value = 1800;
78  static const std::string name = prefix_ + "m";
79  get(name,value);
80  return value;
81  }
82  //friction coefficient
83  virtual double get_mu()const override
84  {
85  double value = 0.8;
86  static const std::string name = prefix_ + "mu";
87  get(name,value);
88  return value;
89  }
90  //gravitational constant
91  virtual double get_g()const override
92  {
93  double value = 9.81;
94  static const std::string name = prefix_ + "g";
95  get(name,value);
96  return value;
97  }
98  //cog height above ground
99  virtual double get_h()const override
100  {
101  double value = 0.5;
102  static const std::string name = prefix_ + "h";
103  get(name,value);
104  return value;
105  }
106  //front normalized tire stiffness for bicycle model
107  virtual double get_cf()const override
108  {
109  double value = 10.8;
110  static const std::string name = prefix_ + "cf";
111  get(name,value);
112  return value;
113  }
114  //rear normalized tire stiffness for bicycle model
115  virtual double get_cr()const override
116  {
117  double value = 17.8;
118  static const std::string name = prefix_ + "cr";
119  get(name,value);
120  return value;
121  }
122  //rotational inertia around up axis devided by mass
123  virtual double get_Iz_m()const override
124  {
125  double value = 1.57;
126  static const std::string name = prefix_ + "Iz_m";
127  get(name,value);
128  return value;
129  }
130  //track width front
131  virtual double get_wf()const override
132  {
133  double value = 1.7;
134  static const std::string name = prefix_ + "wf";
135  get(name,value);
136  return value;
137  }
138  //track width rear
139  virtual double get_wr()const override
140  {
141  double value = 1.7;
142  static const std::string name = prefix_ + "wr";
143  get(name,value);
144  return value;
145  }
146  //maximum width of body, usually between corners of mirrors
147  virtual double get_bodyWidth()const override
148  {
149  double value = 1.82;
150  static const std::string name = prefix_ + "bodyWidth";
151  get(name,value);
152  return value;
153  }
154  //steering ratio
155  virtual double get_steeringRatio()const override
156  {
157  double value = 1.0;
158  static const std::string name = prefix_ + "steeringRatio";
159  get(name,value);
160  return value;
161  }
162  virtual double get_steeringAngleOffsetMeasured()const override
163  {
164  double value = -0.028;
165  static const std::string name = prefix_ + "steeringAngleOffsetMeasured";
166  get(name,value);
167  return value;
168  }
169  virtual double get_steeringAngleOffsetCommand()const override
170  {
171  double value = -0.028;
172  static const std::string name = prefix_ + "steeringAngleOffsetCommand";
173  get(name,value);
174  return value;
175  }
176  virtual double get_steeringAngleMax()const override
177  {
178  double value = 1.57;
179  static const std::string name = prefix_ + "steeringAngleMax";
180  get(name,value);
181  return value;
182  }
183  virtual double get_steeringAngleMin()const override
184  {
185  double value = -1.57;
186  static const std::string name = prefix_ + "steeringAngleMin";
187  get(name,value);
188  return value;
189  }
190  //unnormalized cornering stiffness
191  virtual double get_C()const override
192  {
193  double value = 63000.0;
194  static const std::string name = prefix_ + "C";
195  get(name,value);
196  return value;
197  }
198  //returns the percentage of brake force allocated to the front axle, e.g. 0.6 is a typical value
199  virtual double get_brakeBalanceFront()const override
200  {
201  double value = 0.6;
202  static const std::string name = prefix_ + "brakeBalanceFront";
203  get(name,value);
204  return value;
205  }
206  //returns the percentage of acceleration force allocated to the front axle, e.g. 1.0 for front drive
207  virtual double get_accelerationBalanceFront()const override
208  {
209  double value = 1.0;
210  static const std::string name = prefix_ + "accelerationBalanceFront";
211  get(name,value);
212  return value;
213  }
214  virtual double get_observationPointForPosition()const override
215  {
216  double value = 0.0;
217  static const std::string name = prefix_ + "observationPointForPosition";
218  get(name,value);
219  return value;
220  }
221  virtual double get_observationPointForVelocity()const override
222  {
223  double value = 1.676;
224  static const std::string name = prefix_ + "observationPointForVelocity";
225  get(name,value);
226  return value;
227  }
228  virtual double get_observationPointForAcceleration()const override
229  {
230  double value = 0.0;
231  static const std::string name = prefix_ + "observationPointForAcceleration";
232  get(name,value);
233  return value;
234  }
235  //returns the flag of currently used vehicle
236  virtual double get_vehicleFlag()const override
237  {
238  return 0.0;
239  }
240  };
241  }
242  }
243 }
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_vehicle.h:28
virtual double get_C() const override
unnormalized cornering stiffness
Definition: p_vehicle.h:191
virtual double get_bodyWidth() const override
Definition: p_vehicle.h:147
virtual double get_steeringAngleOffsetCommand() const override
Definition: p_vehicle.h:169
virtual double get_c() const override
front axle to front border
Definition: p_vehicle.h:59
virtual double get_cr() const override
rear normalized tire stiffness for bicycle model
Definition: p_vehicle.h:115
virtual double get_observationPointForVelocity() const override
Definition: p_vehicle.h:221
virtual double get_steeringAngleMin() const override
Definition: p_vehicle.h:183
virtual double get_Iz_m() const override
rotational inertia around up axis devided by mass
Definition: p_vehicle.h:123
PVehicle(ros::NodeHandle n, std::string prefix)
Definition: p_vehicle.h:30
virtual double get_observationPointForAcceleration() const override
Definition: p_vehicle.h:228
virtual double get_wr() const override
track width rear
Definition: p_vehicle.h:139
virtual double get_brakeBalanceFront() const override
returns the percentage of brake force allocated to the front axle, e.g. 0.6 is a typical value
Definition: p_vehicle.h:199
virtual double get_m() const override
mass
Definition: p_vehicle.h:75
virtual std::string get_vehicle_id() const override
ID of current vehicle.
Definition: p_vehicle.h:35
virtual double get_steeringRatio() const override
Definition: p_vehicle.h:155
virtual double get_accelerationBalanceFront() const override
returns the percentage of acceleration force allocated to the front axle, e.g. 1.0 for front drive
Definition: p_vehicle.h:207
virtual double get_g() const override
gravitational constant
Definition: p_vehicle.h:91
virtual double get_steeringAngleMax() const override
Definition: p_vehicle.h:176
virtual double get_b() const override
rear axle to cog
Definition: p_vehicle.h:51
virtual double get_vehicleFlag() const override
returns the flag of currently used vehicle
Definition: p_vehicle.h:236
virtual double get_d() const override
rear border to rear axle
Definition: p_vehicle.h:67
virtual double get_observationPointForPosition() const override
Definition: p_vehicle.h:214
virtual double get_cf() const override
front normalized tire stiffness for bicycle model
Definition: p_vehicle.h:107
virtual double get_steeringAngleOffsetMeasured() const override
Definition: p_vehicle.h:162
virtual double get_a() const override
cog to front axle
Definition: p_vehicle.h:43
virtual double get_wf() const override
track width front
Definition: p_vehicle.h:131
virtual double get_mu() const override
friction coefficient
Definition: p_vehicle.h:83
virtual double get_h() const override
cog height above ground
Definition: p_vehicle.h:99
abstract class for vehicle configuration related paremeters
Definition: ap_vehicle.h:29
Definition: areaofeffectconverter.h:20