Private Types | Private Member Functions | Private Attributes
jsk_pcl_ros::PointcloudScreenpoint Class Reference

#include <pointcloud_screenpoint.h>

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

List of all members.

Private Types

typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::PointCloud2,
geometry_msgs::PointStamped > 
PointApproxSyncPolicy
typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::PointCloud2,
sensor_msgs::PointCloud2 > 
PointCloudApproxSyncPolicy
typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::PointCloud2,
geometry_msgs::PolygonStamped > 
PolygonApproxSyncPolicy

Private Member Functions

void callback_point (const sensor_msgs::PointCloud2ConstPtr &points_ptr, const geometry_msgs::PointStampedConstPtr &pt_ptr)
void callback_point_array (const sensor_msgs::PointCloud2ConstPtr &points_ptr, const sensor_msgs::PointCloud2ConstPtr &pt_arr_ptr)
void callback_poly (const sensor_msgs::PointCloud2ConstPtr &points_ptr, const geometry_msgs::PolygonStampedConstPtr &array_ptr)
void callback_rect (const sensor_msgs::PointCloud2ConstPtr &points_ptr, const geometry_msgs::PolygonStampedConstPtr &array_ptr)
bool checkpoint (pcl::PointCloud< pcl::PointXYZ > &in_pts, int x, int y, float &resx, float &resy, float &resz)
bool extract_point (pcl::PointCloud< pcl::PointXYZ > &in_pts, int reqx, int reqy, float &resx, float &resy, float &resz)
void extract_rect (const sensor_msgs::PointCloud2ConstPtr &points_ptr, int st_x, int st_y, int ed_x, int ed_y)
void onInit ()
void point_array_cb (const sensor_msgs::PointCloud2ConstPtr &pt_arr_ptr)
void point_cb (const geometry_msgs::PointStampedConstPtr &pt_ptr)
void points_cb (const sensor_msgs::PointCloud2ConstPtr &msg)
void poly_cb (const geometry_msgs::PolygonStampedConstPtr &array_ptr)
void rect_cb (const geometry_msgs::PolygonStampedConstPtr &array_ptr)
bool screenpoint_cb (jsk_pcl_ros::TransformScreenpoint::Request &req, jsk_pcl_ros::TransformScreenpoint::Response &res)

Private Attributes

int crop_size_
std_msgs::Header header_
int k_
boost::mutex mutex_callback_
pcl::NormalEstimation
< pcl::PointXYZ, pcl::Normal > 
n3d_
pcl::KdTree< pcl::PointXYZ >::Ptr normals_tree_
message_filters::Subscriber
< sensor_msgs::PointCloud2 > 
point_array_sub_
message_filters::Subscriber
< geometry_msgs::PointStamped > 
point_sub_
message_filters::Subscriber
< sensor_msgs::PointCloud2 > 
points_sub_
message_filters::Subscriber
< geometry_msgs::PolygonStamped > 
poly_sub_
pcl::PointCloud< pcl::PointXYZ > pts_
ros::Publisher pub_point_
ros::Publisher pub_points_
ros::Publisher pub_polygon_
bool publish_point_
bool publish_points_
int queue_size_
message_filters::Subscriber
< geometry_msgs::PolygonStamped > 
rect_sub_
ros::ServiceServer srv_
boost::shared_ptr
< message_filters::Synchronizer
< PointApproxSyncPolicy > > 
sync_a_point_
boost::shared_ptr
< message_filters::Synchronizer
< PointCloudApproxSyncPolicy > > 
sync_a_point_array_
boost::shared_ptr
< message_filters::Synchronizer
< PolygonApproxSyncPolicy > > 
sync_a_poly_
boost::shared_ptr
< message_filters::Synchronizer
< PolygonApproxSyncPolicy > > 
sync_a_rect_
bool use_point_
bool use_point_array_
bool use_poly_
bool use_rect_
bool use_sync_

Detailed Description

Definition at line 61 of file pointcloud_screenpoint.h.


Member Typedef Documentation

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PointStamped > jsk_pcl_ros::PointcloudScreenpoint::PointApproxSyncPolicy [private]

Definition at line 69 of file pointcloud_screenpoint.h.

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > jsk_pcl_ros::PointcloudScreenpoint::PointCloudApproxSyncPolicy [private]

Definition at line 72 of file pointcloud_screenpoint.h.

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PolygonStamped > jsk_pcl_ros::PointcloudScreenpoint::PolygonApproxSyncPolicy [private]

Definition at line 65 of file pointcloud_screenpoint.h.


Member Function Documentation

void jsk_pcl_ros::PointcloudScreenpoint::callback_point ( const sensor_msgs::PointCloud2ConstPtr &  points_ptr,
const geometry_msgs::PointStampedConstPtr &  pt_ptr 
) [private]

Definition at line 301 of file pointcloud_screenpoint_nodelet.cpp.

void jsk_pcl_ros::PointcloudScreenpoint::callback_point_array ( const sensor_msgs::PointCloud2ConstPtr &  points_ptr,
const sensor_msgs::PointCloud2ConstPtr &  pt_arr_ptr 
) [private]

Definition at line 340 of file pointcloud_screenpoint_nodelet.cpp.

void jsk_pcl_ros::PointcloudScreenpoint::callback_poly ( const sensor_msgs::PointCloud2ConstPtr &  points_ptr,
const geometry_msgs::PolygonStampedConstPtr &  array_ptr 
) [private]

Definition at line 386 of file pointcloud_screenpoint_nodelet.cpp.

void jsk_pcl_ros::PointcloudScreenpoint::callback_rect ( const sensor_msgs::PointCloud2ConstPtr &  points_ptr,
const geometry_msgs::PolygonStampedConstPtr &  array_ptr 
) [private]

Definition at line 393 of file pointcloud_screenpoint_nodelet.cpp.

bool jsk_pcl_ros::PointcloudScreenpoint::checkpoint ( pcl::PointCloud< pcl::PointXYZ > &  in_pts,
int  x,
int  y,
float &  resx,
float &  resy,
float &  resz 
) [private]

Definition at line 133 of file pointcloud_screenpoint_nodelet.cpp.

bool jsk_pcl_ros::PointcloudScreenpoint::extract_point ( pcl::PointCloud< pcl::PointXYZ > &  in_pts,
int  reqx,
int  reqy,
float &  resx,
float &  resy,
float &  resz 
) [private]

Definition at line 148 of file pointcloud_screenpoint_nodelet.cpp.

void jsk_pcl_ros::PointcloudScreenpoint::extract_rect ( const sensor_msgs::PointCloud2ConstPtr &  points_ptr,
int  st_x,
int  st_y,
int  ed_x,
int  ed_y 
) [private]

Definition at line 251 of file pointcloud_screenpoint_nodelet.cpp.

void jsk_pcl_ros::PointcloudScreenpoint::onInit ( void  ) [private, virtual]

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 43 of file pointcloud_screenpoint_nodelet.cpp.

void jsk_pcl_ros::PointcloudScreenpoint::point_array_cb ( const sensor_msgs::PointCloud2ConstPtr &  pt_arr_ptr) [private]

Definition at line 315 of file pointcloud_screenpoint_nodelet.cpp.

void jsk_pcl_ros::PointcloudScreenpoint::point_cb ( const geometry_msgs::PointStampedConstPtr &  pt_ptr) [private]

Definition at line 287 of file pointcloud_screenpoint_nodelet.cpp.

void jsk_pcl_ros::PointcloudScreenpoint::points_cb ( const sensor_msgs::PointCloud2ConstPtr &  msg) [private]

Definition at line 244 of file pointcloud_screenpoint_nodelet.cpp.

void jsk_pcl_ros::PointcloudScreenpoint::poly_cb ( const geometry_msgs::PolygonStampedConstPtr &  array_ptr) [private]

Definition at line 365 of file pointcloud_screenpoint_nodelet.cpp.

void jsk_pcl_ros::PointcloudScreenpoint::rect_cb ( const geometry_msgs::PolygonStampedConstPtr &  array_ptr) [private]

Definition at line 345 of file pointcloud_screenpoint_nodelet.cpp.

bool jsk_pcl_ros::PointcloudScreenpoint::screenpoint_cb ( jsk_pcl_ros::TransformScreenpoint::Request &  req,
jsk_pcl_ros::TransformScreenpoint::Response &  res 
) [private]

Definition at line 186 of file pointcloud_screenpoint_nodelet.cpp.


Member Data Documentation

Definition at line 131 of file pointcloud_screenpoint.h.

Definition at line 92 of file pointcloud_screenpoint.h.

Definition at line 129 of file pointcloud_screenpoint.h.

Definition at line 127 of file pointcloud_screenpoint.h.

pcl::NormalEstimation< pcl::PointXYZ, pcl::Normal > jsk_pcl_ros::PointcloudScreenpoint::n3d_ [private]

Definition at line 96 of file pointcloud_screenpoint.h.

pcl::KdTree< pcl::PointXYZ >::Ptr jsk_pcl_ros::PointcloudScreenpoint::normals_tree_ [private]

Definition at line 100 of file pointcloud_screenpoint.h.

Definition at line 79 of file pointcloud_screenpoint.h.

Definition at line 78 of file pointcloud_screenpoint.h.

Definition at line 76 of file pointcloud_screenpoint.h.

Definition at line 80 of file pointcloud_screenpoint.h.

Definition at line 91 of file pointcloud_screenpoint.h.

Definition at line 88 of file pointcloud_screenpoint.h.

Definition at line 87 of file pointcloud_screenpoint.h.

Definition at line 89 of file pointcloud_screenpoint.h.

Definition at line 132 of file pointcloud_screenpoint.h.

Definition at line 133 of file pointcloud_screenpoint.h.

Definition at line 130 of file pointcloud_screenpoint.h.

Definition at line 77 of file pointcloud_screenpoint.h.

Definition at line 90 of file pointcloud_screenpoint.h.

Definition at line 83 of file pointcloud_screenpoint.h.

Definition at line 84 of file pointcloud_screenpoint.h.

Definition at line 85 of file pointcloud_screenpoint.h.

Definition at line 82 of file pointcloud_screenpoint.h.

Definition at line 94 of file pointcloud_screenpoint.h.

Definition at line 94 of file pointcloud_screenpoint.h.

Definition at line 94 of file pointcloud_screenpoint.h.

Definition at line 94 of file pointcloud_screenpoint.h.

Definition at line 94 of file pointcloud_screenpoint.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