Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
FFAnalyzer Class Reference

#include <FFAnalyzer.h>

Inheritance diagram for FFAnalyzer:
Inheritance graph
[legend]

Public Types

typedef Eigen::Matrix3d M3
 
typedef Eigen::MatrixXd MX
 
typedef Eigen::Vector3d V3
 
typedef Eigen::VectorXd VX
 
- Public Types inherited from SeqAnalyzer
typedef Eigen::Matrix3d M3
 
typedef Eigen::MatrixXd MX
 
typedef Eigen::Vector3d V3
 
typedef Eigen::VectorXd VX
 

Public Member Functions

 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 ()
 
- Public Member Functions inherited from SeqAnalyzer
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 ()
 

Private Member Functions

double GenerateCost (WF_edge *ej, const int h, const int t, const int layer_id)
 
bool GenerateSeq (int l, int h, int t)
 

Private Attributes

Timer FF_analyzer_
 
std::vector< std::vector< WF_edge * > > layers_
 
double max_base_dist_
 
double max_z_
 
double min_base_dist_
 
double min_z_
 

Additional Inherited Members

- Public Attributes inherited from SeqAnalyzer
std::vector< choreo_msgs::ElementCandidatePoses > frame_msgs_
 
QuadricCollisionptr_collision_
 
DualGraphptr_dualgraph_
 
WireFrameptr_frame_
 
char * ptr_path_
 
Stiffnessptr_stiffness_
 
- Protected Member Functions inherited from SeqAnalyzer
void Init ()
 
void PrintPillars ()
 
void RecoverStateMap (WF_edge *e, vector< vector< lld >> &state_map)
 
void RecoverStructure (WF_edge *e, bool update_collision=false)
 
WF_edgeRouteEdgeDirection (const WF_edge *prev_e, WF_edge *e)
 
bool TestifyStiffness (WF_edge *e)
 
bool TestRobotKinematics (WF_edge *e, const std::vector< lld > &colli_map)
 
void UpdateStateMap (WF_edge *e, vector< vector< lld >> &state_map)
 
void UpdateStructure (WF_edge *e, bool update_collision=false)
 
- Protected Attributes inherited from SeqAnalyzer
vector< vector< unsigned long long > > angle_state_
 
VX D0_
 
double D_tol_
 
bool file_output_
 
double gamma_
 
std::string hotend_group_name_
 
descartes_core::RobotModelPtr hotend_model_
 
moveit::core::RobotModelConstPtr moveit_model_
 
int Nd_
 
int num_backtrack_
 
int num_p_assign_visited_
 
planning_scene::PlanningScenePtr planning_scene_
 
std::vector< WF_edge * > print_queue_
 
DualGraphptr_wholegraph_
 
Timer rec_map_
 
Timer rec_struct_
 
int search_rerun_
 
bool terminal_output_
 
Timer test_stiff_
 
Timer upd_map_
 
Timer upd_map_collision_
 
Timer upd_struct_
 
bool update_collision_
 
double Wa_
 
double Wi_
 
double Wp_
 

Detailed Description

Definition at line 57 of file FFAnalyzer.h.

Member Typedef Documentation

typedef Eigen::Matrix3d FFAnalyzer::M3

Definition at line 61 of file FFAnalyzer.h.

typedef Eigen::MatrixXd FFAnalyzer::MX

Definition at line 60 of file FFAnalyzer.h.

typedef Eigen::Vector3d FFAnalyzer::V3

Definition at line 63 of file FFAnalyzer.h.

typedef Eigen::VectorXd FFAnalyzer::VX

Definition at line 62 of file FFAnalyzer.h.

Constructor & Destructor Documentation

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

Definition at line 66 of file FFAnalyzer.h.

FFAnalyzer::~FFAnalyzer ( )

Definition at line 3 of file FFAnalyzer.cpp.

Member Function Documentation

double FFAnalyzer::GenerateCost ( WF_edge ej,
const int  h,
const int  t,
const int  layer_id 
)
private

Definition at line 359 of file FFAnalyzer.cpp.

bool FFAnalyzer::GenerateSeq ( int  l,
int  h,
int  t 
)
private

Definition at line 240 of file FFAnalyzer.cpp.

void FFAnalyzer::PrintOutTimer ( )
virtual

Reimplemented from SeqAnalyzer.

Definition at line 558 of file FFAnalyzer.cpp.

bool FFAnalyzer::SeqPrint ( )
virtual

Reimplemented from SeqAnalyzer.

Definition at line 7 of file FFAnalyzer.cpp.

bool FFAnalyzer::SeqPrintLayer ( std::vector< int layer_id)
virtual

Reimplemented from SeqAnalyzer.

Definition at line 106 of file FFAnalyzer.cpp.

Member Data Documentation

Timer FFAnalyzer::FF_analyzer_
private

Definition at line 103 of file FFAnalyzer.h.

std::vector<std::vector<WF_edge*> > FFAnalyzer::layers_
private

Definition at line 95 of file FFAnalyzer.h.

double FFAnalyzer::max_base_dist_
private

Definition at line 101 of file FFAnalyzer.h.

double FFAnalyzer::max_z_
private

Definition at line 98 of file FFAnalyzer.h.

double FFAnalyzer::min_base_dist_
private

Definition at line 100 of file FFAnalyzer.h.

double FFAnalyzer::min_z_
private

Definition at line 97 of file FFAnalyzer.h.


The documentation for this class was generated from the following files:


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