MRPT  2.0.4
List of all members | Classes | Public Types | Public Member Functions | Protected Attributes | Private Member Functions
mrpt::kinematics::CVehicleSimul_Holo Class Reference

Detailed Description

Kinematic simulator of a holonomic 2D robot capable of moving in any direction, with "blended" velocity profiles.

See CVehicleSimul_Holo::sendVelCmd() for a description of the velocity commands in this kinematic model.

Definition at line 23 of file CVehicleSimul_Holo.h.

#include <mrpt/kinematics/CVehicleSimul_Holo.h>

Inheritance diagram for mrpt::kinematics::CVehicleSimul_Holo:

Classes

struct  TVelRampCmd
 

Public Types

using kinematic_cmd_t = CVehicleVelCmd_Holo
 

Public Member Functions

 CVehicleSimul_Holo ()
 
void sendVelRampCmd (double vel, double dir, double ramp_time, double rot_speed)
 Sends a velocity cmd to the holonomic robot. More...
 
void sendVelCmd (const CVehicleVelCmd &cmd_vel) override
 Sends a velocity command to the robot. More...
 
CVehicleVelCmd::Ptr getVelCmdType () const override
 Gets an empty velocity command object that can be queried to find out the number of velcmd components,... More...
 
Kinematic simulation and control interface
void simulateOneTimeStep (const double dt)
 Runs the simulator during "dt" seconds. More...
 
const mrpt::math::TPose2DgetCurrentGTPose () const
 Returns the instantaneous, ground truth pose in world coordinates. More...
 
void setCurrentGTPose (const mrpt::math::TPose2D &pose)
 Brute-force move robot to target coordinates ("teleport") More...
 
const mrpt::math::TPose2DgetCurrentOdometricPose () const
 Returns the current pose according to (noisy) odometry. More...
 
template<typename T >
void setCurrentOdometricPose (const T &pose)
 Brute-force overwrite robot odometry. More...
 
const mrpt::math::TTwist2DgetCurrentGTVel () const
 Returns the instantaneous, ground truth velocity vector (vx,vy,omega) in world coordinates. More...
 
mrpt::math::TTwist2D getCurrentGTVelLocal () const
 Returns the instantaneous, ground truth velocity vector (vx,vy,omega) in the robot local frame. More...
 
const mrpt::math::TTwist2DgetCurrentOdometricVel () const
 Returns the instantaneous, odometric velocity vector (vx,vy,omega) in world coordinates. More...
 
mrpt::math::TTwist2D getCurrentOdometricVelLocal () const
 Returns the instantaneous, odometric velocity vector (vx,vy,omega) in the robot local frame. More...
 
double getTime () const
 Get the current simulation time. More...
 
void setOdometryErrors (bool enabled, double Ax_err_bias=1e-3, double Ax_err_std=10e-3, double Ay_err_bias=1e-3, double Ay_err_std=10e-3, double Aphi_err_bias=mrpt::DEG2RAD(1e-3), double Aphi_err_std=mrpt::DEG2RAD(10e-3))
 Enable/Disable odometry errors. More...
 
void resetStatus ()
 
void resetTime ()
 Reset all simulator variables to 0 (except the. More...
 

Protected Attributes

double m_firmware_control_period {500e-6}
 The period at which the low-level controller updates velocities (Default: 0.5 ms) More...
 
bool m_use_odo_error {false}
 Whether to corrupt odometry with noise. 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
 
State vector
double m_time
 simulation running time More...
 
mrpt::math::TPose2D m_GT_pose
 ground truth pose in world coordinates. More...
 
mrpt::math::TTwist2D m_GT_vel
 Velocity in (x,y,omega) More...
 
mrpt::math::TTwist2D m_odometric_vel
 Velocity in (x,y,omega) More...
 
mrpt::math::TPose2D m_odometry
 

Private Member Functions

void internal_simulControlStep (const double dt) override
 
void internal_clear () override
 Resets all pending cmds. More...
 

Private Attributes

Vel ramp cmds
TVelRampCmd m_vel_ramp_cmd
 the last cmd received from the user. More...
 

Member Typedef Documentation

◆ kinematic_cmd_t

Definition at line 26 of file CVehicleSimul_Holo.h.

Constructor & Destructor Documentation

◆ CVehicleSimul_Holo()

CVehicleSimul_Holo::CVehicleSimul_Holo ( )

Definition at line 17 of file CVehicleSimul_Holo.cpp.

References mrpt::kinematics::CVehicleSimulVirtualBase::resetStatus(), and mrpt::kinematics::CVehicleSimulVirtualBase::resetTime().

Here is the call graph for this function:

Member Function Documentation

◆ getCurrentGTPose()

const mrpt::math::TPose2D& mrpt::kinematics::CVehicleSimulVirtualBase::getCurrentGTPose ( ) const
inlineinherited

Returns the instantaneous, ground truth pose in world coordinates.

Definition at line 45 of file CVehicleSimulVirtualBase.h.

References mrpt::kinematics::CVehicleSimulVirtualBase::m_GT_pose.

Referenced by mrpt::nav::CRobot2NavInterfaceForSimulator_Holo::getCurrentPoseAndSpeeds(), mrpt::nav::CRobot2NavInterfaceForSimulator_DiffDriven::getCurrentPoseAndSpeeds(), and run_rnav_test().

Here is the caller graph for this function:

◆ getCurrentGTVel()

const mrpt::math::TTwist2D& mrpt::kinematics::CVehicleSimulVirtualBase::getCurrentGTVel ( ) const
inlineinherited

Returns the instantaneous, ground truth velocity vector (vx,vy,omega) in world coordinates.

Definition at line 64 of file CVehicleSimulVirtualBase.h.

References mrpt::kinematics::CVehicleSimulVirtualBase::m_GT_vel.

Referenced by mrpt::nav::CRobot2NavInterfaceForSimulator_Holo::getCurrentPoseAndSpeeds(), and mrpt::nav::CRobot2NavInterfaceForSimulator_DiffDriven::getCurrentPoseAndSpeeds().

Here is the caller graph for this function:

◆ getCurrentGTVelLocal()

mrpt::math::TTwist2D CVehicleSimulVirtualBase::getCurrentGTVelLocal ( ) const
inherited

Returns the instantaneous, ground truth velocity vector (vx,vy,omega) in the robot local frame.

Definition at line 83 of file CVehicleSimulVirtualBase.cpp.

References mrpt::kinematics::CVehicleSimulVirtualBase::m_GT_pose, mrpt::kinematics::CVehicleSimulVirtualBase::m_GT_vel, mrpt::math::TPose2D::phi, and mrpt::math::TTwist2D::rotate().

Here is the call graph for this function:

◆ getCurrentOdometricPose()

const mrpt::math::TPose2D& mrpt::kinematics::CVehicleSimulVirtualBase::getCurrentOdometricPose ( ) const
inlineinherited

Returns the current pose according to (noisy) odometry.

See also
setOdometryErrors

Definition at line 51 of file CVehicleSimulVirtualBase.h.

References mrpt::kinematics::CVehicleSimulVirtualBase::m_odometry.

Referenced by mrpt::nav::CRobot2NavInterfaceForSimulator_Holo::getCurrentPoseAndSpeeds(), and mrpt::nav::CRobot2NavInterfaceForSimulator_DiffDriven::getCurrentPoseAndSpeeds().

Here is the caller graph for this function:

◆ getCurrentOdometricVel()

const mrpt::math::TTwist2D& mrpt::kinematics::CVehicleSimulVirtualBase::getCurrentOdometricVel ( ) const
inlineinherited

Returns the instantaneous, odometric velocity vector (vx,vy,omega) in world coordinates.

Definition at line 71 of file CVehicleSimulVirtualBase.h.

References mrpt::kinematics::CVehicleSimulVirtualBase::m_odometric_vel.

◆ getCurrentOdometricVelLocal()

mrpt::math::TTwist2D CVehicleSimulVirtualBase::getCurrentOdometricVelLocal ( ) const
inherited

Returns the instantaneous, odometric velocity vector (vx,vy,omega) in the robot local frame.

Definition at line 90 of file CVehicleSimulVirtualBase.cpp.

References mrpt::kinematics::CVehicleSimulVirtualBase::m_odometric_vel, mrpt::kinematics::CVehicleSimulVirtualBase::m_odometry, mrpt::math::TPose2D::phi, and mrpt::math::TTwist2D::rotate().

Referenced by mrpt::kinematics::CVehicleSimulVirtualBase::simulateOneTimeStep().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getTime()

double mrpt::kinematics::CVehicleSimulVirtualBase::getTime ( ) const
inlineinherited

Get the current simulation time.

Definition at line 80 of file CVehicleSimulVirtualBase.h.

References mrpt::kinematics::CVehicleSimulVirtualBase::m_time.

Referenced by mrpt::nav::CRobot2NavInterfaceForSimulator_Holo::getNavigationTime(), mrpt::nav::CRobot2NavInterfaceForSimulator_DiffDriven::getNavigationTime(), mrpt::nav::CRobot2NavInterfaceForSimulator_Holo::resetNavigationTimer(), and mrpt::nav::CRobot2NavInterfaceForSimulator_DiffDriven::resetNavigationTimer().

Here is the caller graph for this function:

◆ getVelCmdType()

CVehicleVelCmd::Ptr mrpt::kinematics::CVehicleSimul_Holo::getVelCmdType ( ) const
inlineoverridevirtual

Gets an empty velocity command object that can be queried to find out the number of velcmd components,...

Implements mrpt::kinematics::CVehicleSimulVirtualBase.

Definition at line 51 of file CVehicleSimul_Holo.h.

◆ internal_clear()

void CVehicleSimul_Holo::internal_clear ( )
overrideprivatevirtual

Resets all pending cmds.

Implements mrpt::kinematics::CVehicleSimulVirtualBase.

Definition at line 72 of file CVehicleSimul_Holo.cpp.

References m_vel_ramp_cmd.

◆ internal_simulControlStep()

void CVehicleSimul_Holo::internal_simulControlStep ( const double  dt)
overrideprivatevirtual

◆ resetStatus()

void CVehicleSimulVirtualBase::resetStatus ( )
inherited

Definition at line 73 of file CVehicleSimulVirtualBase.cpp.

References mrpt::kinematics::CVehicleSimulVirtualBase::internal_clear(), mrpt::kinematics::CVehicleSimulVirtualBase::m_GT_pose, mrpt::kinematics::CVehicleSimulVirtualBase::m_GT_vel, mrpt::kinematics::CVehicleSimulVirtualBase::m_odometric_vel, and mrpt::kinematics::CVehicleSimulVirtualBase::m_odometry.

Referenced by mrpt::kinematics::CVehicleSimul_DiffDriven::CVehicleSimul_DiffDriven(), and CVehicleSimul_Holo().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ resetTime()

void CVehicleSimulVirtualBase::resetTime ( )
inherited

Reset all simulator variables to 0 (except the.

simulation time).

See also
resetTime Reset time counter
resetStatus

Definition at line 82 of file CVehicleSimulVirtualBase.cpp.

References mrpt::kinematics::CVehicleSimulVirtualBase::m_time.

Referenced by mrpt::kinematics::CVehicleSimul_DiffDriven::CVehicleSimul_DiffDriven(), and CVehicleSimul_Holo().

Here is the caller graph for this function:

◆ sendVelCmd()

void mrpt::kinematics::CVehicleSimul_Holo::sendVelCmd ( const CVehicleVelCmd cmd_vel)
inlineoverridevirtual

Sends a velocity command to the robot.

The number of components and their meaning depends on the vehicle-kinematics derived class

Implements mrpt::kinematics::CVehicleSimulVirtualBase.

Definition at line 40 of file CVehicleSimul_Holo.h.

References ASSERTMSG_, cmd(), mrpt::kinematics::CVehicleSimulVirtualBase::m_odometry, mrpt::math::TPose2D::phi, and sendVelRampCmd().

Referenced by mrpt::nav::CRobot2NavInterfaceForSimulator_Holo::changeSpeeds().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ sendVelRampCmd()

void CVehicleSimul_Holo::sendVelRampCmd ( double  vel,
double  dir,
double  ramp_time,
double  rot_speed 
)

Sends a velocity cmd to the holonomic robot.

Parameters
[in]velLinear speed (m/s)
[in]dirDirection (rad) (In the odometry frame of reference)
[in]ramp_timeBlend the cmd during this period (seconds)
[in]rot_speedRotational speed while there is heading error and to this constant (rad/s)

Definition at line 73 of file CVehicleSimul_Holo.cpp.

References ASSERT_ABOVE_, dir, mrpt::kinematics::CVehicleSimul_Holo::TVelRampCmd::dir, mrpt::kinematics::CVehicleSimul_Holo::TVelRampCmd::init_vel, mrpt::kinematics::CVehicleSimul_Holo::TVelRampCmd::issue_time, mrpt::kinematics::CVehicleSimulVirtualBase::m_odometric_vel, mrpt::kinematics::CVehicleSimulVirtualBase::m_time, m_vel_ramp_cmd, mrpt::kinematics::CVehicleSimul_Holo::TVelRampCmd::ramp_time, mrpt::kinematics::CVehicleSimul_Holo::TVelRampCmd::rot_speed, mrpt::kinematics::CVehicleSimul_Holo::TVelRampCmd::target_vel_x, and mrpt::kinematics::CVehicleSimul_Holo::TVelRampCmd::target_vel_y.

Referenced by sendVelCmd(), and mrpt::nav::CRobot2NavInterfaceForSimulator_Holo::stop().

Here is the caller graph for this function:

◆ setCurrentGTPose()

void CVehicleSimulVirtualBase::setCurrentGTPose ( const mrpt::math::TPose2D pose)
inherited

Brute-force move robot to target coordinates ("teleport")

Definition at line 21 of file CVehicleSimulVirtualBase.cpp.

References mrpt::kinematics::CVehicleSimulVirtualBase::m_GT_pose.

◆ setCurrentOdometricPose()

template<typename T >
void mrpt::kinematics::CVehicleSimulVirtualBase::setCurrentOdometricPose ( const T &  pose)
inlineinherited

Brute-force overwrite robot odometry.

Definition at line 57 of file CVehicleSimulVirtualBase.h.

References mrpt::kinematics::CVehicleSimulVirtualBase::m_odometry.

◆ setOdometryErrors()

void mrpt::kinematics::CVehicleSimulVirtualBase::setOdometryErrors ( bool  enabled,
double  Ax_err_bias = 1e-3,
double  Ax_err_std = 10e-3,
double  Ay_err_bias = 1e-3,
double  Ay_err_std = 10e-3,
double  Aphi_err_bias = mrpt::DEG2RAD(1e-3),
double  Aphi_err_std = mrpt::DEG2RAD(10e-3) 
)
inlineinherited

◆ simulateOneTimeStep()

void CVehicleSimulVirtualBase::simulateOneTimeStep ( const double  dt)
inherited

Runs the simulator during "dt" seconds.

It will be split into periods of "m_firmware_control_period".

Definition at line 26 of file CVehicleSimulVirtualBase.cpp.

References mrpt::random::CRandomGenerator::drawGaussian1D_normalized(), mrpt::kinematics::CVehicleSimulVirtualBase::getCurrentOdometricVelLocal(), mrpt::random::getRandomGenerator(), mrpt::kinematics::CVehicleSimulVirtualBase::internal_simulControlStep(), mrpt::kinematics::CVehicleSimulVirtualBase::m_Aphi_err_bias, mrpt::kinematics::CVehicleSimulVirtualBase::m_Aphi_err_std, mrpt::kinematics::CVehicleSimulVirtualBase::m_Ax_err_bias, mrpt::kinematics::CVehicleSimulVirtualBase::m_Ax_err_std, mrpt::kinematics::CVehicleSimulVirtualBase::m_Ay_err_bias, mrpt::kinematics::CVehicleSimulVirtualBase::m_Ay_err_std, mrpt::kinematics::CVehicleSimulVirtualBase::m_firmware_control_period, mrpt::kinematics::CVehicleSimulVirtualBase::m_GT_pose, mrpt::kinematics::CVehicleSimulVirtualBase::m_GT_vel, mrpt::kinematics::CVehicleSimulVirtualBase::m_odometric_vel, mrpt::kinematics::CVehicleSimulVirtualBase::m_odometry, mrpt::kinematics::CVehicleSimulVirtualBase::m_time, mrpt::kinematics::CVehicleSimulVirtualBase::m_use_odo_error, mrpt::math::TTwist2D::omega, mrpt::math::TPose2D::phi, mrpt::math::TTwist2D::rotate(), mrpt::math::TTwist2D::vx, mrpt::math::TTwist2D::vy, mrpt::math::wrapToPiInPlace(), and mrpt::math::TPose2D::x.

Referenced by run_rnav_test().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ m_Aphi_err_bias

double mrpt::kinematics::CVehicleSimulVirtualBase::m_Aphi_err_bias
protectedinherited

◆ m_Aphi_err_std

double mrpt::kinematics::CVehicleSimulVirtualBase::m_Aphi_err_std
protectedinherited

◆ m_Ax_err_bias

double mrpt::kinematics::CVehicleSimulVirtualBase::m_Ax_err_bias
protectedinherited

◆ m_Ax_err_std

double mrpt::kinematics::CVehicleSimulVirtualBase::m_Ax_err_std
protectedinherited

◆ m_Ay_err_bias

double mrpt::kinematics::CVehicleSimulVirtualBase::m_Ay_err_bias
protectedinherited

◆ m_Ay_err_std

double mrpt::kinematics::CVehicleSimulVirtualBase::m_Ay_err_std
protectedinherited

◆ m_firmware_control_period

double mrpt::kinematics::CVehicleSimulVirtualBase::m_firmware_control_period {500e-6}
protectedinherited

The period at which the low-level controller updates velocities (Default: 0.5 ms)

Definition at line 128 of file CVehicleSimulVirtualBase.h.

Referenced by mrpt::kinematics::CVehicleSimulVirtualBase::simulateOneTimeStep().

◆ m_GT_pose

mrpt::math::TPose2D mrpt::kinematics::CVehicleSimulVirtualBase::m_GT_pose
protectedinherited

◆ m_GT_vel

mrpt::math::TTwist2D mrpt::kinematics::CVehicleSimulVirtualBase::m_GT_vel
protectedinherited

◆ m_odometric_vel

mrpt::math::TTwist2D mrpt::kinematics::CVehicleSimulVirtualBase::m_odometric_vel
protectedinherited

◆ m_odometry

mrpt::math::TPose2D mrpt::kinematics::CVehicleSimulVirtualBase::m_odometry
protectedinherited

◆ m_time

double mrpt::kinematics::CVehicleSimulVirtualBase::m_time
protectedinherited

◆ m_use_odo_error

bool mrpt::kinematics::CVehicleSimulVirtualBase::m_use_odo_error {false}
protectedinherited

◆ m_vel_ramp_cmd

TVelRampCmd mrpt::kinematics::CVehicleSimul_Holo::m_vel_ramp_cmd
private

the last cmd received from the user.

Definition at line 70 of file CVehicleSimul_Holo.h.

Referenced by internal_clear(), internal_simulControlStep(), and sendVelRampCmd().




Page generated by Doxygen 1.8.14 for MRPT 2.0.4 Git: 33de1d0ad Sat Jun 20 11:02:42 2020 +0200 at sáb jun 20 17:35:17 CEST 2020