CarModel.h
Go to the documentation of this file.
1 
7 #ifndef CARMODEL_H_
8 #define CARMODEL_H_
9 
11 #include <iostream>
12 #include <geometry_msgs/Twist.h>
13 #include <memory.h>
14 #include <ros/ros.h>
15 
20 typedef geometry_msgs::Twist twist_msg;
26 typedef std::shared_ptr<std::vector<double>> pose_ptr;
39 class CarModel
40 {
41 public:
54  CarModel(const double dAxis, const ros::Time& time,
55  std::vector<double> initialPose = std::vector<double>(3, 0),
56  const double vMax = 2.0, const double angleMax = 22.5,
57  const double speedMax = 20, const double steeringMax = 50);
70  const pose_ptr getUpdate(const int newSteering, const int newSpeed,
71  const ros::Time& time);
83  const pose_ptr getUpdateTwist(const twist_msg cmd_vel, const ros::Time& time);
88  const int getSteering() const;
93  const double getSteeringAngle() const;
98  const double getTimeStep() const;
103  const double getVelocity() const;
108  const double getAngularVelocity() const;
113  const double getDistance() const;
119  const double getVx() const;
125  const double getVy() const;
131  const double getAx() const;
137  const double getAy() const;
138 
139 private:
141  ros::Time lastUpdate;
142  double vMax;
143  double angleMax;
144  double speedMax;
145  double steeringMax;
146  int steering;
147  double steeringAngle;
148  double timeStep;
149  double velocity;
150  double distance;
151  std::vector<double> pose;
154  double v_x;
156  double v_y;
158  double a_x;
160  double a_y;
167  void steeringToAngle();
173  void angleToSteering(const double alpha);
178  void setSteering(const int steering);
183  void setVelocity(const double newVel);
189  void speedToVelocity(const int speed);
195  void setAngularVelocity(const double oldYaw);
199  void setVelocityComponents();
205  void setAccelerationComponents(const double prevV);
206 };
207 
208 #endif /* CARMODEL_H_ */
double v_x
Definition: CarModel.h:154
Header file for the ForwardKinematics class.
const pose_ptr getUpdate(const int newSteering, const int newSpeed, const ros::Time &time)
Update the simulation with current control settings and time.
Definition: CarModel.cpp:28
double angleMax
Definition: CarModel.h:143
void setAccelerationComponents(const double prevV)
Calculate and set current acceleration components in x and y direction.
Definition: CarModel.cpp:155
CarModel(const double dAxis, const ros::Time &time, std::vector< double > initialPose=std::vector< double >(3, 0), const double vMax=2.0, const double angleMax=22.5, const double speedMax=20, const double steeringMax=50)
CarModel constructor.
Definition: CarModel.cpp:9
std::shared_ptr< std::vector< double > > pose_ptr
shortcut for a pointer to a vector of doubles containing pose information
Definition: CarModel.h:26
void angleToSteering(const double alpha)
Conversion from given steering angle to current steering level based on a lookup table.
Definition: CarModel.cpp:80
double distance
Definition: CarModel.h:150
void setAngularVelocity(const double oldYaw)
Calculate and set angular velocity by providing the orientation of the previous time step...
Definition: CarModel.cpp:115
const double getVy() const
Get current velocity in y direction of the mobile plattform relative to the global coordinate system...
Definition: CarModel.cpp:76
const double getAy() const
Get current acceleration in y direction of the mobile plattform relative to the robot coordinate syst...
Definition: CarModel.cpp:78
double velocity
Definition: CarModel.h:149
The CarModel class simulates kinematic behavoir of a car like mobile platform, by using the ForwardKi...
Definition: CarModel.h:39
void speedToVelocity(const int speed)
Conversion from given motor level to current velocity based on a lookup table.
Definition: CarModel.cpp:111
const int getSteering() const
Get current steering level of the mobile plattform.
Definition: CarModel.cpp:70
void setVelocityComponents()
Calculate and set current velocity components in x and y direction.
Definition: CarModel.cpp:150
std::vector< double > pose
Definition: CarModel.h:151
int steering
Definition: CarModel.h:146
double steeringMax
Definition: CarModel.h:145
ros::Time lastUpdate
Definition: CarModel.h:141
void steeringToAngle()
Conversion from current steering level to steering angle based on a lookup table. ...
Definition: CarModel.cpp:146
const double getTimeStep() const
Get current time step.
Definition: CarModel.cpp:64
double steeringAngle
Definition: CarModel.h:147
double timeStep
Definition: CarModel.h:148
const double getAngularVelocity() const
Get current angular velocity of the mobile plattform.
Definition: CarModel.cpp:73
const double getAx() const
Get current acceleration in x direction of the mobile plattform relative to the robot coordinate syst...
Definition: CarModel.cpp:77
const double getSteeringAngle() const
Get current steering angle of the mobile plattform.
Definition: CarModel.cpp:71
void setVelocity(const double newVel)
Set current velocity.
Definition: CarModel.cpp:95
ForwardKinematics fwdKin
Definition: CarModel.h:140
double vMax
Definition: CarModel.h:142
double a_x
Definition: CarModel.h:158
double speedMax
Definition: CarModel.h:144
double v_y
Definition: CarModel.h:156
const double getVx() const
Get current velocity in x direction of the mobile plattform relative to the global coordinate system...
Definition: CarModel.cpp:75
The ForwardKinematics class simulates kinematic behavoir of a car like mobile platform given its curr...
const double getDistance() const
Get total travelled distance of the mobile plattform.
Definition: CarModel.cpp:66
double angularVelocity
Definition: CarModel.h:153
const double getVelocity() const
Get current velocity of the mobile plattform.
Definition: CarModel.cpp:68
void setSteering(const int steering)
Set current steering level.
Definition: CarModel.cpp:128
const pose_ptr getUpdateTwist(const twist_msg cmd_vel, const ros::Time &time)
Update the simulation with current motion parameters and time.
Definition: CarModel.cpp:46
double a_y
Definition: CarModel.h:160
geometry_msgs::Twist twist_msg
shortcut for the twist message
Definition: CarModel.h:20


pses_simulation
Author(s): Sebastian Ehmes
autogenerated on Wed Dec 13 2017 19:37:54