Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
jsk_pcl_ros::PlaneReasoner Class Reference

#include <plane_reasoner.h>

Inheritance diagram for jsk_pcl_ros::PlaneReasoner:
Inheritance graph
[legend]

List of all members.

Public Types

typedef
jsk_pcl_ros::PlaneReasonerConfig 
Config
typedef pcl::PointXYZRGB PointT
typedef
message_filters::sync_policies::ExactTime
< sensor_msgs::PointCloud2,
jsk_recognition_msgs::ClusterPointIndices,
jsk_recognition_msgs::ModelCoefficientsArray,
jsk_recognition_msgs::PolygonArray > 
SyncPolicy

Public Member Functions

 PlaneReasoner ()

Protected Member Functions

virtual void configCallback (Config &config, uint32_t level)
virtual std::vector
< PlaneInfoContainer
filterHorizontalPlanes (std::vector< PlaneInfoContainer > &infos)
virtual std::vector
< PlaneInfoContainer
filterPlanesAroundAngle (double reference_angle, double thrshold, std::vector< PlaneInfoContainer > &infos)
virtual std::vector
< PlaneInfoContainer
filterVerticalPlanes (std::vector< PlaneInfoContainer > &infos)
virtual void onInit ()
virtual std::vector
< PlaneInfoContainer
packInfo (std::vector< pcl::PointIndices::Ptr > &inliers, std::vector< pcl::ModelCoefficients::Ptr > &coefficients, std::vector< Plane::Ptr > &planes, std::vector< geometry_msgs::PolygonStamped > &polygons)
virtual void publishPlaneInfo (std::vector< PlaneInfoContainer > &containers, const std_msgs::Header &header, pcl::PointCloud< PointT >::Ptr cloud, ros::Publisher &pub_inlier, ros::Publisher &pub_coefficients, ros::Publisher &pub_polygons)
virtual void reason (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &inliers_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons_msg)
virtual void subscribe ()
virtual void unsubscribe ()
virtual void updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)

Protected Attributes

std::string global_frame_id_
double horizontal_angular_threshold_
boost::mutex mutex_
ros::Publisher pub_horizontal_coefficients_
ros::Publisher pub_horizontal_inliers_
ros::Publisher pub_horizontal_polygons_
ros::Publisher pub_vertical_coefficients_
ros::Publisher pub_vertical_inliers_
ros::Publisher pub_vertical_polygons_
boost::shared_ptr
< dynamic_reconfigure::Server
< Config > > 
srv_
message_filters::Subscriber
< jsk_recognition_msgs::ModelCoefficientsArray > 
sub_coefficients_
message_filters::Subscriber
< jsk_recognition_msgs::ClusterPointIndices > 
sub_inliers_
message_filters::Subscriber
< sensor_msgs::PointCloud2 > 
sub_input_
message_filters::Subscriber
< jsk_recognition_msgs::PolygonArray > 
sub_polygons_
boost::shared_ptr
< message_filters::Synchronizer
< SyncPolicy > > 
sync_
tf::TransformListenertf_listener_
double vertical_angular_threshold_

Detailed Description

Definition at line 63 of file plane_reasoner.h.


Member Typedef Documentation

typedef jsk_pcl_ros::PlaneReasonerConfig jsk_pcl_ros::PlaneReasoner::Config

Definition at line 74 of file plane_reasoner.h.

typedef pcl::PointXYZRGB jsk_pcl_ros::PlaneReasoner::PointT

Definition at line 75 of file plane_reasoner.h.

typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::ModelCoefficientsArray, jsk_recognition_msgs::PolygonArray> jsk_pcl_ros::PlaneReasoner::SyncPolicy

Definition at line 73 of file plane_reasoner.h.


Constructor & Destructor Documentation

Definition at line 78 of file plane_reasoner.h.


Member Function Documentation

void jsk_pcl_ros::PlaneReasoner::configCallback ( Config config,
uint32_t  level 
) [protected, virtual]

Definition at line 101 of file plane_reasoner_nodelet.cpp.

Definition at line 240 of file plane_reasoner_nodelet.cpp.

std::vector< PlaneInfoContainer > jsk_pcl_ros::PlaneReasoner::filterPlanesAroundAngle ( double  reference_angle,
double  thrshold,
std::vector< PlaneInfoContainer > &  infos 
) [protected, virtual]

Definition at line 203 of file plane_reasoner_nodelet.cpp.

Definition at line 250 of file plane_reasoner_nodelet.cpp.

void jsk_pcl_ros::PlaneReasoner::onInit ( void  ) [protected, virtual]

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 42 of file plane_reasoner_nodelet.cpp.

std::vector< PlaneInfoContainer > jsk_pcl_ros::PlaneReasoner::packInfo ( std::vector< pcl::PointIndices::Ptr > &  inliers,
std::vector< pcl::ModelCoefficients::Ptr > &  coefficients,
std::vector< Plane::Ptr > &  planes,
std::vector< geometry_msgs::PolygonStamped > &  polygons 
) [protected, virtual]

Definition at line 260 of file plane_reasoner_nodelet.cpp.

void jsk_pcl_ros::PlaneReasoner::publishPlaneInfo ( std::vector< PlaneInfoContainer > &  containers,
const std_msgs::Header header,
pcl::PointCloud< PointT >::Ptr  cloud,
ros::Publisher pub_inlier,
ros::Publisher pub_coefficients,
ros::Publisher pub_polygons 
) [protected, virtual]

Definition at line 169 of file plane_reasoner_nodelet.cpp.

void jsk_pcl_ros::PlaneReasoner::reason ( const sensor_msgs::PointCloud2::ConstPtr &  cloud_msg,
const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &  inliers_msg,
const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &  coefficients_msg,
const jsk_recognition_msgs::PolygonArray::ConstPtr &  polygons_msg 
) [protected, virtual]

Definition at line 122 of file plane_reasoner_nodelet.cpp.

void jsk_pcl_ros::PlaneReasoner::subscribe ( ) [protected, virtual]
void jsk_pcl_ros::PlaneReasoner::unsubscribe ( ) [protected, virtual]

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 109 of file plane_reasoner_nodelet.cpp.


Member Data Documentation

Definition at line 151 of file plane_reasoner.h.

Definition at line 152 of file plane_reasoner.h.

Definition at line 146 of file plane_reasoner.h.

Definition at line 143 of file plane_reasoner.h.

Definition at line 142 of file plane_reasoner.h.

Definition at line 144 of file plane_reasoner.h.

Definition at line 140 of file plane_reasoner.h.

Definition at line 139 of file plane_reasoner.h.

Definition at line 141 of file plane_reasoner.h.

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::PlaneReasoner::srv_ [protected]

Definition at line 137 of file plane_reasoner.h.

message_filters::Subscriber<jsk_recognition_msgs::ModelCoefficientsArray> jsk_pcl_ros::PlaneReasoner::sub_coefficients_ [protected]

Definition at line 134 of file plane_reasoner.h.

message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> jsk_pcl_ros::PlaneReasoner::sub_inliers_ [protected]

Definition at line 133 of file plane_reasoner.h.

Definition at line 132 of file plane_reasoner.h.

message_filters::Subscriber<jsk_recognition_msgs::PolygonArray> jsk_pcl_ros::PlaneReasoner::sub_polygons_ [protected]

Definition at line 135 of file plane_reasoner.h.

Definition at line 136 of file plane_reasoner.h.

Definition at line 138 of file plane_reasoner.h.

Definition at line 153 of file plane_reasoner.h.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:49