ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
vehiclemotionstate9d.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  {
39  {
40  public:
41  double time_ = 0;
42  adoreMatrix<double, 9, 1> data_ = dlib::zeros_matrix<double>(9,1);
48  double getTime()const {return time_;}
54  double getX()const { return data_(0, 0); }
60  double getY()const { return data_(1, 0); }
66  double getZ()const { return data_(2, 0); }
72  double getPSI()const { return data_(3, 0); }
78  double getvx()const { return data_(4, 0); }
84  double getvy()const { return data_(5, 0); }
90  double getOmega()const { return data_(6, 0); }
96  double getAx()const { return data_(7, 0); }
102  double getDelta()const { return data_(8, 0); }
103 
109  void setTime(double value){time_=value;}
115  void setX(double value) { data_(0, 0) = value; }
121  void setY(double value) { data_(1, 0) = value; }
127  void setZ(double value) { data_(2, 0) = value; }
133  void setPSI(double value) { data_(3, 0) = value; }
139  void setvx(double value) { data_(4, 0) = value; }
145  void setvy(double value) { data_(5, 0) = value; }
151  void setOmega(double value) { data_(6, 0) = value; }
157  void setAx(double value) { data_(7, 0) = value; }
163  void setDelta(double value) { data_(8, 0) = value; }
164  };
165  }
166 }
Definition: areaofeffectconverter.h:20
This struct holds the motion state of the vehicle in 9d.
Definition: vehiclemotionstate9d.h:39
void setZ(double value)
Set the z-coordinate.
Definition: vehiclemotionstate9d.h:127
void setY(double value)
Set the y-coordinate.
Definition: vehiclemotionstate9d.h:121
double getX() const
Get the x-coordinate.
Definition: vehiclemotionstate9d.h:54
double getvx() const
Get the longitudinal velocity.
Definition: vehiclemotionstate9d.h:78
adoreMatrix< double, 9, 1 > data_
Definition: vehiclemotionstate9d.h:42
void setAx(double value)
Set the longitudinal acceleration.
Definition: vehiclemotionstate9d.h:157
double getOmega() const
Get the yaw rate.
Definition: vehiclemotionstate9d.h:90
void setvx(double value)
set the longitudinal velocity
Definition: vehiclemotionstate9d.h:139
double getY() const
Get the y-coordinate.
Definition: vehiclemotionstate9d.h:60
double getPSI() const
Get the heading.
Definition: vehiclemotionstate9d.h:72
double getAx() const
Get the longitudinal acceleration.
Definition: vehiclemotionstate9d.h:96
void setOmega(double value)
Set the yaw rate.
Definition: vehiclemotionstate9d.h:151
double getvy() const
Get the lateral velocity.
Definition: vehiclemotionstate9d.h:84
void setX(double value)
Set the x-coordinate.
Definition: vehiclemotionstate9d.h:115
double getZ() const
Get the z-coordinate.
Definition: vehiclemotionstate9d.h:66
double getDelta() const
Get the steering angle.
Definition: vehiclemotionstate9d.h:102
void setPSI(double value)
set the heading
Definition: vehiclemotionstate9d.h:133
void setvy(double value)
set the lateral velocity
Definition: vehiclemotionstate9d.h:145
void setDelta(double value)
Set the steering angle.
Definition: vehiclemotionstate9d.h:163
double time_
Definition: vehiclemotionstate9d.h:41
void setTime(double value)
Set the time.
Definition: vehiclemotionstate9d.h:109
double getTime() const
Get the time.
Definition: vehiclemotionstate9d.h:48