Main Page
Namespaces
Classes
Files
File List
File Members
include
choreo_task_sequence_planner
utils
StiffnessSolver.h
Go to the documentation of this file.
1
/*
2
* ==========================================================================
3
* This file is part of the implementation of
4
*
5
* <FrameFab: Robotic Fabrication of Frame Shapes>
6
* Yijiang Huang, Juyong Zhang, Xin Hu, Guoxian Song, Zhongyuan Liu, Lei Yu, Ligang Liu
7
* In ACM Transactions on Graphics (Proc. SIGGRAPH Asia 2016)
8
----------------------------------------------------------------------------
9
* class: StiffnessSolver
10
*
11
* Description:
12
*
13
* Version: 1.0
14
* Created: Mar/23/2016
15
* Updated: Aug/24/2016
16
*
17
* Author: Xin Hu, Yijiang Huang, Guoxian Song
18
* Company: GCL@USTC
19
* Citation: this module utilize solver and data structure from
20
* Title: Eigen
21
* C++ template library for linear algebra: matrices, vectors, numerical
22
* solvers, and related algorithms.
23
* Code Version: 3.2.9
24
* Availability: http://eigen.tuxfamily.org/index.php?title=Main_Page
25
----------------------------------------------------------------------------
26
* Copyright (C) 2016 Yijiang Huang, Xin Hu, Guoxian Song, Juyong Zhang
27
* and Ligang Liu.
28
*
29
* FrameFab is free software: you can redistribute it and/or modify
30
* it under the terms of the GNU General Public License as published by
31
* the Free Software Foundation, either version 3 of the License, or
32
* (at your option) any later version.
33
*
34
* FrameFab is distributed in the hope that it will be useful,
35
* but WITHOUT ANY WARRANTY; without even the implied warranty of
36
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
37
* GNU General Public License for more details.
38
*
39
* You should have received a copy of the GNU General Public License
40
* along with FrameFab. If not, see <http://www.gnu.org/licenses/>.
41
* ==========================================================================
42
*/
43
44
#ifndef STIFFNESS_SOLVER_H
45
#define STIFFNESS_SOLVER_H
46
47
#include <iostream>
48
#include <Eigen/Dense>
49
#include <Eigen/Sparse>
50
#include <Eigen/SparseCholesky>
51
#include <Eigen/LU>
52
53
#include "
choreo_task_sequence_planner/utils/Timer.h
"
54
55
#define sind(x) (sin(fmod((x),360) * M_PI / 180))
56
#define cosd(x) (cos(fmod((x),360) * M_PI / 180))
57
58
using namespace
std
;
59
60
class
StiffnessSolver
61
{
62
public
:
63
typedef
Eigen::SparseMatrix<double>
SpMat
;
64
typedef
Eigen::MatrixXd
MX
;
65
typedef
Eigen::Matrix3d
M3
;
66
typedef
Eigen::VectorXd
VX
;
67
typedef
Eigen::Vector3d
V3
;
68
typedef
Eigen::VectorXi
VXi
;
69
typedef
Eigen::MatrixXi
MXi
;
70
71
public
:
72
StiffnessSolver
();
73
~StiffnessSolver
(){};
74
75
public
:
76
/* solver I/O*/
77
78
/*
79
* SolveSystem - solve {F} = [K]{D} via L D L' decomposition 2/Dec/2015
80
* This override function is implemented for sovling Kqq * d_q = F_q,
81
* where no partitioned LDLt is needed.
82
* @param K : stiffness matrix for the restrained frame
83
* @param D : displacement vector to be solved
84
* @param F : mechenical force(external load vector)
85
* @param verbose : =1 for copious screenplay
86
* @param info: <0 : not stiffness matrix positive definite
87
* Note: This function use eigen library SimplicialLDLt module to solve the linear system.
88
*/
89
bool
SolveSystem(
90
SpMat &K,
91
VX &D,
92
VX &F,
93
int
verbose
,
94
int
&info
95
);
96
97
98
/*
99
* SolveSystem - solve {F} = [K]{D} via conjugate gradient with guess 30/Mar/2016
100
* This override function is implemented for sovling Kqq * d_q = F_q,
101
* where no partitioned LDLt is needed.
102
* @param K : stiffness matrix for the restrained frame
103
* @param D : displacement vector to be solved
104
* @param F : mechenical force(external load vector)
105
* @param verbose : =1 for copious screenplay
106
* @param info: <0 : not stiffness matrix positive definite
107
* Note: This function use eigen library :ConjugateGradient module to solve the linear system.
108
*/
109
bool
SolveSystem(
110
SpMat &K,
111
VX &D,
112
VX &F,
113
VX &D0,
114
int
verbose,
115
int
&info
116
);
117
118
void
Debug
();
119
120
public
:
121
/*
122
* This LUDecomp module use Eigen library to solve the linear system
123
*/
124
bool
LUDecomp(
125
MX &
A
,
126
VX &
x
,
127
VX &
b
128
);
129
130
public
:
131
Timer
compute_k_
;
132
Timer
solve_d_
;
133
134
/* Timing Stat */
135
bool
detailed_timing_
;
136
};
137
138
#endif
StiffnessSolver::M3
Eigen::Matrix3d M3
Definition:
StiffnessSolver.h:65
verbose
bool verbose
StiffnessSolver::V3
Eigen::Vector3d V3
Definition:
StiffnessSolver.h:67
StiffnessSolver::detailed_timing_
bool detailed_timing_
Definition:
StiffnessSolver.h:135
std
A
StiffnessSolver::MXi
Eigen::MatrixXi MXi
Definition:
StiffnessSolver.h:69
Timer.h
x
GLint GLenum GLint x
Debug
Debug
StiffnessSolver::VXi
Eigen::VectorXi VXi
Definition:
StiffnessSolver.h:68
StiffnessSolver::MX
Eigen::MatrixXd MX
Definition:
StiffnessSolver.h:64
b
GLboolean GLboolean GLboolean b
StiffnessSolver::SpMat
Eigen::SparseMatrix< double > SpMat
Definition:
StiffnessSolver.h:63
StiffnessSolver::compute_k_
Timer compute_k_
Definition:
StiffnessSolver.h:131
StiffnessSolver::~StiffnessSolver
~StiffnessSolver()
Definition:
StiffnessSolver.h:73
StiffnessSolver
Definition:
StiffnessSolver.h:60
Timer
Definition:
Timer.h:48
StiffnessSolver::VX
Eigen::VectorXd VX
Definition:
StiffnessSolver.h:66
StiffnessSolver::solve_d_
Timer solve_d_
Definition:
StiffnessSolver.h:132
choreo_task_sequence_planner
Author(s): Yijiang Huang
autogenerated on Thu Jul 18 2019 04:03:14