#include <FiberPrintPlugIn.h>
Public Types | |
| typedef Eigen::MatrixXd | MX |
| typedef Eigen::VectorXd | VX |
Public Member Functions | |
| bool | ConstructCollisionObjects (const std::vector< int > &print_queue_edge_ids, std::vector< choreo_msgs::WireFrameCollisionObject > &collision_objs) |
| bool | DirectSearch () |
| FiberPrintPlugIn (const std::string &world_frame, const std::string &hotend_group, const std::string &hotend_tcp, const std::string &hotend_base, const std::string &robot_model_plugin) | |
| void | GetDeformation () |
| bool | handleTaskSequencePlanning (choreo_msgs::TaskSequencePlanning::Request &req, choreo_msgs::TaskSequencePlanning::Response &res) |
| bool | Init () |
| ~FiberPrintPlugIn () | |
Public Attributes | |
| std::vector< choreo_msgs::ElementCandidatePoses > | frame_msgs_ |
| QuadricCollision * | ptr_collision_ |
| DualGraph * | ptr_dualgraph_ |
| WireFrame * | ptr_frame_ |
| FiberPrintPARM * | ptr_parm_ |
| char * | ptr_path_ |
| ProcAnalyzer * | ptr_procanalyzer_ |
| SeqAnalyzer * | ptr_seqanalyzer_ |
| Stiffness * | ptr_stiffness_ |
Private Attributes | |
| Timer | fiber_print_ |
| bool | file_output_ |
| std::string | hotend_group_name_ |
| descartes_core::RobotModelPtr | hotend_model_ |
| moveit::core::RobotModelConstPtr | moveit_model_ |
| pluginlib::ClassLoader< descartes_core::RobotModel > | plugin_loader_ |
| bool | terminal_output_ |
| std::string | world_frame_ |
Definition at line 69 of file FiberPrintPlugIn.h.
| typedef Eigen::MatrixXd FiberPrintPlugIn::MX |
Definition at line 72 of file FiberPrintPlugIn.h.
| typedef Eigen::VectorXd FiberPrintPlugIn::VX |
Definition at line 73 of file FiberPrintPlugIn.h.
| FiberPrintPlugIn::FiberPrintPlugIn | ( | const std::string & | world_frame, |
| const std::string & | hotend_group, | ||
| const std::string & | hotend_tcp, | ||
| const std::string & | hotend_base, | ||
| const std::string & | robot_model_plugin | ||
| ) |
Definition at line 285 of file FiberPrintPlugIn.cpp.
| FiberPrintPlugIn::~FiberPrintPlugIn | ( | ) |
Definition at line 333 of file FiberPrintPlugIn.cpp.
| bool FiberPrintPlugIn::ConstructCollisionObjects | ( | const std::vector< int > & | print_queue_edge_ids, |
| std::vector< choreo_msgs::WireFrameCollisionObject > & | collision_objs | ||
| ) |
Definition at line 436 of file FiberPrintPlugIn.cpp.
| bool FiberPrintPlugIn::DirectSearch | ( | ) |
Definition at line 386 of file FiberPrintPlugIn.cpp.
| void FiberPrintPlugIn::GetDeformation | ( | ) |
Definition at line 468 of file FiberPrintPlugIn.cpp.
| bool FiberPrintPlugIn::handleTaskSequencePlanning | ( | choreo_msgs::TaskSequencePlanning::Request & | req, |
| choreo_msgs::TaskSequencePlanning::Response & | res | ||
| ) |
Definition at line 517 of file FiberPrintPlugIn.cpp.
| bool FiberPrintPlugIn::Init | ( | ) |
Definition at line 357 of file FiberPrintPlugIn.cpp.
|
private |
Definition at line 112 of file FiberPrintPlugIn.h.
|
private |
Definition at line 115 of file FiberPrintPlugIn.h.
| std::vector<choreo_msgs::ElementCandidatePoses> FiberPrintPlugIn::frame_msgs_ |
Definition at line 102 of file FiberPrintPlugIn.h.
|
private |
Definition at line 121 of file FiberPrintPlugIn.h.
|
private |
Definition at line 118 of file FiberPrintPlugIn.h.
|
private |
Definition at line 119 of file FiberPrintPlugIn.h.
|
private |
Definition at line 120 of file FiberPrintPlugIn.h.
| QuadricCollision* FiberPrintPlugIn::ptr_collision_ |
Definition at line 100 of file FiberPrintPlugIn.h.
| DualGraph* FiberPrintPlugIn::ptr_dualgraph_ |
Definition at line 99 of file FiberPrintPlugIn.h.
| WireFrame* FiberPrintPlugIn::ptr_frame_ |
Definition at line 98 of file FiberPrintPlugIn.h.
| FiberPrintPARM* FiberPrintPlugIn::ptr_parm_ |
Definition at line 109 of file FiberPrintPlugIn.h.
| char* FiberPrintPlugIn::ptr_path_ |
Definition at line 108 of file FiberPrintPlugIn.h.
| ProcAnalyzer* FiberPrintPlugIn::ptr_procanalyzer_ |
Definition at line 105 of file FiberPrintPlugIn.h.
| SeqAnalyzer* FiberPrintPlugIn::ptr_seqanalyzer_ |
Definition at line 104 of file FiberPrintPlugIn.h.
| Stiffness* FiberPrintPlugIn::ptr_stiffness_ |
Definition at line 101 of file FiberPrintPlugIn.h.
|
private |
Definition at line 114 of file FiberPrintPlugIn.h.
|
private |
Definition at line 123 of file FiberPrintPlugIn.h.