#include <line_segment_detector.h>
Public Types | |
| typedef boost::shared_ptr< LineSegment > | Ptr |
Public Member Functions | |
| virtual bool | addMarkerLine (visualization_msgs::Marker &marker, const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, double minimum_line_length) |
| 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 jsk_recognition_utils::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 91 of file line_segment_detector.h.
Definition at line 126 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 86 of file line_segment_detector_nodelet.cpp.
| jsk_pcl_ros::LineSegment::LineSegment | ( | pcl::PointIndices::Ptr | indices, |
| pcl::ModelCoefficients::Ptr | coefficients | ||
| ) |
Definition at line 79 of file line_segment_detector_nodelet.cpp.
|
virtual |
Definition at line 108 of file line_segment_detector_nodelet.cpp.
|
virtual |
Definition at line 132 of file line_segment_detector_nodelet.cpp.
|
inline |
Definition at line 141 of file line_segment_detector.h.
|
inline |
Definition at line 140 of file line_segment_detector.h.
|
inline |
Definition at line 142 of file line_segment_detector.h.
|
inline |
Definition at line 143 of file line_segment_detector.h.
|
virtual |
Definition at line 112 of file line_segment_detector_nodelet.cpp.
|
protected |
Definition at line 147 of file line_segment_detector.h.
| std_msgs::Header jsk_pcl_ros::LineSegment::header |
Definition at line 144 of file line_segment_detector.h.
|
protected |
Definition at line 146 of file line_segment_detector.h.
|
protected |
Definition at line 148 of file line_segment_detector.h.
|
protected |
Definition at line 149 of file line_segment_detector.h.