Public Types | |
| typedef message_filters::sync_policies::ApproximateTime < sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > | ApproxTimeSync |
Public Member Functions | |
| void | callback (const sensor_msgs::Image::ConstPtr &rgb, const sensor_msgs::Image::ConstPtr &depth, const sensor_msgs::CameraInfo::ConstPtr &camera_info, const sensor_msgs::PointCloud2::ConstPtr &cloud) |
| void | drawBox (const Box &box, pcl::visualization::PCLVisualizer &viz) |
| void | drawCube (const pcl::PointXYZ &c1, const pcl::PointXYZ &c2, const pcl::PointXYZ &c3, const pcl::PointXYZ &c4, const pcl::PointXYZ &c5, const pcl::PointXYZ &c6, const pcl::PointXYZ &c7, const pcl::PointXYZ &c8, pcl::visualization::PCLVisualizer &viz) |
| template<class PointT > | |
| pcl::ModelCoefficients | findPlaneCoefficients (const typename pcl::PointCloud< PointT >::ConstPtr cloud, const Eigen::Vector3f &axis, double eps_angle, pcl::PointIndices::Ptr inliers=boost::shared_ptr< pcl::PointIndices >()) |
| Eigen::Affine3f | getObjectFrame (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr cloud) |
| GrabBox (std::string output_directory) | |
| void | keyPress (const pcl::visualization::KeyboardEvent &e) |
| template<class PointT > | |
| bool | pointInBox (const Box &box, const PointT &pcl_pt) |
| void | reconfigure (simple_object_capture::CaptureConfig &config, uint32_t level) |
| void | spin () |
| ~GrabBox () | |
Public Attributes | |
| rosbag::Bag | bag_ |
| boost::shared_ptr< const sensor_msgs::CameraInfo > | camera_info_ |
| boost::shared_ptr < pcl::PointCloud < pcl::PointXYZRGB > > | cloud_ |
| boost::mutex | cloud_mutex_ |
| boost::shared_ptr < message_filters::Subscriber < sensor_msgs::PointCloud2 > > | cloud_sub |
| simple_object_capture::CaptureConfig | config_ |
| boost::shared_ptr< const sensor_msgs::Image > | depth_ |
| boost::shared_ptr < message_filters::Subscriber < sensor_msgs::Image > > | depth_sub |
| dynamic_reconfigure::Server < simple_object_capture::CaptureConfig > | dyn_conf_server_ |
| bool | has_new_cloud_ |
| boost::shared_ptr < message_filters::Subscriber < sensor_msgs::CameraInfo > > | info_sub |
| Eigen::Affine3f | object_frame_ |
| boost::filesystem::path | output_directory_ |
| bool | recompute_plane_ |
| bool | redraw_box_ |
| boost::shared_ptr< const sensor_msgs::Image > | rgb_ |
| boost::shared_ptr < message_filters::Subscriber < sensor_msgs::Image > > | rgb_sub |
| boost::shared_ptr < message_filters::Synchronizer < ApproxTimeSync > > | sync_ |
| bool | take_snapshot_ |
| pcl::visualization::PCLVisualizer | viz_ |
Definition at line 94 of file grab_box.cpp.
| typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2> GrabBox::ApproxTimeSync |
Definition at line 97 of file grab_box.cpp.
| GrabBox::GrabBox | ( | std::string | output_directory | ) | [inline] |
Definition at line 99 of file grab_box.cpp.
| GrabBox::~GrabBox | ( | ) | [inline] |
Definition at line 126 of file grab_box.cpp.
| void GrabBox::callback | ( | const sensor_msgs::Image::ConstPtr & | rgb, |
| const sensor_msgs::Image::ConstPtr & | depth, | ||
| const sensor_msgs::CameraInfo::ConstPtr & | camera_info, | ||
| const sensor_msgs::PointCloud2::ConstPtr & | cloud | ||
| ) | [inline] |
Definition at line 143 of file grab_box.cpp.
| void GrabBox::drawBox | ( | const Box & | box, |
| pcl::visualization::PCLVisualizer & | viz | ||
| ) | [inline] |
Definition at line 247 of file grab_box.cpp.
| void GrabBox::drawCube | ( | const pcl::PointXYZ & | c1, |
| const pcl::PointXYZ & | c2, | ||
| const pcl::PointXYZ & | c3, | ||
| const pcl::PointXYZ & | c4, | ||
| const pcl::PointXYZ & | c5, | ||
| const pcl::PointXYZ & | c6, | ||
| const pcl::PointXYZ & | c7, | ||
| const pcl::PointXYZ & | c8, | ||
| pcl::visualization::PCLVisualizer & | viz | ||
| ) | [inline] |
Definition at line 172 of file grab_box.cpp.
| pcl::ModelCoefficients GrabBox::findPlaneCoefficients | ( | const typename pcl::PointCloud< PointT >::ConstPtr | cloud, |
| const Eigen::Vector3f & | axis, | ||
| double | eps_angle, | ||
| pcl::PointIndices::Ptr | inliers = boost::shared_ptr<pcl::PointIndices>() |
||
| ) | [inline] |
Definition at line 216 of file grab_box.cpp.
| Eigen::Affine3f GrabBox::getObjectFrame | ( | const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr | cloud | ) | [inline] |
Definition at line 438 of file grab_box.cpp.
| void GrabBox::keyPress | ( | const pcl::visualization::KeyboardEvent & | e | ) | [inline] |
Definition at line 478 of file grab_box.cpp.
| bool GrabBox::pointInBox | ( | const Box & | box, |
| const PointT & | pcl_pt | ||
| ) | [inline] |
Definition at line 159 of file grab_box.cpp.
| void GrabBox::reconfigure | ( | simple_object_capture::CaptureConfig & | config, |
| uint32_t | level | ||
| ) | [inline] |
Definition at line 133 of file grab_box.cpp.
| void GrabBox::spin | ( | ) | [inline] |
Definition at line 272 of file grab_box.cpp.
Definition at line 516 of file grab_box.cpp.
| boost::shared_ptr<const sensor_msgs::CameraInfo> GrabBox::camera_info_ |
Definition at line 509 of file grab_box.cpp.
| boost::shared_ptr<pcl::PointCloud<pcl::PointXYZRGB> > GrabBox::cloud_ |
Definition at line 507 of file grab_box.cpp.
| boost::mutex GrabBox::cloud_mutex_ |
Definition at line 504 of file grab_box.cpp.
| boost::shared_ptr<message_filters::Subscriber<sensor_msgs::PointCloud2> > GrabBox::cloud_sub |
Definition at line 502 of file grab_box.cpp.
| simple_object_capture::CaptureConfig GrabBox::config_ |
Definition at line 496 of file grab_box.cpp.
| boost::shared_ptr<const sensor_msgs::Image> GrabBox::depth_ |
Definition at line 508 of file grab_box.cpp.
| boost::shared_ptr<message_filters::Subscriber<sensor_msgs::Image> > GrabBox::depth_sub |
Definition at line 500 of file grab_box.cpp.
| dynamic_reconfigure::Server<simple_object_capture::CaptureConfig> GrabBox::dyn_conf_server_ |
Definition at line 495 of file grab_box.cpp.
Definition at line 505 of file grab_box.cpp.
| boost::shared_ptr<message_filters::Subscriber<sensor_msgs::CameraInfo> > GrabBox::info_sub |
Definition at line 501 of file grab_box.cpp.
| Eigen::Affine3f GrabBox::object_frame_ |
Definition at line 511 of file grab_box.cpp.
| boost::filesystem::path GrabBox::output_directory_ |
Definition at line 514 of file grab_box.cpp.
Definition at line 512 of file grab_box.cpp.
| bool GrabBox::redraw_box_ |
Definition at line 512 of file grab_box.cpp.
| boost::shared_ptr<const sensor_msgs::Image> GrabBox::rgb_ |
Definition at line 508 of file grab_box.cpp.
| boost::shared_ptr<message_filters::Subscriber<sensor_msgs::Image> > GrabBox::rgb_sub |
Definition at line 500 of file grab_box.cpp.
| boost::shared_ptr<message_filters::Synchronizer<ApproxTimeSync> > GrabBox::sync_ |
Definition at line 499 of file grab_box.cpp.
Definition at line 512 of file grab_box.cpp.
| pcl::visualization::PCLVisualizer GrabBox::viz_ |
Definition at line 498 of file grab_box.cpp.