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 #pragma once
16 
17 #include <adore/mad/adoremath.h>
18 #include <type_traits>
19 
20 namespace adore
21 {
22  namespace fun
23  {
24  struct PlanarVehicleState10d;
25  class SetPoint;
41  {
42  public:
44  {
45  time_ = 0.0;
46  for(int i=0;i<9;i++)data_(i)=0.0;
47  }
48 
49  double time_;
50  adoreMatrix<double, 9, 1> data_;
54  double getTime()const {return time_;}
58  double getX()const { return data_(0, 0); }
62  double getY()const { return data_(1, 0); }
66  double getZ()const { return data_(2, 0); }
70  double getPSI()const { return data_(3, 0); }
74  double getvx()const { return data_(4, 0); }
78  double getvy()const { return data_(5, 0); }
82  double getOmega()const { return data_(6, 0); }
86  double getAx()const { return data_(7, 0); }
90  double getDelta()const { return data_(8, 0); }
95  void setTime(double value){time_=value;}
100  void setX(double value) { data_(0, 0) = value; }
105  void setY(double value) { data_(1, 0) = value; }
110  void setZ(double value) { data_(2, 0) = value; }
115  void setPSI(double value) { data_(3, 0) = value; }
120  void setvx(double value) { data_(4, 0) = value; }
125  void setvy(double value) { data_(5, 0) = value; }
130  void setOmega(double value) { data_(6, 0) = value; }
135  void setAx(double value) { data_(7, 0) = value; }
140  void setDelta(double value) { data_(8, 0) = value; }
141 
153  template<class T,
154  typename = std::enable_if_t< std::is_same<T,PlanarVehicleState10d>::value> >
155  void copyFromPlanar(const T& other)
156  {
157  this->setX(other.getX());
158  this->setY(other.getY());
159  // this->setZ(0.0);
160  this->setPSI(other.getPSI());
161  this->setvx(other.getvx());
162  this->setvy(other.getvy());
163  this->setOmega(other.getOmega());
164  this->setAx(other.getAx());
165  this->setDelta(other.getDelta());
166  }
167  };
168  }
169 }
double getY() const
Definition: vehiclemotionstate9d.h:62
void setvy(double value)
Definition: vehiclemotionstate9d.h:125
double time_
Definition: vehiclemotionstate9d.h:49
void setAx(double value)
Definition: vehiclemotionstate9d.h:135
void setTime(double value)
Definition: vehiclemotionstate9d.h:95
double getTime() const
Definition: vehiclemotionstate9d.h:54
void setPSI(double value)
Definition: vehiclemotionstate9d.h:115
void copyFromPlanar(const T &other)
Offers the possibility to copy relevant fields from a PlanarVehicleState10d to VehicleMotionState9d.
Definition: vehiclemotionstate9d.h:155
VehicleMotionState9d()
Definition: vehiclemotionstate9d.h:43
void setY(double value)
Definition: vehiclemotionstate9d.h:105
void setX(double value)
Definition: vehiclemotionstate9d.h:100
adoreMatrix< double, 9, 1 > data_
Definition: vehiclemotionstate9d.h:50
double getX() const
Definition: vehiclemotionstate9d.h:58
void setZ(double value)
Definition: vehiclemotionstate9d.h:110
void setvx(double value)
Definition: vehiclemotionstate9d.h:120
double getAx() const
Definition: vehiclemotionstate9d.h:86
double getOmega() const
Definition: vehiclemotionstate9d.h:82
double getvy() const
Definition: vehiclemotionstate9d.h:78
double getvx() const
Definition: vehiclemotionstate9d.h:74
double getDelta() const
Definition: vehiclemotionstate9d.h:90
void setOmega(double value)
Definition: vehiclemotionstate9d.h:130
void setDelta(double value)
Definition: vehiclemotionstate9d.h:140
double getPSI() const
Definition: vehiclemotionstate9d.h:70
double getZ() const
Definition: vehiclemotionstate9d.h:66
Definition: areaofeffectconverter.h:20
This struct holds the motion state of the vehicle in 9d.
Definition: vehiclemotionstate9d.h:39
void setY(double value)
Set the y-coordinate.
Definition: vehiclemotionstate9d.h:121
adoreMatrix< double, 9, 1 > data_
Definition: vehiclemotionstate9d.h:42
void setAx(double value)
Set the longitudinal acceleration.
Definition: vehiclemotionstate9d.h:157
void setvx(double value)
set the longitudinal velocity
Definition: vehiclemotionstate9d.h:139
void setOmega(double value)
Set the yaw rate.
Definition: vehiclemotionstate9d.h:151
void setX(double value)
Set the x-coordinate.
Definition: vehiclemotionstate9d.h:115
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