Classes | Public Types | Public Member Functions | Protected Types | Protected Member Functions | Static Protected Member Functions | Protected Attributes
StructureColoring Class Reference

#include <StructureColoring.h>

Inheritance diagram for StructureColoring:
Inheritance graph
[legend]

List of all members.

Classes

struct  SphereBin

Public Types

typedef Cylinder3D::Cylinder3DPtr Cylinder3DPtr
typedef
CylinderPatch::CylinderPatches 
CylinderPatches
typedef
CylinderPatch::CylinderPatchPtr 
CylinderPatchPtr
typedef std::vector
< CylinderPatchPtr
CylinderPatchVector
typedef std::vector< NodePairNodePairs
typedef Plane3D::Plane3DPtr Plane3DPtr
typedef PlanePatch::PlanePatches PlanePatches
typedef PlanePatch::PlanePatchPtr PlanePatchPtr
typedef std::vector
< PlanePatchPtr
PlanePatchVector
typedef pcl::PointCloud< PointTPointCloud
typedef boost::shared_ptr
< PointCloud
PointCloudPtr
typedef pcl::PointXYZRGB PointT

Public Member Functions

void doSegmentation (PointCloudPtr pointCloud, PlanePatchVector &pointMapping, PlanePatches &extractedPlanes, CylinderPatchVector &pointMappingCylinders, CylinderPatches &extractedCylinders)
void filterCloud (PointCloud &pointCloud, std::vector< unsigned int > &undefPoints, const float &zMin, const float &zMax)
void 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)
void getPointsFromFile ()
 getPointsFromFile Start segmentation. Parameters were given through object construction.
void init (ros::NodeHandle &n, int argc, char *argv[])
void init (int argc, char *argv[])
void init ()
void pointCloud2Callback (const sensor_msgs::PointCloud2ConstPtr &msg)
 pointCloud2Callback This method should be called via subscription to a PointCloud2 topic.
void pointCloudCallback (const sensor_msgs::PointCloudConstPtr &msg)
 pointCloudCallback This method should be called via subscription to a PointCloud topic.
void readPointCloudFromPCD (PointCloud &pointCloud, const std::string &filename, unsigned int &width, unsigned int &height, std::vector< unsigned int > &undefPoints, const float &zMin, const float &zMax)
void setParams (StrColParams params)
 StructureColoring (ros::NodeHandle &n, int argc, char *argv[])
 StructureColoring Construct a new StrcutureColoring object from a nodeHandle and console parameters.
 StructureColoring (int argc, char *argv[])
 StructureColoring Construct a new StructureColoring object from console parameters only.
 StructureColoring ()
 StructureColoring Construct a new StructureColoring object without any params.
bool waitOnKinectMsgs ()
 waitOnKinectMsgs Check if object waits for kinect messages.
bool waitOnLaserMsgs ()
 waitOnLaserMsgs Check if object waits for laser messages.
virtual ~StructureColoring ()
 StructureColoring Destructor.

Protected Types

typedef boost::shared_ptr
< GridMap
GridMapPtr
typedef Eigen::Matrix3f Mat3
typedef std::vector
< PlanePatchVector
NodeIndexToPlanePatchPointers
typedef std::vector< int > NodeIndices
typedef OcTree::NodePointerList NodePointerList
typedef OcTree::NodePointers NodePointers
typedef OcTree::NodePtr NodePtr
typedef std::list< NodePtrNodePtrList
typedef std::vector
< NodePtrList::iterator > 
NodePtrListIters
typedef OcTree::Allocator OctreeAllocator
typedef OcTree::OctreePtr OctreePtr
typedef boost::shared_ptr< OcTreeOcTreePtr
typedef OcTree::SamplingMap OctreeSamplingMap
typedef std::pair< unsigned
int, unsigned int > 
Pair2ui
typedef std::vector< int > PairIndices
typedef std::pair
< PlanePatches::iterator, bool > 
PatchIterBoolPair
typedef std::vector
< PatchIterBoolPair
PatchIterBoolPairVector
typedef std::pair
< PlanePatches::iterator,
NodePointers
PatchIterNodePointersPair
typedef std::vector
< PatchIterNodePointersPair
PatchIterNodePointersPairs
typedef std::map
< PlanePatchPtr, NodeIndices,
CompPlanePtr
PatchToNodeIndicesMap
typedef std::map
< PlanePatchPtr, NodePointers,
CompPlanePtr
PatchToNodePointersMap
typedef std::map
< PlanePatchPtr, PointIndices,
CompPlanePtr
PatchToPointIndicesMap
typedef pcl::PointIndices pclPointIndices
typedef std::pair
< PlanePatches::iterator,
PointIndices
PlanePatchIterPointIndicesPair
typedef std::vector
< PlanePatchIterPointIndicesPair
PlanePatchIterPointIndicesPairs
typedef std::vector< int > PointIndices
typedef std::vector< Vec3,
Eigen::aligned_allocator< Vec3 > > 
Points
typedef std::vector< SphereBinSphereBins
typedef std::vector< SphereBinsSphereBinsVec
typedef std::vector
< SphereUniformSampling
SphereUniformSamplings
typedef std::vector< unsigned int > uints
typedef OcTree::ValueClass ValueClass
typedef Eigen::Vector3f Vec3

Protected Member Functions

void addNodesToPlane (PlanePatchPtr &plane, const NodePointers &nodes, const OcTree &octree, const PointCloud &pointCloud, PlanePatchVector &pointMapping)
 addNodesToPlane Add unsegmented points in nodes to plane and it's connected component grid.
void addPlanePatchesAndUpdateSegmented (PlanePatches &extractedPlanes, PlanePatchVector &pointMapping, const PlanePatches &planePatches)
void assignNodesToCylinders (NodePointers &octreeNodes, CylinderPatches &extractedCylinders, CylinderPatchVector &pointMapping, const OcTree &octree, const PointCloud &pointCloud)
 assignNodePairsToCylinders Check all nodePairs from input if they are candidates for previously found cylinders
void assignNodesToPlanes (NodePointers &notAssignedOctreeNodes, const unsigned int &octreeDepth, const OcTree &octree, PlanePatches &extractedPlanes, const PointCloud &pointCloud, PlanePatchVector &pointMapping)
 assignNodesToPlanes Check all nodes in octreeDepth against all planes in mFilteredPlanePatches with respect to node's mean position and it's normal. Generate vector of unassigned nodes.
void calculateMiddlePlane (Plane3D &outParams, const PlanePatch &firstPPP, const PlanePatch &secondPPP)
 Calculate a plane, that parts two planes in the middle through its intersection line.
void callPublisher (const OcTree &octree, PlanePatches &extractedPlanes, const CylinderPatches &extractedCylinders, const PointCloudPtr pointCloud, const PlanePatchVector &pointMapping, const CylinderPatchVector &cylinderPointMapping)
bool checkCylinder (const CylinderPatchPtr &cylinder, const PointCloudPtr &pointCloud) const
bool checkCylinderDimensions (const CylinderPatchPtr &cylinder) const
void determineCandidatePlanes (PatchToNodeIndicesMap &outIndicesMap, PatchToNodePointersMap &outPointersMap, const NodePointers &octreeNodes, PlanePatches &extractedPlanes)
 For every node in.
void determineCandidatePlanes (NodeIndexToPlanePatchPointers &nodeToPlaneCandidates, const NodePointers &octreeNodes, PlanePatches &extractedPlanes)
void 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)
void 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)
void 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)
 Estimate cylinder params, starting from cylinder orientation Hough space.
void estimateCylinderNNNormals (CylinderPatchPtr &cylinder, const PointCloudPtr &pointCloud, const float &sacDist, const float &normalDistanceWeight, const float &minRadius, const float &maxRadius, float searchRadius, const Vec3 &initialAxis)
void estimatePlane (const pclPointIndices::Ptr &inliers, PlanePatchPtr &planePatch, const PointCloudPtr &pointCloud, const float &sacDist)
void 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)
void extractOctreeCylindersFromCloud (CylinderPatches &extractedCylinders, CylinderPatchVector &pointMapping, const OcTree &octree, const PointCloudPtr &pointCloud)
 extractOctreePlanesFromCloud Main segmentation is done here. Most other methods are called from here.
void extractOctreePlanesFromCloud (PlanePatches &extractedPlanes, PlanePatchVector &pointMapping, const OcTree &octree, const PointCloudPtr &pointCloud)
 extractOctreePlanesFromCloud Main segmentation is done here. Most other methods are called from here.
void filterConnectedNodes (std::vector< NodePointers > &CCInlierNodes, const Plane3D &pp, const NodePointers &octreeNodes, float cellSize, GridMap *oldGridMap=NULL, NodePointers *notConnectedNodesOutput=NULL)
void generateCylinderOrientationHB (SphereUniformSampling &cylinderOrientationBins, SphereBinsVec &binNeighborhood, const NodePairs &nodePairs)
 Generate Hough space for cylinder orientation.
void generateNeighboringNodePairs (NodePairs &nodePairs, NodePointers &octreeNodes, const unsigned int neighborhoodSize, const unsigned int &currentOctreeDepth, const OcTree &octree)
 Get all pairs of nodes that are close to each other.
void generateSingleSphereOctreeHTBins (SphereUniformSamplings &houghBins, SphereBinsVec &pointNeighborBins, const NodePointers &octreeNodes)
void generateTextures (const PlanePatches &extractedPlanes, const PointCloud &pointCloud)
void getAllPointsFromNodes (PointIndices &pointIndices, const NodePointers &octreeNodes, const OcTree &octree, const PointCloud &pointCloud)
 getAllPointsFromNodes Get all (!) points, that contributed to input nodes.
void getAllPointsFromNodes (PointIndices &pointIndices, const NodeIndices &nodeIndices, const NodePointers &octreeNodes, const OcTree &octree, const PointCloud &pointCloud)
 getAllPointsFromNodes Get all (!) points, that contributed to input nodes.
float getAngleEpsFromDepth (const unsigned int &depth, const OcTree &octree)
 As AngleEps(ilon) depends on current octree cell size, this method determines this threshold for any given (valid octree-)depth. Global parameters may prune this threshold to a given interval.
float getHTDistanceFromDepth (const unsigned int &depth, const OcTree &octree)
 As HTDistanceThreshold depends on current octree cell size, this method determines this threshold for any given (valid octree-)depth. Global parameters may prune this threshold to a given interval.
void getMinMaxRadiusFromDepth (float &minRadius, float &maxRadius, const OcTree &octree, const float &depth)
void getNodesFromPairs (NodePointers &nodePointers, const PairIndices &pairIndices, const NodePairs &nodePairs)
template<typename PointMappingT >
void getPointsFromNodes (PointIndices &pointIndices, const NodePointers &octreeNodes, const OcTree &octree, const PointCloud &pointCloud, const PointMappingT &pointMapping)
 getPointsFromNodes Get all (non segmented!) points, that contributed to input nodes.
float getSACDistanceFromDepth (const unsigned int &depth, const OcTree &octree)
 As SACDistanceThreshold depends on current octree cell size, this method determines this threshold for any given (valid octree-)depth. Global parameters may prune this threshold to a given interval.
void initNode (ros::NodeHandle &n)
void initOctree ()
void initParams ()
template<typename PointMappingT >
void initSegmentation (PointMappingT &pointMapping, const PointCloud &pointCloud)
void markNodesAsSegmented (const PlanePatch &pp, const NodePointers &nodes, const OcTree &octree, const PointCloud &pointCloud, const float &maxDistance, const float &ratio)
 markNodesAsSegmented Add unsegmented points in nodes to plane and it's connected component grid.
void mergePlanes (PlanePatches &extractedPlanes, PlanePatchVector &pointMapping, const PointCloud &pointCloud)
void parseInput (std::string &paramFilename, std::string &inputFilename, std::string &outputFilename, int argc, char *argv[])
bool planesAreConnected (const PlanePatch &pp1, const PlanePatch &pp2, const PointCloud &pointCloud)
 planesAreConnected Check if any point in pp1 is a connection to the grid of pp2.
template<typename StructurePtrT , typename Structures >
void rebuildPointMapping (std::vector< StructurePtrT > &pointMapping, const Structures &structures)
void refineAssignmentWithCCs (NodeIndexToPlanePatchPointers &nodeToPlaneCandidates, const PatchToNodeIndicesMap &nodeIndicesMap, const PatchToNodePointersMap &nodePointersMap, const NodePointers &octreeNodes, PlanePatches &extractedPlanes)
 For every plane in.
void refineEdges (PatchToNodePointersMap &finalPlaneNodeAssignmentMap, PatchToPointIndicesMap &finalPlanePointAssignment, const NodeIndexToPlanePatchPointers &nodeToPlaneCandidates, const NodePointers &octreeNodes, const OcTree &octree, const PointCloud &pointCloud)
 Refine edges between every 2 planes by looking at every node and decide which side of an edge it belongs to.
double segmentCylinders (CylinderPatches &cylinderPatches, CylinderPatchVector &pointMapping, OcTree &octree, const PointCloudPtr &pointCloud)
double segmentCylindersSAC (CylinderPatches &cylinderPatches, CylinderPatchVector &pointMapping, OcTree &octree, const PointCloudPtr &pointCloud)
double segmentPlanes (PlanePatches &extractedPlanes, PlanePatchVector &pointMapping, OcTree &octree, const PointCloudPtr &pointCloud)
double segmentPlanesSAC (PlanePatches &extractedPlanes, PlanePatchVector &pointMapping, const PointCloudPtr &pointCloud)
void splitIntoConnectedCompononents ()
void spreadNodes (const OcTree &octree, PlanePatches &extractedPlanes, PlanePatchVector &pointMapping, const PointCloud &pointCloud)
 spreadNodes assign all nodes to previously determined planes. This is part of the post-processing.
void spreadPoints ()
void updateCylinderHTBins (SphereUniformSampling &cylinderOrientationBins, const PairIndices &inlierIndices, SphereBinsVec &binNeighborhood)
 Update Hough space, remove inliers from it.
void updateHTBins (const NodeIndices &inliers, SphereUniformSamplings &houghBins, SphereBinsVec &pointNeighborBins)
template<typename StructurePtrT >
void updatePointMapping (std::vector< StructurePtrT > &pointMapping, const PointIndices &pointIndices, const StructurePtrT &structurePointer)
template<typename StructurePtrT >
void updatePointMappingAndInliers (std::vector< StructurePtrT > &pointMapping, PointIndices &pointIndices, const StructurePtrT &structurePointer)
template<typename PointMappingT , typename StructureContainerT >
void 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)

Static Protected Member Functions

static void flipToViewport (Vec3 &vec, const Vec3 &viewport)
 If vec does not point to the viewport, it is flipped.
static NodePointers getNodesFromIndices (const NodeIndices &nodeIndices, const NodePointers &nodes)
 Get nodes from node indices. As this is very inefficient, you should only use this method for debugging. TODO remove this.
static Points getPointsFromIndices (const PointIndices &pointIndices, const PointCloud &cloud)
 Get points from point indices. As this is very inefficient, you should only use this method for debugging. TODO remove this.
static void markAsSegmented (NodePtr currentNode, NodePtr nextNode=NULL, void *data=NULL)
 mark a node as segmented

Protected Attributes

CylinderPatches mCylinderPatches
QMutex mCylinderPatchesMutex
std::string mKinectTopic
float mLastCellSizeWithNormals
ros::NodeHandle * mNodeHandle
OcTreePtr mOcTree
StrColParams mParams
PlanePatches mPlanePatches
QMutex mPlanePatchesMutex
PointCloudPtr mPointCloud
ros::Subscriber mPointCloud2Subscriber
QMutex mPointCloudMutex
ros::Subscriber mPointCloudSubscriber
PlanePatchVector mPointMapping
SphereBinsVec mPointNeighborBins
RosVisualizationmVis

Detailed Description

Definition at line 66 of file StructureColoring.h.


Member Typedef Documentation

Definition at line 77 of file StructureColoring.h.

Definition at line 78 of file StructureColoring.h.

Definition at line 79 of file StructureColoring.h.

Definition at line 80 of file StructureColoring.h.

typedef boost::shared_ptr<GridMap> StructureColoring::GridMapPtr [protected]

Definition at line 144 of file StructureColoring.h.

typedef Eigen::Matrix3f StructureColoring::Mat3 [protected]

Definition at line 155 of file StructureColoring.h.

Definition at line 169 of file StructureColoring.h.

typedef std::vector<int> StructureColoring::NodeIndices [protected]

Definition at line 152 of file StructureColoring.h.

typedef std::vector<NodePair> StructureColoring::NodePairs

Definition at line 82 of file StructureColoring.h.

Definition at line 151 of file StructureColoring.h.

Definition at line 150 of file StructureColoring.h.

Definition at line 145 of file StructureColoring.h.

typedef std::list<NodePtr> StructureColoring::NodePtrList [protected]

Definition at line 162 of file StructureColoring.h.

typedef std::vector<NodePtrList::iterator> StructureColoring::NodePtrListIters [protected]

Definition at line 163 of file StructureColoring.h.

Definition at line 148 of file StructureColoring.h.

Definition at line 147 of file StructureColoring.h.

typedef boost::shared_ptr<OcTree> StructureColoring::OcTreePtr [protected]

Definition at line 492 of file StructureColoring.h.

Definition at line 149 of file StructureColoring.h.

typedef std::pair<unsigned int, unsigned int> StructureColoring::Pair2ui [protected]

Definition at line 164 of file StructureColoring.h.

typedef std::vector<int> StructureColoring::PairIndices [protected]

Definition at line 173 of file StructureColoring.h.

typedef std::pair<PlanePatches::iterator, bool> StructureColoring::PatchIterBoolPair [protected]

Definition at line 157 of file StructureColoring.h.

Definition at line 158 of file StructureColoring.h.

typedef std::pair<PlanePatches::iterator, NodePointers> StructureColoring::PatchIterNodePointersPair [protected]

Definition at line 160 of file StructureColoring.h.

Definition at line 161 of file StructureColoring.h.

Definition at line 170 of file StructureColoring.h.

Definition at line 168 of file StructureColoring.h.

Definition at line 171 of file StructureColoring.h.

Definition at line 165 of file StructureColoring.h.

Definition at line 72 of file StructureColoring.h.

Definition at line 73 of file StructureColoring.h.

typedef std::pair<PlanePatches::iterator, PointIndices > StructureColoring::PlanePatchIterPointIndicesPair [protected]

Definition at line 166 of file StructureColoring.h.

Definition at line 167 of file StructureColoring.h.

Definition at line 74 of file StructureColoring.h.

Definition at line 75 of file StructureColoring.h.

Definition at line 69 of file StructureColoring.h.

typedef boost::shared_ptr<PointCloud> StructureColoring::PointCloudPtr

Definition at line 70 of file StructureColoring.h.

typedef std::vector<int> StructureColoring::PointIndices [protected]

Definition at line 153 of file StructureColoring.h.

typedef std::vector<Vec3, Eigen::aligned_allocator<Vec3> > StructureColoring::Points [protected]

Definition at line 156 of file StructureColoring.h.

typedef pcl::PointXYZRGB StructureColoring::PointT

Definition at line 68 of file StructureColoring.h.

typedef std::vector<SphereBin> StructureColoring::SphereBins [protected]

Definition at line 182 of file StructureColoring.h.

typedef std::vector<SphereBins> StructureColoring::SphereBinsVec [protected]

Definition at line 183 of file StructureColoring.h.

Definition at line 172 of file StructureColoring.h.

typedef std::vector<unsigned int> StructureColoring::uints [protected]

Definition at line 159 of file StructureColoring.h.

Definition at line 146 of file StructureColoring.h.

typedef Eigen::Vector3f StructureColoring::Vec3 [protected]

Definition at line 154 of file StructureColoring.h.


Constructor & Destructor Documentation

StructureColoring::StructureColoring ( ros::NodeHandle &  n,
int  argc,
char *  argv[] 
)

StructureColoring Construct a new StrcutureColoring object from a nodeHandle and console parameters.

Parameters:
nNodeHandle.
argcNumber of arguments.
argvArguments from console call.

Definition at line 64 of file StructureColoring.cpp.

StructureColoring::StructureColoring ( int  argc,
char *  argv[] 
) [inline]

StructureColoring Construct a new StructureColoring object from console parameters only.

Parameters:
argcNumber of arguments.
argvArguments from console call.

Definition at line 95 of file StructureColoring.h.

StructureColoring Construct a new StructureColoring object without any params.

Definition at line 99 of file StructureColoring.h.

StructureColoring Destructor.

Definition at line 113 of file StructureColoring.cpp.


Member Function Documentation

void StructureColoring::addNodesToPlane ( PlanePatchPtr plane,
const NodePointers nodes,
const OcTree octree,
const PointCloud pointCloud,
PlanePatchVector pointMapping 
) [protected]

addNodesToPlane Add unsegmented points in nodes to plane and it's connected component grid.

Parameters:
planeInput and output plane. This is where the points are added to.
nodesInput nodes that are added to the plane in this method.

Definition at line 1343 of file StructureColoring.cpp.

void StructureColoring::addPlanePatchesAndUpdateSegmented ( PlanePatches extractedPlanes,
PlanePatchVector pointMapping,
const PlanePatches planePatches 
) [protected]

Definition at line 2140 of file StructureColoring.cpp.

void StructureColoring::assignNodesToCylinders ( NodePointers octreeNodes,
CylinderPatches extractedCylinders,
CylinderPatchVector pointMapping,
const OcTree octree,
const PointCloud pointCloud 
) [protected]

assignNodePairsToCylinders Check all nodePairs from input if they are candidates for previously found cylinders

Parameters:
nodePairsinput pairs of nodes, will be updated
extractedCylinderspreviously found cylinders, will be updated

Definition at line 1647 of file StructureColoring.cpp.

void StructureColoring::assignNodesToPlanes ( NodePointers notAssignedOctreeNodes,
const unsigned int &  octreeDepth,
const OcTree octree,
PlanePatches extractedPlanes,
const PointCloud pointCloud,
PlanePatchVector pointMapping 
) [protected]

assignNodesToPlanes Check all nodes in octreeDepth against all planes in mFilteredPlanePatches with respect to node's mean position and it's normal. Generate vector of unassigned nodes.

Parameters:
notAssignedOctreeNodesOutput unassigned nodes.
octreeDepthInput octreeDepth to take nodes from. This method tries to assign all nodes to the planes that were already found. If a node can be assign (through normal orientation and mean position) all it's points are added to the plane.

Definition at line 1396 of file StructureColoring.cpp.

void StructureColoring::calculateMiddlePlane ( Plane3D outParams,
const PlanePatch firstPPP,
const PlanePatch secondPPP 
) [protected]

Calculate a plane, that parts two planes in the middle through its intersection line.

Parameters:
outParamsParams of middle plane will be put here.
firstPPPPlanePatchPtr to first plane (best hit).
secondPPPPlanePatchPtr to second plane (second best hit).

Definition at line 1865 of file StructureColoring.cpp.

void StructureColoring::callPublisher ( const OcTree octree,
PlanePatches extractedPlanes,
const CylinderPatches extractedCylinders,
const PointCloudPtr  pointCloud,
const PlanePatchVector pointMapping,
const CylinderPatchVector cylinderPointMapping 
) [protected]

Definition at line 513 of file StructureColoring.cpp.

bool StructureColoring::checkCylinder ( const CylinderPatchPtr cylinder,
const PointCloudPtr pointCloud 
) const [protected]

Definition at line 2443 of file StructureColoring.cpp.

bool StructureColoring::checkCylinderDimensions ( const CylinderPatchPtr cylinder) const [protected]

Definition at line 2438 of file StructureColoring.cpp.

void StructureColoring::determineCandidatePlanes ( PatchToNodeIndicesMap outIndicesMap,
PatchToNodePointersMap outPointersMap,
const NodePointers octreeNodes,
PlanePatches extractedPlanes 
) [protected]

For every node in.

Parameters:
octreeNodes,everyplane is being checked if the node is in the planes distanceThreshold
outIndicesMapMaps PlanePatchPtr to all nodes(indices), that could possibly belong to its plane.
outPointersMapMaps PlanePatchPtr to all nodes(pointers), that could possibly belong to its plane.
octreeNodesInput octree nodes to check against every plane in mFilteredPlanePatches.

Definition at line 1823 of file StructureColoring.cpp.

void StructureColoring::determineCandidatePlanes ( NodeIndexToPlanePatchPointers nodeToPlaneCandidates,
const NodePointers octreeNodes,
PlanePatches extractedPlanes 
) [protected]

Definition at line 1800 of file StructureColoring.cpp.

void StructureColoring::doSegmentation ( PointCloudPtr  pointCloud,
PlanePatchVector pointMapping,
PlanePatches extractedPlanes,
CylinderPatchVector pointMappingCylinders,
CylinderPatches extractedCylinders 
)

Definition at line 278 of file StructureColoring.cpp.

void 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 
) [protected]

Definition at line 671 of file StructureColoring.cpp.

void StructureColoring::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 
) [protected]

Definition at line 904 of file StructureColoring.cpp.

void StructureColoring::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 
) [protected]

Estimate cylinder params, starting from cylinder orientation Hough space.

Parameters:
cylinderOrientationBinsInput Hough space of cylinder oreintations.
nodePairsInput pairs of nodes where Hough space indices point to.
inlierIndicesOutput inlier pairs.
cylinderOutput cylinder patch with inlier estimation (from HT) and cylinder parameters.
depthInput octree depth of nodes and node pairs etc.
octreeInput octree where nodes come from.

Definition at line 1144 of file StructureColoring.cpp.

void StructureColoring::estimateCylinderNNNormals ( CylinderPatchPtr cylinder,
const PointCloudPtr pointCloud,
const float &  sacDist,
const float &  normalDistanceWeight,
const float &  minRadius,
const float &  maxRadius,
float  searchRadius,
const Vec3 initialAxis 
) [protected]

Definition at line 731 of file StructureColoring.cpp.

void StructureColoring::estimatePlane ( const pclPointIndices::Ptr inliers,
PlanePatchPtr planePatch,
const PointCloudPtr pointCloud,
const float &  sacDist 
) [protected]

Definition at line 639 of file StructureColoring.cpp.

void StructureColoring::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 
) [protected]

Definition at line 989 of file StructureColoring.cpp.

void StructureColoring::extractOctreeCylindersFromCloud ( CylinderPatches extractedCylinders,
CylinderPatchVector pointMapping,
const OcTree octree,
const PointCloudPtr pointCloud 
) [protected]

extractOctreePlanesFromCloud Main segmentation is done here. Most other methods are called from here.

Parameters:
extractedCylindersoutput planes, extracted from octree / pointcloud
pointMappingmapping of points to extracted cylinders
octreeinput octree, filled with points from pointcloud and with normals already calculated
pointCloudinput point cloud for segmentation

Definition at line 1679 of file StructureColoring.cpp.

void StructureColoring::extractOctreePlanesFromCloud ( PlanePatches extractedPlanes,
PlanePatchVector pointMapping,
const OcTree octree,
const PointCloudPtr pointCloud 
) [protected]

extractOctreePlanesFromCloud Main segmentation is done here. Most other methods are called from here.

Parameters:
extractedPlanesoutput planes, extracted from octree / pointcloud
pointMappingmapping of points to extracted planes
octreeinput octree, filled with points from pointcloud and with normals already calculated
pointCloudinput point cloud for segmentation

Definition at line 1472 of file StructureColoring.cpp.

void StructureColoring::filterCloud ( PointCloud pointCloud,
std::vector< unsigned int > &  undefPoints,
const float &  zMin,
const float &  zMax 
)

Definition at line 387 of file StructureColoring.cpp.

void StructureColoring::filterConnectedNodes ( std::vector< NodePointers > &  CCInlierNodes,
const Plane3D pp,
const NodePointers octreeNodes,
float  cellSize,
GridMap oldGridMap = NULL,
NodePointers notConnectedNodesOutput = NULL 
) [protected]

Definition at line 603 of file StructureColoring.cpp.

void StructureColoring::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 
)

Definition at line 568 of file StructureColoring.cpp.

void StructureColoring::flipToViewport ( Vec3 vec,
const Vec3 viewport 
) [static, protected]

If vec does not point to the viewport, it is flipped.

Parameters:
vecInput and output vector to be flipped.
viewportInput viewport position.

Definition at line 2187 of file StructureColoring.cpp.

void StructureColoring::generateCylinderOrientationHB ( SphereUniformSampling cylinderOrientationBins,
SphereBinsVec binNeighborhood,
const NodePairs nodePairs 
) [protected]

Generate Hough space for cylinder orientation.

Parameters:
cylinderOrientationBinsOutput Hough bins.
binNeighborhoodOutput mapping from nodePairs to corresponding Hough bins (for Hough bin update).
nodePairsInput pairs of neighboring nodes.

Definition at line 1107 of file StructureColoring.cpp.

void StructureColoring::generateNeighboringNodePairs ( NodePairs nodePairs,
NodePointers octreeNodes,
const unsigned int  neighborhoodSize,
const unsigned int &  currentOctreeDepth,
const OcTree octree 
) [protected]

Get all pairs of nodes that are close to each other.

Parameters:
nodePairsOutput parameter that holds close pairs of nodes.
neighborhoodSizeInput parameter that determines max neighborhoods distance from node in node sizes.
octreeNodesInput parameter but nodes will be marked to avoid double entries.
currentOctreeDepthOctree depth where octreeNodes come from.
octreeOctree to search pairs in.

Definition at line 1083 of file StructureColoring.cpp.

void StructureColoring::generateSingleSphereOctreeHTBins ( SphereUniformSamplings houghBins,
SphereBinsVec pointNeighborBins,
const NodePointers octreeNodes 
) [protected]

Definition at line 955 of file StructureColoring.cpp.

void StructureColoring::generateTextures ( const PlanePatches extractedPlanes,
const PointCloud pointCloud 
) [protected]

Definition at line 505 of file StructureColoring.cpp.

void StructureColoring::getAllPointsFromNodes ( PointIndices pointIndices,
const NodePointers octreeNodes,
const OcTree octree,
const PointCloud pointCloud 
) [protected]

getAllPointsFromNodes Get all (!) points, that contributed to input nodes.

Parameters:
pointIndicespoint's indices in mPointCloud.
octreeNodesInput octree nodes. Method starts leaf search here and generates output from those leafs. No mSegmented check is done here. If you need only unsegmented points, use getPointsFromNodes!

Definition at line 1307 of file StructureColoring.cpp.

void StructureColoring::getAllPointsFromNodes ( PointIndices pointIndices,
const NodeIndices nodeIndices,
const NodePointers octreeNodes,
const OcTree octree,
const PointCloud pointCloud 
) [protected]

getAllPointsFromNodes Get all (!) points, that contributed to input nodes.

Parameters:
pointIndicespoint's indices in mPointCloud.
nodeIndicesInput indices to octree nodes. Only this nodes will be used.
octreeNodesInput octree nodes. Method starts leaf search here and generates output from those leafs. No mSegmented check is done here. If you need only unsegmented points, use getPointsFromNodes!

Definition at line 1325 of file StructureColoring.cpp.

float StructureColoring::getAngleEpsFromDepth ( const unsigned int &  depth,
const OcTree octree 
) [protected]

As AngleEps(ilon) depends on current octree cell size, this method determines this threshold for any given (valid octree-)depth. Global parameters may prune this threshold to a given interval.

Parameters:
depthValid octree depth, greater or equal to zero and less or equal to octrees max-depth.
octreeInput octree.
Returns:
AngleEps(ilon) for given depth and octree.

Definition at line 2179 of file StructureColoring.cpp.

float StructureColoring::getHTDistanceFromDepth ( const unsigned int &  depth,
const OcTree octree 
) [protected]

As HTDistanceThreshold depends on current octree cell size, this method determines this threshold for any given (valid octree-)depth. Global parameters may prune this threshold to a given interval.

Parameters:
depthValid octree depth, greater or equal to zero and less or equal to octrees max-depth.
octreeInput octree.
Returns:
THDistanceThreshold for given depth and octree.

Definition at line 2164 of file StructureColoring.cpp.

void StructureColoring::getMinMaxRadiusFromDepth ( float &  minRadius,
float &  maxRadius,
const OcTree octree,
const float &  depth 
) [protected]

Definition at line 2172 of file StructureColoring.cpp.

StructureColoring::NodePointers StructureColoring::getNodesFromIndices ( const NodeIndices nodeIndices,
const NodePointers nodes 
) [inline, static, protected]

Get nodes from node indices. As this is very inefficient, you should only use this method for debugging. TODO remove this.

Parameters:
nodeIndicesindices to nodes
nodesinput nodes
Returns:
copy of indexed NodePointers

Definition at line 505 of file StructureColoring.h.

void StructureColoring::getNodesFromPairs ( NodePointers nodePointers,
const PairIndices pairIndices,
const NodePairs nodePairs 
) [protected]

Definition at line 1790 of file StructureColoring.cpp.

getPointsFromFile Start segmentation. Parameters were given through object construction.

Definition at line 403 of file StructureColoring.cpp.

StructureColoring::Points StructureColoring::getPointsFromIndices ( const PointIndices pointIndices,
const PointCloud cloud 
) [inline, static, protected]

Get points from point indices. As this is very inefficient, you should only use this method for debugging. TODO remove this.

Parameters:
pointIndicesindices to points in cloud
cloudinput pointcloud
Returns:
copy of indexed Points in cloud

Definition at line 514 of file StructureColoring.h.

template<typename PointMappingT >
void StructureColoring::getPointsFromNodes ( PointIndices pointIndices,
const NodePointers octreeNodes,
const OcTree octree,
const PointCloud pointCloud,
const PointMappingT &  pointMapping 
) [protected]

getPointsFromNodes Get all (non segmented!) points, that contributed to input nodes.

Parameters:
pointIndicespoint's indices in mPointCloud.
octreeNodesInput octree nodes. Method starts leaf search here and generates output from those leafs. Points that are returned here, do not belong to any segment at this moment. If you also need segmented points, use getAllPointsFromNodes!

Definition at line 532 of file StructureColoring.h.

float StructureColoring::getSACDistanceFromDepth ( const unsigned int &  depth,
const OcTree octree 
) [protected]

As SACDistanceThreshold depends on current octree cell size, this method determines this threshold for any given (valid octree-)depth. Global parameters may prune this threshold to a given interval.

Parameters:
depthValid octree depth, greater or equal to zero and less or equal to octrees max-depth.
octreeInput octree.
Returns:
SACDistanceThreshold for given depth and octree.

Definition at line 2155 of file StructureColoring.cpp.

void StructureColoring::init ( ros::NodeHandle &  n,
int  argc,
char *  argv[] 
)

Definition at line 71 of file StructureColoring.cpp.

void StructureColoring::init ( int  argc,
char *  argv[] 
)

Definition at line 85 of file StructureColoring.cpp.

Definition at line 105 of file StructureColoring.cpp.

void StructureColoring::initNode ( ros::NodeHandle &  n) [protected]

Definition at line 229 of file StructureColoring.cpp.

void StructureColoring::initOctree ( ) [protected]

Definition at line 252 of file StructureColoring.cpp.

void StructureColoring::initParams ( ) [protected]

Definition at line 244 of file StructureColoring.cpp.

template<typename PointMappingT >
void StructureColoring::initSegmentation ( PointMappingT &  pointMapping,
const PointCloud pointCloud 
) [protected]

Definition at line 552 of file StructureColoring.h.

void StructureColoring::markAsSegmented ( NodePtr  currentNode,
NodePtr  nextNode = NULL,
void *  data = NULL 
) [inline, static, protected]

mark a node as segmented

Parameters:
currentNodemark this node
nextNodedoing nothing (for compatibility only)
datadoing nothing (for compatibility only)

Definition at line 523 of file StructureColoring.h.

void StructureColoring::markNodesAsSegmented ( const PlanePatch pp,
const NodePointers nodes,
const OcTree octree,
const PointCloud pointCloud,
const float &  maxDistance,
const float &  ratio 
) [protected]

markNodesAsSegmented Add unsegmented points in nodes to plane and it's connected component grid.

Parameters:
pointIndicesInput pointIndices. This points are inliers marked as segmented.
nodesInput nodes pointers. This nodes are being marked, if almost all points in it are segmented.
ratioInput ratio determines, how many points must be marked as segmented to mark the nodes.

Definition at line 1378 of file StructureColoring.cpp.

void StructureColoring::mergePlanes ( PlanePatches extractedPlanes,
PlanePatchVector pointMapping,
const PointCloud pointCloud 
) [protected]

Iterate over all planes in extractedPlanes and merge planes that are similarly oriented and each others center of gravity is on the other plane. Connection via connected component is handled via "planesAreConnected"-check. As std::merge is used in this method, Plane indices MUST be sorted! --> sort is being called on local copies .. //TODO Check if it hurts.

Definition at line 2068 of file StructureColoring.cpp.

void StructureColoring::parseInput ( std::string &  paramFilename,
std::string &  inputFilename,
std::string &  outputFilename,
int  argc,
char *  argv[] 
) [protected]

Definition at line 120 of file StructureColoring.cpp.

bool StructureColoring::planesAreConnected ( const PlanePatch pp1,
const PlanePatch pp2,
const PointCloud pointCloud 
) [protected]

planesAreConnected Check if any point in pp1 is a connection to the grid of pp2.

Parameters:
pp1First input planePatchPtr.
pp2Second input planePatchPtr.
pointCloudInput PointCloud that inlierIndices refer to.

Definition at line 2128 of file StructureColoring.cpp.

void StructureColoring::pointCloud2Callback ( const sensor_msgs::PointCloud2ConstPtr &  msg)

pointCloud2Callback This method should be called via subscription to a PointCloud2 topic.

Parameters:
msgMessage pointer.

Definition at line 263 of file StructureColoring.cpp.

void StructureColoring::pointCloudCallback ( const sensor_msgs::PointCloudConstPtr &  msg)

pointCloudCallback This method should be called via subscription to a PointCloud topic.

Parameters:
msgMessage pointer.

Definition at line 323 of file StructureColoring.cpp.

void 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 
)

Definition at line 347 of file StructureColoring.cpp.

template<typename StructurePtrT , typename Structures >
void StructureColoring::rebuildPointMapping ( std::vector< StructurePtrT > &  pointMapping,
const Structures &  structures 
) [protected]

Definition at line 625 of file StructureColoring.h.

void StructureColoring::refineAssignmentWithCCs ( NodeIndexToPlanePatchPointers nodeToPlaneCandidates,
const PatchToNodeIndicesMap nodeIndicesMap,
const PatchToNodePointersMap nodePointersMap,
const NodePointers octreeNodes,
PlanePatches extractedPlanes 
) [protected]

For every plane in.

Parameters:
nodePointersMapeach node is put in it's grid and the main connected component is extracted to output.
nodeToPlaneCandidatesFor each node, each possible plane is stored here.
nodeIndicesMapInput Map that maps PlanePatchPtr to candidate nodes, without knowing anything about connected components yet.
nodePointersMapInput Map that maps PlanePatchPtr to candidate nodes, without knowing anything about connected components yet.
octreeNodesInput octree nodes to map indices to nodePointers.

Definition at line 1845 of file StructureColoring.cpp.

void StructureColoring::refineEdges ( PatchToNodePointersMap finalPlaneNodeAssignmentMap,
PatchToPointIndicesMap finalPlanePointAssignment,
const NodeIndexToPlanePatchPointers nodeToPlaneCandidates,
const NodePointers octreeNodes,
const OcTree octree,
const PointCloud pointCloud 
) [protected]

Refine edges between every 2 planes by looking at every node and decide which side of an edge it belongs to.

Parameters:
finalPlaneNodeAssignmentMapFinal plane to node assignment is put here.
nodeToPlaneCandidatesFor each node here must be stored which planes it could possibly belong (after connection check).
octreeNodesInput octree nodes to map indices to nodePointers.

Definition at line 1891 of file StructureColoring.cpp.

double StructureColoring::segmentCylinders ( CylinderPatches cylinderPatches,
CylinderPatchVector pointMapping,
OcTree octree,
const PointCloudPtr pointCloud 
) [protected]

Definition at line 477 of file StructureColoring.cpp.

double StructureColoring::segmentCylindersSAC ( CylinderPatches cylinderPatches,
CylinderPatchVector pointMapping,
OcTree octree,
const PointCloudPtr pointCloud 
) [protected]

Definition at line 2351 of file StructureColoring.cpp.

double StructureColoring::segmentPlanes ( PlanePatches extractedPlanes,
PlanePatchVector pointMapping,
OcTree octree,
const PointCloudPtr pointCloud 
) [protected]

Definition at line 452 of file StructureColoring.cpp.

double StructureColoring::segmentPlanesSAC ( PlanePatches extractedPlanes,
PlanePatchVector pointMapping,
const PointCloudPtr pointCloud 
) [protected]

Definition at line 2195 of file StructureColoring.cpp.

void StructureColoring::setParams ( StrColParams  params) [inline]

Definition at line 142 of file StructureColoring.h.

void StructureColoring::spreadNodes ( const OcTree octree,
PlanePatches extractedPlanes,
PlanePatchVector pointMapping,
const PointCloud pointCloud 
) [protected]

spreadNodes assign all nodes to previously determined planes. This is part of the post-processing.

Parameters:
depthShould be called with mOctreeDepth. This method does not check normal orientations but only the node's center-of-gravity against any planes for minimal distance. This method touches every node and changes any mapping, that was made before.

Definition at line 2009 of file StructureColoring.cpp.

void StructureColoring::spreadPoints ( ) [protected]
void StructureColoring::updateCylinderHTBins ( SphereUniformSampling cylinderOrientationBins,
const PairIndices inlierIndices,
SphereBinsVec binNeighborhood 
) [protected]

Update Hough space, remove inliers from it.

Parameters:
cylinderOrientationBinsOutput Hough space where inlier are removed from.
inlierIndicesInput indices of inlier to be removed.
binNeighborhoodInput/Output Neighborhood of indices is stored here, and will be erased (for indices that are removed).

Definition at line 1294 of file StructureColoring.cpp.

void StructureColoring::updateHTBins ( const NodeIndices inliers,
SphereUniformSamplings houghBins,
SphereBinsVec pointNeighborBins 
) [protected]

inliers - is a vector of (int) indices of a subset of nodes on current depth

Definition at line 1070 of file StructureColoring.cpp.

template<typename StructurePtrT >
void StructureColoring::updatePointMapping ( std::vector< StructurePtrT > &  pointMapping,
const PointIndices pointIndices,
const StructurePtrT &  structurePointer 
) [protected]

Definition at line 612 of file StructureColoring.h.

template<typename StructurePtrT >
void StructureColoring::updatePointMappingAndInliers ( std::vector< StructurePtrT > &  pointMapping,
PointIndices pointIndices,
const StructurePtrT &  structurePointer 
) [protected]

Definition at line 595 of file StructureColoring.h.

waitOnKinectMsgs Check if object waits for kinect messages.

Definition at line 113 of file StructureColoring.h.

waitOnLaserMsgs Check if object waits for laser messages.

Definition at line 117 of file StructureColoring.h.

template<typename PointMappingT , typename StructureContainerT >
void StructureColoring::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 
) [protected]

Definition at line 559 of file StructureColoring.h.


Member Data Documentation

Definition at line 489 of file StructureColoring.h.

Definition at line 490 of file StructureColoring.h.

std::string StructureColoring::mKinectTopic [protected]

Definition at line 480 of file StructureColoring.h.

Definition at line 500 of file StructureColoring.h.

ros::NodeHandle* StructureColoring::mNodeHandle [protected]

Definition at line 479 of file StructureColoring.h.

Definition at line 493 of file StructureColoring.h.

Definition at line 499 of file StructureColoring.h.

Definition at line 487 of file StructureColoring.h.

Definition at line 488 of file StructureColoring.h.

Definition at line 484 of file StructureColoring.h.

ros::Subscriber StructureColoring::mPointCloud2Subscriber [protected]

Definition at line 481 of file StructureColoring.h.

Definition at line 486 of file StructureColoring.h.

ros::Subscriber StructureColoring::mPointCloudSubscriber [protected]

Definition at line 482 of file StructureColoring.h.

Definition at line 485 of file StructureColoring.h.

Definition at line 497 of file StructureColoring.h.

Definition at line 495 of file StructureColoring.h.


The documentation for this class was generated from the following files:


structure_coloring_fkie
Author(s): Bastian Gaspers
autogenerated on Sun Jan 5 2014 11:38:09