#include <line_segment_detector.h>
Public Types | |
typedef boost::shared_ptr < LineSegment > | Ptr |
Public Member Functions | |
virtual void | addMarkerLine (visualization_msgs::Marker &marker, const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud) |
pcl::ModelCoefficients::Ptr | getCoefficients () |
pcl::PointIndices::Ptr | getIndices () |
pcl::PointCloud< pcl::PointXYZ > ::Ptr | getPoints () |
pcl::PointCloud< pcl::PointXYZ > ::Ptr | getRawPoints () |
LineSegment (const std_msgs::Header &input_header, pcl::PointIndices::Ptr indices, pcl::ModelCoefficients::Ptr coefficients, pcl::PointCloud< pcl::PointXYZ >::Ptr cloud) | |
LineSegment (pcl::PointIndices::Ptr indices, pcl::ModelCoefficients::Ptr coefficients) | |
virtual Line::Ptr | toSegment () |
virtual | ~LineSegment () |
Public Attributes | |
std_msgs::Header | header |
Protected Attributes | |
pcl::ModelCoefficients::Ptr | coefficients_ |
pcl::PointIndices::Ptr | indices_ |
pcl::PointCloud< pcl::PointXYZ > ::Ptr | points_ |
pcl::PointCloud< pcl::PointXYZ > ::Ptr | raw_points_ |
Definition at line 55 of file line_segment_detector.h.
typedef boost::shared_ptr<LineSegment> jsk_pcl_ros::LineSegment::Ptr |
Definition at line 58 of file line_segment_detector.h.
jsk_pcl_ros::LineSegment::LineSegment | ( | const std_msgs::Header & | input_header, |
pcl::PointIndices::Ptr | indices, | ||
pcl::ModelCoefficients::Ptr | coefficients, | ||
pcl::PointCloud< pcl::PointXYZ >::Ptr | cloud | ||
) |
Definition at line 54 of file line_segment_detector_nodelet.cpp.
jsk_pcl_ros::LineSegment::LineSegment | ( | pcl::PointIndices::Ptr | indices, |
pcl::ModelCoefficients::Ptr | coefficients | ||
) |
Definition at line 47 of file line_segment_detector_nodelet.cpp.
jsk_pcl_ros::LineSegment::~LineSegment | ( | ) | [virtual] |
Definition at line 76 of file line_segment_detector_nodelet.cpp.
void jsk_pcl_ros::LineSegment::addMarkerLine | ( | visualization_msgs::Marker & | marker, |
const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud | ||
) | [virtual] |
Definition at line 99 of file line_segment_detector_nodelet.cpp.
pcl::ModelCoefficients::Ptr jsk_pcl_ros::LineSegment::getCoefficients | ( | ) | [inline] |
Definition at line 72 of file line_segment_detector.h.
pcl::PointIndices::Ptr jsk_pcl_ros::LineSegment::getIndices | ( | ) | [inline] |
Definition at line 71 of file line_segment_detector.h.
pcl::PointCloud<pcl::PointXYZ>::Ptr jsk_pcl_ros::LineSegment::getPoints | ( | ) | [inline] |
Definition at line 73 of file line_segment_detector.h.
pcl::PointCloud<pcl::PointXYZ>::Ptr jsk_pcl_ros::LineSegment::getRawPoints | ( | ) | [inline] |
Definition at line 74 of file line_segment_detector.h.
Line::Ptr jsk_pcl_ros::LineSegment::toSegment | ( | ) | [virtual] |
Definition at line 80 of file line_segment_detector_nodelet.cpp.
pcl::ModelCoefficients::Ptr jsk_pcl_ros::LineSegment::coefficients_ [protected] |
Definition at line 78 of file line_segment_detector.h.
Definition at line 75 of file line_segment_detector.h.
pcl::PointIndices::Ptr jsk_pcl_ros::LineSegment::indices_ [protected] |
Definition at line 77 of file line_segment_detector.h.
pcl::PointCloud<pcl::PointXYZ>::Ptr jsk_pcl_ros::LineSegment::points_ [protected] |
Definition at line 79 of file line_segment_detector.h.
pcl::PointCloud<pcl::PointXYZ>::Ptr jsk_pcl_ros::LineSegment::raw_points_ [protected] |
Definition at line 80 of file line_segment_detector.h.