#include <snapit.h>

| Public Types | |
| typedef message_filters::sync_policies::ExactTime< jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > | SyncPolygonPolicy | 
| Public Member Functions | |
| SnapIt () | |
| virtual | ~SnapIt () | 
| Protected Member Functions | |
| virtual geometry_msgs::PoseStamped | alignPose (Eigen::Affine3f &pose, jsk_recognition_utils::ConvexPolygon::Ptr convex) | 
| virtual void | convexAlignCallback (const geometry_msgs::PoseStamped::ConstPtr &pose_msg) | 
| virtual void | convexAlignPolygonCallback (const geometry_msgs::PolygonStamped::ConstPtr &poly_msg) | 
| virtual std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > | createConvexes (const std::string &frame_id, const ros::Time &stamp, jsk_recognition_msgs::PolygonArray::ConstPtr polygons) | 
| virtual int | findNearestConvex (const Eigen::Vector3f &pose_point, const std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes) | 
| virtual bool | footstepAlignServiceCallback (jsk_recognition_msgs::SnapFootstep::Request &req, jsk_recognition_msgs::SnapFootstep::Response &res) | 
| virtual void | onInit () | 
| virtual void | polygonAlignCallback (const geometry_msgs::PoseStamped::ConstPtr &pose_msg) | 
| virtual void | polygonCallback (const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg) | 
| virtual void | subscribe () | 
| virtual void | unsubscribe () | 
| Protected Attributes | |
| ros::ServiceServer | align_footstep_srv_ | 
| ros::Subscriber | convex_align_polygon_sub_ | 
| ros::Subscriber | convex_align_sub_ | 
| ros::Publisher | convex_aligned_pose_array_marker_pub_ | 
| ros::Publisher | convex_aligned_pose_array_pub_ | 
| ros::Publisher | convex_aligned_pub_ | 
| boost::mutex | mutex_ | 
| ros::Subscriber | polygon_align_sub_ | 
| ros::Publisher | polygon_aligned_pub_ | 
| jsk_recognition_msgs::PolygonArray::ConstPtr | polygons_ | 
| message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > | sub_coefficients_ | 
| message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > | sub_polygons_ | 
| boost::shared_ptr< message_filters::Synchronizer< SyncPolygonPolicy > > | sync_polygon_ | 
| tf::TransformListener * | tf_listener_ | 
| bool | use_service_ | 
| typedef message_filters::sync_policies::ExactTime< jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray> jsk_pcl_ros::SnapIt::SyncPolygonPolicy | 
| 
 | virtual | 
Definition at line 110 of file snapit_nodelet.cpp.
| 
 | protectedvirtual | 
Definition at line 320 of file snapit_nodelet.cpp.
| 
 | protectedvirtual | 
Definition at line 290 of file snapit_nodelet.cpp.
| 
 | protectedvirtual | 
Definition at line 235 of file snapit_nodelet.cpp.
| 
 | protectedvirtual | 
Definition at line 347 of file snapit_nodelet.cpp.
| 
 | protectedvirtual | 
Definition at line 269 of file snapit_nodelet.cpp.
| 
 | protectedvirtual | 
Definition at line 198 of file snapit_nodelet.cpp.
| 
 | protectedvirtual | 
Definition at line 91 of file snapit_nodelet.cpp.
| 
 | protectedvirtual | 
Definition at line 159 of file snapit_nodelet.cpp.
| 
 | protectedvirtual | 
Definition at line 150 of file snapit_nodelet.cpp.
| 
 | protectedvirtual | 
Definition at line 121 of file snapit_nodelet.cpp.
| 
 | protectedvirtual | 
Definition at line 139 of file snapit_nodelet.cpp.
| 
 | protected | 
| 
 | protected | 
| 
 | protected | 
| 
 | protected | 
| 
 | protected | 
| 
 | protected | 
| 
 | protected | 
| 
 | protected | 
| 
 | protected | 
| 
 | protected | 
| 
 | protected | 
| 
 | protected | 
| 
 | protected | 
| 
 | protected |