, including all inherited members.
addNodesToPlane(PlanePatchPtr &plane, const NodePointers &nodes, const OcTree &octree, const PointCloud &pointCloud, PlanePatchVector &pointMapping) | StructureColoring | [protected] |
addPlanePatchesAndUpdateSegmented(PlanePatches &extractedPlanes, PlanePatchVector &pointMapping, const PlanePatches &planePatches) | StructureColoring | [protected] |
assignNodesToCylinders(NodePointers &octreeNodes, CylinderPatches &extractedCylinders, CylinderPatchVector &pointMapping, const OcTree &octree, const PointCloud &pointCloud) | StructureColoring | [protected] |
assignNodesToPlanes(NodePointers ¬AssignedOctreeNodes, const unsigned int &octreeDepth, const OcTree &octree, PlanePatches &extractedPlanes, const PointCloud &pointCloud, PlanePatchVector &pointMapping) | StructureColoring | [protected] |
calculateMiddlePlane(Plane3D &outParams, const PlanePatch &firstPPP, const PlanePatch &secondPPP) | StructureColoring | [protected] |
callPublisher(const OcTree &octree, PlanePatches &extractedPlanes, const CylinderPatches &extractedCylinders, const PointCloudPtr pointCloud, const PlanePatchVector &pointMapping, const CylinderPatchVector &cylinderPointMapping) | StructureColoring | [protected] |
checkCylinder(const CylinderPatchPtr &cylinder, const PointCloudPtr &pointCloud) const | StructureColoring | [protected] |
checkCylinderDimensions(const CylinderPatchPtr &cylinder) const | StructureColoring | [protected] |
Cylinder3DPtr typedef | StructureColoring | |
CylinderPatches typedef | StructureColoring | |
CylinderPatchPtr typedef | StructureColoring | |
CylinderPatchVector typedef | StructureColoring | |
determineCandidatePlanes(PatchToNodeIndicesMap &outIndicesMap, PatchToNodePointersMap &outPointersMap, const NodePointers &octreeNodes, PlanePatches &extractedPlanes) | StructureColoring | [protected] |
determineCandidatePlanes(NodeIndexToPlanePatchPointers &nodeToPlaneCandidates, const NodePointers &octreeNodes, PlanePatches &extractedPlanes) | StructureColoring | [protected] |
doSegmentation(PointCloudPtr pointCloud, PlanePatchVector &pointMapping, PlanePatches &extractedPlanes, CylinderPatchVector &pointMappingCylinders, CylinderPatches &extractedCylinders) | StructureColoring | |
estimateCylinder(pclPointIndices &inliers, CylinderPatchPtr &cylinder, unsigned int &numPointsBefRansac, const NodePointers &octreeNodes, const OcTree &octree, const PointCloudPtr &pointCloud, const float &sacDist, const float &normalDistanceWeight, const float &minRadius, const float &maxRadius) | StructureColoring | [protected] |
estimateCylinderFromNodes(NodeIndices &inliers, CylinderPatchPtr &cylinder, const NodePointers &octreeNodes, const OcTree &octree, const PointCloudPtr &pointCloud, const float &sacDist, const float &normalDistanceWeight, const float &minRadius, const float &maxRadius) | StructureColoring | [protected] |
estimateCylinderHT(const SphereUniformSampling &cylinderOrientationBins, const NodePairs &nodePairs, PairIndices &inlierIndices, CylinderPatchPtr &cylinder, const unsigned int &depth, const OcTree &octree, const CylinderPatchVector &pointMapping, const PointCloud &pointCloud, const float &minRadius, const float &maxRadius) | StructureColoring | [protected] |
estimateCylinderNNNormals(CylinderPatchPtr &cylinder, const PointCloudPtr &pointCloud, const float &sacDist, const float &normalDistanceWeight, const float &minRadius, const float &maxRadius, float searchRadius, const Vec3 &initialAxis) | StructureColoring | [protected] |
estimatePlane(const pclPointIndices::Ptr &inliers, PlanePatchPtr &planePatch, const PointCloudPtr &pointCloud, const float &sacDist) | StructureColoring | [protected] |
estimatePlaneSingleSphereOctreeHT(pclPointIndices &inliers, Plane3DPtr &planePatch, const SphereUniformSamplings &houghBins, const SphereBinsVec &pointNeighborBins, const NodePointers &octreeNodes, NodeIndices &inlierNodes, const PointCloud &pointCloud, const OcTree &octree, const unsigned int &depth, const PlanePatchVector &pointMapping) | StructureColoring | [protected] |
extractOctreeCylindersFromCloud(CylinderPatches &extractedCylinders, CylinderPatchVector &pointMapping, const OcTree &octree, const PointCloudPtr &pointCloud) | StructureColoring | [protected] |
extractOctreePlanesFromCloud(PlanePatches &extractedPlanes, PlanePatchVector &pointMapping, const OcTree &octree, const PointCloudPtr &pointCloud) | StructureColoring | [protected] |
filterCloud(PointCloud &pointCloud, std::vector< unsigned int > &undefPoints, const float &zMin, const float &zMax) | StructureColoring | |
filterConnectedNodes(std::vector< NodePointers > &CCInlierNodes, const Plane3D &pp, const NodePointers &octreeNodes, float cellSize, GridMap *oldGridMap=NULL, NodePointers *notConnectedNodesOutput=NULL) | StructureColoring | [protected] |
filterMsgSetupCloud(PointCloud &pointCloud, const sensor_msgs::PointCloud2ConstPtr &pMsg, double zMin, double zMax, bool fromKinect, bool writePic=false, const std::string &picFilename="", unsigned int picCounter=0) | StructureColoring | |
flipToViewport(Vec3 &vec, const Vec3 &viewport) | StructureColoring | [protected, static] |
generateCylinderOrientationHB(SphereUniformSampling &cylinderOrientationBins, SphereBinsVec &binNeighborhood, const NodePairs &nodePairs) | StructureColoring | [protected] |
generateNeighboringNodePairs(NodePairs &nodePairs, NodePointers &octreeNodes, const unsigned int neighborhoodSize, const unsigned int ¤tOctreeDepth, const OcTree &octree) | StructureColoring | [protected] |
generateSingleSphereOctreeHTBins(SphereUniformSamplings &houghBins, SphereBinsVec &pointNeighborBins, const NodePointers &octreeNodes) | StructureColoring | [protected] |
generateTextures(const PlanePatches &extractedPlanes, const PointCloud &pointCloud) | StructureColoring | [protected] |
getAllPointsFromNodes(PointIndices &pointIndices, const NodePointers &octreeNodes, const OcTree &octree, const PointCloud &pointCloud) | StructureColoring | [protected] |
getAllPointsFromNodes(PointIndices &pointIndices, const NodeIndices &nodeIndices, const NodePointers &octreeNodes, const OcTree &octree, const PointCloud &pointCloud) | StructureColoring | [protected] |
getAngleEpsFromDepth(const unsigned int &depth, const OcTree &octree) | StructureColoring | [protected] |
getHTDistanceFromDepth(const unsigned int &depth, const OcTree &octree) | StructureColoring | [protected] |
getMinMaxRadiusFromDepth(float &minRadius, float &maxRadius, const OcTree &octree, const float &depth) | StructureColoring | [protected] |
getNodesFromIndices(const NodeIndices &nodeIndices, const NodePointers &nodes) | StructureColoring | [inline, protected, static] |
getNodesFromPairs(NodePointers &nodePointers, const PairIndices &pairIndices, const NodePairs &nodePairs) | StructureColoring | [protected] |
getPointsFromFile() | StructureColoring | |
getPointsFromIndices(const PointIndices &pointIndices, const PointCloud &cloud) | StructureColoring | [inline, protected, static] |
getPointsFromNodes(PointIndices &pointIndices, const NodePointers &octreeNodes, const OcTree &octree, const PointCloud &pointCloud, const PointMappingT &pointMapping) | StructureColoring | [protected] |
getSACDistanceFromDepth(const unsigned int &depth, const OcTree &octree) | StructureColoring | [protected] |
GridMapPtr typedef | StructureColoring | [protected] |
init(ros::NodeHandle &n, int argc, char *argv[]) | StructureColoring | |
init(int argc, char *argv[]) | StructureColoring | |
init() | StructureColoring | |
initNode(ros::NodeHandle &n) | StructureColoring | [protected] |
initOctree() | StructureColoring | [protected] |
initParams() | StructureColoring | [protected] |
initSegmentation(PointMappingT &pointMapping, const PointCloud &pointCloud) | StructureColoring | [protected] |
markAsSegmented(NodePtr currentNode, NodePtr nextNode=NULL, void *data=NULL) | StructureColoring | [inline, protected, static] |
markNodesAsSegmented(const PlanePatch &pp, const NodePointers &nodes, const OcTree &octree, const PointCloud &pointCloud, const float &maxDistance, const float &ratio) | StructureColoring | [protected] |
Mat3 typedef | StructureColoring | [protected] |
mCylinderPatches | StructureColoring | [protected] |
mCylinderPatchesMutex | StructureColoring | [protected] |
mergePlanes(PlanePatches &extractedPlanes, PlanePatchVector &pointMapping, const PointCloud &pointCloud) | StructureColoring | [protected] |
mKinectTopic | StructureColoring | [protected] |
mLastCellSizeWithNormals | StructureColoring | [protected] |
mNodeHandle | StructureColoring | [protected] |
mOcTree | StructureColoring | [protected] |
mParams | StructureColoring | [protected] |
mPlanePatches | StructureColoring | [protected] |
mPlanePatchesMutex | StructureColoring | [protected] |
mPointCloud | StructureColoring | [protected] |
mPointCloud2Subscriber | StructureColoring | [protected] |
mPointCloudMutex | StructureColoring | [protected] |
mPointCloudSubscriber | StructureColoring | [protected] |
mPointMapping | StructureColoring | [protected] |
mPointNeighborBins | StructureColoring | [protected] |
mVis | StructureColoring | [protected] |
NodeIndexToPlanePatchPointers typedef | StructureColoring | [protected] |
NodeIndices typedef | StructureColoring | [protected] |
NodePairs typedef | StructureColoring | |
NodePointerList typedef | StructureColoring | [protected] |
NodePointers typedef | StructureColoring | [protected] |
NodePtr typedef | StructureColoring | [protected] |
NodePtrList typedef | StructureColoring | [protected] |
NodePtrListIters typedef | StructureColoring | [protected] |
OctreeAllocator typedef | StructureColoring | [protected] |
OctreePtr typedef | StructureColoring | [protected] |
OcTreePtr typedef | StructureColoring | [protected] |
OctreeSamplingMap typedef | StructureColoring | [protected] |
Pair2ui typedef | StructureColoring | [protected] |
PairIndices typedef | StructureColoring | [protected] |
parseInput(std::string ¶mFilename, std::string &inputFilename, std::string &outputFilename, int argc, char *argv[]) | StructureColoring | [protected] |
PatchIterBoolPair typedef | StructureColoring | [protected] |
PatchIterBoolPairVector typedef | StructureColoring | [protected] |
PatchIterNodePointersPair typedef | StructureColoring | [protected] |
PatchIterNodePointersPairs typedef | StructureColoring | [protected] |
PatchToNodeIndicesMap typedef | StructureColoring | [protected] |
PatchToNodePointersMap typedef | StructureColoring | [protected] |
PatchToPointIndicesMap typedef | StructureColoring | [protected] |
pclPointIndices typedef | StructureColoring | [protected] |
Plane3DPtr typedef | StructureColoring | |
PlanePatches typedef | StructureColoring | |
PlanePatchIterPointIndicesPair typedef | StructureColoring | [protected] |
PlanePatchIterPointIndicesPairs typedef | StructureColoring | [protected] |
PlanePatchPtr typedef | StructureColoring | |
PlanePatchVector typedef | StructureColoring | |
planesAreConnected(const PlanePatch &pp1, const PlanePatch &pp2, const PointCloud &pointCloud) | StructureColoring | [protected] |
PointCloud typedef | StructureColoring | |
pointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr &msg) | StructureColoring | |
pointCloudCallback(const sensor_msgs::PointCloudConstPtr &msg) | StructureColoring | |
PointCloudPtr typedef | StructureColoring | |
PointIndices typedef | StructureColoring | [protected] |
Points typedef | StructureColoring | [protected] |
PointT typedef | StructureColoring | |
readPointCloudFromPCD(PointCloud &pointCloud, const std::string &filename, unsigned int &width, unsigned int &height, std::vector< unsigned int > &undefPoints, const float &zMin, const float &zMax) | StructureColoring | |
rebuildPointMapping(std::vector< StructurePtrT > &pointMapping, const Structures &structures) | StructureColoring | [protected] |
refineAssignmentWithCCs(NodeIndexToPlanePatchPointers &nodeToPlaneCandidates, const PatchToNodeIndicesMap &nodeIndicesMap, const PatchToNodePointersMap &nodePointersMap, const NodePointers &octreeNodes, PlanePatches &extractedPlanes) | StructureColoring | [protected] |
refineEdges(PatchToNodePointersMap &finalPlaneNodeAssignmentMap, PatchToPointIndicesMap &finalPlanePointAssignment, const NodeIndexToPlanePatchPointers &nodeToPlaneCandidates, const NodePointers &octreeNodes, const OcTree &octree, const PointCloud &pointCloud) | StructureColoring | [protected] |
segmentCylinders(CylinderPatches &cylinderPatches, CylinderPatchVector &pointMapping, OcTree &octree, const PointCloudPtr &pointCloud) | StructureColoring | [protected] |
segmentCylindersSAC(CylinderPatches &cylinderPatches, CylinderPatchVector &pointMapping, OcTree &octree, const PointCloudPtr &pointCloud) | StructureColoring | [protected] |
segmentPlanes(PlanePatches &extractedPlanes, PlanePatchVector &pointMapping, OcTree &octree, const PointCloudPtr &pointCloud) | StructureColoring | [protected] |
segmentPlanesSAC(PlanePatches &extractedPlanes, PlanePatchVector &pointMapping, const PointCloudPtr &pointCloud) | StructureColoring | [protected] |
setParams(StrColParams params) | StructureColoring | [inline] |
SphereBins typedef | StructureColoring | [protected] |
SphereBinsVec typedef | StructureColoring | [protected] |
SphereUniformSamplings typedef | StructureColoring | [protected] |
splitIntoConnectedCompononents() | StructureColoring | [protected] |
spreadNodes(const OcTree &octree, PlanePatches &extractedPlanes, PlanePatchVector &pointMapping, const PointCloud &pointCloud) | StructureColoring | [protected] |
spreadPoints() | StructureColoring | [protected] |
StructureColoring(ros::NodeHandle &n, int argc, char *argv[]) | StructureColoring | |
StructureColoring(int argc, char *argv[]) | StructureColoring | [inline] |
StructureColoring() | StructureColoring | [inline] |
uints typedef | StructureColoring | [protected] |
updateCylinderHTBins(SphereUniformSampling &cylinderOrientationBins, const PairIndices &inlierIndices, SphereBinsVec &binNeighborhood) | StructureColoring | [protected] |
updateHTBins(const NodeIndices &inliers, SphereUniformSamplings &houghBins, SphereBinsVec &pointNeighborBins) | StructureColoring | [protected] |
updatePointMapping(std::vector< StructurePtrT > &pointMapping, const PointIndices &pointIndices, const StructurePtrT &structurePointer) | StructureColoring | [protected] |
updatePointMappingAndInliers(std::vector< StructurePtrT > &pointMapping, PointIndices &pointIndices, const StructurePtrT &structurePointer) | StructureColoring | [protected] |
ValueClass typedef | StructureColoring | [protected] |
Vec3 typedef | StructureColoring | [protected] |
waitOnKinectMsgs() | StructureColoring | [inline] |
waitOnLaserMsgs() | StructureColoring | [inline] |
writeSegments(const unsigned int &width, const unsigned int &height, const std::vector< unsigned int > &undefPoints, const PointMappingT &pointMapping, const std::string &outFilename, const StructureContainerT &extractedStructures) | StructureColoring | [protected] |
~StructureColoring() | StructureColoring | [virtual] |