37 std::string value =
"default vehicle";
38 static const std::string name =
prefix_ +
"VehicleID";
43 virtual double get_a()
const override
46 static const std::string name =
prefix_ +
"a";
51 virtual double get_b()
const override
54 static const std::string name =
prefix_ +
"b";
59 virtual double get_c()
const override
62 static const std::string name =
prefix_ +
"c";
67 virtual double get_d()
const override
70 static const std::string name =
prefix_ +
"d";
75 virtual double get_m()
const override
78 static const std::string name =
prefix_ +
"m";
83 virtual double get_mu()
const override
86 static const std::string name =
prefix_ +
"mu";
91 virtual double get_g()
const override
94 static const std::string name =
prefix_ +
"g";
99 virtual double get_h()
const override
102 static const std::string name =
prefix_ +
"h";
110 static const std::string name =
prefix_ +
"cf";
118 static const std::string name =
prefix_ +
"cr";
126 static const std::string name =
prefix_ +
"Iz_m";
134 static const std::string name =
prefix_ +
"wf";
142 static const std::string name =
prefix_ +
"wr";
150 static const std::string name =
prefix_ +
"bodyWidth";
158 static const std::string name =
prefix_ +
"steeringRatio";
164 double value = -0.028;
165 static const std::string name =
prefix_ +
"steeringAngleOffsetMeasured";
171 double value = -0.028;
172 static const std::string name =
prefix_ +
"steeringAngleOffsetCommand";
179 static const std::string name =
prefix_ +
"steeringAngleMax";
185 double value = -1.57;
186 static const std::string name =
prefix_ +
"steeringAngleMin";
191 virtual double get_C()
const override
193 double value = 63000.0;
194 static const std::string name =
prefix_ +
"C";
202 static const std::string name =
prefix_ +
"brakeBalanceFront";
210 static const std::string name =
prefix_ +
"accelerationBalanceFront";
217 static const std::string name =
prefix_ +
"observationPointForPosition";
223 double value = 1.676;
224 static const std::string name =
prefix_ +
"observationPointForVelocity";
231 static const std::string name =
prefix_ +
"observationPointForAcceleration";
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