DK1 Exoskeleton
This page contains all relevant dimensions and measurements of the SenseGlove DK1 Exoskeleton. The SenseGlove DK1 consists of five (5) identical “fingers” mounted on a central “hub”. Each finger measures four (4) angles, creating an accurate representation of the glove in 3D space.
The Hub and Glove Origin
The “Glove Origin” is defined as a point on the exoskeleton that is used as a reference for the locations & rotations in the SGCore API. It can be found using two references:
The midpoint of the curve at the back of the Hub when viewed from the top. This midpoint is located at equal distance from the left and right side of the Hub, between the middle and ring finger assembly.
The seam that is created by the top- and bottom layers of the hub assembly, when viewed from the back.
The X-Axis runs parallel to the glove’s flat sides, where the positive direction is from the back of the hub to the front of the hub (where the fingers are).
The Y-Axis runs parallel to the seam created where the top- and bottom halves of the hub meet at the back of the glove. For right hands, the positive direction is defined from the pinky to the thumb. For left hands, the positive direction is defined from the thumb to the pinky.
The Z-Axis runs orthogonal (perpendicular) to the X- and Y axis. The flat sides of the middle- and/or ring finger Force-Feedback modules can be used as a reference. The positive direction is defined from the bottom of the glove (with the soft padding) to the top of the glove.
Note
The difference in Y-Axis between the left- and right hand is there to ensure that finger flexion for both hands results in a “positive” direction, and extension results in a negative direction. It also means that the reference frame(s) for the fingers are the same for each hand.
The Fingers
The “Fingers” of a DK1 are defined by 5 linkages or 6 points. The points are marked in the image below as numbers 0-5, which correspond to their index within the SG_GlovePose. When all exoskeleton angles are at [0, 0, 0], the finger assembly is completely “folded” and pointing straight forward like in the image below. In this configuration, all reference frames share the same x, y, z axes as indicated on the left side of the image. The finger assemblies use a right-handed coordinate system to determine which rotations are positive.
At point 0, which lies a the base of each force-feedback module, we measure a rotation around the Z- axis. This angle, normally given in radians, will typically be in the [-90 .. 90] degrees range.
Point 1 is a special case; you might notice that the Finger Assembly can twist around the X axis around this location. We do not measure this angle (it is assumed to be [0, 0, 0]), but it is still considered a separate part of the linkage in case one wishes to incorporate it.
At point 2, we measure a rotation around the Y-axis. Following the right-handed coordinate system, rotation in the “flexion” direction is considered positive, and rotation in the “extension” direction is negative. This angle, normally given in radians, will typically be in the [-30 .. 90] degrees range.
At point 3, we measure a rotation around the Y-axis, using the same indication for positive/negative as point 2. This angle, normally given in radians, will typically be in the [-90 .. 0] degrees range.
At point 4, we measure a rotation around the Y-axis, using the same indication for positive/negative as point 2. This angle, normally given in radians, will typically be in the [0 .. 290] degrees range.
Point 5 is located at the very end the “Thimble” plastics, along the seam where the two halves of the last linkage meet. Due to the finger assembly joints being slightly offset, this seam ends exactly at the same y-coordinate as point 0 in the CAD model.
Glove Linkage Translations
The same for each finger (assembly). Within its fully folded state, each finger assembly uses the following translations to get from one reference frame to the next. [x, y, z], in mm.
dX |
dY |
dZ |
|
---|---|---|---|
Linkage 01 |
9.12 |
0 |
7.6 |
Linkage 12 |
14.28 |
0 |
1 |
Linkage 23 |
23 |
88 |
0 |
Linkage 34 |
-64 |
0 |
-12 |
Linkage 45 |
22.03 |
0 |
-10.68 |
Sensor Ranges
The same for each finger (assembly). These are the possible sensor ranges [min .. max] that can be measured in each position, [x, y, z], in degrees.
X rotation |
Y rotation |
Z rotation |
|
---|---|---|---|
Point 0 |
0 |
0 |
-90 .. 90 |
Point 1 |
0 |
0 |
0 |
Point 2 |
0 |
-30 .. 90 |
0 |
Point 3 |
0 |
-90 .. 0 |
0 |
Point 4 |
0 |
0 .. 290 |
0 |
Point 5 |
0 |
0 |
0 |
Starting Positions (Right Hand)
These starting positions indicate the x, y, z coordinates - in mm, of point 0 of each finger assembly, relative to the Glove Origin.
Finger |
X |
Y |
Z |
---|---|---|---|
Thumb |
-46.56 |
52.0347 |
-22.1293 |
Index |
44.36 |
33.09 |
6.95 |
Middle |
62.22 |
11.0 |
8.0 |
Ring |
54.22 |
-11.0 |
8.0 |
Pinky |
41.25 |
-33.07 |
6.95 |
Starting Rotations (Right Hand)
These starting rotations indicate the Quaternion Notation [x, y, z, w] / Approximation in degrees [x, y, z] of point 0 of each finger assembly, relative to the Glove Origin.
Finger |
qX |
qY |
qZ |
qW |
Euler X |
Euler Y |
Euler Z |
---|---|---|---|---|---|---|---|
Thumb |
-0.5531433 |
0.1174416 |
0.7583794 |
0.324192 |
-145 |
101 |
-20 |
Index |
0 |
0 |
0 |
1 |
0 |
0 |
0 |
Middle |
0 |
0 |
0 |
1 |
0 |
0 |
0 |
Ring |
0 |
0 |
0 |
1 |
0 |
0 |
0 |
Pinky |
0 |
0 |
0 |
1 |
0 |
0 |
0 |
Starting Positions (Left Hand)
These starting positions indicate the x, y, z coordinates - in mm, of point 0 of each finger assembly, relative to the Glove Origin.
Finger |
X |
Y |
Z |
---|---|---|---|
Thumb |
-46.56 |
-52.0347 |
-22.1293 |
Index |
44.36 |
-33.09 |
6.95 |
Middle |
62.22 |
-11.0 |
8.0 |
Ring |
54.22 |
11.0 |
8.0 |
Pinky |
41.25 |
33.07 |
6.95 |
Starting Rotations (Left Hand)
These starting rotations indicate the Quaternion Notation [x, y, z, w] / Approximation in degrees [x, y, z] of point 0 of each finger assembly, relative to the Glove Origin.
Finger |
qX |
qY |
qZ |
qW |
Euler X |
Euler Y |
Euler Z |
---|---|---|---|---|---|---|---|
Thumb |
-0.5531433 |
-0.1174416 |
0.7583794 |
-0.324192 |
145 |
101 |
-20 |
Index |
0 |
0 |
0 |
1 |
0 |
0 |
0 |
Middle |
0 |
0 |
0 |
1 |
0 |
0 |
0 |
Ring |
0 |
0 |
0 |
1 |
0 |
0 |
0 |
Pinky |
0 |
0 |
0 |
1 |
0 |
0 |
0 |
The Exoskeleton in Code
Assuming C++ for this document, though the architecture is the same in C#.
SG_GloveInfo
You can access all glove-related variables, including handed-ness, starting positions and -rotations and translation matrices of your exoskeleton from a SenseGlove instance by calling the GetGloveInfo() function.
SGCore::SG::SenseGlove testGlove;
if (SGCore::SG::SenseGlove::GetSenseGlove(testGlove)) //retrieves the first Sense Glove it can find. Returns true if one can be found
{
SGCore::SG::SG_GloveInfo model = testGlove.GetGloveModel();
std::cout << model.ToString(true) << std::endl; //Log some basic information to the user. (true indicates a short notation is desired)
}
The startPositions, startRotations and gloveLengths are all std::vectors of length 5, whose first index corresponds to the finger: Values for the thumb being stored at [0], while values for the pinky are stored at index [4].
The startPositions parameter of this model contains the starting position of each linkage relative to the glove origin, in mm - It will have the same values as documented in the previous section.
The startPositions parameter of this model contains the starting rotation of each linkage relative to the glove origin, as a Quaternion - It will have the same values as documented in the previous section.
The gloveLengths paramater contains the individual translation matrices for each linkage, for each finger, in mm, relative to the previous reference frame.
From more information on this class and its functions, visit: https://github.com/Adjuvo/SenseGlove-API/blob/master/Core/SGCoreCpp/incl/SG_GloveInfo.h
SG_GlovePose
Represents a SenseGlove DK1 glove pose, as a collection of positions, rotations and angles, which should be all you need to draw a wireframe of the glove, or to animate it inside a 3D virtual environment. Within the SGCore API, you can retrieve a GlovePose from a SenseGlove instance by calling the GetGlovePose() function. This automatically takes the latest sensor data, puts it in the right place, and calculates the forward kinematics of the glove.
SGCore::SG::SenseGlove testGlove;
if (SGCore::SG::SenseGlove::GetSenseGlove(testGlove)) //retrieves the first Sense Glove it can find. Returns true if one can be found
{
//Retrieving Glove Pose: The position / rotation of the glove, as well as its sensor angles placed in the right direction.
SGCore::SG::SG_GlovePose glovePose;
if (testGlove.GetGlovePose(glovePose))
{
std::cout << glovePose.ToString() << std::endl; //Print out the GlovePose
}
}
The jointAngles, jointPositions and jointRotations of the SG_GlovePose are all std::vectors of length 5, whose first index corresponds to the finger: Values for the thumb being stored at [0], while values for the pinky are stored at index [4].
The jointAngles variable contains the (sensor) angles between the linkages, in radians, as an x, y, z vector. It is a 2D array, where the first index indicates the finger (5), and the second, the points in the finger assembly (point 0-4). These angles form a rotation matrix to get from said point, to the next one. Therefore, there is no jointAngle for the last linkage (point 5 - the Thimble).
The jointPositions variable contains the positions of each point within the finger assembly, in mm, relative to the glove origin. It is a 2D array, where the first index indicates the finger (5), and the second, the points in the finger assembly (points 0-5).
The jointRotations variable contains the quaternion rotation of each point within the finger assembly, relative to the glove origin. It is a 2D array, where the first index indicates the finger (5), and the second, the points in the finger assembly (points 0-5).
The jointPositions and jointRotations are all relative to the glove origin, rather than to the previous linkage. This makes it easier to compare the fingers against one another, or to a finger / hand of which we only know the position relative to the glove. It also allows us to draw a wireframe or apply rotations in any 3D space.
From more information on this class and its functions, visit: https://github.com/Adjuvo/SenseGlove-API/blob/master/Core/SGCoreCpp/incl/SG_GlovePose.h
Thimble & Fingertip Positions
If your main interest is in finding the positions and rotations of the thimbles to use in inverse kinematics, then you’ll need the variables at the last jointPositions and jointRotations of each linkage. Easy access to these is provided through ThimblePositions() / ThimbleRotations() function.
// Also possible - but only for one finger
SGCore::Kinematics::Vect3D> thumbThimblePos = glovePose.jointPositions[0][glovePose.JointPositions[0].size() - 1];
// Easier Access - For all the fingers
std::vector<SGCore::Kinematics::Vect3D> thimblePos = glovePose.ThimblePositions();
std::vector<SGCore::Kinematics::Quat> thimbleRot glovePose.ThimbleRotations();
Note that the fingertip and thimble (point 5) are not the same. While your thimble is connected to your finger, latter extends further beyond the plastics. There isn’t any way to calibrate these values within the SenseGlove API. Though if you have an indication of the finger’s displacement relative to the thimble’s reference frame, you can calculate a rough fingertip location by adding an additional forward kinematics step.
int finger = 1; //1 = index finger, 0 = thumb, 4 = pinky.
// we do have a default offsets; it's [5, 0, -8]; 5mm forward, 8mm down to the finger bone
SGCore::Kinematics::Vect3D thimble_finger_translation = SGCore::SG::SG_HandProfile::dThimbleOffset;
//let's say the finger bends a little further (2.5 degrees) in the flexion (positive) y direction than the thimble
SGCore::Kinematics::Quat thimble_finger_rotation = SGCore::Kinematics::Quat::FromAngleAxis(SGCore::Kinematics::Values::Deg2Rad * 2.5f, 0, 1, 0);
//Now we can caluclate fingertip positions based on some basic forward kinematics;
SGCore::Kinematics::Quat fingertip_rotation = thimbleRot[finger] * thimble_finger_rotation;
SGCore::Kinematics::Quat fingertip_position = thimblePos[finger] + (thimbleRot[finger] * thimble_finger_translation);