FFAnalyzer.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: FFAnalyzer
10 *
11 * Description: perform the greedy searching algorithm in FrameFab to generate
12 * a collision-free, structurally-stable path.
13 *
14 * Version: 2.0
15 * Created: Oct/10/2015
16 * Updated: Aug/24/2016
17 *
18 * Author: Xin Hu, Yijiang Huang, Guoxian Song
19 * Company: GCL@USTC
20 * Note: Backtracking Greedy Approach:
21 * At every decision state, a trail solution is performed,
22 * unvisited current layer edges that are connected to already printed
23 * structure and calculate their adjacency,collision and stiffness weight.
24 *
25 * The total printing cost is weighted sum of the three:
26 *
27 * Wp_*P + Wa_*A + Wi_*I
28 *
29 * P: stabiliy weight
30 * L: collision cost
31 * A: influence weight
32 ----------------------------------------------------------------------------
33 * Copyright (C) 2016 Yijiang Huang, Xin Hu, Guoxian Song, Juyong Zhang
34 * and Ligang Liu.
35 *
36 * FrameFab is free software: you can redistribute it and/or modify
37 * it under the terms of the GNU General Public License as published by
38 * the Free Software Foundation, either version 3 of the License, or
39 * (at your option) any later version.
40 *
41 * FrameFab is distributed in the hope that it will be useful,
42 * but WITHOUT ANY WARRANTY; without even the implied warranty of
43 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
44 * GNU General Public License for more details.
45 *
46 * You should have received a copy of the GNU General Public License
47 * along with FrameFab. If not, see <http://www.gnu.org/licenses/>.
48 * ==========================================================================
49 */
50 
51 #pragma once
52 #include <cmath>
53 #include <cstring>
54 
56 
57 class FFAnalyzer : public SeqAnalyzer
58 {
59  public:
60  typedef Eigen::MatrixXd MX;
61  typedef Eigen::Matrix3d M3;
62  typedef Eigen::VectorXd VX;
63  typedef Eigen::Vector3d V3;
64 
65  public:
66  explicit FFAnalyzer(
67  DualGraph *ptr_dualgraph,
68  QuadricCollision *ptr_collision,
69  Stiffness *ptr_stiffness,
70  FiberPrintPARM *ptr_parm,
71  char *ptr_path,
72  bool terminal_output,
73  bool file_output,
74  descartes_core::RobotModelPtr hotend_model,
75  moveit::core::RobotModelConstPtr moveit_model,
76  std::string hotend_group_name
77  ) noexcept
78  : SeqAnalyzer(ptr_dualgraph, ptr_collision, ptr_stiffness,
79  ptr_parm, ptr_path, terminal_output, file_output,
80  hotend_model, moveit_model, hotend_group_name){}
81  ~FFAnalyzer();
82 
83  public:
84  bool SeqPrint();
85  bool SeqPrintLayer(std::vector<int> layer_id);
86 
87  private:
88  bool GenerateSeq(int l, int h, int t);
89  double GenerateCost(WF_edge* ej, const int h, const int t, const int layer_id);
90 
91  public:
92  void PrintOutTimer();
93 
94  private:
95  std::vector<std::vector<WF_edge*>> layers_; // store dual_node's id for each layers
96 
97  double min_z_;
98  double max_z_;
99 
102 
104 };
105 
double max_z_
Definition: FFAnalyzer.h:98
Timer FF_analyzer_
Definition: FFAnalyzer.h:103
Eigen::VectorXd VX
Definition: FFAnalyzer.h:62
bool GenerateSeq(int l, int h, int t)
Definition: FFAnalyzer.cpp:240
bool SeqPrintLayer(std::vector< int > layer_id)
Definition: FFAnalyzer.cpp:106
double min_base_dist_
Definition: FFAnalyzer.h:100
SeqAnalyzer(DualGraph *ptr_dualgraph, QuadricCollision *ptr_collision, Stiffness *ptr_stiffness, FiberPrintPARM *ptr_parm, char *ptr_path, bool terminal_output, bool file_output, descartes_core::RobotModelPtr hotend_model, moveit::core::RobotModelConstPtr moveit_model, std::string hotend_group_name) noexcept
double min_z_
Definition: FFAnalyzer.h:97
Eigen::Vector3d V3
Definition: FFAnalyzer.h:63
GLdouble GLdouble t
bool SeqPrint()
Definition: FFAnalyzer.cpp:7
double GenerateCost(WF_edge *ej, const int h, const int t, const int layer_id)
Definition: FFAnalyzer.cpp:359
GLfloat GLfloat GLfloat GLfloat h
FFAnalyzer(DualGraph *ptr_dualgraph, QuadricCollision *ptr_collision, Stiffness *ptr_stiffness, FiberPrintPARM *ptr_parm, char *ptr_path, bool terminal_output, bool file_output, descartes_core::RobotModelPtr hotend_model, moveit::core::RobotModelConstPtr moveit_model, std::string hotend_group_name) noexcept
Definition: FFAnalyzer.h:66
double max_base_dist_
Definition: FFAnalyzer.h:101
Eigen::MatrixXd MX
Definition: FFAnalyzer.h:60
Eigen::Matrix3d M3
Definition: FFAnalyzer.h:61
Definition: Timer.h:48
std::vector< std::vector< WF_edge * > > layers_
Definition: FFAnalyzer.h:95
void PrintOutTimer()
Definition: FFAnalyzer.cpp:558


choreo_task_sequence_planner
Author(s): Yijiang Huang
autogenerated on Thu Jul 18 2019 04:03:14