#include <SeqAnalyzer.h>
|
typedef Eigen::Matrix3d | M3 |
|
typedef Eigen::MatrixXd | MX |
|
typedef Eigen::Vector3d | V3 |
|
typedef Eigen::VectorXd | VX |
|
|
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 () |
|
Definition at line 70 of file SeqAnalyzer.h.
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 |
SeqAnalyzer::~SeqAnalyzer |
( |
| ) |
|
|
virtual |
bool SeqAnalyzer::ConstructCollisionObjsInQueue |
( |
const std::vector< int > & |
print_queue_edge_ids, |
|
|
std::vector< choreo_msgs::WireFrameCollisionObject > & |
collision_objs |
|
) |
| |
void SeqAnalyzer::Init |
( |
| ) |
|
|
protected |
bool SeqAnalyzer::InputPrintOrder |
( |
const std::vector< int > & |
print_queue | ) |
|
void SeqAnalyzer::OutputPrintOrder |
( |
std::vector< WF_edge * > & |
print_queue | ) |
|
void SeqAnalyzer::PrintOutTimer |
( |
| ) |
|
|
virtual |
void SeqAnalyzer::PrintPillars |
( |
| ) |
|
|
protected |
std::vector< moveit_msgs::CollisionObject > SeqAnalyzer::RecoverCollisionObjects |
( |
WF_edge * |
e, |
|
|
bool |
shrink = false |
|
) |
| |
|
private |
void SeqAnalyzer::RecoverStateMap |
( |
WF_edge * |
e, |
|
|
vector< vector< lld >> & |
state_map |
|
) |
| |
|
protected |
void SeqAnalyzer::RecoverStructure |
( |
WF_edge * |
e, |
|
|
bool |
update_collision = false |
|
) |
| |
|
protected |
bool SeqAnalyzer::SeqPrint |
( |
| ) |
|
|
virtual |
bool SeqAnalyzer::SeqPrintLayer |
( |
std::vector< int > |
layer_id | ) |
|
|
virtual |
void SeqAnalyzer::setFrameMsgs |
( |
const std::vector< choreo_msgs::ElementCandidatePoses > & |
frame_msg | ) |
|
|
inline |
bool SeqAnalyzer::TestifyStiffness |
( |
WF_edge * |
e | ) |
|
|
protected |
bool SeqAnalyzer::TestRobotKinematics |
( |
WF_edge * |
e, |
|
|
const std::vector< lld > & |
colli_map |
|
) |
| |
|
protected |
std::vector< moveit_msgs::CollisionObject > SeqAnalyzer::UpdateCollisionObjects |
( |
WF_edge * |
e, |
|
|
bool |
shrink = false |
|
) |
| |
|
private |
void SeqAnalyzer::UpdateStateMap |
( |
WF_edge * |
e, |
|
|
vector< vector< lld >> & |
state_map |
|
) |
| |
|
protected |
void SeqAnalyzer::UpdateStructure |
( |
WF_edge * |
e, |
|
|
bool |
update_collision = false |
|
) |
| |
|
protected |
vector<vector<unsigned long long> > SeqAnalyzer::angle_state_ |
|
protected |
double SeqAnalyzer::D_tol_ |
|
protected |
bool SeqAnalyzer::file_output_ |
|
protected |
std::vector<choreo_msgs::ElementCandidatePoses> SeqAnalyzer::frame_msgs_ |
double SeqAnalyzer::gamma_ |
|
protected |
descartes_core::RobotModelPtr SeqAnalyzer::hotend_model_ |
|
protected |
moveit::core::RobotModelConstPtr SeqAnalyzer::moveit_model_ |
|
protected |
int SeqAnalyzer::num_backtrack_ |
|
protected |
int SeqAnalyzer::num_p_assign_visited_ |
|
protected |
planning_scene::PlanningScenePtr SeqAnalyzer::planning_scene_ |
|
protected |
std::vector<WF_edge*> SeqAnalyzer::print_queue_ |
|
protected |
char* SeqAnalyzer::ptr_path_ |
Timer SeqAnalyzer::rec_map_ |
|
protected |
Timer SeqAnalyzer::rec_struct_ |
|
protected |
int SeqAnalyzer::search_rerun_ |
|
protected |
bool SeqAnalyzer::terminal_output_ |
|
protected |
Timer SeqAnalyzer::test_stiff_ |
|
protected |
Timer SeqAnalyzer::upd_map_ |
|
protected |
Timer SeqAnalyzer::upd_map_collision_ |
|
protected |
Timer SeqAnalyzer::upd_struct_ |
|
protected |
bool SeqAnalyzer::update_collision_ |
|
protected |
The documentation for this class was generated from the following files: