#include <pointcloud_screenpoint.h>
Protected Types | |
typedef PointcloudScreenpointConfig | Config |
typedef mf::sync_policies::ApproximateTime < sensor_msgs::PointCloud2, geometry_msgs::PointStamped > | PointApproxSyncPolicy |
typedef mf::sync_policies::ApproximateTime < sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | PointCloudApproxSyncPolicy |
typedef mf::sync_policies::ExactTime < sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | PointCloudExactSyncPolicy |
typedef mf::sync_policies::ExactTime < sensor_msgs::PointCloud2, geometry_msgs::PointStamped > | PointExactSyncPolicy |
typedef mf::sync_policies::ApproximateTime < sensor_msgs::PointCloud2, geometry_msgs::PolygonStamped > | PolygonApproxSyncPolicy |
typedef mf::sync_policies::ExactTime < sensor_msgs::PointCloud2, geometry_msgs::PolygonStamped > | PolygonExactSyncPolicy |
Protected Member Functions | |
bool | checkpoint (const pcl::PointCloud< pcl::PointXYZ > &in_pts, int x, int y, float &resx, float &resy, float &resz) |
virtual void | configCallback (Config &config, uint32_t level) |
bool | extract_point (const pcl::PointCloud< pcl::PointXYZ > &in_pts, int reqx, int reqy, float &resx, float &resy, float &resz) |
void | extract_rect (const pcl::PointCloud< pcl::PointXYZ > &in_pts, int st_x, int st_y, int ed_x, int ed_y, sensor_msgs::PointCloud2 &out_pts) |
virtual void | onInit () |
void | point_array_cb (const sensor_msgs::PointCloud2::ConstPtr &pt_arr_ptr) |
void | point_cb (const geometry_msgs::PointStamped::ConstPtr &pt_ptr) |
void | points_cb (const sensor_msgs::PointCloud2::ConstPtr &msg) |
void | poly_cb (const geometry_msgs::PolygonStamped::ConstPtr &array_ptr) |
void | rect_cb (const geometry_msgs::PolygonStamped::ConstPtr &array_ptr) |
bool | screenpoint_cb (jsk_recognition_msgs::TransformScreenpoint::Request &req, jsk_recognition_msgs::TransformScreenpoint::Response &res) |
virtual void | subscribe () |
void | sync_point_array_cb (const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const sensor_msgs::PointCloud2::ConstPtr &pt_arr_ptr) |
void | sync_point_cb (const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const geometry_msgs::PointStamped::ConstPtr &pt_ptr) |
void | sync_poly_cb (const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const geometry_msgs::PolygonStamped::ConstPtr &array_ptr) |
void | sync_rect_cb (const sensor_msgs::PointCloud2ConstPtr &points_ptr, const geometry_msgs::PolygonStamped::ConstPtr &array_ptr) |
virtual void | unsubscribe () |
Protected Attributes | |
bool | approximate_sync_ |
boost::shared_ptr < mf::Synchronizer < PointApproxSyncPolicy > > | async_point_ |
boost::shared_ptr < mf::Synchronizer < PointCloudApproxSyncPolicy > > | async_point_array_ |
boost::shared_ptr < mf::Synchronizer < PolygonApproxSyncPolicy > > | async_poly_ |
boost::shared_ptr < mf::Synchronizer < PolygonApproxSyncPolicy > > | async_rect_ |
int | crop_size_ |
boost::shared_ptr < dynamic_reconfigure::Server < Config > > | dyn_srv_ |
pcl::PointCloud< pcl::PointXYZ > | latest_cloud_ |
std_msgs::Header | latest_cloud_header_ |
boost::mutex | mutex_ |
pcl::NormalEstimation < pcl::PointXYZ, pcl::Normal > | n3d_ |
pcl::search::KdTree < pcl::PointXYZ >::Ptr | normals_tree_ |
mf::Subscriber < sensor_msgs::PointCloud2 > | point_array_sub_ |
mf::Subscriber < geometry_msgs::PointStamped > | point_sub_ |
mf::Subscriber < sensor_msgs::PointCloud2 > | points_sub_ |
mf::Subscriber < geometry_msgs::PolygonStamped > | poly_sub_ |
ros::Publisher | pub_point_ |
ros::Publisher | pub_points_ |
ros::Publisher | pub_polygon_ |
int | queue_size_ |
mf::Subscriber < geometry_msgs::PolygonStamped > | rect_sub_ |
int | search_size_ |
ros::ServiceServer | srv_ |
boost::shared_ptr < mf::Synchronizer < PointExactSyncPolicy > > | sync_point_ |
boost::shared_ptr < mf::Synchronizer < PointCloudExactSyncPolicy > > | sync_point_array_ |
boost::shared_ptr < mf::Synchronizer < PolygonExactSyncPolicy > > | sync_poly_ |
boost::shared_ptr < mf::Synchronizer < PolygonExactSyncPolicy > > | sync_rect_ |
bool | synchronization_ |
double | timeout_ |
Definition at line 56 of file pointcloud_screenpoint.h.
typedef PointcloudScreenpointConfig jsk_pcl_ros::PointcloudScreenpoint::Config [protected] |
Definition at line 59 of file pointcloud_screenpoint.h.
typedef mf::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PointStamped > jsk_pcl_ros::PointcloudScreenpoint::PointApproxSyncPolicy [protected] |
Definition at line 68 of file pointcloud_screenpoint.h.
typedef mf::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > jsk_pcl_ros::PointcloudScreenpoint::PointCloudApproxSyncPolicy [protected] |
Definition at line 72 of file pointcloud_screenpoint.h.
typedef mf::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > jsk_pcl_ros::PointcloudScreenpoint::PointCloudExactSyncPolicy [protected] |
Definition at line 85 of file pointcloud_screenpoint.h.
typedef mf::sync_policies::ExactTime< sensor_msgs::PointCloud2, geometry_msgs::PointStamped > jsk_pcl_ros::PointcloudScreenpoint::PointExactSyncPolicy [protected] |
Definition at line 81 of file pointcloud_screenpoint.h.
typedef mf::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PolygonStamped > jsk_pcl_ros::PointcloudScreenpoint::PolygonApproxSyncPolicy [protected] |
Definition at line 64 of file pointcloud_screenpoint.h.
typedef mf::sync_policies::ExactTime< sensor_msgs::PointCloud2, geometry_msgs::PolygonStamped > jsk_pcl_ros::PointcloudScreenpoint::PolygonExactSyncPolicy [protected] |
Definition at line 77 of file pointcloud_screenpoint.h.
bool jsk_pcl_ros::PointcloudScreenpoint::checkpoint | ( | const pcl::PointCloud< pcl::PointXYZ > & | in_pts, |
int | x, | ||
int | y, | ||
float & | resx, | ||
float & | resy, | ||
float & | resz | ||
) | [protected] |
Definition at line 458 of file pointcloud_screenpoint_nodelet.cpp.
void jsk_pcl_ros::PointcloudScreenpoint::configCallback | ( | Config & | config, |
uint32_t | level | ||
) | [protected, virtual] |
Definition at line 157 of file pointcloud_screenpoint_nodelet.cpp.
bool jsk_pcl_ros::PointcloudScreenpoint::extract_point | ( | const pcl::PointCloud< pcl::PointXYZ > & | in_pts, |
int | reqx, | ||
int | reqy, | ||
float & | resx, | ||
float & | resy, | ||
float & | resz | ||
) | [protected] |
Definition at line 481 of file pointcloud_screenpoint_nodelet.cpp.
void jsk_pcl_ros::PointcloudScreenpoint::extract_rect | ( | const pcl::PointCloud< pcl::PointXYZ > & | in_pts, |
int | st_x, | ||
int | st_y, | ||
int | ed_x, | ||
int | ed_y, | ||
sensor_msgs::PointCloud2 & | out_pts | ||
) | [protected] |
Definition at line 521 of file pointcloud_screenpoint_nodelet.cpp.
void jsk_pcl_ros::PointcloudScreenpoint::onInit | ( | void | ) | [protected, virtual] |
Definition at line 47 of file pointcloud_screenpoint_nodelet.cpp.
void jsk_pcl_ros::PointcloudScreenpoint::point_array_cb | ( | const sensor_msgs::PointCloud2::ConstPtr & | pt_arr_ptr | ) | [protected] |
Definition at line 320 of file pointcloud_screenpoint_nodelet.cpp.
void jsk_pcl_ros::PointcloudScreenpoint::point_cb | ( | const geometry_msgs::PointStamped::ConstPtr & | pt_ptr | ) | [protected] |
Definition at line 289 of file pointcloud_screenpoint_nodelet.cpp.
void jsk_pcl_ros::PointcloudScreenpoint::points_cb | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) | [protected] |
Definition at line 280 of file pointcloud_screenpoint_nodelet.cpp.
void jsk_pcl_ros::PointcloudScreenpoint::poly_cb | ( | const geometry_msgs::PolygonStamped::ConstPtr & | array_ptr | ) | [protected] |
Definition at line 394 of file pointcloud_screenpoint_nodelet.cpp.
void jsk_pcl_ros::PointcloudScreenpoint::rect_cb | ( | const geometry_msgs::PolygonStamped::ConstPtr & | array_ptr | ) | [protected] |
Definition at line 352 of file pointcloud_screenpoint_nodelet.cpp.
bool jsk_pcl_ros::PointcloudScreenpoint::screenpoint_cb | ( | jsk_recognition_msgs::TransformScreenpoint::Request & | req, |
jsk_recognition_msgs::TransformScreenpoint::Response & | res | ||
) | [protected] |
Definition at line 187 of file pointcloud_screenpoint_nodelet.cpp.
void jsk_pcl_ros::PointcloudScreenpoint::subscribe | ( | ) | [protected, virtual] |
Definition at line 70 of file pointcloud_screenpoint_nodelet.cpp.
void jsk_pcl_ros::PointcloudScreenpoint::sync_point_array_cb | ( | const sensor_msgs::PointCloud2::ConstPtr & | points_ptr, |
const sensor_msgs::PointCloud2::ConstPtr & | pt_arr_ptr | ||
) | [protected] |
Definition at line 432 of file pointcloud_screenpoint_nodelet.cpp.
void jsk_pcl_ros::PointcloudScreenpoint::sync_point_cb | ( | const sensor_msgs::PointCloud2::ConstPtr & | points_ptr, |
const geometry_msgs::PointStamped::ConstPtr & | pt_ptr | ||
) | [protected] |
Definition at line 423 of file pointcloud_screenpoint_nodelet.cpp.
void jsk_pcl_ros::PointcloudScreenpoint::sync_poly_cb | ( | const sensor_msgs::PointCloud2::ConstPtr & | points_ptr, |
const geometry_msgs::PolygonStamped::ConstPtr & | array_ptr | ||
) | [protected] |
Definition at line 441 of file pointcloud_screenpoint_nodelet.cpp.
void jsk_pcl_ros::PointcloudScreenpoint::sync_rect_cb | ( | const sensor_msgs::PointCloud2ConstPtr & | points_ptr, |
const geometry_msgs::PolygonStamped::ConstPtr & | array_ptr | ||
) | [protected] |
Definition at line 450 of file pointcloud_screenpoint_nodelet.cpp.
void jsk_pcl_ros::PointcloudScreenpoint::unsubscribe | ( | ) | [protected, virtual] |
Definition at line 148 of file pointcloud_screenpoint_nodelet.cpp.
bool jsk_pcl_ros::PointcloudScreenpoint::approximate_sync_ [protected] |
Definition at line 152 of file pointcloud_screenpoint.h.
boost::shared_ptr< mf::Synchronizer < PointApproxSyncPolicy > > jsk_pcl_ros::PointcloudScreenpoint::async_point_ [protected] |
Definition at line 138 of file pointcloud_screenpoint.h.
boost::shared_ptr< mf::Synchronizer < PointCloudApproxSyncPolicy > > jsk_pcl_ros::PointcloudScreenpoint::async_point_array_ [protected] |
Definition at line 139 of file pointcloud_screenpoint.h.
boost::shared_ptr< mf::Synchronizer < PolygonApproxSyncPolicy > > jsk_pcl_ros::PointcloudScreenpoint::async_poly_ [protected] |
Definition at line 140 of file pointcloud_screenpoint.h.
boost::shared_ptr< mf::Synchronizer < PolygonApproxSyncPolicy > > jsk_pcl_ros::PointcloudScreenpoint::async_rect_ [protected] |
Definition at line 137 of file pointcloud_screenpoint.h.
int jsk_pcl_ros::PointcloudScreenpoint::crop_size_ [protected] |
Definition at line 155 of file pointcloud_screenpoint.h.
boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::PointcloudScreenpoint::dyn_srv_ [protected] |
Definition at line 127 of file pointcloud_screenpoint.h.
pcl::PointCloud<pcl::PointXYZ> jsk_pcl_ros::PointcloudScreenpoint::latest_cloud_ [protected] |
Definition at line 159 of file pointcloud_screenpoint.h.
Definition at line 158 of file pointcloud_screenpoint.h.
Definition at line 126 of file pointcloud_screenpoint.h.
pcl::NormalEstimation< pcl::PointXYZ, pcl::Normal > jsk_pcl_ros::PointcloudScreenpoint::n3d_ [protected] |
Definition at line 148 of file pointcloud_screenpoint.h.
pcl::search::KdTree< pcl::PointXYZ >::Ptr jsk_pcl_ros::PointcloudScreenpoint::normals_tree_ [protected] |
Definition at line 149 of file pointcloud_screenpoint.h.
mf::Subscriber< sensor_msgs::PointCloud2 > jsk_pcl_ros::PointcloudScreenpoint::point_array_sub_ [protected] |
Definition at line 135 of file pointcloud_screenpoint.h.
mf::Subscriber< geometry_msgs::PointStamped > jsk_pcl_ros::PointcloudScreenpoint::point_sub_ [protected] |
Definition at line 134 of file pointcloud_screenpoint.h.
mf::Subscriber< sensor_msgs::PointCloud2 > jsk_pcl_ros::PointcloudScreenpoint::points_sub_ [protected] |
Definition at line 132 of file pointcloud_screenpoint.h.
mf::Subscriber< geometry_msgs::PolygonStamped > jsk_pcl_ros::PointcloudScreenpoint::poly_sub_ [protected] |
Definition at line 136 of file pointcloud_screenpoint.h.
Definition at line 129 of file pointcloud_screenpoint.h.
Definition at line 128 of file pointcloud_screenpoint.h.
Definition at line 130 of file pointcloud_screenpoint.h.
int jsk_pcl_ros::PointcloudScreenpoint::queue_size_ [protected] |
Definition at line 153 of file pointcloud_screenpoint.h.
mf::Subscriber< geometry_msgs::PolygonStamped > jsk_pcl_ros::PointcloudScreenpoint::rect_sub_ [protected] |
Definition at line 133 of file pointcloud_screenpoint.h.
int jsk_pcl_ros::PointcloudScreenpoint::search_size_ [protected] |
Definition at line 154 of file pointcloud_screenpoint.h.
Definition at line 131 of file pointcloud_screenpoint.h.
boost::shared_ptr< mf::Synchronizer < PointExactSyncPolicy > > jsk_pcl_ros::PointcloudScreenpoint::sync_point_ [protected] |
Definition at line 143 of file pointcloud_screenpoint.h.
boost::shared_ptr< mf::Synchronizer < PointCloudExactSyncPolicy > > jsk_pcl_ros::PointcloudScreenpoint::sync_point_array_ [protected] |
Definition at line 144 of file pointcloud_screenpoint.h.
boost::shared_ptr< mf::Synchronizer < PolygonExactSyncPolicy > > jsk_pcl_ros::PointcloudScreenpoint::sync_poly_ [protected] |
Definition at line 145 of file pointcloud_screenpoint.h.
boost::shared_ptr< mf::Synchronizer < PolygonExactSyncPolicy > > jsk_pcl_ros::PointcloudScreenpoint::sync_rect_ [protected] |
Definition at line 142 of file pointcloud_screenpoint.h.
bool jsk_pcl_ros::PointcloudScreenpoint::synchronization_ [protected] |
Definition at line 152 of file pointcloud_screenpoint.h.
double jsk_pcl_ros::PointcloudScreenpoint::timeout_ [protected] |
Definition at line 156 of file pointcloud_screenpoint.h.