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

The ForwardKinematics class simulates kinematic behavoir of a car like mobile platform given its current control parameters (e.g. steering, speed etc.) More...

#include <ForwardKinematics.h>

Public Member Functions

std::pair< double, double > calcICC (double alpha)
 Calculates the current instantaneous center of curvature given a steering angle. More...
 
double calcRadius (std::pair< double, double > ICC)
 Calculate the radius of the current robot tracjectory around the instantaneous center of curvature (ICC). More...
 
Eigen::Matrix4d * calcRot (double theta, double alpha)
 Calculate the current rotation matrix. More...
 
double calcTheta (double distance, double radius)
 Calculate the current orientation of the robot with respect to the coordinate system of the previous update. More...
 
Eigen::Matrix4d * calcTrans (double radius, double distance, double alpha, std::pair< double, double > ICC)
 Calculate the current translation matrix. More...
 
double degToRad (double angle)
 Conversion from degrees to radiants. More...
 
double flattenZeros (double value)
 Rounds values close to zero to exactly zero. More...
 
 ForwardKinematics ()
 ForwardKinematics default constructor. More...
 
 ForwardKinematics (const ForwardKinematics &other)
 ForwardKinematics default copy constructor. More...
 
 ForwardKinematics (double k, std::vector< double > initialPose=std::vector< double >(3, 0))
 ForwardKinematics constructor. More...
 
const double getRadius () const
 Get the radius of the current robot tracjectory around the instantaneous center of curvature (ICC). More...
 
std::vector< double > & getUpdate (double alpha, double distance)
 Get the current position and orientation. More...
 
double radToDeg (double angle)
 Conversion from radiants to degrees. More...
 

Public Attributes

double PI
 

Private Member Functions

void init ()
 Initialize simulation. More...
 

Private Attributes

std::vector< double > currentPosition
 
Eigen::Matrix4d initT
 
double k
 
Eigen::Matrix4d prevT
 
double radius
 
std::vector< Eigen::Matrix4d > T
 

Detailed Description

The ForwardKinematics class simulates kinematic behavoir of a car like mobile platform given its current control parameters (e.g. steering, speed etc.)

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 28 of file ForwardKinematics.h.

Constructor & Destructor Documentation

ForwardKinematics::ForwardKinematics ( )

ForwardKinematics default constructor.

Definition at line 9 of file ForwardKinematics.cpp.

ForwardKinematics::ForwardKinematics ( const ForwardKinematics other)

ForwardKinematics default copy constructor.

Definition at line 10 of file ForwardKinematics.cpp.

ForwardKinematics::ForwardKinematics ( double  k,
std::vector< double >  initialPose = std::vector<double>(3, 0) 
)

ForwardKinematics constructor.

Parameters
[in]kwheel base of the mobile robot in meters.
[in]initialPoseinitial pose of the robot. (0: - y-coordinate, 1: x-coordinate, 2: yaw in radiants)

Definition at line 21 of file ForwardKinematics.cpp.

Member Function Documentation

std::pair< double, double > ForwardKinematics::calcICC ( double  alpha)

Calculates the current instantaneous center of curvature given a steering angle.

Parameters
[in]alphacurrent steering angle
Returns
pair of coordinates of the ICC (first: x, second: y)

Definition at line 52 of file ForwardKinematics.cpp.

double ForwardKinematics::calcRadius ( std::pair< double, double >  ICC)

Calculate the radius of the current robot tracjectory around the instantaneous center of curvature (ICC).

Parameters
[in]ICCpair of coordinates of the ICC (first: x, second: y)
Returns
radius in meters

Definition at line 65 of file ForwardKinematics.cpp.

Eigen::Matrix4d * ForwardKinematics::calcRot ( double  theta,
double  alpha 
)

Calculate the current rotation matrix.

Parameters
[in]thetaorientation of the previous update
[in]alphacurrent steering angle
Returns
current rotation matrix

Definition at line 74 of file ForwardKinematics.cpp.

double ForwardKinematics::calcTheta ( double  distance,
double  radius 
)

Calculate the current orientation of the robot with respect to the coordinate system of the previous update.

Parameters
[in]distancedistance travelled between updates
[in]radiusradius with respect to the ICC in meters
Returns
current orientation in radiants

Definition at line 70 of file ForwardKinematics.cpp.

Eigen::Matrix4d * ForwardKinematics::calcTrans ( double  radius,
double  distance,
double  alpha,
std::pair< double, double >  ICC 
)

Calculate the current translation matrix.

Parameters
[in]alphacurrent steering angle
[in]distancedistance travelled between updates
[in]radiusradius with respect to the ICC in meters
[in]ICCpair of coordinates of the ICC (first: x, second: y)
Returns
current translation matrix

Definition at line 96 of file ForwardKinematics.cpp.

double ForwardKinematics::degToRad ( double  angle)

Conversion from degrees to radiants.

Parameters
[in]angleangle in degrees
Returns
angle in radiants

Definition at line 62 of file ForwardKinematics.cpp.

double ForwardKinematics::flattenZeros ( double  value)

Rounds values close to zero to exactly zero.

Returns
0 if value > epsilon, else value.

Definition at line 58 of file ForwardKinematics.cpp.

const double ForwardKinematics::getRadius ( ) const

Get the radius of the current robot tracjectory around the instantaneous center of curvature (ICC).

Returns
radius in meters

Definition at line 50 of file ForwardKinematics.cpp.

std::vector< double > & ForwardKinematics::getUpdate ( double  alpha,
double  distance 
)

Get the current position and orientation.

Parameters
[in]alphacurrent steering angle
[in]distancedistance travelled between updates
Returns
current Current pose (0: - y-coordinate, 1: x-coordinate, 2: yaw in radiants)

Definition at line 135 of file ForwardKinematics.cpp.

void ForwardKinematics::init ( )
private

Initialize simulation.

Definition at line 23 of file ForwardKinematics.cpp.

double ForwardKinematics::radToDeg ( double  angle)

Conversion from radiants to degrees.

Parameters
[in]angleangle in radiants
Returns
angle in degrees

Definition at line 63 of file ForwardKinematics.cpp.

Member Data Documentation

std::vector<double> ForwardKinematics::currentPosition
private

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

Definition at line 118 of file ForwardKinematics.h.

Eigen::Matrix4d ForwardKinematics::initT
private

Initial forward kinematic transformation matrix

Definition at line 115 of file ForwardKinematics.h.

double ForwardKinematics::k
private

Wheelbase in meters

Definition at line 113 of file ForwardKinematics.h.

double ForwardKinematics::PI

pi

Definition at line 110 of file ForwardKinematics.h.

Eigen::Matrix4d ForwardKinematics::prevT
private

Previous kinematic transformation matrix

Definition at line 117 of file ForwardKinematics.h.

double ForwardKinematics::radius
private

Radius of the current robot tracjectory around the instantaneous center of curvature (ICC)

Definition at line 114 of file ForwardKinematics.h.

std::vector<Eigen::Matrix4d> ForwardKinematics::T
private

History of kinematic transformation matrices

Definition at line 116 of file ForwardKinematics.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