The CarModel class simulates kinematic behavoir of a car like mobile platform, by using the ForwardKinematics library. More...
#include "pses_simulation/CarModel.h"
Public Member Functions | |
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. More... | |
const double | getAngularVelocity () const |
Get current angular velocity of the mobile plattform. More... | |
const double | getAx () const |
Get current acceleration in x direction of the mobile plattform relative to the robot coordinate system. More... | |
const double | getAy () const |
Get current acceleration in y direction of the mobile plattform relative to the robot coordinate system. More... | |
const double | getDistance () const |
Get total travelled distance of the mobile plattform. More... | |
const int | getSteering () const |
Get current steering level of the mobile plattform. More... | |
const double | getSteeringAngle () const |
Get current steering angle of the mobile plattform. More... | |
const double | getTimeStep () const |
Get current time step. More... | |
const pose_ptr | getUpdate (const int newSteering, const int newSpeed, const ros::Time &time) |
Update the simulation with current control settings and time. More... | |
const pose_ptr | getUpdateTwist (const twist_msg cmd_vel, const ros::Time &time) |
Update the simulation with current motion parameters and time. More... | |
const double | getVelocity () const |
Get current velocity of the mobile plattform. More... | |
const double | getVx () const |
Get current velocity in x direction of the mobile plattform relative to the global coordinate system. More... | |
const double | getVy () const |
Get current velocity in y direction of the mobile plattform relative to the global coordinate system. More... | |
Private Member Functions | |
void | angleToSteering (const double alpha) |
Conversion from given steering angle to current steering level based on a lookup table. More... | |
void | setAccelerationComponents (const double prevV) |
Calculate and set current acceleration components in x and y direction. More... | |
void | setAngularVelocity (const double oldYaw) |
Calculate and set angular velocity by providing the orientation of the previous time step. More... | |
void | setSteering (const int steering) |
Set current steering level. More... | |
void | setVelocity (const double newVel) |
Set current velocity. More... | |
void | setVelocityComponents () |
Calculate and set current velocity components in x and y direction. More... | |
void | speedToVelocity (const int speed) |
Conversion from given motor level to current velocity based on a lookup table. More... | |
void | steeringToAngle () |
Conversion from current steering level to steering angle based on a lookup table. More... | |
Private Attributes | |
double | a_x |
double | a_y |
double | angleMax |
double | angularVelocity |
double | distance |
ForwardKinematics | fwdKin |
ros::Time | lastUpdate |
std::vector< double > | pose |
double | speedMax |
int | steering |
double | steeringAngle |
double | steeringMax |
double | timeStep |
double | v_x |
double | v_y |
double | velocity |
double | vMax |
The CarModel class simulates kinematic behavoir of a car like mobile platform, by using the ForwardKinematics library.
This is not physically accurate simulation of forces, torque and accelerations. Its mainly used to demonstrate kinematic behaviour of car like robot in an ideal environment, i.e. infinite acceleration, zero steering lag and perfect tire grip.
Definition at line 39 of file CarModel.h.
CarModel::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.
[in] | dAxis | wheel base of the mobile robot in meters. |
[in] | time | current Ros::Time. |
[in] | initialPose | initial pose of the robot. (0: - y-coordinate, 1: x-coordinate, 2: yaw in radiants). |
[in] | vMax | maximum speed of the mobile robot in meters/second. |
[in] | angleMax | maximum steering angle of the mobile robot in degrees. |
[in] | speedMax | maximum motor level of the mobile robot. |
[in] | steeringMax | maximum steering level of the mobile robot. |
Definition at line 9 of file CarModel.cpp.
|
private |
Conversion from given steering angle to current steering level based on a lookup table.
[in] | alpha | steering angle in degrees |
Definition at line 80 of file CarModel.cpp.
const double CarModel::getAngularVelocity | ( | ) | const |
Get current angular velocity of the mobile plattform.
Definition at line 73 of file CarModel.cpp.
const double CarModel::getAx | ( | ) | const |
Get current acceleration in x direction of the mobile plattform relative to the robot coordinate system.
Definition at line 77 of file CarModel.cpp.
const double CarModel::getAy | ( | ) | const |
Get current acceleration in y direction of the mobile plattform relative to the robot coordinate system.
Definition at line 78 of file CarModel.cpp.
const double CarModel::getDistance | ( | ) | const |
Get total travelled distance of the mobile plattform.
Definition at line 66 of file CarModel.cpp.
const int CarModel::getSteering | ( | ) | const |
Get current steering level of the mobile plattform.
Definition at line 70 of file CarModel.cpp.
const double CarModel::getSteeringAngle | ( | ) | const |
Get current steering angle of the mobile plattform.
Definition at line 71 of file CarModel.cpp.
const double CarModel::getTimeStep | ( | ) | const |
const pose_ptr CarModel::getUpdate | ( | const int | newSteering, |
const int | newSpeed, | ||
const ros::Time & | time | ||
) |
Update the simulation with current control settings and time.
Given a current time, the simulation will calculate changes in position orientation as well as speed and rotation of the robot during the time interval from this to the previous update.
[in] | newSteering | current steering level of the mobile robot. |
[in] | newSpeed | current motor level of the mobile robot. |
[in] | time | current Ros::Time |
Definition at line 28 of file CarModel.cpp.
Update the simulation with current motion parameters and time.
Given a current time, the simulation will calculate changes in position orientation as well as speed and rotation of the robot during the time interval from this to the previous update.
[in] | cmd_vel | current speed and steering angle of the robot. |
[in] | time | current Ros::Time |
Definition at line 46 of file CarModel.cpp.
const double CarModel::getVelocity | ( | ) | const |
Get current velocity of the mobile plattform.
Definition at line 68 of file CarModel.cpp.
const double CarModel::getVx | ( | ) | const |
Get current velocity in x direction of the mobile plattform relative to the global coordinate system.
Definition at line 75 of file CarModel.cpp.
const double CarModel::getVy | ( | ) | const |
Get current velocity in y direction of the mobile plattform relative to the global coordinate system.
Definition at line 76 of file CarModel.cpp.
|
private |
Calculate and set current acceleration components in x and y direction.
[in] | prevV | previous velocity |
Definition at line 155 of file CarModel.cpp.
|
private |
Calculate and set angular velocity by providing the orientation of the previous time step.
[in] | oldYaw | previous orientation |
Definition at line 115 of file CarModel.cpp.
|
private |
Set current steering level.
[in] | steering | current steering level |
Definition at line 128 of file CarModel.cpp.
|
private |
Set current velocity.
[in] | newVel | current velocity |
Definition at line 95 of file CarModel.cpp.
|
private |
Calculate and set current velocity components in x and y direction.
Definition at line 150 of file CarModel.cpp.
|
private |
Conversion from given motor level to current velocity based on a lookup table.
[in] | speed | motor level |
Definition at line 111 of file CarModel.cpp.
|
private |
Conversion from current steering level to steering angle based on a lookup table.
Definition at line 146 of file CarModel.cpp.
|
private |
Current acceleration in x direction relative to the robot coordinate system.
Definition at line 158 of file CarModel.h.
|
private |
Current acceleration in y direction relative to the robot coordinate system.
Definition at line 160 of file CarModel.h.
|
private |
Maximum steering angle in degrees
Definition at line 143 of file CarModel.h.
|
private |
Current angular velocity in rad/s
Definition at line 153 of file CarModel.h.
|
private |
Total driven distance
Definition at line 150 of file CarModel.h.
|
private |
Simulation of ackerman kinematics
Definition at line 140 of file CarModel.h.
|
private |
Ros time of last update
Definition at line 141 of file CarModel.h.
|
private |
Current pose (0: - y-coordinate, 1: x-coordinate, 2: yaw in radiants)
Definition at line 151 of file CarModel.h.
|
private |
Maximum motor level
Definition at line 144 of file CarModel.h.
|
private |
Current steering level
Definition at line 146 of file CarModel.h.
|
private |
Current steering angle
Definition at line 147 of file CarModel.h.
|
private |
Maximum steering level
Definition at line 145 of file CarModel.h.
|
private |
Current time step
Definition at line 148 of file CarModel.h.
|
private |
Current velocity in x direction relative to the global coordinate system.
Definition at line 154 of file CarModel.h.
|
private |
Current velocity in y direction relative to the global coordinate system.
Definition at line 156 of file CarModel.h.
|
private |
Current velocity
Definition at line 149 of file CarModel.h.
|
private |
Maximum velocity in m/s
Definition at line 142 of file CarModel.h.