12 #include <geometry_msgs/Twist.h> 26 typedef std::shared_ptr<std::vector<double>>
pose_ptr;
54 CarModel(
const double dAxis,
const ros::Time& time,
55 std::vector<double> initialPose = std::vector<double>(3, 0),
71 const ros::Time& time);
119 const double getVx()
const;
125 const double getVy()
const;
131 const double getAx()
const;
137 const double getAy()
const;
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.
void setAccelerationComponents(const double prevV)
Calculate and set current acceleration components in x and y direction.
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.
std::shared_ptr< std::vector< double > > pose_ptr
shortcut for a pointer to a vector of doubles containing pose information
void angleToSteering(const double alpha)
Conversion from given steering angle to current steering level based on a lookup table.
void setAngularVelocity(const double oldYaw)
Calculate and set angular velocity by providing the orientation of the previous time step...
const double getVy() const
Get current velocity in y direction of the mobile plattform relative to the global coordinate system...
const double getAy() const
Get current acceleration in y direction of the mobile plattform relative to the robot coordinate syst...
The CarModel class simulates kinematic behavoir of a car like mobile platform, by using the ForwardKi...
void speedToVelocity(const int speed)
Conversion from given motor level to current velocity based on a lookup table.
const int getSteering() const
Get current steering level of the mobile plattform.
void setVelocityComponents()
Calculate and set current velocity components in x and y direction.
std::vector< double > pose
void steeringToAngle()
Conversion from current steering level to steering angle based on a lookup table. ...
const double getTimeStep() const
Get current time step.
const double getAngularVelocity() const
Get current angular velocity of the mobile plattform.
const double getAx() const
Get current acceleration in x direction of the mobile plattform relative to the robot coordinate syst...
const double getSteeringAngle() const
Get current steering angle of the mobile plattform.
void setVelocity(const double newVel)
Set current velocity.
const double getVx() const
Get current velocity in x direction of the mobile plattform relative to the global coordinate system...
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.
const double getVelocity() const
Get current velocity of the mobile plattform.
void setSteering(const int steering)
Set current steering level.
const pose_ptr getUpdateTwist(const twist_msg cmd_vel, const ros::Time &time)
Update the simulation with current motion parameters and time.
geometry_msgs::Twist twist_msg
shortcut for the twist message