Skeletal Animation Multithread Face
Classes | Public Member Functions | Private Attributes | List of all members
Hand Class Reference

Class Hand. More...

#include <hand.h>

Collaboration diagram for Hand:
Collaboration graph
[legend]

Classes

struct  PngImage
 

Public Member Functions

 Hand (Exoskeleton *exo_handler, AnimatedHand *anim_hand, const std::string &mesh_name, const std::string &graph_name, const std::string &texture_name, bool type, const Eigen::Vector3d &origin)
 Constructor. More...
 
void update (const std::vector< AnimatedHand::EulerID > &euler_id)
 Updates the hand. More...
 
Eigen::MatrixXd get_vertices (void)
 Returns the vertices of the hand. More...
 
Eigen::MatrixXi get_surface_indices (void)
 

Private Attributes

Eigen::MatrixXd m_vol_mesh_vert
 Volume mesh Vertices (V) More...
 
Eigen::MatrixXd m_vol_mesh_vert_init
 
Eigen::MatrixXi m_tetr_indices
 Volume mesh tetrahedral indices(T) and surface element indices(F) More...
 
Eigen::MatrixXi m_surf_indices
 
Eigen::MatrixXi m_bone_edges_indices
 Bone-edges skeleton indices (BE) More...
 
Eigen::VectorXi m_point_handles
 Point handles list (P) More...
 
Eigen::MatrixXd m_vertex_pos
 List of vertex positions (C) More...
 
Eigen::VectorXi m_boundary_indices
 List of boundary indices (b) More...
 
Eigen::MatrixXd m_boundary_conditions
 List of boundary conditions of each weight function (bc) More...
 
igl::BBWData m_bbw_data
 BBW weights matrix (bbw_data) More...
 
Eigen::MatrixXd m_weights
 List of weights (W) More...
 
Eigen::MatrixXd m_g_weights
 Global weights (M) More...
 
Exoskeletonm_exo_handler
 Exoskeleton handler pointer. More...
 
AnimatedHandm_anim_hand
 Animated hand pointer. More...
 
std::vector< int > m_hand_idx_iter
 Hand index iterator. More...
 
RotationList m_anim_pose
 Animation pose. More...
 
int m_pose_size = 20
 Pose size. More...
 
PngImage m_texture
 Texture image. More...
 
bool m_hand_type
 Hand type. More...
 
Eigen::Vector3d m_origin
 Hand origin. More...
 

Detailed Description

Class Hand.

This class defines the hand and performs all the kinematics and the skinning of the hand. For this it uses the tecnique of Bounded Biharmonic Weights (BBW). See https://www.youtube.com/watch?v=P9fqm8vgdB8&ab_channel=AlecJacobson. libigl exposes a lot of functions for doing this. See https://github.com/libigl/libigl/blob/main/tutorial/403_BoundedBiharmonicWeights/main.cpp.

Definition at line 33 of file hand.h.

Constructor & Destructor Documentation

◆ Hand()

Hand::Hand ( Exoskeleton exo_handler,
AnimatedHand anim_hand,
const std::string &  mesh_name,
const std::string &  graph_name,
const std::string &  texture_name,
bool  type,
const Eigen::Vector3d &  origin 
)

Constructor.

Construct a new Hand:: Hand object.

Parameters
exo_handlerPointer to the Exoskeleton object.
anim_handPointer to the AnimatedHand object.
mesh_nameThe name of the mesh file.
graph_nameThe name of the graph file (contains the conections between the bones aka the kinematic model).
texture_nameThe name of the texture file.
typeBool the define whether the hand is left(0) or right(1).
originThe origin of the hand.

Definition at line 15 of file hand.cpp.

18{
19 // Read volume mesh
20 igl::readMESH(mesh_name, m_vol_mesh_vert, m_tetr_indices, m_surf_indices);
21
22 // Set initial mesh vertices
24
25 // Read graph file
26 igl::readTGF(graph_name, m_vertex_pos, m_bone_edges_indices);
27
28 // Retrieve parents for forward kinematics
29 igl::directed_edge_parents(m_bone_edges_indices, m_point_handles);
30
31 // Set boundary conditions
32 igl::boundary_conditions(m_vol_mesh_vert, m_tetr_indices, m_vertex_pos,
33 Eigen::VectorXi(), m_bone_edges_indices , Eigen::MatrixXi(),
35
36 // Only a few iterations
37 m_bbw_data.active_set_params.max_iter = 8;
38 m_bbw_data.verbosity = 2;
39
42 {
43 std::cout << "Error: BBW Error" << std::endl;
44 }
45
46 // Normalize weights to sum to one
47 igl::normalize_row_sums(m_weights, m_weights);
48
49 // Precompute linear blend skinning matrix
50 igl::lbs_matrix(m_vol_mesh_vert, m_weights, m_g_weights);
51
52 // Get exoskeleton handler pointer
53 m_exo_handler = exo_handler;
54
55 // Get animation hand pointer
56 m_anim_hand = anim_hand;
57
58 // Get hand index iterator
60
61 // Initialize animation pose
63
64 for (size_t i = 0; i < m_pose_size; i++)
65 {
66 m_anim_pose.at(i) = Eigen::Quaterniond::Identity();
67 }
68
69 // Read texture
70 igl::png::readPNG(texture_name, m_texture.red, m_texture.green,
72
73 // Get hand type
74 m_hand_type = type;
75
76 // Get hand origin
77 m_origin = origin;
78}
std::vector< int > get_hand_idx_iterator(void)
Definition: animated_hand.h:46
Eigen::MatrixXd m_vertex_pos
List of vertex positions (C)
Definition: hand.h:82
Eigen::MatrixXi m_tetr_indices
Volume mesh tetrahedral indices(T) and surface element indices(F)
Definition: hand.h:73
PngImage m_texture
Texture image.
Definition: hand.h:117
igl::BBWData m_bbw_data
BBW weights matrix (bbw_data)
Definition: hand.h:91
Eigen::MatrixXd m_weights
List of weights (W)
Definition: hand.h:94
Eigen::VectorXi m_boundary_indices
List of boundary indices (b)
Definition: hand.h:85
Eigen::MatrixXd m_vol_mesh_vert_init
Definition: hand.h:70
Eigen::Vector3d m_origin
Hand origin.
Definition: hand.h:123
Eigen::MatrixXi m_bone_edges_indices
Bone-edges skeleton indices (BE)
Definition: hand.h:76
Eigen::MatrixXi m_surf_indices
Definition: hand.h:73
RotationList m_anim_pose
Animation pose.
Definition: hand.h:111
Eigen::VectorXi m_point_handles
Point handles list (P)
Definition: hand.h:79
std::vector< int > m_hand_idx_iter
Hand index iterator.
Definition: hand.h:108
Eigen::MatrixXd m_vol_mesh_vert
Volume mesh Vertices (V)
Definition: hand.h:70
Eigen::MatrixXd m_g_weights
Global weights (M)
Definition: hand.h:97
int m_pose_size
Pose size.
Definition: hand.h:114
Exoskeleton * m_exo_handler
Exoskeleton handler pointer.
Definition: hand.h:102
AnimatedHand * m_anim_hand
Animated hand pointer.
Definition: hand.h:105
Eigen::MatrixXd m_boundary_conditions
List of boundary conditions of each weight function (bc)
Definition: hand.h:88
bool m_hand_type
Hand type.
Definition: hand.h:120
Eigen::Matrix< unsigned char, Eigen::Dynamic, Eigen::Dynamic > red
Definition: hand.h:46
Eigen::Matrix< unsigned char, Eigen::Dynamic, Eigen::Dynamic > blue
Definition: hand.h:48
Eigen::Matrix< unsigned char, Eigen::Dynamic, Eigen::Dynamic > a
Definition: hand.h:49
Eigen::Matrix< unsigned char, Eigen::Dynamic, Eigen::Dynamic > green
Definition: hand.h:47
Here is the call graph for this function:

Member Function Documentation

◆ get_surface_indices()

Eigen::MatrixXi Hand::get_surface_indices ( void  )
inline
Returns
Eigen::MatrixXi Matrix of hand indices.

Definition at line 65 of file hand.h.

65{ return m_surf_indices; }

◆ get_vertices()

Eigen::MatrixXd Hand::get_vertices ( void  )
inline

Returns the vertices of the hand.

Returns
Eigen::MatrixXd Matrix of hand vertices.

Definition at line 59 of file hand.h.

59{return m_vol_mesh_vert; }

◆ update()

void Hand::update ( const std::vector< AnimatedHand::EulerID > &  euler_id)

Updates the hand.

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 and calcualtes all the hand vertices.

Parameters
euler_idThe custom EulerID structure as described in AnimatedHand::EulerID.

Definition at line 87 of file hand.cpp.

88{
89 for (size_t i = 0; i < euler_id.size(); i++)
90 {
91 // Get euler id i
92 std::vector<double> euler_i = euler_id.at(i).euler_angles;
93
94 // // Get frame id i
95 int frame_id_i = euler_id.at(i).frame_id;
96
97 // Transform angles to quaternions
100 euler_i.at(1), euler_i.at(2));
101
102 // Set animation pose
103 m_anim_pose.at(frame_id_i) = Eigen::Quaterniond(quatern.w, quatern.x,
104 quatern.y, quatern.z);
105 }
106
107 // Propagate relative rotations via FK to retrieve absolute transformations
108 RotationList v_rot;
109 std::vector<Eigen::Vector3d> v_tran;
110
111 // Forward kinematics
112 igl::forward_kinematics(m_vertex_pos, m_bone_edges_indices,
113 m_point_handles, m_anim_pose, v_rot, v_tran);
114
115 // Get verted dimension
116 int vert_dim = m_vertex_pos.cols();
117
118 // Total transformation matrix
119 Eigen::MatrixXd t_mat(m_bone_edges_indices.rows()*(vert_dim+1), vert_dim);
120
121 // Perform trasnformation
122 for (int i = 0 ; i < m_bone_edges_indices.rows(); i++)
123 {
124 Eigen::Affine3d a = Eigen::Affine3d::Identity();
125
126 // Translate (has a trick to account for mirroring in case of right hand)
127 a.translate(v_tran.at(i) + (-2.0 * (double)m_hand_type + 1) * m_origin);
128
129 // Rotate
130 a.rotate(v_rot.at(i));
131
132 t_mat.block(i*(vert_dim+1), 0, vert_dim+1, vert_dim) =
133 a.matrix().transpose().block(0, 0, vert_dim+1, vert_dim);
134 }
135
136 // Compute deformation via LBS as matrix multiplication
138
139 if (m_hand_type) // check if it's the right hand and mirror it
140 {
141 Eigen::Matrix3d mirror = Eigen::Matrix3d::Identity();
142 mirror(0, 0) = -1.0;
143 m_vol_mesh_vert = (mirror * m_vol_mesh_vert.transpose()).transpose();
144 }
145}
static Quaternions euler_to_quaternions(double phi, double theta, double psi)
Convert Euler angles to quaternions.
std::vector< Eigen::Quaterniond, Eigen::aligned_allocator< Eigen::Quaterniond > > RotationList
Definition: hand.h:22
Custom quaternions struct: .
Here is the call graph for this function:

Member Data Documentation

◆ m_anim_hand

AnimatedHand* Hand::m_anim_hand
private

Animated hand pointer.

Definition at line 105 of file hand.h.

◆ m_anim_pose

RotationList Hand::m_anim_pose
private

Animation pose.

Definition at line 111 of file hand.h.

◆ m_bbw_data

igl::BBWData Hand::m_bbw_data
private

BBW weights matrix (bbw_data)

Definition at line 91 of file hand.h.

◆ m_bone_edges_indices

Eigen::MatrixXi Hand::m_bone_edges_indices
private

Bone-edges skeleton indices (BE)

Definition at line 76 of file hand.h.

◆ m_boundary_conditions

Eigen::MatrixXd Hand::m_boundary_conditions
private

List of boundary conditions of each weight function (bc)

Definition at line 88 of file hand.h.

◆ m_boundary_indices

Eigen::VectorXi Hand::m_boundary_indices
private

List of boundary indices (b)

Definition at line 85 of file hand.h.

◆ m_exo_handler

Exoskeleton* Hand::m_exo_handler
private

Exoskeleton handler pointer.

Definition at line 102 of file hand.h.

◆ m_g_weights

Eigen::MatrixXd Hand::m_g_weights
private

Global weights (M)

Definition at line 97 of file hand.h.

◆ m_hand_idx_iter

std::vector<int> Hand::m_hand_idx_iter
private

Hand index iterator.

Definition at line 108 of file hand.h.

◆ m_hand_type

bool Hand::m_hand_type
private

Hand type.

Definition at line 120 of file hand.h.

◆ m_origin

Eigen::Vector3d Hand::m_origin
private

Hand origin.

Definition at line 123 of file hand.h.

◆ m_point_handles

Eigen::VectorXi Hand::m_point_handles
private

Point handles list (P)

Definition at line 79 of file hand.h.

◆ m_pose_size

int Hand::m_pose_size = 20
private

Pose size.

Definition at line 114 of file hand.h.

◆ m_surf_indices

Eigen::MatrixXi Hand::m_surf_indices
private

Definition at line 73 of file hand.h.

◆ m_tetr_indices

Eigen::MatrixXi Hand::m_tetr_indices
private

Volume mesh tetrahedral indices(T) and surface element indices(F)

Definition at line 73 of file hand.h.

◆ m_texture

PngImage Hand::m_texture
private

Texture image.

Definition at line 117 of file hand.h.

◆ m_vertex_pos

Eigen::MatrixXd Hand::m_vertex_pos
private

List of vertex positions (C)

Definition at line 82 of file hand.h.

◆ m_vol_mesh_vert

Eigen::MatrixXd Hand::m_vol_mesh_vert
private

Volume mesh Vertices (V)

Definition at line 70 of file hand.h.

◆ m_vol_mesh_vert_init

Eigen::MatrixXd Hand::m_vol_mesh_vert_init
private

Definition at line 70 of file hand.h.

◆ m_weights

Eigen::MatrixXd Hand::m_weights
private

List of weights (W)

Definition at line 94 of file hand.h.


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