NimbRo ROS Soccer Package
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
gait_interface.h
1 // Interface classes for data exchange between the generic gait motion module and gait engines
2 // File: gait_interface.h
3 // Author: Philipp Allgeuer <pallgeuer@ais.uni-bonn.de>
4 
5 // Ensure header is only included once
6 #ifndef GAIT_INTERFACE_H
7 #define GAIT_INTERFACE_H
8 
9 // Includes
10 #include <gait/gait_common.h>
11 #include <gait/gait_command.h>
12 
13 // Gait namespace
14 namespace gait
15 {
23  {
26 
28  void reset()
29  {
30  for(int i = 0; i < NUM_JOINTS; i++)
31  jointPos[i] = 0.0;
32  timestamp = 0.0;
33  nominaldT = 0.0;
34  truedT = 0.0;
35  gaitCmd.reset();
36  motionPending = false;
37  motionID = MID_NONE;
38  motionStance = STANCE_DEFAULT;
39  motionAdjustLeftFoot = false;
40  motionAdjustRightFoot = false;
41  }
42 
43  // Joint states
44  double jointPos[NUM_JOINTS];
45 
46  // System parameters
47  double timestamp;
48  double nominaldT;
49  double truedT;
50 
51  // Gait command
53 
54  // Motion parameters
60  };
61 
69  {
72 
74  void reset()
75  {
76  for(int i = 0; i < NUM_JOINTS; i++)
77  {
78  jointCmd[i] = 0.0;
79  jointEffort[i] = 0.0;
80  }
81  useRawJointCmds = false;
82  walking = false;
83  supportCoeffLeftLeg = 0.0;
85  for(int i = 0; i < 3; i++)
86  {
87  odomPosition[i] = 0.0;
88  odomOrientation[i+1] = 0.0;
89  }
90  odomOrientation[0] = 1.0;
91  }
92 
93  // Joint commands
94  double jointCmd[NUM_JOINTS];
95  double jointEffort[NUM_JOINTS];
97 
98  // Status flags
99  bool walking;
100 
101  // Support coefficients
104 
105  // Robot odometry transform
106  double odomPosition[3];
107  double odomOrientation[4];
108  };
109 }
110 
111 #endif /* GAIT_INTERFACE_H */
112 // EOF
MotionID
Enumeration of motion IDs that can be used in the GaitCommand::motion field to trigger motions throug...
Definition: gait_common.h:85
Gait command data structure.
Definition: gait_command.h:20
double timestamp
The current time in seconds (guaranteed to be monotonic increasing)
Definition: gait_interface.h:47
Data struct for passing gait engine output data from the gait engine to the generic gait motion modul...
Definition: gait_interface.h:68
GaitEngineInput()
Default constructor.
Definition: gait_interface.h:25
bool motionAdjustRightFoot
Boolean flag whether the right foot should be used to adjust the stopping stance. ...
Definition: gait_interface.h:59
double jointEffort[NUM_JOINTS]
Commanded joint effort (indexed by the JointID enum, in the range [0,1]).
Definition: gait_interface.h:95
bool walking
Flag specifying whether the gait is currently active and walking (true) or halted (false)...
Definition: gait_interface.h:99
MotionID motionID
The ID of the motion that is pending.
Definition: gait_interface.h:56
MotionStance
Enumeration of motion stances that can be commanded to a gait engine.
Definition: gait_common.h:107
void reset()
Reset function.
Definition: gait_interface.h:74
void reset(bool shouldWalk=false)
Reset function.
Definition: gait_command.h:26
double odomPosition[3]
Position (x,y,z) of the robot's body-fixed base transform (centred at the robot's centre of mass) in ...
Definition: gait_interface.h:106
double nominaldT
The nominal time between calls to the gait engine's step() function.
Definition: gait_interface.h:48
double odomOrientation[4]
Orientation (w,x,y,z) of the robot's body-fixed base transform (centred at the robot's centre of mass...
Definition: gait_interface.h:107
GaitCommand gaitCmd
Gait command (e.g. desired walking velocity and so on).
Definition: gait_interface.h:52
GaitEngineOutput()
Default constructor.
Definition: gait_interface.h:71
bool motionAdjustLeftFoot
Boolean flag whether the left foot should be used to adjust the stopping stance.
Definition: gait_interface.h:58
double jointCmd[NUM_JOINTS]
Commanded position for each joint (indexed by the JointID enum, in rad).
Definition: gait_interface.h:94
Data struct for passing gait engine input data from the generic gait motion module to the gait engine...
Definition: gait_interface.h:22
MotionStance motionStance
The stopping stance required for the playing of the pending motion.
Definition: gait_interface.h:57
double truedT
The true time since the last call to the gait engine's step() function. This value is coerced to avoi...
Definition: gait_interface.h:49
void reset()
Reset function.
Definition: gait_interface.h:28
bool useRawJointCmds
Apply the joint commands directly to the hardware, without using compensation or actuator controller(...
Definition: gait_interface.h:96
double jointPos[NUM_JOINTS]
Current measured position of each joint (indexed by the JointID enum, in rad).
Definition: gait_interface.h:44
bool motionPending
Boolean flag whether a motion is pending.
Definition: gait_interface.h:55
double supportCoeffLeftLeg
Current support coefficient of the left leg.
Definition: gait_interface.h:102
double supportCoeffRightLeg
Current support coefficient of the right leg.
Definition: gait_interface.h:103