MRPT  1.9.9
CVehicleSimul_DiffDriven.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include "kinematics-precomp.h" // Precompiled header
11 
13 
14 using namespace mrpt::kinematics;
15 
17 {
18  resetStatus();
19  resetTime();
20 }
23 {
24  Command_Time = .0;
25  Command_v = .0;
26  Command_w = .0;
27  m_v = m_w = 0;
28 }
29 
31 {
32  // Change velocities:
33  // ----------------------------------------------------------------
34  double elapsed_time = this->m_time - Command_Time;
35  elapsed_time -= cDELAY;
36  elapsed_time = std::max(0.0, elapsed_time);
37 
38  if (cTAU == 0 && cDELAY == 0)
39  {
40  m_v = Command_v;
41  m_w = Command_w;
42  }
43  else
44  {
45  m_v = Command_v0 +
46  (Command_v - Command_v0) * (1 - exp(-elapsed_time / cTAU));
47  m_w = Command_w0 +
48  (Command_w - Command_w0) * (1 - exp(-elapsed_time / cTAU));
49  }
50 
51  // Local to global frame:
55 }
56 
57 /*************************************************************************
58  Gives a movement command to the robot:
59  This actually saves the command for execution later on, if we have
60  to take into account the robot low-pass behavior in velocities.
61 *************************************************************************/
62 void CVehicleSimul_DiffDriven::movementCommand(double lin_vel, double ang_vel)
63 {
64  // Just save the command:
66  Command_v = lin_vel;
67  Command_w = ang_vel;
68 
69  // Current values:
70  Command_v0 = m_v;
71  Command_w0 = m_w;
72 }
double cDELAY
The delay constant for the velocities changes.
mrpt::math::TTwist2D m_odometric_vel
Velocity in (x,y,omega)
double m_v
lin & angular velocity in the robot local frame.
double cTAU
The time-constants for the first order low-pass filter for the velocities changes.
double Command_Time
Dynamic limitations of the robot.
double vx
Velocity components: X,Y (m/s)
Definition: TTwist2D.h:26
void movementCommand(double lin_vel, double ang_vel)
Used to command the robot a desired movement:
void resetTime()
Reset all simulator variables to 0 (except the.
void internal_clear() override
Resets all pending cmds.
double phi
Orientation (rads)
Definition: TPose2D.h:32
double omega
Angular velocity (rad/s)
Definition: TTwist2D.h:28
void internal_simulControlStep(const double dt) override



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020