#include <structure_learner_base.h>

Public Member Functions | |
| void | addPreviousGraphs () |
| void | analyzeTopologyOfGraphs () |
| std::vector< double > | downsampleStamps (std::vector< double > vec, size_t num) |
| void | enumerateGraphs () |
| void | evalFast (bool setCurrent) |
| void | evalFull () |
| void | evalTree () |
| KinematicGraph | getSpanningTree (bool increasing) |
| KinematicStructureLearner () | |
| void | poseCallback (const PoseStampedConstPtr &pose, size_t id) |
| void | poseCallback (const PoseStampedIdMsgConstPtr &pose) |
| void | poseCallback1 (const PoseStampedConstPtr &pose) |
| void | poseCallback2 (const PoseStampedConstPtr &pose) |
| void | poseCallback3 (const PoseStampedConstPtr &pose) |
| void | poseCallback4 (const PoseStampedConstPtr &pose) |
| void | saveBICEval () |
| void | saveDOFLinkEval () |
| void | saveGraphEval () |
| void | saveRuntimeEval () |
| virtual void | selectSceneModel () |
| virtual void | sendModels (KinematicGraph E_new) |
| virtual void | sendSceneModel () |
| virtual void | sendStructureVisualization (KinematicGraph graph) |
| virtual void | sendTreeTransforms (KinematicGraph E_new) |
| void | showEvaluation () |
Public Attributes | |
| KinematicGraph | currentGraph |
| std::map< int, double > | evalDOF |
| std::map< int, double > | evalFastBIC |
| std::map< int, double > | evalFastRuntime |
| std::map< std::string, EvalStruct > | evalGraph |
| std::map< int, double > | evalGraphBIC |
| std::map< int, double > | evalGraphRuntime |
| std::map< int, double > | evalLinks |
| std::map< int, double > | evalModelsRuntime |
| std::map< int, double > | evalTreeBIC |
| std::map< int, double > | evalTreeRuntime |
| boost::mutex | frame_mutex_ |
| map< string, KinematicGraph > | graphMap |
| ros::Publisher | marker_pub |
| ros::Publisher | model_pub |
| ros::NodeHandle | nh |
| ros::NodeHandle | nh_local |
| ros::Subscriber | pose_sub1 |
| ros::Subscriber | pose_sub2 |
| ros::Subscriber | pose_sub3 |
| ros::Subscriber | pose_sub4 |
| map< string, KinematicGraph > | previousGraphs |
Definition at line 44 of file structure_learner_base.h.
| KinematicStructureLearner::KinematicStructureLearner | ( | ) |
Definition at line 12 of file structure_learner_base.cpp.
| void KinematicStructureLearner::addPreviousGraphs | ( | ) |
Definition at line 534 of file structure_learner_base.cpp.
| void KinematicStructureLearner::analyzeTopologyOfGraphs | ( | ) |
Definition at line 1021 of file structure_learner_base.cpp.
| std::vector< double > KinematicStructureLearner::downsampleStamps | ( | std::vector< double > | vec, | |
| size_t | num | |||
| ) |
Definition at line 513 of file structure_learner_base.cpp.
| void KinematicStructureLearner::enumerateGraphs | ( | ) |
Definition at line 778 of file structure_learner_base.cpp.
| void KinematicStructureLearner::evalFast | ( | bool | setCurrent | ) |
Definition at line 691 of file structure_learner_base.cpp.
| void KinematicStructureLearner::evalFull | ( | ) |
Definition at line 611 of file structure_learner_base.cpp.
| void KinematicStructureLearner::evalTree | ( | ) |
Definition at line 589 of file structure_learner_base.cpp.
| KinematicGraph KinematicStructureLearner::getSpanningTree | ( | bool | increasing | ) |
Definition at line 27 of file structure_learner_base.cpp.
| void KinematicStructureLearner::poseCallback | ( | const PoseStampedConstPtr & | pose, | |
| size_t | id | |||
| ) |
Definition at line 946 of file structure_learner_base.cpp.
| void KinematicStructureLearner::poseCallback | ( | const PoseStampedIdMsgConstPtr & | pose | ) |
Definition at line 895 of file structure_learner_base.cpp.
| void KinematicStructureLearner::poseCallback1 | ( | const PoseStampedConstPtr & | pose | ) |
Definition at line 1005 of file structure_learner_base.cpp.
| void KinematicStructureLearner::poseCallback2 | ( | const PoseStampedConstPtr & | pose | ) |
Definition at line 1009 of file structure_learner_base.cpp.
| void KinematicStructureLearner::poseCallback3 | ( | const PoseStampedConstPtr & | pose | ) |
Definition at line 1013 of file structure_learner_base.cpp.
| void KinematicStructureLearner::poseCallback4 | ( | const PoseStampedConstPtr & | pose | ) |
Definition at line 1017 of file structure_learner_base.cpp.
| void KinematicStructureLearner::saveBICEval | ( | ) |
Definition at line 270 of file structure_learner_base.cpp.
| void KinematicStructureLearner::saveDOFLinkEval | ( | ) |
Definition at line 333 of file structure_learner_base.cpp.
| void KinematicStructureLearner::saveGraphEval | ( | ) |
Definition at line 143 of file structure_learner_base.cpp.
| void KinematicStructureLearner::saveRuntimeEval | ( | ) |
Definition at line 307 of file structure_learner_base.cpp.
| void KinematicStructureLearner::selectSceneModel | ( | ) | [virtual] |
Definition at line 565 of file structure_learner_base.cpp.
| void KinematicStructureLearner::sendModels | ( | KinematicGraph | E_new | ) | [virtual] |
Definition at line 90 of file structure_learner_base.cpp.
| void KinematicStructureLearner::sendSceneModel | ( | ) | [virtual] |
Definition at line 888 of file structure_learner_base.cpp.
| void KinematicStructureLearner::sendStructureVisualization | ( | KinematicGraph | graph | ) | [virtual] |
Definition at line 356 of file structure_learner_base.cpp.
| void KinematicStructureLearner::sendTreeTransforms | ( | KinematicGraph | E_new | ) | [virtual] |
Definition at line 123 of file structure_learner_base.cpp.
| void KinematicStructureLearner::showEvaluation | ( | ) |
Definition at line 876 of file structure_learner_base.cpp.
Definition at line 74 of file structure_learner_base.h.
| std::map< int, double> KinematicStructureLearner::evalDOF |
Definition at line 71 of file structure_learner_base.h.
| std::map< int, double> KinematicStructureLearner::evalFastBIC |
Definition at line 63 of file structure_learner_base.h.
| std::map< int, double> KinematicStructureLearner::evalFastRuntime |
Definition at line 68 of file structure_learner_base.h.
| std::map< std::string, EvalStruct> KinematicStructureLearner::evalGraph |
Definition at line 60 of file structure_learner_base.h.
| std::map< int, double> KinematicStructureLearner::evalGraphBIC |
Definition at line 62 of file structure_learner_base.h.
| std::map< int, double> KinematicStructureLearner::evalGraphRuntime |
Definition at line 67 of file structure_learner_base.h.
| std::map< int, double> KinematicStructureLearner::evalLinks |
Definition at line 72 of file structure_learner_base.h.
| std::map< int, double> KinematicStructureLearner::evalModelsRuntime |
Definition at line 66 of file structure_learner_base.h.
| std::map< int, double> KinematicStructureLearner::evalTreeBIC |
Definition at line 64 of file structure_learner_base.h.
| std::map< int, double> KinematicStructureLearner::evalTreeRuntime |
Definition at line 69 of file structure_learner_base.h.
| boost::mutex KinematicStructureLearner::frame_mutex_ |
Definition at line 46 of file structure_learner_base.h.
| map< string, KinematicGraph > KinematicStructureLearner::graphMap |
Definition at line 59 of file structure_learner_base.h.
| ros::Publisher KinematicStructureLearner::marker_pub |
Definition at line 49 of file structure_learner_base.h.
| ros::Publisher KinematicStructureLearner::model_pub |
Definition at line 48 of file structure_learner_base.h.
| ros::NodeHandle KinematicStructureLearner::nh |
Definition at line 51 of file structure_learner_base.h.
| ros::NodeHandle KinematicStructureLearner::nh_local |
Definition at line 52 of file structure_learner_base.h.
| ros::Subscriber KinematicStructureLearner::pose_sub1 |
Definition at line 54 of file structure_learner_base.h.
| ros::Subscriber KinematicStructureLearner::pose_sub2 |
Definition at line 55 of file structure_learner_base.h.
| ros::Subscriber KinematicStructureLearner::pose_sub3 |
Definition at line 56 of file structure_learner_base.h.
| ros::Subscriber KinematicStructureLearner::pose_sub4 |
Definition at line 57 of file structure_learner_base.h.
| map< string, KinematicGraph > KinematicStructureLearner::previousGraphs |
Definition at line 75 of file structure_learner_base.h.