ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
vehiclebasemeasurement.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 #pragma once
15 
16 namespace adore
17 {
18  namespace fun
19  {
24  {
25  private:
27  std::vector<float> wheel_speeds_;
28  float yaw_rate_;
29  float esp_ax_;
30  float esp_ay_; //@TODO: continue
31  public:
32  //VehicleBaseMeasurement():wheel_speeds_(4,0){}
33  void setSteeringAngle(float value){steering_angle_=value;}
34  float getSteeringAngle()const{return steering_angle_;}
35 
36  void setWheelSpeeds(const std::vector<float> value){wheel_speeds_=value;}
37  const std::vector<float>& getWheelSpeeds()const{return wheel_speeds_;}
38 
39  void setYawRate(float value){yaw_rate_=value;}
40  float getYawRate()const{return yaw_rate_;}
41 
42  void setEspAx(float value){esp_ax_=value;}
43  float getEspAx()const{return esp_ax_;}
44 
45  void setEspAy(float value){esp_ay_=value;}
46  float getEspAy()const{return esp_ay_;}
47 
48  };
49  }
50 }
Definition: vehiclebasemeasurement.h:24
float getEspAx() const
Definition: vehiclebasemeasurement.h:43
void setEspAx(float value)
Definition: vehiclebasemeasurement.h:42
void setYawRate(float value)
Definition: vehiclebasemeasurement.h:39
void setWheelSpeeds(const std::vector< float > value)
Definition: vehiclebasemeasurement.h:36
std::vector< float > wheel_speeds_
Definition: vehiclebasemeasurement.h:27
float getEspAy() const
Definition: vehiclebasemeasurement.h:46
float yaw_rate_
Definition: vehiclebasemeasurement.h:28
float steering_angle_
Definition: vehiclebasemeasurement.h:26
void setSteeringAngle(float value)
Definition: vehiclebasemeasurement.h:33
void setEspAy(float value)
Definition: vehiclebasemeasurement.h:45
float getYawRate() const
Definition: vehiclebasemeasurement.h:40
const std::vector< float > & getWheelSpeeds() const
Definition: vehiclebasemeasurement.h:37
float getSteeringAngle() const
Definition: vehiclebasemeasurement.h:34
float esp_ay_
Definition: vehiclebasemeasurement.h:30
float esp_ax_
Definition: vehiclebasemeasurement.h:29
Definition: areaofeffectconverter.h:20