Public Member Functions | Private Member Functions | Private Attributes | List of all members
CarModel Class Reference

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
 

Detailed Description

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.

Constructor & Destructor Documentation

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.

Parameters
[in]dAxiswheel base of the mobile robot in meters.
[in]timecurrent Ros::Time.
[in]initialPoseinitial pose of the robot. (0: - y-coordinate, 1: x-coordinate, 2: yaw in radiants).
[in]vMaxmaximum speed of the mobile robot in meters/second.
[in]angleMaxmaximum steering angle of the mobile robot in degrees.
[in]speedMaxmaximum motor level of the mobile robot.
[in]steeringMaxmaximum steering level of the mobile robot.

Definition at line 9 of file CarModel.cpp.

Member Function Documentation

void CarModel::angleToSteering ( const double  alpha)
private

Conversion from given steering angle to current steering level based on a lookup table.

Parameters
[in]alphasteering angle in degrees

Definition at line 80 of file CarModel.cpp.

const double CarModel::getAngularVelocity ( ) const

Get current angular velocity of the mobile plattform.

Returns
current angular velocity

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.

Returns
current acceleration in x direction

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.

Returns
current acceleration in y direction

Definition at line 78 of file CarModel.cpp.

const double CarModel::getDistance ( ) const

Get total travelled distance of the mobile plattform.

Returns
total travelled distance

Definition at line 66 of file CarModel.cpp.

const int CarModel::getSteering ( ) const

Get current steering level of the mobile plattform.

Returns
current steering level

Definition at line 70 of file CarModel.cpp.

const double CarModel::getSteeringAngle ( ) const

Get current steering angle of the mobile plattform.

Returns
current steering angle

Definition at line 71 of file CarModel.cpp.

const double CarModel::getTimeStep ( ) const

Get current time step.

Returns
current time step

Definition at line 64 of file CarModel.cpp.

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.

Parameters
[in]newSteeringcurrent steering level of the mobile robot.
[in]newSpeedcurrent motor level of the mobile robot.
[in]timecurrent Ros::Time
Returns
current position/speed/orientation/rotation of this mobile robot

Definition at line 28 of file CarModel.cpp.

const pose_ptr CarModel::getUpdateTwist ( const twist_msg  cmd_vel,
const ros::Time &  time 
)

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.

Parameters
[in]cmd_velcurrent speed and steering angle of the robot.
[in]timecurrent Ros::Time
Returns
current position/speed/orientation/rotation of this mobile robot

Definition at line 46 of file CarModel.cpp.

const double CarModel::getVelocity ( ) const

Get current velocity of the mobile plattform.

Returns
current velocity

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.

Returns
current velocity in x direction

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.

Returns
current velocity in y direction

Definition at line 76 of file CarModel.cpp.

void CarModel::setAccelerationComponents ( const double  prevV)
private

Calculate and set current acceleration components in x and y direction.

Parameters
[in]prevVprevious velocity

Definition at line 155 of file CarModel.cpp.

void CarModel::setAngularVelocity ( const double  oldYaw)
private

Calculate and set angular velocity by providing the orientation of the previous time step.

Parameters
[in]oldYawprevious orientation

Definition at line 115 of file CarModel.cpp.

void CarModel::setSteering ( const int  steering)
private

Set current steering level.

Parameters
[in]steeringcurrent steering level

Definition at line 128 of file CarModel.cpp.

void CarModel::setVelocity ( const double  newVel)
private

Set current velocity.

Parameters
[in]newVelcurrent velocity

Definition at line 95 of file CarModel.cpp.

void CarModel::setVelocityComponents ( )
private

Calculate and set current velocity components in x and y direction.

Definition at line 150 of file CarModel.cpp.

void CarModel::speedToVelocity ( const int  speed)
private

Conversion from given motor level to current velocity based on a lookup table.

Parameters
[in]speedmotor level

Definition at line 111 of file CarModel.cpp.

void CarModel::steeringToAngle ( )
private

Conversion from current steering level to steering angle based on a lookup table.

Definition at line 146 of file CarModel.cpp.

Member Data Documentation

double CarModel::a_x
private

Current acceleration in x direction relative to the robot coordinate system.

Definition at line 158 of file CarModel.h.

double CarModel::a_y
private

Current acceleration in y direction relative to the robot coordinate system.

Definition at line 160 of file CarModel.h.

double CarModel::angleMax
private

Maximum steering angle in degrees

Definition at line 143 of file CarModel.h.

double CarModel::angularVelocity
private

Current angular velocity in rad/s

Definition at line 153 of file CarModel.h.

double CarModel::distance
private

Total driven distance

Definition at line 150 of file CarModel.h.

ForwardKinematics CarModel::fwdKin
private

Simulation of ackerman kinematics

Definition at line 140 of file CarModel.h.

ros::Time CarModel::lastUpdate
private

Ros time of last update

Definition at line 141 of file CarModel.h.

std::vector<double> CarModel::pose
private

Current pose (0: - y-coordinate, 1: x-coordinate, 2: yaw in radiants)

Definition at line 151 of file CarModel.h.

double CarModel::speedMax
private

Maximum motor level

Definition at line 144 of file CarModel.h.

int CarModel::steering
private

Current steering level

Definition at line 146 of file CarModel.h.

double CarModel::steeringAngle
private

Current steering angle

Definition at line 147 of file CarModel.h.

double CarModel::steeringMax
private

Maximum steering level

Definition at line 145 of file CarModel.h.

double CarModel::timeStep
private

Current time step

Definition at line 148 of file CarModel.h.

double CarModel::v_x
private

Current velocity in x direction relative to the global coordinate system.

Definition at line 154 of file CarModel.h.

double CarModel::v_y
private

Current velocity in y direction relative to the global coordinate system.

Definition at line 156 of file CarModel.h.

double CarModel::velocity
private

Current velocity

Definition at line 149 of file CarModel.h.

double CarModel::vMax
private

Maximum velocity in m/s

Definition at line 142 of file CarModel.h.


The documentation for this class was generated from the following files:


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