Kinematics Animation Multithread
Public Member Functions | Private Member Functions | Private Attributes | List of all members
Hand Class Reference

Class Hand. More...

#include <hand.h>

Public Member Functions

 Hand ()
 Empty constructor. More...
 
void initialize (igl::opengl::glfw::Viewer *viewer, Exoskeleton *exo_handler, AnimatedHand *anim_hand, bool type, const Eigen::Vector3d &origin)
 Initialize the hand. More...
 
void update (const std::vector< Eigen::Vector3d > &euler_id, igl::opengl::glfw::Viewer &viewer)
 It updates the hand vertices based on the euler angles for its skeleton joints. These are fed throught the AnimatedHand::EulerID struct. Based on the defined mapping it performs the forward kinematics for each finger and calcualtes all the hand vertices. More...
 

Private Member Functions

template<typename T >
std::vector< T > concatenate_data (const std::vector< std::vector< T > > &data)
 Concatenates vertex or face data to a std vector. More...
 
Eigen::MatrixXd translation_matrix (const Eigen::Vector3d &offset, size_t vert_num)
 This function offset a set of vertices by a given offset. More...
 

Private Attributes

std::string m_config_rel_path = "share/hand_config.json"
 
std::filesystem::path m_config_abs_path
 Absolute name of hand's configuration file. More...
 
std::vector< std::string > m_hand_config = {"Thumb", "Index", "Middle"}
 Hand configuration. More...
 
std::vector< Fingerm_fingers
 Vector of finger handles. More...
 
Eigen::Matrix3d m_hand_rot
 
Eigen::Vector3d m_hand_origin
 Hand origin with respect to the inertial frame of reference $ F $. More...
 
std::vector< Eigen::MatrixXd > m_vertex_data
 Vertex data container. More...
 
Eigen::MatrixXd m_concatenated_hand_vertex_data
 Concatenated hand vertex data. More...
 
int m_viewer_data_lower_idx
 
int m_viewer_data_upper_idx
 
int m_data_list_size
 

Detailed Description

Class Hand.

This class defines the hand stucture. It calls the finger class (see Finger::) to compose the three fingers and develop the full kinematic model of the hand.

Definition at line 23 of file hand.h.

Constructor & Destructor Documentation

◆ Hand()

Hand::Hand ( )
inline

Empty constructor.

Definition at line 27 of file hand.h.

27{};

Member Function Documentation

◆ concatenate_data()

template<typename T >
std::vector< T > Hand::concatenate_data ( const std::vector< std::vector< T > > &  data)
private

Concatenates vertex or face data to a std vector.

This function is used to concatenate Eigen matrices. More specifically each link of the finger is imported as an Eigen::Matrix. The total finger is then a vector of Eigen matrices. The whole hand is a vector of fingers or a vector of a vector of links. This function takes this vector of vectors of links and converts to a vector of fingers.

Template Parameters
TThe type of Eigen::Matrix to concatenate (MatrixXd, MatrixXi etc).
Parameters
dataThe vector of vectors of matrices.
Returns
std::vector<T> The vector of matrices.

Definition at line 108 of file hand.h.

109{
110 // Vertex data concatenated
111 std::vector<T> data_conc;
112
113 // Concatenate data to a single vector
114 for (auto data_j : data)
115 {
116 for (size_t i = 0; i < data_j.size(); i++)
117 {
118 data_conc.push_back(data_j.at(i));
119 }
120 }
121
122 return data_conc;
123}

◆ initialize()

void Hand::initialize ( igl::opengl::glfw::Viewer *  viewer,
Exoskeleton exo_handler,
AnimatedHand anim_hand,
bool  type,
const Eigen::Vector3d &  origin 
)

Initialize the hand.

The function first reads the hand configuration file (m_config_rel_path) and sets up all the its fingers.

Parameters
viewerPointer to the viewer object.
exo_handlerPoint to the exoskeleton object.
anim_handPointer to the hand animation object.
typeDefines whether the hand is the left one (0) or the right one (1).
originDefines the origin of the hand $ f_{{W}_{0}} $ with respct to the inertial frame $ F $.

Definition at line 15 of file hand.cpp.

18{
19 // Define absolute path of hand configuration file
20 m_config_abs_path = std::filesystem::current_path() / m_config_rel_path;
21
22 // Parse json file
23 std::ifstream file(m_config_abs_path);
24 nlohmann::json json_file = nlohmann::json::parse(file);
25
26 // Define hand pose
27 m_hand_origin = origin;
28 m_hand_rot = Eigen::Matrix3d::Identity();
29 if (type) // Check if it's the right hand and apply mirror transformation
30 {
31 m_hand_rot(1, 1) = -1.0;
32 }
33
34 // Resize fingers vector
35 m_fingers.resize(m_hand_config.size());
36
37 // Intitialize vertex data
38 std::vector<std::vector<Eigen::MatrixXd>> vertex_data;
39
40 // Get lower viewer data idx
41 m_viewer_data_lower_idx = (viewer->data_list.size() == 1) ? 0 :
42 viewer->data_list.size();
43
44 // Mesh idx initialization
45 int mesh_idx = m_viewer_data_lower_idx;
46
47 // Initialize fingers
48 for (size_t i = 0; i < m_fingers.size(); i++)
49 {
50 m_fingers.at(i).initialize(m_hand_config.at(i), json_file, viewer,
51 mesh_idx);
52
53 // Update mesh idx
54 mesh_idx = viewer->data_list.size();
55 }
56
57 // Get upper viewer data idx
58 m_viewer_data_upper_idx = viewer->data_list.size();
59
60 // Data list size
62}
std::string m_config_rel_path
Definition: hand.h:47
std::filesystem::path m_config_abs_path
Absolute name of hand's configuration file.
Definition: hand.h:50
int m_viewer_data_lower_idx
Definition: hand.h:87
int m_data_list_size
Definition: hand.h:91
std::vector< std::string > m_hand_config
Hand configuration.
Definition: hand.h:53
std::vector< Finger > m_fingers
Vector of finger handles.
Definition: hand.h:56
Eigen::Vector3d m_hand_origin
Hand origin with respect to the inertial frame of reference .
Definition: hand.h:63
int m_viewer_data_upper_idx
Definition: hand.h:87
Eigen::Matrix3d m_hand_rot
Definition: hand.h:60
Here is the caller graph for this function:

◆ translation_matrix()

Eigen::MatrixXd Hand::translation_matrix ( const Eigen::Vector3d &  offset,
size_t  vert_num 
)
private

This function offset a set of vertices by a given offset.

This is not a homogenous transformation matrix. Instead it is used for shifting a matrix of vertices (as defined by libigl) by a given offset.

Parameters
offsetThe offset to shift the matrix of vertices.
vert_numThe number of matrices.
Returns
Eigen::MatrixXd The output translation matrix.

Definition at line 135 of file hand.cpp.

137{
138 // Initialize matrix
139 Eigen::MatrixXd t_mat = Eigen::MatrixXd(vert_num, offset.rows());
140
141 // Ones vector
142 Eigen::VectorXd ones_vec = Eigen::VectorXd::Ones(vert_num);
143
144 for(size_t i = 0; i < offset.rows(); i++)
145 {
146 t_mat.col(i) = offset(i) * ones_vec;
147 }
148
149 return t_mat;
150}
Here is the caller graph for this function:

◆ update()

void Hand::update ( const std::vector< Eigen::Vector3d > &  euler_id,
igl::opengl::glfw::Viewer &  viewer 
)

It updates the hand vertices based on the euler angles for its skeleton joints. These are fed throught the AnimatedHand::EulerID struct. Based on the defined mapping it performs the forward kinematics for each finger and calcualtes all the hand vertices.

Parameters
euler_idThe custom EulerID structure as described in AnimatedHand::EulerID.
viewerPointer to the viewer object.

Definition at line 72 of file hand.cpp.

74{
75 // Intitialize vertex data
76 std::vector<std::vector<Eigen::MatrixXd>> vertex_data;
77
78 // Update fingers
79 for (size_t i = 0; i < m_fingers.size(); i++)
80 {
81 // Get finger frame ids
82 std::vector<int> frame_ids = m_fingers.at(i).get_frame_ids();
83
84 // Get current state of finger
85 std::vector<dm::JointState> state_vec = m_fingers.at(i).get_state();
86
87 for (size_t j = 0; j < frame_ids.size(); j++)
88 {
89 state_vec.at(j).euler = euler_id.at(frame_ids.at(j));
90 }
91
92 // Update finger
93 m_fingers.at(i).update(state_vec);
94
95 // Get vertices for finger i
96 std::vector<Eigen::MatrixXd> finger_i_vertices =
97 m_fingers.at(i).get_vertices();
98
99 // Transform the data to match the hand position
100 for (size_t j = 0; j < finger_i_vertices.size(); j++)
101 {
102 // Get the translation matrix
103 Eigen::MatrixXd t_mat = translation_matrix(m_hand_origin,
104 finger_i_vertices.at(j).rows());
105
106 // Perform transformation
107 finger_i_vertices.at(j) = t_mat + (m_hand_rot *
108 finger_i_vertices.at(j).transpose()).transpose();
109 }
110
111 // Push back vertex data
112 vertex_data.push_back(finger_i_vertices);
113 }
114
115 // Set vertex data
116 m_vertex_data = concatenate_data<Eigen::MatrixXd>(vertex_data);
117
118 // Send vertex data to viewer
119 for (size_t i = 0; i < m_data_list_size; i++)
120 {
121 // Send vertex data to viewer
122 viewer.data_list.at(m_viewer_data_lower_idx +
123 i).set_vertices(m_vertex_data.at(i));
124 }
125}
Eigen::MatrixXd translation_matrix(const Eigen::Vector3d &offset, size_t vert_num)
This function offset a set of vertices by a given offset.
Definition: hand.cpp:135
std::vector< Eigen::MatrixXd > m_vertex_data
Vertex data container.
Definition: hand.h:72
Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ m_concatenated_hand_vertex_data

Eigen::MatrixXd Hand::m_concatenated_hand_vertex_data
private

Concatenated hand vertex data.

Definition at line 75 of file hand.h.

◆ m_config_abs_path

std::filesystem::path Hand::m_config_abs_path
private

Absolute name of hand's configuration file.

Definition at line 50 of file hand.h.

◆ m_config_rel_path

std::string Hand::m_config_rel_path = "share/hand_config.json"
private

Relative name of hand's configuration file. This is a json file that contains the geometric characteristics of each finger (link lengths of the finger, ordered as [proximal, middle, distal]), the position and orientation of the finger's frame with respect to the local hand frame $ T_{f_{O_{i}}}^{f_{W_{0}}} $ with $ i = 0, 3, 6 $ and the finger's frame names as illustrated in the figure below.

Definition at line 47 of file hand.h.

◆ m_data_list_size

int Hand::m_data_list_size
private

The total size of the vertices of this instance of the hand on the data_list container.

Definition at line 91 of file hand.h.

◆ m_fingers

std::vector<Finger> Hand::m_fingers
private

Vector of finger handles.

Definition at line 56 of file hand.h.

◆ m_hand_config

std::vector<std::string> Hand::m_hand_config = {"Thumb", "Index", "Middle"}
private

Hand configuration.

Definition at line 53 of file hand.h.

◆ m_hand_origin

Eigen::Vector3d Hand::m_hand_origin
private

Hand origin with respect to the inertial frame of reference $ F $.

Definition at line 63 of file hand.h.

◆ m_hand_rot

Eigen::Matrix3d Hand::m_hand_rot
private

The total rotation matrix of the hand $ T_{f_{W_{0}}}^{F} $, with respect to the inertial frame of reference $ F $.

Definition at line 60 of file hand.h.

◆ m_vertex_data

std::vector<Eigen::MatrixXd> Hand::m_vertex_data
private

Vertex data container.

Definition at line 72 of file hand.h.

◆ m_viewer_data_lower_idx

int Hand::m_viewer_data_lower_idx
private

Viewer data lower and upper idx. The viewer object of libigl stores the vertex data into a container. This includes ALL the bodies that are rendered on the screen. For setting the vertices when they are updated it is important to know where the vertices for each object are located inside this container. These two variables define the lower and upper index for these specific instance of the hand. This way when we set the data for this hand to the viewer.data_list we know what vertices to update. For more info on how libigl handles multiple meshes at https://github.com/libigl/libigl/blob/main/tutorial/107_MultipleMeshes/main.cpp.

Definition at line 87 of file hand.h.

◆ m_viewer_data_upper_idx

int Hand::m_viewer_data_upper_idx
private

Definition at line 87 of file hand.h.


The documentation for this class was generated from the following files: