Kinematics Animation Multithread
hand.h
Go to the documentation of this file.
1#pragma once
2
3#include <iostream>
4#include <vector>
5#include <filesystem>
6#include <fstream>
7#include <eigen3/Eigen/Dense>
8
9#include "./nlohmann/json.hpp"
10#include <igl/opengl/glfw/Viewer.h>
11
12#include "dynamics_math.h"
13#include "exoskeleton.h"
14#include "animated_hand.h"
15#include "finger.h"
16
18
23class Hand
24{
25public:
27 Hand(){};
28
30 void initialize(igl::opengl::glfw::Viewer* viewer,
31 Exoskeleton* exo_handler, AnimatedHand* anim_hand,
32 bool type, const Eigen::Vector3d& origin);
33
34 // Update the hand.
35 void update(const std::vector<Eigen::Vector3d>& euler_id,
36 igl::opengl::glfw::Viewer& viewer);
37
38private:
47 std::string m_config_rel_path = "share/hand_config.json";
48
50 std::filesystem::path m_config_abs_path;
51
53 std::vector<std::string> m_hand_config = {"Thumb", "Index", "Middle"};
54
56 std::vector<Finger> m_fingers;
57
60 Eigen::Matrix3d m_hand_rot;
61
63 Eigen::Vector3d m_hand_origin;
64
65private:
66
68 template <typename T>
69 std::vector<T> concatenate_data(const std::vector<std::vector<T>>& data);
70
72 std::vector<Eigen::MatrixXd> m_vertex_data;
73
76
88
92
94 Eigen::MatrixXd translation_matrix(const Eigen::Vector3d& offset, size_t vert_num);
95};
96
107template <typename T>
108std::vector<T> Hand::concatenate_data(const std::vector<std::vector<T>>& data)
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}
Class Exoskeleton.
Definition: exoskeleton.h:20
Class Hand.
Definition: hand.h:24
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
Eigen::MatrixXd m_concatenated_hand_vertex_data
Concatenated hand vertex data.
Definition: hand.h:75
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
Hand()
Empty constructor.
Definition: hand.h:27
std::vector< T > concatenate_data(const std::vector< std::vector< T > > &data)
Concatenates vertex or face data to a std vector.
Definition: hand.h:108
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