SGCore HandPose reference
This page shows you how to access and use a HandPose
class from the SenseGlove Native APIs.
The HandPose
is a data class which contains everyting one might need to represent the joints of a hand in 3D space.
Like all Native classes, it exists within the SGCore
namespace.
Using a HandPose
The HandPose contains several different variables that can be used to represent a pose of the hand in 3D space. This guide assumes you are familliar with the anatomical notation of bones, joints and movements of the hand. If you aren’t, there’s an excellent reseach paper on the topic here.
Coordinate System
When the wrist rotation is 0, 0, 0, the following is true:
The X-Axis runs parallel with the stretched fingers, running roughly from the wrist joint to the middle finger MCP joint.
The Y-Axis runs along the MCP joints. For right hands, the positive direction is from pinky MCP to index finger MCP. For left hands, the positive direction is from index MCP to the index finger MCP.
The Z-Axis points ‘up’ from the hand palm. The positive direction is from the palm of the hand to the back of the hand.
The SenseGlove internal coordinate-system is a right-handed system.
Note
Our left- and right hands share the same ‘forward’ and ‘upward’ directions. The difference in positive y-direction between left- and right hands means that finger flexion also shares the same positive / negative direction between the hands.
Using Arrays
Several of the variables in the HandPose class are contained within arrays T[]
or nested arrays T[][]
for C# or std::vector<T>
and std::vector<std::vector<T>>
for C++.
In both cases, the arrays will have a length of 5, and the first index will always be used to indicate the finger, sorted from thumb [0]
to pinky [4]
.
Imagine accessing these as [finger]
.
For nested arrays, the second index will always indicate the finger joint, sorted from most proximal (closest to the wrist) to distal (furthest from the wrist).
Imagine accessing these as [finger][joint]
.
These nested arrays are of length 5x4, with the exception of the jointAngles
variable, which is of length 5x3 - as these do not include the fingertips.
In the thumb, the joint index is used to access the { Thumb CMC [0]
, Thumb MCP [1]
, Thumb IP [2]
, Thumb Tip [3]
} joints. For the fingers, the joint index is used to access the {Finger MCP [0]
, Finger PIP [1]
, Finger DIP [2]
, Finger Tip [3]
} joints.
Note
We use nested arrays because it’s easier to iterate over each finger. No need to calculate an index based on which finger you’re on. If we were to add additional joints to the thumb or pinky, the other fingers are also not affected.
Below are the public
variables fo the HandPose:
IsRight
///<summary> Whether or not this HandPose was created to be a right- or left hand. </summary>
bool isRight;
///<summary> Whether or not this HandPose was created to be a right- or left hand. </summary>
public bool isRight;
As the description implies, the rightHanded
parameter lets us know if this HandPose was created for a right hand (true
) or left hand (false
).
Usually, you’ll already know which hand you’re retrieveing data from, or find it out using use the IsRight()
function of your HapticGlove
.
It is still useful to have when you’re loading a HandPose from disk, or as a sanity check.
WristPosition and WristRotation
At the moment, the HandPose
does not contain information on the wrist position and -rotation.
This information is commonly retrieved from a 3rd party API, such as using OpenVR to retrieve a Vive Tracker position.
When you have a position and rotation of your tracked object, you can calculate the position and rotation of your glove origin or wrist using the functions contained in the HapticGlove class:
/// <summary> Retrieve the location of the wrist, based on a reference location and default glove-hand offsets. </summary>
/// <remarks> The simplest interface, using default offsets </remarks>
/// <param name="refPosition">Position of the tracked object, in mm, relative to your origin</param>
/// <param name="refRotation">Rotation of the tracked object relative to your origin</param>
/// <param name="trackingHardware">The hardware mounted on the SenseGlove.</param>
/// <param name="wristPos">The 3D Position of the wrist, in mm, relative to your origin</param>
/// <param name="wristRot">The 3D Rotation of the wrist, relative to your origin</param>
virtual void GetWristLocation(Kinematics::Vect3D& refPosition, Kinematics::Quat& refRotation, PosTrackingHardware trackingHardware, Kinematics::Vect3D& wristPos, Kinematics::Quat& wristRot);
/// <summary> Retrieve the location of the glove origin, based on a reference location. </summary>
/// <param name="refPosition">Position of the tracked object, in mm, relative to your origin</param>
/// <param name="refRotation">Rotation of the tracked object relative to your origin</param>
/// <param name="trackingHardware">The hardware mounted on the SenseGlove.</param>
/// <param name="mountedOn">Which finger module the hardware is mounted on.</param>
/// <param name="glovePos">The 3D Position of the glove, in mm, relative to your origin</param>
/// <param name="gloveRot">The 3D Rotation of the glove, relative to your origin</param>
virtual void GetGloveLocation(Kinematics::Vect3D& refPosition, Kinematics::Quat& refRotation, PosTrackingHardware trackingHardware, Kinematics::Vect3D& glovePos, Kinematics::Quat& gloveRot);
bool rightHand = true;
std::shared_ptr<SGCore::HapticGlove> glove; //HapticGlove Instance to calculate offsets
if (SGCore::HapticGlove::GetGlove(rightHand, glove))
{
SGCore::Kinematics::Vect3D trackerPosition = SGCore::Kinematics::Vect3D::zero; //Take these from your 3rd party API
SGCore::Kinematics::Quat trackerRotation = SGCore::Kinematics::Quat::identity; //Take these from your 3rd party API
SGCore::Kinematics::Vect3D wristPosition; SGCore::Kinematics::Quat wristRotation; //these will be calculated by the SGCore API
glove->GetWristLocation(trackerPosition, trackerRotation, SGCore::PosTrackingHardware::ViveTracker, wristPosition, wristRotation); //We're assuming a Vive Tracker is used
//TODO: Do something with wristPosition & WristRotation
}
/// <summary> Retrieve the location of the wrist, based on a reference location and default glove-hand offsets. </summary>
/// <remarks> The simplest interface, using default offsets </remarks>
/// <param name="refPosition">Position of the tracked object, in mm, relative to your origin</param>
/// <param name="refRotation">Rotation of the tracked object relative to your origin</param>
/// <param name="trackingHardware">The hardware mounted on the SenseGlove.</param>
/// <param name="wristPos">The 3D Position of the wrist, in mm, relative to your origin</param>
/// <param name="wristRot">The 3D Rotation of the wrist, relative to your origin</param>
public virtual void GetWristLocation(Vect3D refPosition, Quat refRotation, PosTrackingHardware trackingHardware, out Vect3D wristPos, out Quat wristRot);
/// <summary> Retrieve the location of the glove origin, based on a reference location. </summary>
/// <param name="refPosition">Position of the tracked object, in mm, relative to your origin</param>
/// <param name="refRotation">Rotation of the tracked object relative to your origin</param>
/// <param name="trackingHardware">The hardware mounted on the SenseGlove.</param>
/// <param name="glovePos">The 3D Position of the glove, in mm, relative to your origin</param>
/// <param name="gloveRot">The 3D Rotation of the glove, relative to your origin</param>
public virtual void GetGloveLocation(Vect3D refPosition, Quat refRotation, PosTrackingHardware trackingHardware, out Vect3D glovePos, out Quat gloveRot);
//Example Usage:
bool rightHand = true;
HapticGlove glove; //HapticGlove Instance to calculate offsets
if (HapticGlove.GetGlove(rightHand, out glove))
{
Vect3D trackerPosition = Vect3D.zero; //Take these from your 3rd party API
Quat trackerRotation = Quat.identity; //Take these from your 3rd party API
Vect3D wristPosition; Quat wristRotation; //these will be calculated by the SGCore API
glove.GetWristLocation(trackerPosition, trackerRotation, PosTrackingHardware.ViveTracker, out wristPosition, out wristRotation); //We're assuming a Vive Tracker is used
//TODO: Do something with wristPosition & WristRotation
}
Since the offsets are dependent on which type of glove (SenseGlove DK1 or Nova Glove) you have, it’s easiest to let the HapticGlove work out its own position / rotation.
When accessing finger tracking data, you’ll already have access to a HapticGlove instance either way.
Note that you can pass a PosTrackingHardware
parameter, which determines which (hard-coded) offsets your HapticGlove will use.
If you’d you’d like to calculate the wrist position outside of the HapticGlove class; each of its subclasses contains a static
CalculateWristLocation
and CalculateGloveLocation
implementation that performs the same function, though it requires more parameters. You’ll need to know what deviceType and which hand you are using beforehand:
//NovaGlove.h
/// <summary> Retrieve the location of the wrist, based on a reference location and default glove-hand offsets, without needing an object reference. </summary>
/// <remarks> The simplest interface, using default offsets </remarks>
/// <param name="refPosition">Position of the tracked object, in mm, relative to your origin</param>
/// <param name="refRotation">Rotation of the tracked object relative to your origin</param>
/// <param name="trackingHardware">The hardware mounted on the SenseGlove.</param>
/// <param name="rightHand">Whether this is right or left hand</param>
/// <param name="wristPos">The 3D Position of the wrist, in mm, relative to your origin</param>
/// <param name="wristRot">The 3D Rotation of the wrist, relative to your origin</param>
static void CalculateWristLocation(Kinematics::Vect3D& refPosition, Kinematics::Quat& refRotation, PosTrackingHardware trackingHardware, bool rightHand,
Kinematics::Vect3D& wristPos, Kinematics::Quat& wristRot);
//SenseGlove.h
/// <summary> Retrieve the location of the wrist, based on a reference location without requiring an object reference. </summary>
/// <param name="refPosition">Position of the tracked object, in mm, relative to your origin</param>
/// <param name="refRotation">Rotation of the tracked object relative to your origin</param>
/// <param name="trackingHardware">The hardware mounted on the SenseGlove.</param>
/// <param name="rightHand">Whether or not this is a left or right handed glove.</param>
/// <param name="mountedOn">Which finger module the hardware is mounted on. Default is Middle finger.</param>
/// <param name="wristPos">The 3D Position of the wrist, in mm, relative to your origin</param>
/// <param name="wristRot">The 3D Rotation of the wrist, relative to your origin</param>
/// <param name="gloveWristOffPos"></param>
/// <param name="gloveWristOffRot"></param>
static void CalculateWristLocation(Kinematics::Vect3D& refPosition, Kinematics::Quat& refRotation, PosTrackingHardware trackingHardware, bool rightHand,
Finger mountedOn, Kinematics::Vect3D& gloveWristOffPos, Kinematics::Quat& gloveWristOffRot, Kinematics::Vect3D& wristPos, Kinematics::Quat& wristRot);
//NovaGlove.cs
/// <summary> Retrieve the location of the wrist, based on a reference location and default glove-hand offsets, without needing an object reference. </summary>
/// <remarks> The simplest interface, using default offsets </remarks>
/// <param name="refPosition">Position of the tracked object, in mm, relative to your origin</param>
/// <param name="refRotation">Rotation of the tracked object relative to your origin</param>
/// <param name="trackingHardware">The hardware mounted on the SenseGlove.</param>
/// <param name="gloveInfo">Whether this is right or left hand</param>
/// <param name="wristPos">The 3D Position of the wrist, in mm, relative to your origin</param>
/// <param name="wristRot">The 3D Rotation of the wrist, relative to your origin</param>
public static void CalculateWristLocation(Vect3D refPosition, Quat refRotation, PosTrackingHardware trackingHardware,
Nova_GloveInfo gloveInfo, out Vect3D wristPos, out Quat wristRot)
//SenseGlove.cs
/// <summary> Retrieve the location of the wrist, based on a reference location without requiring an object reference.. </summary>
/// <param name="refPosition">Position of the tracked object, in mm, relative to your origin</param>
/// <param name="refRotation">Rotation of the tracked object relative to your origin</param>
/// <param name="trackingHardware">The hardware mounted on the SenseGlove.</param>
/// <param name="rightHand">Whether or not this is a left or right handed glove.</param>
/// <param name="mountedOn">Which finger module the hardware is mounted on. Default is Middle finger.</param>
/// <param name="wristPos">The 3D Position of the wrist, in mm, relative to your origin</param>
/// <param name="wristRot">The 3D Rotation of the wrist, relative to your origin</param>
/// <param name="gloveWristOffPos"></param>
/// <param name="gloveWristOffRot"></param>
public static void CalculateWristLocation(Vect3D refPosition, Quat refRotation, PosTrackingHardware trackingHardware,
bool rightHand, Finger mountedOn, Vect3D gloveWristOffPos, Quat gloveWristOffRot, out Vect3D wristPos, out Quat wristRot)
HandAngles
///<summary> Euler representations of all possible hand angles. From thumb to pinky, proximal to distal. </summary>
std::vector< std::vector<Kinematics::Vect3D> > handAngles;
///<summary> Euler representations of all possible hand angles. From thumb to pinky, proximal to distal. </summary>
public Vect3D[][] handAngles;
The handAngles
variable contains the Euler angles of each joint of each finger, in radians, relative to the previous joint, contained in a Vect3D. For the first joints of each finger, the angles are relative to the wrist reference frame. It’s size is 5x3.
x represents the joint’s pronation / supination (twisting), in radians, relative to the previous joint. It’s mainly relevant for the thumb’s CMC joint (
jointAngles[0][0].x
).y represents the joint’s flexion / extension (finger bending) in radians, relative to the previous joint. For both hands, flexion is positive and extension is negative.
z represents the joint’s abduction / adduction (sideways motion) in radians, relative to the previous joint. It’s mainly relevant for the first joint of each finger (
jointAngles[finger][0]
).
The values of these angles are limited to “normal” human ranges. Note that the values below are given in degrees for readability. The values read from the API will be in radians.
Movement Name |
Joint Index |
Range Left [°] |
Range Right [°] |
---|---|---|---|
Thumb CMC Twist |
jointAngles[0][0].x |
-20 … 20 |
-20 … 20 |
Thumb CMC Flexion |
jointAngles[0][0].y |
-10 … 35 |
-10 … 35 |
Thumb CMC Abduction |
jointAngles[0][0].z |
-60 … 10 |
-10 … 60 |
Thumb MCP Flexion |
jointAngles[0][1].y |
0 … 50 |
0 … 50 |
Thumb IP Flexion |
jointAngles[0][2].y |
-10 … 90 |
-10 … 90 |
Finger MCP Flexion |
jointAngles[finger][0].y |
-30 … 90 |
-30 … 90 |
Finger MCP Abduction |
jointAngles[finger][0].z |
-20 … 20 |
-20 … 20 |
Finger PIP Flexion |
jointAngles[finger][1].y |
0 … 100 |
0 … 100 |
Finger DIP Flexion |
jointAngles[finger][2].y |
-5 … 90 |
-5 … 90 |
You can turn these euler angles into our Quaternion (Quat
) notation by using Quat.ToEuler(Vector3) function.
JointRotations
///<summary> Quaternion rotations of all hand joints. From thumb to pinky, proximal to distal. </summary>
std::vector< std::vector<Kinematics::Quat> > jointRotations;
///<summary> Quaternion rotations of all hand joints. From thumb to pinky, proximal to distal. </summary>
public Quat[][] jointRotations;
The jointRotations
are the Quaternion rotations of each finger’s joints, all of which are relative to the wrist. This notation allow us to apply the quaternion rotation directly to each joint, using something along these lines:
SGCore::Kinematics::Quat wristRotation = SGCore::Kinematics::Quat::identity; // Could also be a position retrieved from a Vive Tracker, Quest2 controller, etc.
for (int f = 0; f < 5; f++) //finger (f), [0..4].
{
for (int j = 0; j < 4; j++) //Joint Index; proximal to distal, where 4 = fingerTip.
{
SGCore::Kinematics::Quat jointWorldRotation = wristRotation * handPose.jointRotations[f][j];
// TODO: Apply joint rotation
}
}
Quat wristRotation = Quat.identity; // Could also be a position retrieved from a Vive Tracker, Quest2 controller, etc.
for (int f=0; f<5; f++) //finger (f), [0..4].
{
for (int j=0; j<4; j++) //Joint Index; proximal to distal, where 4 = fingerTip.
{
Quat jointWorldRotation = wristRotation * handPose.jointRotations[f][j];
// TODO: Apply joint rotation
}
}
If these quaternions are identity quaternions (Quaternion::identity
or [0,0,0,1]); all fingers are stretched and parallel to the hand palm.
The thumb is a special case: When the CMC joint rotation is an identity quaternion (all angles 0), the thumb is also stretched parallel to the fingers,
and it has an identical flexion direction as a finger. This is because a “starting position” of the thumb is incorporated in Quaternion at jointRotations[0][0]
.
This starting rotation is a Quaternion made form Euler angles [90,0,0] (left hands) and [-90,0,0] (right hands).
We encourage you to look at the starting pose of the Prefab Hand Models inside the Unity Plugin to see exactly what is meant by this.
JointPositions
///<summary> Positions of all hand joints relative to the Sense Glove origin. From thumb to pinky, proximal to distal. </summary>
std::vector< std::vector<Kinematics::Vect3D> > jointPositions;
///<summary> Positions of all hand joints relative to the Sense Glove origin. From thumb to pinky, proximal to distal. </summary>
public Vect3D[][] jointPositions;
The jointPositions
variable is a nested array of Vector3’s, which represent the position of each finger’s joint, all of which are relative to the wrist.
It’s size is 5x4.
If you wish to convert these positions to your world space, you can calculate these using the following method:
SGCore::Kinematics::Vect3D wristPosition = SGCore::Kinematics::Vect3D::zero; //TODO; Get these off your tracker
SGCore::Kinematics::Quat wristRotation = SGCore::Kinematics::Quat::identity; //TODO; Get these off your tracker
for (int f = 0; f < 5; f++) //finger (f), [0..4].
{
for (int j = 0; j < 4; j++) //Joint Index; proximal to distal, where 4 = fingerTip.
{
SGCore::Kinematics::Vect3D jointWorldPosition = wristPosition + (wristRotation * handPose.jointPositions[f][j]);
// TODO: Apply the position to something
}
}
Vect3D wristPosition = Vect3D.zero; //TODO; Get these off your tracker
Quat wristRotation = Quat.identity; //TODO; Get these off your tracker
for (int f=0; f<5; f++) //finger (f), [0..4].
{
for (int j=0; j<4; j++) //Joint Index; proximal to distal, where 4 = fingerTip.
{
Vect3D jointWorldPosition = wristPosition + (wristRotation * handPose.jointPositions[f][j]);
// TODO: Apply the position to something
}
}
GetNormalizedFlexion()
///<summary> Returns the total flexion the fingers as a value between 0 (fully extended) and 1 (fully flexed). </summary>
///<remarks> Useful for animation or for detecting gestures </remarks>
std::vector<float> GetNormalizedFlexion(bool clamp01 = true);
///<summary> Returns the total flexion the fingers as a value between 0 (fully extended) and 1 (fully flexed). </summary>
///<remarks> Useful for animation or for detecting gestures </remarks>
public float[] GetNormalizedFlexion(bool clamp01 = true)
The GetNormalizedFlexion()
function returns the simplest representation of joint movements within the API.
It consists of five values which represent the level of flexion (a.k.a. finger bending) in the range of [0…1].
This array is sorted by finger, from thumb [0]
to pinky [4]
.
By summing all of the flexion angles of the finger, and dividing these by the maximum total flexion achievable within the finger’s natural limits, we get the Normalized Flexion. A value of 0 represents a fully straightened finger, parallel to the palm, while a value of 1 represents a fully flexed (bent) finger. A value in between, 0.25 for example, represents a finger that is roughly 25% bent. A negative value indicates hyperextension or the fingers.
It can be used for simple gesture or intent detection, of for (simple) hand animation.
Accessing a HandPose
To access the latest HandPose
from your SenseGlove device, you’ll a reference to said device.
Currently, the most generic way to do so is via the HapticGlove
class: Both the SenseGlove Nova (SGCore.Nova.NovaGlove
) and DK1 (SGCore.SG.SenseGlove
) are subclasses of HapticGlove
. Future SenseGlove products are likely to fall under this class as well.
This guide assumes you’re interfacing with your device through the HapticGlove
class, though a setup for only Nova or DK1 gloves will have a near-identical syntax:
The following functions are availale to you when retrieving a HandPose from a HapticGlove:
// 1) Calculate a HandPose with 'default' hand dimensions, using the latest calibration profile on the disk.
virtual bool GetHandPose(HandPose& handPose);
// 2) Calculate a HandPose with known hand dimensions, using the latest calibration profile on the disk.
virtual bool GetHandPose(Kinematics::BasicHandModel& handGeometry, HandPose& handPose);
// 3) Calculate a HandPose with 'default' hand dimensions, using a custom calibration profile.
virtual bool GetHandPose(HandProfile& handProfile, HandPose& handPose);
// 4) Calculate a HandPose with known hand dimensions, using a custom calibration profile.
virtual bool GetHandPose(Kinematics::BasicHandModel& handGeometry, HandProfile& handProfile, HandPose& handPose);
Function definitions are taken from HapticGlove.h.
// 1) Calculate a HandPose with 'default' hand dimensions, using the latest calibration profile on the disk.
public bool GetHandPose(out HandPose handPose);
// 2) Calculate a HandPose with known hand dimensions, using the latest calibration profile on the disk.
public bool GetHandPose(BasicHandModel handGeometry, out HandPose handPose);
// 3) Calculate a HandPose with 'default' hand dimensions, using a custom calibration profile.
public virtual bool GetHandPose(HandProfile handProfile, out HandPose handPose);
// 4) Calculate a HandPose with known hand dimensions, using a custom calibration profile.
public virtual bool GetHandPose(BasicHandModel handGeometry, HandProfile handProfile, out HandPose handPose);
More information on the Handpose class can be found in the HTML code reference in the Core/SGCoreCs/doc/ folder.
In most cases, you’ll want to use option 2; passing a ‘custom’ hand geometry that matches your virtual hand model, and leave the loading of profiles to the SenseGlove API. If you’re only interested in the joint rotations, then you could go for option 1) and use the default hand geometry.
As you can see from these functions, all methods of retrieving a HandPose return a boolean value.
If these functions return true
, the handPose parameter will contain the latest valid HandPose.
If these functions return false
, then a HandPose could not be retrieved. Perhaps the device was turned off, or sensor packets were corrupted.
Below are code samples to show you how these functions are meant to be used:
std::shared_ptr<SGCore::HapticGlove> glove;
if (SGCore::HapticGlove::GetGlove(rightHand, glove))
{
// We want to get the pose of the hand - to animate a virtual model
SGCore::HandPose handPose; //The handPose class contains all data you'll need to animate a virtual hand
if (glove->GetHandPose(handPose)) //returns the HandPose based on the latest device data, using the latest Profile and the default HandGeometry
{
std::cout << "Retrieved the latest Hand Pose from " + glove->ToString() + ". The ToString() function reports important finger angles, in degrees, in our coodinate system:" << std::endl;
std::cout << handPose.ToString() << std::endl;
}
}
SGCore.HapticGlove glove;
if (SGCore.HapticGlove.GetGlove(rightHand, out glove))
{
// We want to get the pose of the hand - to animate a virtual model
SGCore.HandPose handPose; //The handPose class contains all data you'll need to animate a virtual hand
if (glove.GetHandPose(out handPose)) //returns the HandPose based on the latest device data, using the latest Profile and the default HandGeometry
{
Console.WriteLine("Retrieved the latest Hand Pose from " + glove.ToString() + ". The ToString() function reports important finger angles, in degrees, in our coodinate system:");
Console.WriteLine(handPose.ToString());
}
}
Generating Custom HandPoses
Below are various ways to generate your own Custom HandPose from sets of HandAngles.
These functions allow you to pass an optional SGCore.Kinematics.BasicHandModel
, containing the finger lengths and starting location of the fingers, as a parameter.
When no BasicHandModel
is passed, the ‘default’ values are used.
Preset HandPoses
You can generate a HandPose based on presets; such as a fist, a thumbs-up, or an open hand. These are used in the calibration preview you see in SenseCom, for example.
/// <summary> Create a new instance of a left or right handed Pose that is "idle"; in a neutral position. </summary>
/// <param name="rightHand"></param>
/// <param name="handDimensions"></param>
/// <returns></returns>
static HandPose DefaultIdle(bool rightHand, Kinematics::BasicHandModel& handDimensions);
/// <summary> Create a new instance of a left or right handed Pose that is "idle"; in a neutral position. </summary>
/// <param name="rightHand"></param>
/// <returns></returns>
static HandPose DefaultIdle(bool rightHand);
/// <summary> Generates a HandPose representing an 'open hand', used in calibration to determine finger extension. </summary>
/// <param name="rightHand"></param>
/// <param name="handDimensions"></param>
/// <returns></returns>
static HandPose FlatHand(bool rightHand, Kinematics::BasicHandModel& handDimensions);
/// <summary> Generates a HandPose representing an 'open hand', used in calibration to determine finger extension. </summary>
/// <param name="rightHand"></param>
/// <returns></returns>
static HandPose FlatHand(bool rightHand);
/// <summary> Generates a HandPose representing a 'thumbs up', used in calibration to determine finger flexion, thumb extension and adduction. </summary>
/// <param name="rightHand"></param>
/// <param name="handDimensions"></param>
/// <returns></returns>
static HandPose ThumbsUp(bool rightHand, Kinematics::BasicHandModel& handDimensions);
/// <summary> Generates a HandPose representing a 'thumbs up', used in calibration to determine finger flexion, thumb extension and adduction. </summary>
/// <param name="rightHand"></param>
/// <returns></returns>
static HandPose ThumbsUp(bool rightHand);
/// <summary> Generates a HandPose representing a 'fist', used in calibration to determine, thumb flexion and abduction. </summary>
/// <param name="rightHand"></param>
/// <param name="handDimensions"></param>
/// <returns></returns>
static HandPose Fist(bool rightHand, Kinematics::BasicHandModel& handDimensions);
/// <summary> Generates a HandPose representing a 'fist', used in calibration to determine, thumb flexion and abduction. </summary>
/// <param name="rightHand"></param>
/// <returns></returns>
static HandPose Fist(bool rightHand);
In the C# implementation, you’ll also need to pass the right
boolean to indicate which side of hand this pose is generated for.
It is there as a fallback for the current implementation in case the code:BasicHandModel parameter is null
.
/// <summary> Create a new instance of a left or right handed Pose that is "idle": Fingers stretched and thumb abducted by 30 degrees. </summary>
/// <param name="right"></param>
/// <param name="handDimensions"></param>
/// <returns></returns>
public static HandPose DefaultIdle(bool right, BasicHandModel handDimensions = null);
/// <summary> Generates a HandPose representing an 'open hand', used in calibration to determine finger extension: Fingers stretched and Thumb parallel to the fingers </summary>
/// <param name="rightHand"></param>
/// <param name="handDimensions"></param>
/// <returns></returns>
public static HandPose FlatHand(bool rightHand, BasicHandModel handDimensions = null);
/// <summary> Generates a HandPose representing a 'thumbs up', used in calibration to determine finger flexion, thumb extension and adduction. </summary>
/// <param name="rightHand"></param>
/// <param name="handDimensions"></param>
/// <returns></returns>
public static HandPose ThumbsUp(bool rightHand, BasicHandModel handDimensions = null);
/// <summary> Generates a HandPose representing a 'fist', used in calibration to determine, thumb flexion and abduction. </summary>
/// <param name="rightHand"></param>
/// <param name="handDimensions"></param>
/// <returns></returns>
public static HandPose Fist(bool rightHand, BasicHandModel handDimensions = null);
Preset HandAngles
If you’re looking to get a set of HandAngles to use as a reference; the SGCore.Kinematics.Anatomy
class contains the HandAngles that are used to generate the preset HandPoses above.
/// <summary> Get Hand Angles that would make a Default (Idle) Pose </summary>
static std::vector < std::vector < Vect3D > > HandAngles_Default(bool rightHand);
/// <summary> Get Hand Angles that would make a flat hand </summary>
static std::vector < std::vector < Vect3D > > HandAngles_Flat(bool rightHand);
/// <summary> Get Hand Angles that would make a thumbs up </summary>
static std::vector < std::vector < Vect3D > > HandAngles_ThumbsUp(bool rightHand);
/// <summary> Get Hand Angles that would make a fist </summary>
static std::vector < std::vector < Vect3D > > HandAngles_Fist(bool rightHand);
/// <summary> Get Hand Angles that would make a Default Pose; fingers stretched and thumb abducted by 30 degrees. </summary>
/// <param name="rightHand"></param>
/// <returns></returns>
public static Vect3D[][] HandAngles_Default(bool rightHand);
/// <summary> Get Hand Angles that would make a flat hand </summary>
/// <param name="rightHand"></param>
/// <returns></returns>
public static Vect3D[][] HandAngles_Flat(bool rightHand);
/// <summary> Get Hand Angles that would make a thumbs up </summary>
/// <param name="rightHand"></param>
/// <returns></returns>
public static Vect3D[][] HandAngles_ThumbsUp(bool rightHand);
/// <summary> Get Hand Angles that would make a fist </summary>
/// <param name="rightHand"></param>
/// <returns></returns>
public static Vect3D[][] HandAngles_Fist(bool rightHand);
From normalized values
This function allows you to generate a HandPose by defining finger flexion, thumb abduction and finger spread as values between [0..1]. The flexion of each finger joint is controlled by the same value, so it cannot be used to define individual joint values.
//Unfortunately, this function is not yet available in C++, only in C#
/// <summary> Generates a set of HandAngles from normalized finger flexions, thumb abduction and a global finger spread. </summary>
/// <param name="isRight"></param>
/// <param name="flexions01"></param>
/// <param name="thumbAbd01"></param>
/// <param name="fingerSpread01"></param>
/// <returns></returns>
public static Vect3D[][] HandAngles_FromNormalized(bool isRight, float[] flexions01, float thumbAbd01, float fingerSpread01);
Variable Name |
Affects |
---|---|
flexions01[0] |
Thumb_CMC_Flexion, Thumb_CMP_Flexion, Thumb_IP_Flexion |
flexions01[1] |
Index_MCP_Flexion, Index_PIP_Flexion, Index_DIP_Flexion |
flexions01[2] |
Middle_MCP_Flexion, Middle_PIP_Flexion, Middle_DIP_Flexion |
flexions01[3] |
Ring_MCP_Flexion, Ring_PIP_Flexion, Ring_DIP_Flexion |
flexions01[4] |
Pinky_MCP_Flexion, Pinky_PIP_Flexion, Pinky_DIP_Flexion |
thumbAbd01 |
Thumb_CMC_Abduction |
fingerSpread01 |
Index_MCP_Abduction, Middle_MCP_Abduction, Ring_MCP_Abduction, Pinky_MCP_Abduction |
A value of 0 for each parameter results in a hand where the thumb and fingers are all stretched to be parrallel with one another and in the same direction as the hand palm.
This pose is equal to the one generated by the HandAngles_Flat
function in SGCore.Kinematics.Anatomy
.
Setting all values to 1 results in a fist, where all fingers are bent, and the thumb is on the outside of the fingers.
Moving the fingerSpread01
parameter from 0 to 1 will result in the four fingers spreading ‘outward’ by a maximum of 20 degrees, except for the middle finger.
From a set of HandAngles
It is possible to generate your own Handpose from a set of handAngles, allowing full control of the rotation in each joint.
You would need to define a 5x3 nested array of Vect3D’s containing the joint angles in radians, relative to the previous joint.
For more information on the format of this array, refer to the HandAngles section above.
If you’re looking for example sets of HandAngles, you can use the preset handAngles as defined in SGCore.Kinematics.Anatomy
.
/// <summary> Generate a HandPose based on articulation angles (handAngles). </summary>
/// <param name="handAngles"></param>
/// <param name="rightHanded"></param>
/// <param name="handDimensions"></param>
/// <returns></returns>
static HandPose FromHandAngles(std::vector<std::vector<Kinematics::Vect3D>>& handAngles, bool rightHanded, Kinematics::BasicHandModel& handDimensions);
/// <summary> Generate a HandPose based on articulation angles (handAngles), with a default HandModel. </summary>
/// <param name="handAngles"></param>
/// <param name="rightHanded"></param>
/// <returns></returns>
static HandPose FromHandAngles(std::vector<std::vector<Kinematics::Vect3D>>& handAngles, bool rightHanded);
/// <summary> Generate a HandPose based on articulation angles (handAngles). </summary>
/// <param name="handAngles"></param>
/// <param name="rightHanded"></param>
/// <param name="handDimensions"></param>
/// <returns></returns>
public static HandPose FromHandAngles(Vect3D[][] handAngles, bool rightHanded, BasicHandModel handDimensions = null)
Serialization
When you retrieve your HandPose, you can convert it into a string notation using the Serialize()
function on the instance.
This will condense all relevant data into a single line of text, that can be stored on disk or hard-coded, and unpacked later.
The static Deserialize() function can be used to convert a string notation back into a HandPose class.
///<summary> Serialize this HandProfile into a string representation </summary>
std::string Serialize();
///<summary> Deserialize a HandProfile back into useable values. </summary>
static HandPose Deserialize(std::string serializedString);
// Example Implementation
void TestSerialization( SGCore::HandPose pose )
{
std::string serializedPose = pose.Serialize();
//I can now store serializedPose in a text file, for example
SGCore::HandPose loadedPose = SGCore::HandPose::Deserialize(serializedPose);
//LoadedPose should be identical to the original
bool equalPoses = loadedPose.Equals(pose);
}
/// <summary> Create a string representation of this HandPose to store on disk. It can later be deserialized. </summary>
/// <returns></returns>
public string Serialize()
/// <summary> Unpack a HandPose back into its Class representation. </summary>
/// <param name="serializedString"></param>
/// <returns></returns>
public static HandPose Deserialize(string serializedString);
// Example Implementation
public void TestSerialization( HandPose pose )
{
string serializedPose = pose.Serialize();
//I can now store serializedPose in a text file, for example
HandPose loadedPose = HandPose.Deserialize(serializedPose);
//LoadedPose should be identical to the original
bool equalPoses = loadedPose.Equals(pose);
}