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

#include <GecodeAnalyzer.h>

Inheritance diagram for GecodeAnalyzer:
Inheritance graph
[legend]

Public Types

enum  CSPDataMatrixStorageType { ROW_MAJOR, COL_MAJOR }
 
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

void debug ()
 
 GecodeAnalyzer (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 ()
 
 ~GecodeAnalyzer ()
 
- 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
 
virtual bool SeqPrintLayer (std::vector< int > layer_id)
 
void setFrameMsgs (const std::vector< choreo_msgs::ElementCandidatePoses > &frame_msg)
 
virtual ~SeqAnalyzer ()
 

Private Member Functions

void ComputeGecodeInput (const std::vector< WF_edge * > &layer_e, std::vector< int > &A, std::vector< int > &G, std::vector< int > &T, CSPDataMatrixStorageType m_type)
 

Private Attributes

Timer gecode_analyzer_
 
std::vector< std::vector< WF_edge * > > layers_
 
double max_z_
 
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 155 of file GecodeAnalyzer.h.

Member Typedef Documentation

typedef Eigen::Matrix3d GecodeAnalyzer::M3

Definition at line 165 of file GecodeAnalyzer.h.

typedef Eigen::MatrixXd GecodeAnalyzer::MX

Definition at line 164 of file GecodeAnalyzer.h.

typedef Eigen::Vector3d GecodeAnalyzer::V3

Definition at line 167 of file GecodeAnalyzer.h.

typedef Eigen::VectorXd GecodeAnalyzer::VX

Definition at line 166 of file GecodeAnalyzer.h.

Member Enumeration Documentation

Enumerator
ROW_MAJOR 
COL_MAJOR 

Definition at line 158 of file GecodeAnalyzer.h.

Constructor & Destructor Documentation

GecodeAnalyzer::GecodeAnalyzer ( 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 170 of file GecodeAnalyzer.h.

GecodeAnalyzer::~GecodeAnalyzer ( )

Definition at line 73 of file GecodeAnalyzer.cpp.

Member Function Documentation

void GecodeAnalyzer::ComputeGecodeInput ( const std::vector< WF_edge * > &  layer_e,
std::vector< int > &  A,
std::vector< int > &  G,
std::vector< int > &  T,
CSPDataMatrixStorageType  m_type 
)
private

Definition at line 157 of file GecodeAnalyzer.cpp.

void GecodeAnalyzer::debug ( )

Definition at line 278 of file GecodeAnalyzer.cpp.

void GecodeAnalyzer::PrintOutTimer ( )
virtual

Reimplemented from SeqAnalyzer.

Definition at line 272 of file GecodeAnalyzer.cpp.

bool GecodeAnalyzer::SeqPrint ( )
virtual

Reimplemented from SeqAnalyzer.

Definition at line 77 of file GecodeAnalyzer.cpp.

Member Data Documentation

Timer GecodeAnalyzer::gecode_analyzer_
private

Definition at line 205 of file GecodeAnalyzer.h.

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

Definition at line 200 of file GecodeAnalyzer.h.

double GecodeAnalyzer::max_z_
private

Definition at line 203 of file GecodeAnalyzer.h.

double GecodeAnalyzer::min_z_
private

Definition at line 202 of file GecodeAnalyzer.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