Kinematics Animation Multithread
hand.cpp
Go to the documentation of this file.
1#include "../include/hand.h"
2
15void Hand::initialize(igl::opengl::glfw::Viewer* viewer,
16 Exoskeleton* exo_handler, AnimatedHand* anim_hand,
17 bool type, const Eigen::Vector3d& origin)
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}
63
72void Hand::update(const std::vector<Eigen::Vector3d>& euler_id,
73 igl::opengl::glfw::Viewer& viewer)
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}
126
135Eigen::MatrixXd Hand::translation_matrix(const Eigen::Vector3d& offset,
136 size_t vert_num)
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}
Class Exoskeleton.
Definition: exoskeleton.h:20
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 through...
Definition: hand.cpp:72
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
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
void initialize(igl::opengl::glfw::Viewer *viewer, Exoskeleton *exo_handler, AnimatedHand *anim_hand, bool type, const Eigen::Vector3d &origin)
Initialize the hand.
Definition: hand.cpp:15
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
std::vector< Eigen::MatrixXd > m_vertex_data
Vertex data container.
Definition: hand.h:72