#include <FFAnalyzer.h>
|
| typedef Eigen::Matrix3d | M3 |
| |
| typedef Eigen::MatrixXd | MX |
| |
| typedef Eigen::Vector3d | V3 |
| |
| typedef Eigen::VectorXd | VX |
| |
| typedef Eigen::Matrix3d | M3 |
| |
| typedef Eigen::MatrixXd | MX |
| |
| typedef Eigen::Vector3d | V3 |
| |
| typedef Eigen::VectorXd | VX |
| |
|
| | 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 |
| |
| void | PrintOutTimer () |
| |
| bool | SeqPrint () |
| |
| bool | SeqPrintLayer (std::vector< int > layer_id) |
| |
| | ~FFAnalyzer () |
| |
| bool | ConstructCollisionObjsInQueue (const std::vector< int > &print_queue_edge_ids, std::vector< choreo_msgs::WireFrameCollisionObject > &collision_objs) |
| |
| bool | InputPrintOrder (const std::vector< int > &print_queue) |
| |
| void | OutputPrintOrder (std::vector< WF_edge * > &print_queue) |
| |
| void | OutputTaskSequencePlanningResult (std::vector< SingleTaskPlanningResult > &planning_result) |
| |
| | 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 |
| |
| void | setFrameMsgs (const std::vector< choreo_msgs::ElementCandidatePoses > &frame_msg) |
| |
| virtual | ~SeqAnalyzer () |
| |
Definition at line 57 of file FFAnalyzer.h.
| FFAnalyzer::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 |
|
) |
| |
|
inlineexplicitnoexcept |
| FFAnalyzer::~FFAnalyzer |
( |
| ) |
|
| double FFAnalyzer::GenerateCost |
( |
WF_edge * |
ej, |
|
|
const int |
h, |
|
|
const int |
t, |
|
|
const int |
layer_id |
|
) |
| |
|
private |
| bool FFAnalyzer::GenerateSeq |
( |
int |
l, |
|
|
int |
h, |
|
|
int |
t |
|
) |
| |
|
private |
| void FFAnalyzer::PrintOutTimer |
( |
| ) |
|
|
virtual |
| bool FFAnalyzer::SeqPrint |
( |
| ) |
|
|
virtual |
| bool FFAnalyzer::SeqPrintLayer |
( |
std::vector< int > |
layer_id | ) |
|
|
virtual |
| Timer FFAnalyzer::FF_analyzer_ |
|
private |
| std::vector<std::vector<WF_edge*> > FFAnalyzer::layers_ |
|
private |
| double FFAnalyzer::max_base_dist_ |
|
private |
| double FFAnalyzer::max_z_ |
|
private |
| double FFAnalyzer::min_base_dist_ |
|
private |
| double FFAnalyzer::min_z_ |
|
private |
The documentation for this class was generated from the following files: