NimbRo ROS Soccer Package
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
gait_common.h
1 // Common definitions for the generic gait motion module and underlying gait engines
2 // File: gait_common.h
3 // Author: Philipp Allgeuer <pallgeuer@ais.uni-bonn.de>
4 
5 // Ensure header is only included once
6 #ifndef GAIT_COMMON_H
7 #define GAIT_COMMON_H
8 
9 // Includes
10 #include <gait_msgs/GaitCommand.h>
11 #include <string>
12 
13 // Gait namespace
14 namespace gait
15 {
17  enum JointID
18  {
19  ARMS_BEGIN,
20  LEFT_ARM_BEGIN = ARMS_BEGIN,
21  L_SHOULDER_PITCH = LEFT_ARM_BEGIN,
22  L_SHOULDER_ROLL,
23  L_ELBOW_PITCH,
24  LEFT_ARM_END = L_ELBOW_PITCH,
25 
26  RIGHT_ARM_BEGIN,
27  R_SHOULDER_PITCH = RIGHT_ARM_BEGIN,
28  R_SHOULDER_ROLL,
29  R_ELBOW_PITCH,
30  RIGHT_ARM_END = R_ELBOW_PITCH,
31  ARMS_END = RIGHT_ARM_END,
32 
33  LEGS_BEGIN,
34  LEFT_LEG_BEGIN = LEGS_BEGIN,
35  L_HIP_YAW = LEFT_LEG_BEGIN,
36  L_HIP_ROLL,
37  L_HIP_PITCH,
38  L_KNEE_PITCH,
39  L_ANKLE_PITCH,
40  L_ANKLE_ROLL,
41  LEFT_LEG_END = L_ANKLE_ROLL,
42 
43  RIGHT_LEG_BEGIN,
44  R_HIP_YAW = RIGHT_LEG_BEGIN,
45  R_HIP_ROLL,
46  R_HIP_PITCH,
47  R_KNEE_PITCH,
48  R_ANKLE_PITCH,
49  R_ANKLE_ROLL,
50  RIGHT_LEG_END = R_ANKLE_ROLL,
51  LEGS_END = RIGHT_LEG_END,
52 
53  NUM_JOINTS
54  };
55 
57  const std::string jointName[NUM_JOINTS] = {
58  "left_shoulder_pitch", // <-- LEFT_ARM_BEGIN
59  "left_shoulder_roll", // ...
60  "left_elbow_pitch", // <-- LEFT_ARM_END
61 
62  "right_shoulder_pitch", // <-- RIGHT_ARM_BEGIN
63  "right_shoulder_roll", // ...
64  "right_elbow_pitch", // <-- RIGHT_ARM_END
65 
66  "left_hip_yaw", // <-- LEFT_LEG_BEGIN
67  "left_hip_roll", // ...
68  "left_hip_pitch", // ...
69  "left_knee_pitch", // ...
70  "left_ankle_pitch", // ...
71  "left_ankle_roll", // <-- LEFT_LEG_END
72 
73  "right_hip_yaw", // <-- RIGHT_LEG_BEGIN
74  "right_hip_roll", // ...
75  "right_hip_pitch", // ...
76  "right_knee_pitch", // ...
77  "right_ankle_pitch", // ...
78  "right_ankle_roll" // <-- RIGHT_LEG_END
79  };
80 
82  const std::string gaitOdomFrame = "/odom_gait";
83 
85  enum MotionID
86  {
87  MID_NONE,
88  MID_KICK_LEFT,
89  MID_KICK_RIGHT,
90  MID_DIVE_LEFT,
91  MID_DIVE_RIGHT,
92  MID_DIVE_SIT,
93  MID_COUNT
94  };
95 
97  static const std::string motionName[MID_COUNT] = {
98  "",
99  "kick_left",
100  "kick_right",
101  "left_dive",
102  "right_dive",
103  "sit_dive"
104  };
105 
108  {
109  STANCE_DEFAULT,
110  STANCE_KICK,
111  STANCE_COUNT
112  };
113 
115  inline void resetGaitCommand(gait_msgs::GaitCommand& cmd)
116  {
117  // Reset the gait command to its default values
118  cmd.gcvX = cmd.gcvY = cmd.gcvZ = 0.0;
119  cmd.walk = false;
120  cmd.motion = MID_NONE;
121  }
122 }
123 
124 #endif
125 // EOF
MotionID
Enumeration of motion IDs that can be used in the GaitCommand::motion field to trigger motions throug...
Definition: gait_common.h:85
MotionStance
Enumeration of motion stances that can be commanded to a gait engine.
Definition: gait_common.h:107
JointID
ID list of joints used by the gait motion module.
Definition: gait_common.h:17
const std::string jointName[NUM_JOINTS]
List of names of the joints that are required by the gait motion module (indexed by the JointID enum)...
Definition: gait_common.h:57
void resetGaitCommand(gait_msgs::GaitCommand &cmd)
Reset a gait command to zero.
Definition: gait_common.h:115
const std::string gaitOdomFrame
Name of the tf frame that is used for publishing the gait odometry.
Definition: gait_common.h:82