NimbRo ROS Soccer Package
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
gait_engine.h
1 // Base class for all gait engines
2 // File: gait_engine.h
3 // Author: Philipp Allgeuer <pallgeuer@ais.uni-bonn.de>
4 
5 // Ensure header is only included once
6 #ifndef GAIT_ENGINE_H
7 #define GAIT_ENGINE_H
8 
9 // Includes
10 #include <gait/gait_common.h>
11 #include <gait/gait_interface.h>
12 
13 // Forwards declarations
14 namespace robotcontrol
15 {
16  class RobotModel;
17 }
18 
19 // Gait namespace
20 namespace gait
21 {
22  // Class forward declarations
23  class Gait;
24 
30  class GaitEngine
31  {
32  public:
35  : model(NULL)
36  , haltJointCmd()
37  , haltJointEffort()
38  , haltUseRawJointCmds(false)
39  , m_gait(NULL)
40  , m_posX(0.0)
41  , m_posY(0.0)
42  , m_rotZ(0.0)
43  {
44  in.reset();
45  out.reset();
48  }
49 
51  virtual ~GaitEngine() {}
52 
61  virtual void reset() {}
62 
76  virtual void updateHaltPose();
77 
90  virtual void step();
91 
102  virtual void setOdometry(double posX, double posY, double rotZ);
103 
113  virtual void updateOdometry();
114 
122  virtual void handleJoystickButton(int button) {}
123 
124  // Gait engine data interface structs
127 
128  protected:
135  const robotcontrol::RobotModel* model;
136 
143  void resetBase()
144  {
145  in.reset();
146  out.reset();
147  updateHaltPose();
148  m_posX = 0.0;
149  m_posY = 0.0;
150  m_rotZ = 0.0;
151  }
152 
153  // Halt pose specification
154  double haltJointCmd[NUM_JOINTS];
155  double haltJointEffort[NUM_JOINTS];
157 
158  // Pointer to the owning gait class
159  const Gait* m_gait;
160 
161  private:
162  // Internal variables
163  double m_posX;
164  double m_posY;
165  double m_rotZ;
166 
167  // Function to set gait owner
168  void setGaitOwner(const Gait* gaitPtr) { m_gait = gaitPtr; }
169 
170  // Friend classes
171  friend class Gait;
172  };
173 }
174 
175 #endif /* GAIT_ENGINE_H */
176 // EOF
Base implementation of a gait engine, made to work with the Gait motion module.
Definition: gait_engine.h:30
virtual void setOdometry(double posX, double posY, double rotZ)
Set the CoM odometry to a particular 2D position and orientation.
Definition: gait_engine.cpp:63
double haltJointCmd[NUM_JOINTS]
Commanded halt position for each joint (indexed by the JointID enum, in rad).
Definition: gait_engine.h:154
bool haltUseRawJointCmds
Apply the joint commands directly to the hardware in the halt pose, without using compensation or act...
Definition: gait_engine.h:156
Generic gait motion module that can execute a given GaitEngine.
Definition: gait.h:54
GaitEngine()
Default constructor.
Definition: gait_engine.h:34
Data struct for passing gait engine output data from the gait engine to the generic gait motion modul...
Definition: gait_interface.h:68
const robotcontrol::RobotModel * model
Pointer to the RobotModel object to use for retrieving state information in each step.
Definition: gait_engine.h:135
GaitEngineOutput out
Gait engine output data struct.
Definition: gait_engine.h:126
virtual ~GaitEngine()
Default destructor.
Definition: gait_engine.h:51
virtual void handleJoystickButton(int button)
Notify the gait engine that a particular joystick button has been pressed and released by the user...
Definition: gait_engine.h:122
void reset()
Reset function.
Definition: gait_interface.h:74
double haltJointEffort[NUM_JOINTS]
Commanded halt joint effort (indexed by the JointID enum, in the range [0,1]).
Definition: gait_engine.h:155
virtual void updateOdometry()
Force an update of the CoM odometry in terms of 3D position and orientation.
Definition: gait_engine.cpp:75
virtual void updateHaltPose()
Update the halt pose desired by the gait engine.
Definition: gait_engine.cpp:46
virtual void step()
Main step function of the gait engine.
Definition: gait_engine.cpp:21
void resetBase()
Reset the GaitEngine base class.
Definition: gait_engine.h:143
GaitEngineInput in
Gait engine input data struct.
Definition: gait_engine.h:125
Data struct for passing gait engine input data from the generic gait motion module to the gait engine...
Definition: gait_interface.h:22
virtual void reset()
Reset the gait engine.
Definition: gait_engine.h:61
void reset()
Reset function.
Definition: gait_interface.h:28