Full Body Pose Estimation for Sports Analysis - Pose Representation

From RidgeRun Developer Wiki



Previous: 3D Pose Estimation Index Next: Skeleton Calibration




Introduction

The pose representation library is intended to model the movement of any type of skeleton. This is done by using a kinematic tree representation, which means that each skeleton joint has a parent joint defined, and this one is going to serve as its reference to calculate the absolute position.

Figure 1. Pose representation module location in general workflow

Basic Concepts

This library is intended to work with any type of skeleton, however, for clarity, we will use the human skeleton as an example. The diagram shown in Figure 1 explains many of the concepts we will present here.

Figure 2: Skeleton diagram.

Coordinate Systems

There are two types of coordinate systems necessary to compute the absolute positions. These are the local and global coordinate systems.

Global Coordinate System

The global coordinate system is also known as the world coordinate system, and it is the one that all local coordinate systems take as reference. This coordinate system represents all the absolute positions and it is defined arbitrarily, but following the right-hand rule.

Local Coordinate Systems

Each joint will have its own coordinate system, which will not necessarily be equal to the global one. This can be seen in Figure 1, where not all joints have the same pointing directions for the x, y, and z axes. You can define the coordinate systems as you please, the only convention here is to orient each joint local coordinate system in a way that the +x axis points to the parent location. Since the root joint is its own parent, it cannot point to itself, then it is recommended that its local coordinate system is the same as the global one. These systems also follow the right-hand rule.

Joints

As we mentioned before, the kinematic tree is a structure where each node or joint has a parent. Since it is a tree structure, it has a root joint that will be the base of the tree, and whose parent will be that same root. In Figure 1 this tree structure can be seen by following the red axes in the local coordinate systems because they all point to their parent joints.

There are two types of joints, the invisible and the visible ones. You should mark them differently to keep in mind that ones will be shown and the others will not. However, all of them need their own local coordinate system and parent, since it will be important to model the movement. The invisible joints are used to add rotation movement in certain joints, therefore they must be located in the same place as the joint which they will improve movement for. They are called invisible because they are in the same place of visible ones and also they have a length of zero.

Limbs

Due to the tree structure, it is understood that a limb is always the bone between a joint and its parent. Then, when we want to refer to a specific limb it is enough to provide the ID of the child joint of that limb.

Kinematic Chain

This is another name given to the kinematic tree structure. It is a set of joints related through a parent-child relationship that allows to model the skeleton using relative rotations and translations instead of absolute 3D positions. It is called a chain because every joint is related to another joint, therefore from any joint we start, we will be able to reach the root. However, this chain is unidirectional, which means that it is meant to be followed only in the child-to-parent direction.

Position Computing

This is a recursive algorithm that computes the joint position from the perspective of all the other joints in the kinematic chain until it reaches the root joint. This may be seen in a better way following the next example.

Let us have the kinematic chain Left Ankle --> Left Knee --> Left Hip --> Pelvis taken from Figure 1. Here the joint on the left side of the arrow is the child, and the one on the right side is the parent.

To compute the position from the parent point of view we need the equation:

where:

  • is the position from the joint's parent point of view.
  • is the rotation matrix that maps the position from the joint's coordinate system to the joint's parent coordinate system. This matrix is obtained by the product where and are the rotation matrices needed to align the parent's and child coordinate systems, respectively, with the world coordinate system.
  • is the last position computed for the joint, which starts as at the iteration of the algorithm.
  • is the translation of the joint from the parent point of view.

Now, following with the example, if we want to compute the absolute position of the Left Ankle we will compute the position from the Left Knee, Left Hip and finally from the Pelvis points of view:

1.

2.

3.

Since the pelvis is the root and we already calculated the Left Ankle position from its point of view, then the algorithm stops.

Note that at the first step is , since the Left Ankle is at the origin of it's own coordinate system.

The skeleton structure precalculates the and variables, leaving as unknown only the positions from the different points of view.

Skeleton Movement

The skeleton movement is done through rotations on each of its joints. Each joint may rotate around any of its three axes with angles in the range [-180°, 180°]. These rotations follow the ZYX order and are extrinsic. This means that they take as a reference to a fixed coordinate system (the global one) that does not change along with the rotations.

Note that since this is a kinematic chain, when you rotate a joint, all of its children will move as well.

There are two types of rotations:

  • Base pose rotation: the rotation is applied from the initial pose of the skeleton:

  • Current pose rotation: the rotation is applied from the current pose of the skeleton:

Pose Generation

There are two ways of using the library for generating skeleton poses:

Manual

In this case, you may call each of the joints and assign them a rotation angle in its different axes. This is useful when you need to model very specific poses.

Random Generation Feature

Here, the library will choose a random angle from the given range for all the axes of each joint. This will generate a random pose with uniformly distributed rotation angles.

There is also an option to set a range of "common" rotation angles. This may be used in cases when a joint has a given range of angles but it is more likely that it rotates in just a smaller subrange from the original. For example, in the human skeleton, it is more likely that we keep our arms down most of the time, even though we can have them up. In this case, you can set optionally in the configuration file, a mean and a standard deviation for describing the probability of the rotation angles using a normal distribution.

Examples

Here we present some examples of uses that you can give to the library. If you are interested in how they were implemented, check section 7.

Human Skeleton Movement

Here we show in Figure 2 the model of a human skeleton doing a simple movement routine. This is done by increasing the rotation angles every frame and then decreasing it to return to the base position.

Figure 3. Example of human skeleton movement.

Dog Skeleton Movement

Figure 3 shows the almost same movement routine, but this time applied to a dog skeleton. In order to do this, we just needed to provide a configuration file with the description of the dog skeleton joints and assign the rotation angles to the corresponding joints. This shows how the library is suitable for any type of skeleton.

Figure 4. Example of dog skeleton movement.

Pose Generation

In Figure 4 we present a sequence of randomly generated poses obtained with the random pose generation feature. These are "common" poses achieved by providing the parameters of the normal distributions for each joint rotation angles.

Figure 5. Example of human random pose generation.

How to Use the Module

Skeleton JSON File

All the relationships between joints and its parents, among other properties, are defined within a JSON file that serves as input to create the skeleton structure. Here we will explain the JSON properties using as an example the human skeleton shown on Figure 1, but remember that the concepts are applicable to any type of skeleton.

global_rotations_zyx

In order to compute each joint relative rotation to its parent, you should provide the rotations required to align the joint own coordinate system with the global coordinate system.

These rotations are provided as a list of lists of three elements that include the rotation angles in degrees in z, y, x order. Since some joints may have the same type of coordinate system orientation, such as the neck and the nose (see Figure 1), just provide the rotation needed to align this type with the global coordinate system once, in order to avoid repeating elements in the list. In the end, you should have a list of the size of the number of different local coordinate systems orientations.

These angles are applied consecutively but taking as a reference to the global coordinate system. In Figure 5 it can be seen that rotations are applied in the z, y, x order and at the end of the sequence the joint coordinate system is the same as the global one.

Figure 6. Example of how rotations are applied

These rotations can be added to the list in any order, just keep in mind that order, since in the joints definition you will have to provide in the global_rotation property which of these rotations corresponds to that joint.

Example: In the human example in Figure 1 we have 5 different coordinate system orientations. This can be seen by grouping all the joints that have the x, y, z axes pointing in the same directions, and then counting the number of groups. These coordinate systems would need the following rotations to align with the global coordinate system:

 "global_rotations_zyx": [
    [0,90,90],  #for 0, 1, 15, 16 and 17
    [0,180,0],  #for 9 and 12
    [0,0,180],  #for 3 and 6
    [0,-90,-90],#for 4, 5, 7, 8, 10, 11, 13 and 14 
    [0,0,0]     #for 2 and 18
 ]

joints

The main component of the skeleton definition is the joints property, which is a list of JSON objects with the following properties:

  • id: identifier number of the joint.
  • name: identifier string of the joint.
  • freedom_degrees: list of three elements that could be either 1 or 0 to indicate if movement along the x, y, and z axes is allowed or not.

Example: [1,0,1] means the movement is allowed in x and z axes but not in y.

  • angle_ranges: list of six elements defining the minimum and maximum rotation angles values in degrees for x, y, z in the following order: [min_x,max_x,min_y,max_y,min_z,max_z]. These angle values can go from [-180,180]. Also, remember that these angles are set according to the local coordinate systems that you defined for each joint.

Example:

 "angle_ranges": [-45,45,0,90,-90,0]
  • parent_id: identifier number of the parent joint in the kinematic chain.

Example: in Figure 1, all the joints +x axes (red), except for the pelvis, are pointing to its parent joint. Then, if we take as an example the left knee (7) its parent id would be 6.

  • global_rotation: list index pointing to which of the global rotations defined above is applied to align the joint local coordinate system with the global coordinate system.

Example: for the neck (15), it is necessary to apply a rotation of 0° in z, 90° in y, and 90° in x in order to align its coordinate system with the global one, so according to the global rotations defined above it would be

 "global_rotation": 0
  • length: distance from the joint to its parent.

Special cases:

1. Invisible joints must have a value of 0.

2. The root joint must have a value of -1 in order to indicate that it is its own parent.

  • mu_sigma (optional): list of six elements with mu and sigma of common movement angle ranges for x, y, z axes, where mu and sigma are the mean and standard deviation in a Gaussian distribution. The order of the elements is [mu_x,sigma_x,mu_y,sigma_y,mu_z,sigma_z]. This property is useful mainly for random pose generation.

Example: [0,10,10,5,0,20] means that the joint most probable angles are at 0°, 10°, and 0° for x, y, and z axes respectively. Also, the Gaussian distribution establishes that 99.7% of the values must be within -3 sigma and 3 sigma which means that the angles for the x, y, and z axes could be in the [-30,30], [-5,25], [-60,60] ranges respectively.

  • base_translation: list of three elements that could be either 0, 1 or -1 to indicate if the joint is along the x, -x, y, -y, z, or -z direction from the parent viewpoint. Invisible joints must have all the elements as 0, since they are located in the same place as its parents.

Example: the left elbow (4) is on the -z axis direction from its parent (3) viewpoint. Therefore this property would be

 "base_translation" : [0,0,-1]

Note: Be sure to order the joints definition according to its id for clarity.

root_id

This is the id of the joint that will be the root of the kinematic tree.

  • Example: in the human skeleton above the pelvis is the root
       "root_id": 2

Example

For the human skeleton whole example check the JSON file here.

Colors JSON File

The pose representation module includes a class for visualization. Using this class you can plot different skeletons of the same type. The skeleton visualizer class uses as input a skeleton object and a colors JSON.

The colors JSON contains only the colors property. This is a list of strings with hexadecimal color codes for the joints described in the skeleton definition. There must be a color code for each joint defined.

You can keep different color files since there is an option for assigning different color schemes to each plotted skeleton.

  • Example:
 {
   "colors":[
     "#e30909",
     "#bd0dd1",
     "#eff542", 
     "#add10d", 
     "#d17c0d", 
     "#0dc1d1", 
     "#0d6cd1", 
     "#d1c40d", 
     "#b40dd1", 
     "#07dff2", 
     "#0c9454", 
     "#94520c", 
     "#f22c96", 
     "#f54242", 
     "#eff542",
     "#07dff2",
     "#d1c40d",
     "#f22c96",
     "#e30909"
   ]
 }

You can find an example of the colors JSON file for a human skeleton here.

How to Create and Plot a Skeleton

Figure 7. Example of plotting skeleton in its base pose.

Here is an example of how to plot a skeleton on its base pose in two different canvases with different color schemes.

#Define the skeleton and colors json
COLORS_1_JSON = "path/to/colors1/json"
COLORS_2_JSON = "path/to/colors2/json"
SKELETON_JSON = "path/to/skeleton/json"
  
#Create the skeleton object
skeleton = Skeleton(SKELETON_JSON)

#Create the visualizer object and set the number of skeletons and colors for each one
skeleton_visualizer = SkeletonVisualizer3D(skeleton)
skeleton_visualizer.create_skeleton_scenes(2, [COLORS_1_JSON, COLORS_2_JSON])

#Get the skeleton positions
skeleton_positions = skeleton.get_pose()
  
#Plot the skeletons providing a list of skeleton positions according to the number 
#of skeletons and a list of the labels for each plot. In this case it is 2 plots
#but the same skeleton.
skeleton_visualizer.plot_skeletons([skeleton_positions, skeleton_positions], 
                                   ["Color Scheme 1", "Color Scheme 2"])

After running this code with the JSON files provided here you should see something like Figure 6.

How to Generate Movement for a Skeleton

Here we will show how the movement in Figure 2 was generated. Remember that the joint's names that you use depend on the skeleton JSON file.

#Define the skeleton and colors json
COLORS_JSON = "path/to/colors/json"
SKELETON_JSON = "path/to/skeleton/json"
  
#Create the skeleton object
skeleton = Skeleton(SKELETON_JSON)

#Create the visualizer object and set the number of skeletons and colors
skeleton_visualizer = SkeletonVisualizer3D(skeleton)
skeleton_visualizer.create_skeleton_scenes(1, [COLORS_JSON])

#Loops for angle variation (movement)

#We will rotate from 0 to 80 degrees from the base pose in the shoulders y 
#axes and in the hips x axes. Remember the rotation order is z,y,x.
 
for i in range(80):
    skeleton.rotate_joint("Left_Shoulder", 0, i, 0)
    skeleton.rotate_joint("Right_Shoulder", 0, i, 0)
    skeleton.rotate_joint("Left_Hip", 0, 0, i)
    skeleton.rotate_joint("Right_Hip", 0, 0, i)

    #Plotting. There's a third argument for the function to indicate how much
    #time to wait before the next update. If no argument is provided, as in this
    #case, the plot will be updated when pressing any key.
    skeleton_visualizer.plot_skeletons([skeleton.get_pose()], ["Human"])

#We will rotate from 80 to 0 degrees by decreasing the angle from the current pose 
#in the shoulders y axes and in the hips x axes.

for i in range(80):
    skeleton.rotate_joint("Left_Shoulder", 0, -1, 0, from_base=False)
    skeleton.rotate_joint("Right_Shoulder", 0, -1, 0, from_base=False)
    skeleton.rotate_joint("Left_Hip", 0, 0, -1, from_base=False)
    skeleton.rotate_joint("Right_Hip", 0, 0, -1, from_base=False)
    #Plotting
    skeleton_visualizer.plot_skeletons([skeleton.get_pose()], ["Human"])

How to Generate Random Poses for a Skeleton

Here we will show how the poses in Figure 4 were generated.

#Define the skeleton and colors json
COLORS_JSON = "path/to/colors/json"
SKELETON_JSON = "path/to/skeleton/json"
  
#Create the skeleton object
skeleton = Skeleton(SKELETON_JSON)

#Create the visualizer object and set the number of skeletons and colors
skeleton_visualizer = SkeletonVisualizer3D(skeleton)
skeleton_visualizer.create_skeleton_scenes(1, [COLORS_JSON])

#Loop for 39 poses generation using the common poses feature (ordinary=True)
for i in range(39):
    #Random pose is composed of the positions and the sines and cosines of the angles
    #We just want the positions, so we index the first position of the function result
    random_pose = skeleton.get_random_pose(ordinary=True)[0]
    #We want a delay of 0.5 seconds before each update
    skeleton_visualizer.plot_skeletons([random_pose], ["Human"], 0.5)



Previous: 3D Pose Estimation Index Next: Skeleton Calibration