#include <RosVisualization.h>
Public Types | |
| typedef CylinderPatch::CylinderPatches | CylinderPatches |
| typedef OcTree::NodePointerList | NodePointerList |
| typedef OcTree::NodePointers | NodePointers |
| typedef algorithm::OcTreeSamplingMap < float, NormalEstimationValueClass > | OctreeSamplingMap |
| typedef PlanePatch::PlanePatches | PlanePatches |
| typedef std::vector < PlanePatch::PlanePatchPtr > | PlanePatchVector |
| typedef pcl::PointCloud< PointT > | PointCloud |
| typedef PlanePatch::PointIndices | PointIndices |
| typedef PlanePatch::Points | Points |
| typedef pcl::PointXYZRGB | PointT |
| typedef std::vector < SphereUniformSampling > | SphereUniformSamplings |
| typedef Eigen::Vector3f | Vec3 |
Public Member Functions | |
| void | printTopics () |
| void | publishCylinderMarker (const CylinderPatches &cylinders, const std::string &namePrefix="cylinder ") |
| void | publishCylinderPoints (const CylinderPatches &cylinders, const boost::shared_ptr< pcl::PointCloud< pcl::PointXYZRGB > > inputPC) |
| void | publishCylinderPointsNormals (const PointCloud &partCloud, const pcl::PointCloud< pcl::Normal > &normalCloud, const std::string &name="no identifier") |
| void | publishHistogramMarker (const SphereUniformSampling &HTBins, const float &scale, const Eigen::Vector3f &translation) |
| void | publishHTBinCloud (const SphereUniformSamplings &HTBins) |
| void | publishHTBinCloud (PointCloud histogramCloud) |
| void | publishOctreeNormalMarker (const OcTree &octree) |
| void | publishPairMarker (const NodePairs &nodePairs) |
| void | publishPlaneMarker (const PlanePatches &planes, const std::string &namePrefix="plane ") |
| void | publishPointCloud (const PointCloud &pointCloud) |
| void | publishPoints (const Points &points, const std::string &nameAppendix, const Vec3 &color) |
| template<typename PointAssignment , typename StructureContainer > | |
| void | publishSegmentedPointcloud (const PointAssignment &segmented, const StructureContainer &planes, const PointCloud &pointCloud) |
| RosVisualization (ros::NodeHandle &nh) | |
| void | setFrame (const std::string &frame_id) |
Static Public Member Functions | |
| static void | getColorByIndex (float *rgb, unsigned int index, unsigned int total) |
Private Attributes | |
| ros::Publisher | mCylinderMarkerPublisher |
| ros::Publisher | mCylinderPointCloudPublisher |
| std::string | mFrameID |
| ros::Publisher | mHistogramPC2Publisher |
| std::string | mLaserTopic |
| ros::Publisher | mMarkerPublisher |
| ros::Publisher | mPC2Publisher |
| ros::Publisher | mSegmentedCloudPublisher |
Definition at line 51 of file RosVisualization.h.
Definition at line 55 of file RosVisualization.h.
Definition at line 64 of file RosVisualization.h.
Definition at line 63 of file RosVisualization.h.
| typedef algorithm::OcTreeSamplingMap<float, NormalEstimationValueClass> RosVisualization::OctreeSamplingMap |
Definition at line 56 of file RosVisualization.h.
Definition at line 53 of file RosVisualization.h.
| typedef std::vector<PlanePatch::PlanePatchPtr> RosVisualization::PlanePatchVector |
Definition at line 54 of file RosVisualization.h.
Definition at line 62 of file RosVisualization.h.
Definition at line 58 of file RosVisualization.h.
Definition at line 60 of file RosVisualization.h.
| typedef pcl::PointXYZRGB RosVisualization::PointT |
Definition at line 61 of file RosVisualization.h.
| typedef std::vector<SphereUniformSampling> RosVisualization::SphereUniformSamplings |
Definition at line 57 of file RosVisualization.h.
| typedef Eigen::Vector3f RosVisualization::Vec3 |
Definition at line 59 of file RosVisualization.h.
| RosVisualization::RosVisualization | ( | ros::NodeHandle & | nh | ) |
Definition at line 44 of file RosVisualization.cpp.
| void RosVisualization::getColorByIndex | ( | float * | rgb, |
| unsigned int | index, | ||
| unsigned int | total | ||
| ) | [static] |
Definition at line 56 of file RosVisualization.cpp.
| void RosVisualization::printTopics | ( | ) |
Definition at line 552 of file RosVisualization.cpp.
| void RosVisualization::publishCylinderMarker | ( | const CylinderPatches & | cylinders, |
| const std::string & | namePrefix = "cylinder " |
||
| ) |
Definition at line 199 of file RosVisualization.cpp.
| void RosVisualization::publishCylinderPoints | ( | const CylinderPatches & | cylinders, |
| const boost::shared_ptr< pcl::PointCloud< pcl::PointXYZRGB > > | inputPC | ||
| ) |
Definition at line 421 of file RosVisualization.cpp.
| void RosVisualization::publishCylinderPointsNormals | ( | const PointCloud & | partCloud, |
| const pcl::PointCloud< pcl::Normal > & | normalCloud, | ||
| const std::string & | name = "no identifier" |
||
| ) |
Definition at line 500 of file RosVisualization.cpp.
| void RosVisualization::publishHistogramMarker | ( | const SphereUniformSampling & | HTBins, |
| const float & | scale, | ||
| const Eigen::Vector3f & | translation | ||
| ) |
Definition at line 348 of file RosVisualization.cpp.
| void RosVisualization::publishHTBinCloud | ( | const SphereUniformSamplings & | HTBins | ) |
Definition at line 393 of file RosVisualization.cpp.
| void RosVisualization::publishHTBinCloud | ( | PointCloud | histogramCloud | ) |
| void RosVisualization::publishOctreeNormalMarker | ( | const OcTree & | octree | ) |
Definition at line 243 of file RosVisualization.cpp.
| void RosVisualization::publishPairMarker | ( | const NodePairs & | nodePairs | ) |
Definition at line 92 of file RosVisualization.cpp.
| void RosVisualization::publishPlaneMarker | ( | const PlanePatches & | planes, |
| const std::string & | namePrefix = "plane " |
||
| ) |
Definition at line 128 of file RosVisualization.cpp.
| void RosVisualization::publishPointCloud | ( | const PointCloud & | pointCloud | ) |
Definition at line 458 of file RosVisualization.cpp.
| void RosVisualization::publishPoints | ( | const Points & | points, |
| const std::string & | nameAppendix, | ||
| const Vec3 & | color | ||
| ) |
Definition at line 469 of file RosVisualization.cpp.
| void RosVisualization::publishSegmentedPointcloud | ( | const PointAssignment & | segmented, |
| const StructureContainer & | planes, | ||
| const PointCloud & | pointCloud | ||
| ) |
Definition at line 99 of file RosVisualization.h.
| void RosVisualization::setFrame | ( | const std::string & | frame_id | ) | [inline] |
Definition at line 70 of file RosVisualization.h.
ros::Publisher RosVisualization::mCylinderMarkerPublisher [private] |
Definition at line 93 of file RosVisualization.h.
ros::Publisher RosVisualization::mCylinderPointCloudPublisher [private] |
Definition at line 91 of file RosVisualization.h.
std::string RosVisualization::mFrameID [private] |
Definition at line 94 of file RosVisualization.h.
ros::Publisher RosVisualization::mHistogramPC2Publisher [private] |
Definition at line 88 of file RosVisualization.h.
std::string RosVisualization::mLaserTopic [private] |
Definition at line 95 of file RosVisualization.h.
ros::Publisher RosVisualization::mMarkerPublisher [private] |
Definition at line 92 of file RosVisualization.h.
ros::Publisher RosVisualization::mPC2Publisher [private] |
Definition at line 89 of file RosVisualization.h.
ros::Publisher RosVisualization::mSegmentedCloudPublisher [private] |
Definition at line 90 of file RosVisualization.h.