Public Types | Public Member Functions | Public Attributes | Protected Attributes | List of all members
jsk_pcl_ros::LineSegment Class Reference

#include <line_segment_detector.h>

Public Types

typedef boost::shared_ptr< LineSegmentPtr
 

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_
 

Detailed Description

Definition at line 59 of file line_segment_detector.h.

Member Typedef Documentation

Definition at line 62 of file line_segment_detector.h.

Constructor & Destructor Documentation

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.

Member Function Documentation

bool jsk_pcl_ros::LineSegment::addMarkerLine ( visualization_msgs::Marker &  marker,
const pcl::PointCloud< pcl::PointXYZ >::Ptr cloud,
double  minimum_line_length 
)
virtual

Definition at line 100 of file line_segment_detector_nodelet.cpp.

pcl::ModelCoefficients::Ptr jsk_pcl_ros::LineSegment::getCoefficients ( )
inline

Definition at line 77 of file line_segment_detector.h.

pcl::PointIndices::Ptr jsk_pcl_ros::LineSegment::getIndices ( )
inline

Definition at line 76 of file line_segment_detector.h.

pcl::PointCloud<pcl::PointXYZ>::Ptr jsk_pcl_ros::LineSegment::getPoints ( )
inline

Definition at line 78 of file line_segment_detector.h.

pcl::PointCloud<pcl::PointXYZ>::Ptr jsk_pcl_ros::LineSegment::getRawPoints ( )
inline

Definition at line 79 of file line_segment_detector.h.

jsk_recognition_utils::Line::Ptr jsk_pcl_ros::LineSegment::toSegment ( )
virtual

Definition at line 80 of file line_segment_detector_nodelet.cpp.

Member Data Documentation

pcl::ModelCoefficients::Ptr jsk_pcl_ros::LineSegment::coefficients_
protected

Definition at line 83 of file line_segment_detector.h.

std_msgs::Header jsk_pcl_ros::LineSegment::header

Definition at line 80 of file line_segment_detector.h.

pcl::PointIndices::Ptr jsk_pcl_ros::LineSegment::indices_
protected

Definition at line 82 of file line_segment_detector.h.

pcl::PointCloud<pcl::PointXYZ>::Ptr jsk_pcl_ros::LineSegment::points_
protected

Definition at line 84 of file line_segment_detector.h.

pcl::PointCloud<pcl::PointXYZ>::Ptr jsk_pcl_ros::LineSegment::raw_points_
protected

Definition at line 85 of file line_segment_detector.h.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:48