Enki  1.9
DifferentialWheeled.h
Go to the documentation of this file.
1 /*
2  Enki - a fast 2D robot simulator
3  Copyright (C) 1999-2016 Stephane Magnenat <stephane at magnenat dot net>
4  Copyright (C) 2004-2005 Markus Waibel <markus dot waibel at epfl dot ch>
5  Copyright (c) 2004-2005 Antoine Beyeler <abeyeler at ab-ware dot com>
6  Copyright (C) 2005-2006 Laboratory of Intelligent Systems, EPFL, Lausanne
7  Copyright (C) 2006-2008 Laboratory of Robotics Systems, EPFL, Lausanne
8  See AUTHORS for details
9 
10  This program is free software; the authors of any publication
11  arising from research using this software are asked to add the
12  following reference:
13  Enki - a fast 2D robot simulator
14  http://home.gna.org/enki
15  Stephane Magnenat <stephane at magnenat dot net>,
16  Markus Waibel <markus dot waibel at epfl dot ch>
17  Laboratory of Intelligent Systems, EPFL, Lausanne.
18 
19  You can redistribute this program and/or modify
20  it under the terms of the GNU General Public License as published by
21  the Free Software Foundation; either version 2 of the License, or
22  (at your option) any later version.
23 
24  This program is distributed in the hope that it will be useful,
25  but WITHOUT ANY WARRANTY; without even the implied warranty of
26  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
27  GNU General Public License for more details.
28 
29  You should have received a copy of the GNU General Public License
30  along with this program; if not, write to the Free Software
31  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
32 */
33 
34 #ifndef __ENKI_DIFFERENTIAL_WHEELED_H
35 #define __ENKI_DIFFERENTIAL_WHEELED_H
36 
41 #include <enki/PhysicalEngine.h>
42 
43 namespace Enki
44 {
45  class DifferentialWheeled: public virtual Robot
46  {
47  public:
49  double leftSpeed;
51  double rightSpeed;
52 
54  double leftEncoder;
56  double rightEncoder;
58  double leftOdometry;
60  double rightOdometry;
61 
62  protected:
66  double maxSpeed;
68  double noiseAmount;
69 
70  private:
72  double cmdAngSpeed;
74  double cmdSpeed;
75 
76  public:
78  DifferentialWheeled(double distBetweenWheels, double maxSpeed, double noiseAmount);
79 
81  void resetEncoders();
82 
84  virtual void controlStep(double dt);
86  virtual void applyForces(double dt);
87  };
88 }
89 
90 #endif
virtual void applyForces(double dt)
Consider that robot wheels have immobile contact points with ground, and override speeds...
Definition: DifferentialWheeled.cpp:98
double distBetweenWheels
Distance between the left and right driving wheels.
Definition: DifferentialWheeled.h:64
void resetEncoders()
Reset the encoder. Should be called when robot is moved manually. Odometry is cleared too...
Definition: DifferentialWheeled.cpp:63
Definition: DifferentialWheeled.h:45
virtual void controlStep(double dt)
Set the real speed of the robot given leftSpeed and rightSpeed. Add noise. Update encoders...
Definition: DifferentialWheeled.cpp:69
DifferentialWheeled(double distBetweenWheels, double maxSpeed, double noiseAmount)
Constructor.
Definition: DifferentialWheeled.cpp:52
double leftEncoder
The encoder for left wheel; this is not a real encoder, but rather the physical leftSpeed.
Definition: DifferentialWheeled.h:54
Enki is the namespace of the Enki simulator. All Enki functions and classes excepted the math one are...
Definition: BluetoothBase.cpp:44
double leftSpeed
Left speed of the robot.
Definition: DifferentialWheeled.h:49
double cmdAngSpeed
Resulting angular speed from wheels.
Definition: DifferentialWheeled.h:72
double rightOdometry
The odometry (accumulation of encoders) for right wheel.
Definition: DifferentialWheeled.h:60
double leftOdometry
The odometry (accumulation of encoders) for left wheel.
Definition: DifferentialWheeled.h:58
double cmdSpeed
Resulting tangent speed from wheels.
Definition: DifferentialWheeled.h:74
double rightSpeed
Reft speed of the robot.
Definition: DifferentialWheeled.h:51
double noiseAmount
Relative amount of motor noise.
Definition: DifferentialWheeled.h:68
double rightEncoder
The encoder for right wheel; this is not a real encoder, but rather the physical rightSpeed.
Definition: DifferentialWheeled.h:56
The core of Enki.
double maxSpeed
Maximum speed wheels can provide.
Definition: DifferentialWheeled.h:66
A robot is a PhysicalObject that has additional interactions and a controller.
Definition: PhysicalEngine.h:379