This class can be used to simulate the kinematics and dynamics of a differential driven planar mobile robot, including odometry errors and dynamics limitations.
The main methods are:
Versions:
Definition at line 38 of file CRobotSimulator.h.
#include <mrpt/utils/CRobotSimulator.h>
Public Member Functions | |
CRobotSimulator (float TAU=0, float DELAY=0) | |
Constructor with default dynamic model-parameters. More... | |
virtual | ~CRobotSimulator () |
Destructor. More... | |
void | setDelayModelParams (float TAU_delay_sec=1.8f, float CMD_delay_sec=0.3f) |
Change the model of delays used for the orders sent to the robot. More... | |
void | setOdometryErrors (bool enabled, double Ax_err_bias=1e-6, double Ax_err_std=10e-6, double Ay_err_bias=1e-6, double Ay_err_std=10e-6, double Aphi_err_bias=DEG2RAD(1e-6), double Aphi_err_std=DEG2RAD(10e-6)) |
Enable/Disable odometry errors Errors in odometry are introduced per millisecond. More... | |
void | setRealPose (const mrpt::poses::CPose2D &p) |
Reset actual robot pose (inmediately, without simulating the movement along time) More... | |
double | getX () const |
Read the instantaneous, error-free status of the simulated robot. More... | |
double | getY () |
Read the instantaneous, error-free status of the simulated robot. More... | |
double | getPHI () |
Read the instantaneous, error-free status of the simulated robot. More... | |
double | getT () |
Read the instantaneous, error-free status of the simulated robot. More... | |
double | getV () |
Read the instantaneous, error-free status of the simulated robot. More... | |
double | getW () |
Read the instantaneous, error-free status of the simulated robot. More... | |
void | setV (double v) |
Set actual robot pose (inmediately, without simulating the movement along time) (Not to be called normally!!) More... | |
void | setW (double w) |
void | movementCommand (double lin_vel, double ang_vel) |
Used to command the robot a desired movement (velocities) More... | |
void | resetStatus () |
Reset all the simulator variables to 0 (All but current simulator time). More... | |
void | resetTime () |
Reset time counter. More... | |
void | simulateInterval (double At) |
This method must be called periodically to simulate discrete time intervals. More... | |
void | resetOdometry (const mrpt::poses::CPose2D &newOdo=mrpt::poses::CPose2D()) |
Forces odometry to be set to a specified values. More... | |
void | getOdometry (mrpt::poses::CPose2D &pose) const |
Reads the simulated robot odometry (this is NOT equal to the actual error-free robot coordinates). More... | |
void | getOdometry (mrpt::math::TPose2D &pose) const |
Reads the simulated robot odometry (this is NOT equal to the actual error-free robot coordinates). More... | |
void | getRealPose (mrpt::poses::CPose2D &pose) const |
Reads the real robot pose. More... | |
void | getRealPose (mrpt::math::TPose2D &pose) const |
Reads the real robot pose. More... | |
Private Attributes | |
mrpt::poses::CPose2D | m_pose |
Global, absolute and error-free robot coordinates. More... | |
mrpt::poses::CPose2D | m_odometry |
Used to simulate odometry (with optional error) More... | |
double | v |
Instantaneous velocity of the robot (linear, m/s) More... | |
double | w |
Instantaneous velocity of the robot (angular, rad/s) More... | |
double | t |
Simulation time variable. More... | |
bool | usar_error_odometrico |
Whether to corrupt odometry with noise. More... | |
double | Command_Time |
Dynamic limitations of the robot. More... | |
double | Command_v |
double | Command_w |
double | Command_v0 |
double | Command_w0 |
float | cTAU |
The time-constants for the first order low-pass filter for the velocities changes. More... | |
float | cDELAY |
The delay constant for the velocities changes. More... | |
double | m_Ax_err_bias |
double | m_Ax_err_std |
double | m_Ay_err_bias |
double | m_Ay_err_std |
double | m_Aphi_err_bias |
double | m_Aphi_err_std |
mrpt::utils::CRobotSimulator::CRobotSimulator | ( | float | TAU = 0 , |
float | DELAY = 0 |
||
) |
Constructor with default dynamic model-parameters.
|
virtual |
Destructor.
|
inline |
Reads the simulated robot odometry (this is NOT equal to the actual error-free robot coordinates).
Definition at line 176 of file CRobotSimulator.h.
|
inline |
Reads the simulated robot odometry (this is NOT equal to the actual error-free robot coordinates).
Definition at line 183 of file CRobotSimulator.h.
|
inline |
Read the instantaneous, error-free status of the simulated robot.
Definition at line 132 of file CRobotSimulator.h.
References mrpt::poses::CPose2D::phi().
|
inline |
|
inline |
|
inline |
Read the instantaneous, error-free status of the simulated robot.
Definition at line 136 of file CRobotSimulator.h.
References t().
|
inline |
Read the instantaneous, error-free status of the simulated robot.
Definition at line 140 of file CRobotSimulator.h.
|
inline |
Read the instantaneous, error-free status of the simulated robot.
Definition at line 143 of file CRobotSimulator.h.
|
inline |
Read the instantaneous, error-free status of the simulated robot.
Definition at line 124 of file CRobotSimulator.h.
References mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::x().
|
inline |
Read the instantaneous, error-free status of the simulated robot.
Definition at line 128 of file CRobotSimulator.h.
References mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::y().
void mrpt::utils::CRobotSimulator::movementCommand | ( | double | lin_vel, |
double | ang_vel | ||
) |
Used to command the robot a desired movement (velocities)
|
inline |
Forces odometry to be set to a specified values.
Definition at line 169 of file CRobotSimulator.h.
void mrpt::utils::CRobotSimulator::resetStatus | ( | ) |
Reset all the simulator variables to 0 (All but current simulator time).
|
inline |
Reset time counter.
Definition at line 161 of file CRobotSimulator.h.
|
inline |
Change the model of delays used for the orders sent to the robot.
Definition at line 91 of file CRobotSimulator.h.
|
inline |
Enable/Disable odometry errors Errors in odometry are introduced per millisecond.
Definition at line 99 of file CRobotSimulator.h.
|
inline |
Reset actual robot pose (inmediately, without simulating the movement along time)
Definition at line 120 of file CRobotSimulator.h.
|
inline |
Set actual robot pose (inmediately, without simulating the movement along time) (Not to be called normally!!)
Definition at line 148 of file CRobotSimulator.h.
|
inline |
Definition at line 149 of file CRobotSimulator.h.
void mrpt::utils::CRobotSimulator::simulateInterval | ( | double | At | ) |
This method must be called periodically to simulate discrete time intervals.
|
private |
The delay constant for the velocities changes.
Definition at line 75 of file CRobotSimulator.h.
|
private |
Dynamic limitations of the robot.
Approximation to non-infinity motor forces: A first order low-pass filter, using: Command_Time: Time "t" when the last order was received. Command_v, Command_w: The user-desired velocities. Command_v0, Command_w0: Actual robot velocities at the moment of user request.
Definition at line 67 of file CRobotSimulator.h.
|
private |
Definition at line 67 of file CRobotSimulator.h.
|
private |
Definition at line 67 of file CRobotSimulator.h.
|
private |
Definition at line 67 of file CRobotSimulator.h.
|
private |
Definition at line 67 of file CRobotSimulator.h.
|
private |
The time-constants for the first order low-pass filter for the velocities changes.
Definition at line 72 of file CRobotSimulator.h.
|
private |
Definition at line 79 of file CRobotSimulator.h.
|
private |
Definition at line 79 of file CRobotSimulator.h.
|
private |
Definition at line 77 of file CRobotSimulator.h.
|
private |
Definition at line 77 of file CRobotSimulator.h.
|
private |
Definition at line 78 of file CRobotSimulator.h.
|
private |
Definition at line 78 of file CRobotSimulator.h.
|
private |
Used to simulate odometry (with optional error)
Definition at line 44 of file CRobotSimulator.h.
|
private |
Global, absolute and error-free robot coordinates.
Definition at line 43 of file CRobotSimulator.h.
|
private |
Simulation time variable.
Definition at line 56 of file CRobotSimulator.h.
|
private |
Whether to corrupt odometry with noise.
Definition at line 59 of file CRobotSimulator.h.
|
private |
Instantaneous velocity of the robot (linear, m/s)
Definition at line 48 of file CRobotSimulator.h.
|
private |
Instantaneous velocity of the robot (angular, rad/s)
Definition at line 52 of file CRobotSimulator.h.
Page generated by Doxygen 1.8.9.1 for MRPT 1.3.2 SVN:Unversioned directory at Tue Dec 8 09:49:21 UTC 2015 |