FiberPrintPlugIn.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: FiberPrintPlugin
10 *
11 * Description: This module is a container for several searching and cut computational
12 * module, which are public slots to renderwidgets.
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 ----------------------------------------------------------------------------
21 * Copyright (C) 2016 Yijiang Huang, Xin Hu, Guoxian Song, Juyong Zhang
22 * and Ligang Liu.
23 *
24 * FrameFab is free software: you can redistribute it and/or modify
25 * it under the terms of the GNU General Public License as published by
26 * the Free Software Foundation, either version 3 of the License, or
27 * (at your option) any later version.
28 *
29 * FrameFab is distributed in the hope that it will be useful,
30 * but WITHOUT ANY WARRANTY; without even the implied warranty of
31 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
32 * GNU General Public License for more details.
33 *
34 * You should have received a copy of the GNU General Public License
35 * along with FrameFab. If not, see <http://www.gnu.org/licenses/>.
36 * ==========================================================================
37 */
38 
39 #ifndef FIBERPRINTPLUGIN_H
40 #define FIBERPRINTPLUGIN_H
41 
42 // choreo utils
47 
49 //#include "choreo_task_sequence_planner/sequence_analyzers/GecodeAnalyzer.h"
50 
52 
53 // ros srv
54 #include <choreo_msgs/TaskSequencePlanning.h>
55 
56 // ros msg
57 #include <choreo_msgs/ElementCandidatePoses.h>
58 #include <choreo_msgs/WireFrameCollisionObject.h>
59 
60 // robot model
61 #include <descartes_core/robot_model.h>
62 #include <pluginlib/class_loader.h>
63 
65 {
66 
67 };
68 
70 {
71  public:
72  typedef Eigen::MatrixXd MX;
73  typedef Eigen::VectorXd VX;
74 
75  public:
76  FiberPrintPlugIn(const std::string& world_frame,
77  const std::string& hotend_group, const std::string& hotend_tcp, const std::string& hotend_base,
78  const std::string& robot_model_plugin);
79 
81 
82  public:
83  bool Init();
84 
85  bool DirectSearch();
86  bool ConstructCollisionObjects(const std::vector<int>& print_queue_edge_ids,
87  std::vector<choreo_msgs::WireFrameCollisionObject>& collision_objs);
88 
89  /* apply stiffness computation directly to the input frame shape */
90  void GetDeformation();
91 
92  /* ros service */
93  bool handleTaskSequencePlanning(
94  choreo_msgs::TaskSequencePlanning::Request& req,
95  choreo_msgs::TaskSequencePlanning::Response& res);
96 
97  public:
102  std::vector<choreo_msgs::ElementCandidatePoses> frame_msgs_;
103 
106 
107  // output saving path
108  char *ptr_path_;
110 
111  private:
113 
116 
117  private:
118  descartes_core::RobotModelPtr hotend_model_;
119  moveit::core::RobotModelConstPtr moveit_model_;
120  pluginlib::ClassLoader<descartes_core::RobotModel> plugin_loader_; // kept around so code doesn't get unloaded
121  std::string hotend_group_name_;
122 
123  std::string world_frame_;
124 };
125 
126 #endif // FIBERPRINTPLUGIN_H
SeqAnalyzer * ptr_seqanalyzer_
WireFrame * ptr_frame_
Eigen::VectorXd VX
moveit::core::RobotModelConstPtr moveit_model_
QuadricCollision * ptr_collision_
pluginlib::ClassLoader< descartes_core::RobotModel > plugin_loader_
descartes_core::RobotModelPtr hotend_model_
Stiffness * ptr_stiffness_
FiberPrintPARM * ptr_parm_
std::vector< choreo_msgs::ElementCandidatePoses > frame_msgs_
std::string world_frame_
Eigen::MatrixXd MX
DualGraph * ptr_dualgraph_
ProcAnalyzer * ptr_procanalyzer_
GLuint res
Definition: Timer.h:48
std::string hotend_group_name_


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