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

#include <SeqAnalyzer.h>

Inheritance diagram for SeqAnalyzer:
Inheritance graph
[legend]

Public Types

typedef Eigen::Matrix3d M3
 
typedef Eigen::MatrixXd MX
 
typedef Eigen::Vector3d V3
 
typedef Eigen::VectorXd VX
 

Public Member Functions

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

Public Attributes

std::vector< choreo_msgs::ElementCandidatePoses > frame_msgs_
 
QuadricCollisionptr_collision_
 
DualGraphptr_dualgraph_
 
WireFrameptr_frame_
 
char * ptr_path_
 
Stiffnessptr_stiffness_
 

Protected Member Functions

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

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_
 

Private Member Functions

std::vector< moveit_msgs::CollisionObject > RecoverCollisionObjects (WF_edge *e, bool shrink=false)
 
std::vector< moveit_msgs::CollisionObject > UpdateCollisionObjects (WF_edge *e, bool shrink=false)
 

Detailed Description

Definition at line 70 of file SeqAnalyzer.h.

Member Typedef Documentation

typedef Eigen::Matrix3d SeqAnalyzer::M3

Definition at line 74 of file SeqAnalyzer.h.

typedef Eigen::MatrixXd SeqAnalyzer::MX

Definition at line 73 of file SeqAnalyzer.h.

typedef Eigen::Vector3d SeqAnalyzer::V3

Definition at line 76 of file SeqAnalyzer.h.

typedef Eigen::VectorXd SeqAnalyzer::VX

Definition at line 75 of file SeqAnalyzer.h.

Constructor & Destructor Documentation

SeqAnalyzer::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 
)
explicitnoexcept

Definition at line 155 of file SeqAnalyzer.cpp.

SeqAnalyzer::~SeqAnalyzer ( )
virtual

Definition at line 194 of file SeqAnalyzer.cpp.

Member Function Documentation

bool SeqAnalyzer::ConstructCollisionObjsInQueue ( const std::vector< int > &  print_queue_edge_ids,
std::vector< choreo_msgs::WireFrameCollisionObject > &  collision_objs 
)

Definition at line 888 of file SeqAnalyzer.cpp.

void SeqAnalyzer::Init ( )
protected

Definition at line 214 of file SeqAnalyzer.cpp.

bool SeqAnalyzer::InputPrintOrder ( const std::vector< int > &  print_queue)

Definition at line 869 of file SeqAnalyzer.cpp.

void SeqAnalyzer::OutputPrintOrder ( std::vector< WF_edge * > &  print_queue)

Definition at line 933 of file SeqAnalyzer.cpp.

void SeqAnalyzer::OutputTaskSequencePlanningResult ( std::vector< SingleTaskPlanningResult > &  planning_result)

Definition at line 944 of file SeqAnalyzer.cpp.

void SeqAnalyzer::PrintOutTimer ( )
virtual

Reimplemented in GecodeAnalyzer, and FFAnalyzer.

Definition at line 210 of file SeqAnalyzer.cpp.

void SeqAnalyzer::PrintPillars ( )
protected

Definition at line 262 of file SeqAnalyzer.cpp.

std::vector< moveit_msgs::CollisionObject > SeqAnalyzer::RecoverCollisionObjects ( WF_edge e,
bool  shrink = false 
)
private

Definition at line 549 of file SeqAnalyzer.cpp.

void SeqAnalyzer::RecoverStateMap ( WF_edge e,
vector< vector< lld >> &  state_map 
)
protected

Definition at line 421 of file SeqAnalyzer.cpp.

void SeqAnalyzer::RecoverStructure ( WF_edge e,
bool  update_collision = false 
)
protected

Definition at line 357 of file SeqAnalyzer.cpp.

WF_edge * SeqAnalyzer::RouteEdgeDirection ( const WF_edge prev_e,
WF_edge e 
)
protected

Definition at line 783 of file SeqAnalyzer.cpp.

bool SeqAnalyzer::SeqPrint ( )
virtual

Reimplemented in GecodeAnalyzer, and FFAnalyzer.

Definition at line 200 of file SeqAnalyzer.cpp.

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

Reimplemented in FFAnalyzer.

Definition at line 205 of file SeqAnalyzer.cpp.

void SeqAnalyzer::setFrameMsgs ( const std::vector< choreo_msgs::ElementCandidatePoses > &  frame_msg)
inline

Definition at line 94 of file SeqAnalyzer.h.

bool SeqAnalyzer::TestifyStiffness ( WF_edge e)
protected

Definition at line 640 of file SeqAnalyzer.cpp.

bool SeqAnalyzer::TestRobotKinematics ( WF_edge e,
const std::vector< lld > &  colli_map 
)
protected

Definition at line 681 of file SeqAnalyzer.cpp.

std::vector< moveit_msgs::CollisionObject > SeqAnalyzer::UpdateCollisionObjects ( WF_edge e,
bool  shrink = false 
)
private

Definition at line 447 of file SeqAnalyzer.cpp.

void SeqAnalyzer::UpdateStateMap ( WF_edge e,
vector< vector< lld >> &  state_map 
)
protected

Definition at line 380 of file SeqAnalyzer.cpp.

void SeqAnalyzer::UpdateStructure ( WF_edge e,
bool  update_collision = false 
)
protected

Definition at line 305 of file SeqAnalyzer.cpp.

Member Data Documentation

vector<vector<unsigned long long> > SeqAnalyzer::angle_state_
protected

Definition at line 151 of file SeqAnalyzer.h.

VX SeqAnalyzer::D0_
protected

Definition at line 153 of file SeqAnalyzer.h.

double SeqAnalyzer::D_tol_
protected

Definition at line 157 of file SeqAnalyzer.h.

bool SeqAnalyzer::file_output_
protected

Definition at line 164 of file SeqAnalyzer.h.

std::vector<choreo_msgs::ElementCandidatePoses> SeqAnalyzer::frame_msgs_

Definition at line 138 of file SeqAnalyzer.h.

double SeqAnalyzer::gamma_
protected

Definition at line 156 of file SeqAnalyzer.h.

std::string SeqAnalyzer::hotend_group_name_
protected

Definition at line 177 of file SeqAnalyzer.h.

descartes_core::RobotModelPtr SeqAnalyzer::hotend_model_
protected

Definition at line 175 of file SeqAnalyzer.h.

moveit::core::RobotModelConstPtr SeqAnalyzer::moveit_model_
protected

Definition at line 176 of file SeqAnalyzer.h.

int SeqAnalyzer::Nd_
protected

Definition at line 143 of file SeqAnalyzer.h.

int SeqAnalyzer::num_backtrack_
protected

Definition at line 182 of file SeqAnalyzer.h.

int SeqAnalyzer::num_p_assign_visited_
protected

Definition at line 181 of file SeqAnalyzer.h.

planning_scene::PlanningScenePtr SeqAnalyzer::planning_scene_
protected

Definition at line 179 of file SeqAnalyzer.h.

std::vector<WF_edge*> SeqAnalyzer::print_queue_
protected

Definition at line 148 of file SeqAnalyzer.h.

QuadricCollision* SeqAnalyzer::ptr_collision_

Definition at line 135 of file SeqAnalyzer.h.

DualGraph* SeqAnalyzer::ptr_dualgraph_

Definition at line 133 of file SeqAnalyzer.h.

WireFrame* SeqAnalyzer::ptr_frame_

Definition at line 132 of file SeqAnalyzer.h.

char* SeqAnalyzer::ptr_path_

Definition at line 136 of file SeqAnalyzer.h.

Stiffness* SeqAnalyzer::ptr_stiffness_

Definition at line 134 of file SeqAnalyzer.h.

DualGraph* SeqAnalyzer::ptr_wholegraph_
protected

Definition at line 146 of file SeqAnalyzer.h.

Timer SeqAnalyzer::rec_map_
protected

Definition at line 172 of file SeqAnalyzer.h.

Timer SeqAnalyzer::rec_struct_
protected

Definition at line 169 of file SeqAnalyzer.h.

int SeqAnalyzer::search_rerun_
protected

Definition at line 184 of file SeqAnalyzer.h.

bool SeqAnalyzer::terminal_output_
protected

Definition at line 163 of file SeqAnalyzer.h.

Timer SeqAnalyzer::test_stiff_
protected

Definition at line 173 of file SeqAnalyzer.h.

Timer SeqAnalyzer::upd_map_
protected

Definition at line 170 of file SeqAnalyzer.h.

Timer SeqAnalyzer::upd_map_collision_
protected

Definition at line 171 of file SeqAnalyzer.h.

Timer SeqAnalyzer::upd_struct_
protected

Definition at line 168 of file SeqAnalyzer.h.

bool SeqAnalyzer::update_collision_
protected

Definition at line 166 of file SeqAnalyzer.h.

double SeqAnalyzer::Wa_
protected

Definition at line 159 of file SeqAnalyzer.h.

double SeqAnalyzer::Wi_
protected

Definition at line 160 of file SeqAnalyzer.h.

double SeqAnalyzer::Wp_
protected

Definition at line 158 of file SeqAnalyzer.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