ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
vehiclestate10d.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  * Daniel Heß - initial API and implementation
13  ********************************************************************************/
14 
15 
16 #pragma once
17 
18 #include <adore/mad/adoremath.h>
19 
20 namespace adore
21 {
22  namespace env
23  {
40  {
41  public:
42  adoreMatrix<double, 10, 1> data;
48  double getX()const { return data(0, 0); }
54  double getY()const { return data(1, 0); }
60  double getPSI()const { return data(2, 0); }
66  double getvx()const { return data(3, 0); }
72  double getvy()const { return data(4, 0); }
78  double getOmega()const { return data(5, 0); }
84  double getAx()const { return data(6, 0); }
90  double getDelta()const { return data(7, 0); }
96  double getDAx()const { return data(8, 0); }
102  double getDDelta()const { return data(9, 0); }
103 
109  void setX(double value) { data(0, 0) = value; }
115  void setY(double value) { data(1, 0) = value; }
121  void setPSI(double value) { data(2, 0) = value; }
127  void setvx(double value) { data(3, 0) = value; }
133  void setvy(double value) { data(4, 0) = value; }
139  void setOmega(double value) { data(5, 0) = value; }
145  void setAx(double value) { data(6, 0) = value; }
151  void setDelta(double value) { data(7, 0) = value; }
157  void setDAx(double value) { data(8, 0) = value; }
163  void setDDelta(double value) { data(9, 0) = value; }
164  };
165  }
166 }
This struct holds the state of the vehicle in 10d.
Definition: vehiclestate10d.h:40
void setDAx(double value)
Set the derivation of the longitudinal acceleration.
Definition: vehiclestate10d.h:157
void setOmega(double value)
Set the yaw rate.
Definition: vehiclestate10d.h:139
double getvy() const
Get the lateral velocity.
Definition: vehiclestate10d.h:72
void setX(double value)
Set the x-coordinate.
Definition: vehiclestate10d.h:109
double getX() const
Get the x-coordinate.
Definition: vehiclestate10d.h:48
void setvy(double value)
Set the lateral velocity.
Definition: vehiclestate10d.h:133
void setDDelta(double value)
Set the derivation of the steering angle.
Definition: vehiclestate10d.h:163
void setY(double value)
Set the y-coordinate.
Definition: vehiclestate10d.h:115
void setDelta(double value)
Set the steering angle.
Definition: vehiclestate10d.h:151
adoreMatrix< double, 10, 1 > data
Definition: vehiclestate10d.h:42
double getvx() const
Get the longitudinal velocity.
Definition: vehiclestate10d.h:66
double getAx() const
Get the longitudinal acceleration.
Definition: vehiclestate10d.h:84
void setPSI(double value)
Set the heading.
Definition: vehiclestate10d.h:121
void setAx(double value)
Set the longitudinal acceleration.
Definition: vehiclestate10d.h:145
double getDelta() const
Get the steering angle.
Definition: vehiclestate10d.h:90
double getDAx() const
Get the derivation of the longitudinal acceleration.
Definition: vehiclestate10d.h:96
double getDDelta() const
Get the derivation of the steering angle.
Definition: vehiclestate10d.h:102
void setvx(double value)
Set the longitudinal velocity.
Definition: vehiclestate10d.h:127
double getOmega() const
Get the yaw rate.
Definition: vehiclestate10d.h:78
double getPSI() const
Get the heading.
Definition: vehiclestate10d.h:60
double getY() const
Get the y-coordinate.
Definition: vehiclestate10d.h:54
Definition: areaofeffectconverter.h:20