ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
ap_vehicle_dummy.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
17 namespace adore
18 {
19  namespace params
20  {
25  class APVehicleDummy:public adore::params::APVehicle //@TODO create encapsulation for parameter server
26  {
27  virtual std::string get_vehicle_id()const override
28  {
29  return "Dummy Vehicle";
30  }//ID of current vehicle
31  virtual double get_a() const override
32  {
33  return 1.014;
34  }//cog to front axle
35  virtual double get_b() const override
36  {
37  return 1.676;
38  }//rear axle to cog
39  virtual double get_c() const override
40  {
41  return 0.97;
42  }//front axle to front border
43  virtual double get_d() const override
44  {
45  return 1.12;
46  }//rear border to rear axle
47  virtual double get_m() const override
48  {
49  return 1800.0;
50  }//mass
51  virtual double get_mu() const override
52  {
53  return 0.8;
54  }//friction coefficient
55  virtual double get_g() const override
56  {
57  return 9.81;
58  }//gravitational constant
59  virtual double get_h() const override
60  {
61  return 0.5;
62  }//cog height above ground
63  virtual double get_cf() const override
64  {
65  return 10.8;
66  }//front normalized tire stiffness for bicycle model
67  virtual double get_cr() const override
68  {
69  return 17.8;
70  }//rear normalized tire stiffness for bicycle model
71  virtual double get_Iz_m() const override
72  {
73  return 1.57;
74  }//rotational inertia around up axis devided by mass
75  virtual double get_wf() const override
76  {
77  return 1.7;
78  }//track width front
79  virtual double get_wr() const override
80  {
81  return 1.7;
82  }//track width rear
83  virtual double get_bodyWidth() const override
84  {
85  return 1.82;
86  }
87  virtual double get_steeringRatio() const override
88  {
89  return 1.0;
90  }
91  virtual double get_steeringAngleOffsetMeasured() const override
92  {
93  return 0.0;
94  }
95  virtual double get_steeringAngleOffsetCommand() const override
96  {
97  return 0.0;
98  }
99  virtual double get_steeringAngleMax() const override
100  {
101  return 0.7;
102  }
103  virtual double get_steeringAngleMin() const override
104  {
105  return -0.7;
106  }
107  virtual double get_C() const override
108  {
109  return 63000.0;
110  }//unnormalized cornering stiffness
111  virtual double get_brakeBalanceFront() const override
112  {
113  return 0.6;
114  }//returns the percentage of brake force allocated to the front axle, e.g. 0.6 is a typical value
115  virtual double get_accelerationBalanceFront() const override
116  {
117  return 0.4;
118  }//returns the percentage of acceleration force allocated to the front axle, e.g. 1.0 for front drive
119  virtual double get_observationPointForPosition() const override
120  {
121  return 0.0;
122  }
123  virtual double get_observationPointForVelocity() const override
124  {
125  return 0.0;
126  }
127  virtual double get_observationPointForAcceleration() const override
128  {
129  return 0.0;
130  }
131  virtual double get_vehicleFlag() const override
132  {
133  return 0.0;
134  }//returns the flag of currently used vehicle
135  };
136  }
137 }
dummy implementation of an abstract vehicle parameter object for testing purposes
Definition: ap_vehicle_dummy.h:26
virtual std::string get_vehicle_id() const override
ID of current vehicle.
Definition: ap_vehicle_dummy.h:27
virtual double get_d() const override
rear border to rear axle
Definition: ap_vehicle_dummy.h:43
virtual double get_steeringAngleMax() const override
Definition: ap_vehicle_dummy.h:99
virtual double get_wf() const override
track width front
Definition: ap_vehicle_dummy.h:75
virtual double get_a() const override
cog to front axle
Definition: ap_vehicle_dummy.h:31
virtual double get_wr() const override
track width rear
Definition: ap_vehicle_dummy.h:79
virtual double get_observationPointForAcceleration() const override
Definition: ap_vehicle_dummy.h:127
virtual double get_m() const override
mass
Definition: ap_vehicle_dummy.h:47
virtual double get_steeringAngleMin() const override
Definition: ap_vehicle_dummy.h:103
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: ap_vehicle_dummy.h:111
virtual double get_steeringAngleOffsetCommand() const override
Definition: ap_vehicle_dummy.h:95
virtual double get_observationPointForPosition() const override
Definition: ap_vehicle_dummy.h:119
virtual double get_steeringRatio() const override
Definition: ap_vehicle_dummy.h:87
virtual double get_bodyWidth() const override
Definition: ap_vehicle_dummy.h:83
virtual double get_cf() const override
front normalized tire stiffness for bicycle model
Definition: ap_vehicle_dummy.h:63
virtual double get_vehicleFlag() const override
returns the flag of currently used vehicle
Definition: ap_vehicle_dummy.h:131
virtual double get_g() const override
gravitational constant
Definition: ap_vehicle_dummy.h:55
virtual double get_cr() const override
rear normalized tire stiffness for bicycle model
Definition: ap_vehicle_dummy.h:67
virtual double get_steeringAngleOffsetMeasured() const override
Definition: ap_vehicle_dummy.h:91
virtual double get_mu() const override
friction coefficient
Definition: ap_vehicle_dummy.h:51
virtual double get_b() const override
rear axle to cog
Definition: ap_vehicle_dummy.h:35
virtual double get_observationPointForVelocity() const override
Definition: ap_vehicle_dummy.h:123
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: ap_vehicle_dummy.h:115
virtual double get_C() const override
unnormalized cornering stiffness
Definition: ap_vehicle_dummy.h:107
virtual double get_h() const override
cog height above ground
Definition: ap_vehicle_dummy.h:59
virtual double get_c() const override
front axle to front border
Definition: ap_vehicle_dummy.h:39
virtual double get_Iz_m() const override
rotational inertia around up axis devided by mass
Definition: ap_vehicle_dummy.h:71
abstract class for vehicle configuration related paremeters
Definition: ap_vehicle.h:29
Definition: areaofeffectconverter.h:20