$search
00001 #include <simple_object_capture/common.h> 00002 #include <simple_object_capture/CaptureConfig.h> 00003 #include <dynamic_reconfigure/server.h> 00004 00005 #include <pcl/features/integral_image_normal.h> 00006 #include <pcl/sample_consensus/method_types.h> 00007 #include <pcl/sample_consensus/model_types.h> 00008 #include <pcl/segmentation/sac_segmentation.h> 00009 #include <pcl/visualization/pcl_visualizer.h> 00010 #include <pcl/kdtree/kdtree_flann.h> 00011 #include <pcl/kdtree/kdtree.h> 00012 #include <pcl/surface/mls.h> 00013 00014 #include <ros/ros.h> 00015 #include <message_filters/subscriber.h> 00016 #include <message_filters/time_synchronizer.h> 00017 #include <message_filters/synchronizer.h> 00018 #include <message_filters/sync_policies/approximate_time.h> 00019 #include <sensor_msgs/PointCloud2.h> 00020 #include <sensor_msgs/Image.h> 00021 #include <sensor_msgs/CameraInfo.h> 00022 #include <geometry_msgs/PoseStamped.h> 00023 00024 #include <opencv2/opencv.hpp> 00025 #include <cv_bridge/cv_bridge.h> 00026 00027 #include <boost/filesystem.hpp> 00028 #include <rosbag/bag.h> 00029 00030 //NOTE: THIS FUNCTION REALLY SHOULDN"T BE REUSED 00031 boost::shared_ptr<pcl::PointIndices> getIndexDifferenceAssumingSortedIndex(const pcl::PointIndices& input, int rows, int cols) 00032 { 00033 boost::shared_ptr<pcl::PointIndices> output(new pcl::PointIndices()); 00034 int index = 0; 00035 for(int i = 0; i < (int)input.indices.size() - 1; ++i) 00036 { 00037 if(input.indices[i] >= input.indices[i+1]) 00038 { 00039 assert(false); 00040 printf("THE INDICES ARE NOT SORTED!!!!!!!!!!\n"); 00041 } 00042 } 00043 00044 int input_index = 0; 00045 for(int i = 0; i < rows; ++i) 00046 { 00047 for(int j = 0; j < cols; ++j) 00048 { 00049 if(input_index >= (int)input.indices.size()) 00050 return output; 00051 00052 if(input.indices[input_index] == index) 00053 input_index++; 00054 else 00055 output->indices.push_back(index); 00056 00057 index++; 00058 } 00059 } 00060 00061 return output; 00062 } 00063 00064 00065 const static float CUBE_SIZE = 0.4; 00066 00067 pcl::PointXYZ operator *(const Eigen::Affine3f& t, const pcl::PointXYZ& p) 00068 { 00069 Eigen::Vector3f ep(p.x, p.y, p.z); 00070 ep = t * ep; 00071 return pcl::PointXYZ(ep[0], ep[1], ep[2]); 00072 } 00073 00074 pcl::PointXYZRGB operator *(const Eigen::Affine3f& t, const pcl::PointXYZRGB& p) 00075 { 00076 Eigen::Vector3f ep(p.x, p.y, p.z); 00077 ep = t * ep; 00078 pcl::PointXYZRGB ret; 00079 ret.x = ep[0]; 00080 ret.y = ep[1]; 00081 ret.z = ep[2]; 00082 ret.rgb = p.rgb; 00083 return ret; 00084 } 00085 00086 struct Box 00087 { 00088 Eigen::Vector3f center; 00089 Eigen::Vector3f scale; 00090 Eigen::Affine3f transform; 00091 }; 00092 00093 00094 class GrabBox 00095 { 00096 public: 00097 typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2> ApproxTimeSync; 00098 00099 GrabBox(std::string output_directory) : viz_("Grab"), has_new_cloud_(false), 00100 cloud_(new pcl::PointCloud<pcl::PointXYZRGB>()), 00101 take_snapshot_(false), recompute_plane_(true), redraw_box_(false), output_directory_(output_directory) 00102 { 00103 //make sure that the directory we wish to save in exists 00104 if(!boost::filesystem::exists(output_directory_)) 00105 { 00106 boost::filesystem::create_directory(output_directory_); 00107 } 00108 00109 bag_.open(boost::filesystem::path(output_directory_ / "object_capture.bag").string(), rosbag::bagmode::Write); 00110 00111 // hook up reconfigure callback 00112 dynamic_reconfigure::Server<simple_object_capture::CaptureConfig>::CallbackType reconfigure_cb(boost::bind(&GrabBox::reconfigure, this, _1, _2)); 00113 dyn_conf_server_.setCallback(reconfigure_cb); 00114 00115 ros::NodeHandle camera_in_nh("camera"); 00116 rgb_sub.reset(new message_filters::Subscriber<sensor_msgs::Image>(camera_in_nh, "rgb/image_color", 2)); 00117 depth_sub.reset(new message_filters::Subscriber<sensor_msgs::Image>(camera_in_nh, "depth_registered/image", 2)); 00118 info_sub.reset(new message_filters::Subscriber<sensor_msgs::CameraInfo>(camera_in_nh, "rgb/camera_info", 2)); 00119 cloud_sub.reset(new message_filters::Subscriber<sensor_msgs::PointCloud2>(camera_in_nh, "depth_registered/points", 2)); 00120 00121 sync_.reset(new message_filters::Synchronizer<ApproxTimeSync>(ApproxTimeSync(20), *rgb_sub, *depth_sub, *info_sub, *cloud_sub)); 00122 sync_->registerCallback(boost::bind(&GrabBox::callback, this, _1, _2, _3, _4)); 00123 00124 } 00125 00126 ~GrabBox() 00127 { 00128 printf("Writing bag to disk\n"); 00129 bag_.close(); 00130 } 00131 00132 00133 void reconfigure(simple_object_capture::CaptureConfig &config, uint32_t level) 00134 { 00135 ROS_DEBUG("Calling Dynamic reconfigure"); 00136 00137 boost::mutex::scoped_lock lock(cloud_mutex_); 00138 config_ = config; 00139 redraw_box_ = true; 00140 } 00141 00142 00143 void callback(const sensor_msgs::Image::ConstPtr& rgb, const sensor_msgs::Image::ConstPtr& depth, 00144 const sensor_msgs::CameraInfo::ConstPtr& camera_info, const sensor_msgs::PointCloud2::ConstPtr& cloud) 00145 { 00146 ROS_DEBUG("Camera callback"); 00147 00148 boost::mutex::scoped_lock lock(cloud_mutex_); 00149 00150 //copy over the data for the working thread 00151 pcl::fromROSMsg(*cloud, *cloud_); 00152 rgb_ = rgb; 00153 depth_ = depth; 00154 camera_info_ = camera_info; 00155 has_new_cloud_ = true; 00156 } 00157 00158 template <class PointT> 00159 bool pointInBox(const Box& box, const PointT& pcl_pt) 00160 { 00161 if(isnan(pcl_pt.x) || isnan(pcl_pt.y) || isnan(pcl_pt.z)) 00162 return false; 00163 00164 Eigen::Vector3f pt(pcl_pt.x, pcl_pt.y, pcl_pt.z); 00165 Eigen::Vector3f pt_box = box.transform.inverse() * pt; 00166 00167 return fabs(pt_box[0] - box.center[0]) < box.scale[0] / 2 00168 && fabs(pt_box[1] - box.center[1]) < box.scale[1] / 2 00169 && fabs(pt_box[2] - box.center[2]) < box.scale[2] / 2; 00170 } 00171 00172 void drawCube(const pcl::PointXYZ& c1, const pcl::PointXYZ& c2, const pcl::PointXYZ& c3, const pcl::PointXYZ& c4, 00173 const pcl::PointXYZ& c5, const pcl::PointXYZ& c6, const pcl::PointXYZ& c7, const pcl::PointXYZ& c8, 00174 pcl::visualization::PCLVisualizer& viz) 00175 { 00176 pcl::PointCloud<pcl::PointXYZ> polygon; 00177 polygon.is_dense = true; 00178 polygon.width = 8; 00179 polygon.height = 1; 00180 00181 polygon.points.push_back(c1); 00182 polygon.points.push_back(c2); 00183 polygon.points.push_back(c3); 00184 polygon.points.push_back(c4); 00185 00186 //remove the old box from the viewer 00187 viz.removeShape("poly1"); 00188 viz.removeShape("poly2"); 00189 viz.removeShape("poly3"); 00190 viz.removeShape("poly4"); 00191 00192 viz.addPolygon<pcl::PointXYZ>(polygon.makeShared(), 1.0, 0.0, 0.0, "poly1"); 00193 00194 polygon.points[0] = c4; 00195 polygon.points[1] = c3; 00196 polygon.points[2] = c7; 00197 polygon.points[3] = c8; 00198 viz.addPolygon<pcl::PointXYZ>(polygon.makeShared(), 1.0, 0.0, 0.0, "poly3"); 00199 00200 polygon.points[0] = c1; 00201 polygon.points[1] = c2; 00202 polygon.points[2] = c6; 00203 polygon.points[3] = c5; 00204 viz.addPolygon<pcl::PointXYZ>(polygon.makeShared(), 1.0, 0.0, 0.0, "poly4"); 00205 00206 polygon.points[0] = c5; 00207 polygon.points[1] = c6; 00208 polygon.points[2] = c7; 00209 polygon.points[3] = c8; 00210 viz.addPolygon<pcl::PointXYZ>(polygon.makeShared(), 0.0, 0.0, 1.0, "poly2"); 00211 00212 00213 } 00214 00215 template <class PointT> 00216 pcl::ModelCoefficients findPlaneCoefficients(const typename pcl::PointCloud<PointT>::ConstPtr cloud, const Eigen::Vector3f& axis, double eps_angle, 00217 pcl::PointIndices::Ptr inliers = boost::shared_ptr<pcl::PointIndices>()) 00218 { 00219 if (!inliers) 00220 inliers.reset(new pcl::PointIndices); 00221 // Segments the plane from the cloud 00222 pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients); 00223 pcl::SACSegmentation<PointT> seg; 00224 seg.setMaxIterations(10000); 00225 seg.setOptimizeCoefficients(true); 00226 seg.setModelType(pcl::SACMODEL_PERPENDICULAR_PLANE); 00227 seg.setMethodType(pcl::SAC_RANSAC); 00228 seg.setDistanceThreshold(0.01); 00229 seg.setInputCloud(cloud); 00230 seg.setAxis(axis); 00231 seg.setEpsAngle(eps_angle); 00232 seg.segment(*inliers, *coefficients); 00233 00234 if (inliers->indices.size() == 0) 00235 { 00236 PCL_ERROR("Could not estimate a plane (no inliers found)"); 00237 } 00238 else 00239 { 00240 printf("Plane coefficients: (%f, %f, %f, %f)\n", 00241 coefficients->values[0], coefficients->values[1], 00242 coefficients->values[2], coefficients->values[3]); 00243 } 00244 return *coefficients; 00245 } 00246 00247 void drawBox(const Box& box, pcl::visualization::PCLVisualizer& viz) 00248 { 00249 pcl::PointXYZ c1(box.scale[0]/2 + box.center[0], box.scale[1]/2 + box.center[1], -box.scale[2]/2 + box.center[2]); 00250 pcl::PointXYZ c2(-box.scale[0]/2 + box.center[0], box.scale[1]/2 + box.center[1], -box.scale[2]/2 + box.center[2]); 00251 pcl::PointXYZ c3(-box.scale[0]/2 + box.center[0], box.scale[1]/2 + box.center[1], box.scale[2]/2 + box.center[2]); 00252 pcl::PointXYZ c4(box.scale[0]/2 + box.center[0], box.scale[1]/2 + box.center[1], box.scale[2]/2 + box.center[2]); 00253 00254 pcl::PointXYZ c5(box.scale[0]/2 + box.center[0], -box.scale[1]/2 + box.center[1], -box.scale[2]/2 + box.center[2]); 00255 pcl::PointXYZ c6(-box.scale[0]/2 + box.center[0], -box.scale[1]/2 + box.center[1], -box.scale[2]/2 + box.center[2]); 00256 pcl::PointXYZ c7(-box.scale[0]/2 + box.center[0], -box.scale[1]/2 + box.center[1], box.scale[2]/2 + box.center[2]); 00257 pcl::PointXYZ c8(box.scale[0]/2 + box.center[0], -box.scale[1]/2 + box.center[1], box.scale[2]/2 + box.center[2]); 00258 00259 //make sure to transform the cube into the frame of the camera 00260 c1 = box.transform * c1; 00261 c2 = box.transform * c2; 00262 c3 = box.transform * c3; 00263 c4 = box.transform * c4; 00264 c5 = box.transform * c5; 00265 c6 = box.transform * c6; 00266 c7 = box.transform * c7; 00267 c8 = box.transform * c8; 00268 00269 drawCube(c1, c2, c3, c4, c5, c6, c7, c8, viz); 00270 } 00271 00272 void spin() 00273 { 00274 pcl::PointCloud<pcl::PointXYZRGB>::Ptr viz_cloud; 00275 pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr original_cloud; 00276 ros::Duration update_period(1.0); 00277 float box_angle = 0.0f; 00278 int snapshot_index = 0; 00279 00280 Box box; 00281 //register a callback we'll use to do different operations 00282 viz_.registerKeyboardCallback(boost::bind(&GrabBox::keyPress, this, _1)); 00283 00284 while (!viz_.wasStopped()) 00285 { 00286 ros::spinOnce(); 00287 viz_.spinOnce(); 00288 { 00289 if (has_new_cloud_) 00290 { 00291 // If the GUI locks up intermitantly, this is probably why 00292 { 00293 boost::mutex::scoped_lock lock(cloud_mutex_); 00294 box.scale = Eigen::Vector3f(config_.box_width, config_.box_depth, config_.box_height); 00295 box.center = Eigen::Vector3f(0, 0, box.scale[2]/2); 00296 00297 viz_cloud.reset(new pcl::PointCloud<pcl::PointXYZRGB>(*cloud_)); 00298 original_cloud = cloud_; 00299 } 00300 00301 if(recompute_plane_) 00302 { 00303 object_frame_ = getObjectFrame(viz_cloud); 00304 box.transform = object_frame_ * Eigen::AngleAxisf(box_angle, Eigen::Vector3f(0, 0, 1)); 00305 printf("Drawing the cube with angle %.2f\n", box_angle); 00306 drawBox(box, viz_); 00307 recompute_plane_ = false; 00308 } 00309 00310 if(redraw_box_) 00311 { 00312 drawBox(box, viz_); 00313 redraw_box_ = false; 00314 } 00315 00316 for(size_t i = 0; i < viz_cloud->points.size(); ++i) 00317 { 00318 if(!pointInBox(box, viz_cloud->points[i])) 00319 { 00320 viz_cloud->points[i].r = viz_cloud->points[i].r / 2; 00321 viz_cloud->points[i].g = viz_cloud->points[i].g / 2; 00322 viz_cloud->points[i].b = viz_cloud->points[i].b / 2; 00323 } 00324 else 00325 { 00326 viz_cloud->points[i].g = std::min(viz_cloud->points[i].g + 50, 255); 00327 } 00328 } 00329 00330 if (!viz_.updatePointCloud(viz_cloud, "cloud")) 00331 { 00332 viz_.addPointCloud(viz_cloud, "cloud"); 00333 viz_.resetCameraViewpoint("cloud"); 00334 00335 } 00336 has_new_cloud_ = false; 00337 } 00338 00339 if (take_snapshot_) 00340 { 00341 // Removes the plane from the point cloud 00342 pcl::PointIndices::Ptr inliers(new pcl::PointIndices); 00343 pcl::ModelCoefficients coefficients = findPlaneCoefficients<pcl::PointXYZRGB>(original_cloud, Eigen::Vector3f(0, -cos(M_PI/8), -sin(M_PI/8)), M_PI/4, inliers); 00344 00345 assert(inliers->indices.size() > 0); 00346 pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented (new pcl::PointCloud<pcl::PointXYZRGB>); 00347 boost::shared_ptr<pcl::PointIndices> outliers = getIndexDifferenceAssumingSortedIndex(*inliers, original_cloud->height, original_cloud->width); 00348 extractIndices(original_cloud, outliers, *segmented, true); 00349 00350 // Finds the points inside the box 00351 pcl::PointCloud<pcl::PointXYZRGB>::Ptr box_cloud(new pcl::PointCloud<pcl::PointXYZRGB>()); 00352 box_cloud->is_dense = true; 00353 box_cloud->width = 0; 00354 box_cloud->height = 1; 00355 Eigen::Affine3f sensor_frame = Eigen::Translation3f(original_cloud->sensor_origin_.head<3>()) * original_cloud->sensor_orientation_; 00356 Eigen::Affine3f box_sensor_frame = box.transform.inverse() * sensor_frame; 00357 box_cloud->sensor_origin_.head<3>() = box_sensor_frame.translation(); 00358 box_cloud->sensor_origin_[3] = 0.f; 00359 box_cloud->sensor_orientation_ = (Eigen::Quaternionf)box_sensor_frame.rotation(); 00360 00361 //we want to create a masked image as we find points in the box 00362 cv::Mat_<uint8_t> mask = cv::Mat_<uint8_t>::zeros(original_cloud->height, original_cloud->width); 00363 00364 //get a pointer to the beginning of the uint array 00365 uint8_t* mask_array = mask.ptr<uint8_t>(0); 00366 for(size_t i = 0; i < segmented->points.size(); ++i) 00367 { 00368 if(pointInBox(box, segmented->points[i])) 00369 { 00370 // Transforms the points into the box frame 00371 pcl::PointXYZRGB box_pt = box.transform.inverse() * segmented->points[i]; 00372 box_cloud->points.push_back(box_pt); 00373 box_cloud->width++; 00374 00375 //we want to mark the object as valid 00376 mask_array[outliers->indices[i]] = 255; 00377 } 00378 } 00379 00380 //compute normals for the cloud 00381 pcl::PointCloud<pcl::PointXYZRGB>::Ptr downsampled_cloud = downsample<pcl::PointXYZRGB>(box_cloud, 0.005); 00382 pcl::PointCloud<pcl::Normal>::Ptr normals = compute_surface_normals<pcl::PointXYZRGB, pcl::Normal>(downsampled_cloud, 0.03); 00383 //quickViz<pcl::PointXYZRGB, pcl::Normal>(downsampled_cloud, normals, "cloud + normals"); 00384 00385 //concatenate the cloud for saving 00386 pcl::PointCloud<pcl::PointXYZRGBNormal> combined_box_cloud; 00387 pcl::concatenateFields(*normals, *downsampled_cloud, combined_box_cloud); 00388 00389 00390 char buf[1024]; 00391 snprintf(buf, 1024, "snapshot%02d.pcd", snapshot_index); 00392 ++snapshot_index; 00393 pcl::io::savePCDFile<pcl::PointXYZRGBNormal>(boost::filesystem::path(output_directory_ / buf).string(), combined_box_cloud); 00394 00395 box_angle += config_.angle_increment * M_PI / 180; 00396 if (box_angle > 2 * M_PI) 00397 box_angle -= 2 * M_PI; 00398 box.transform = object_frame_ * Eigen::AngleAxisf(box_angle, Eigen::Vector3f(0, 0, 1)); 00399 printf("Re-drawing the cube with angle %.2f\n", box_angle); 00400 drawBox(box, viz_); 00401 00402 //we'll also make sure to write the necessary topics 00403 bag_.write("camera/depth/camera_info", ros::Time::now(), camera_info_); 00404 bag_.write("camera/depth/image", ros::Time::now(), depth_); 00405 bag_.write("camera/rgb/camera_info", ros::Time::now(), camera_info_); 00406 bag_.write("camera/rgb/image_color", ros::Time::now(), rgb_); 00407 00408 //Publish Mask 00409 cv_bridge::CvImage img_bridge; 00410 img_bridge.encoding = "mono8"; 00411 img_bridge.header = camera_info_->header; 00412 img_bridge.image = mask; 00413 00414 boost::shared_ptr<sensor_msgs::Image> img_msg = img_bridge.toImageMsg(); 00415 bag_.write("camera/mask", ros::Time::now(), img_msg); 00416 00417 //Publish Pose 00418 geometry_msgs::PoseStamped pose_msg; 00419 pose_msg.header = camera_info_->header; 00420 pose_msg.pose.position.x = box.transform.translation()[0]; 00421 pose_msg.pose.position.y = box.transform.translation()[1]; 00422 pose_msg.pose.position.z = box.transform.translation()[2]; 00423 00424 Eigen::Quaternionf q(box.transform.rotation()); 00425 pose_msg.pose.orientation.w = q.w(); 00426 pose_msg.pose.orientation.x = q.x(); 00427 pose_msg.pose.orientation.y = q.y(); 00428 pose_msg.pose.orientation.z = q.z(); 00429 00430 bag_.write("camera/pose", ros::Time::now(), pose_msg); 00431 00432 take_snapshot_ = false; 00433 } 00434 } 00435 } 00436 } 00437 00438 Eigen::Affine3f getObjectFrame(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr cloud) 00439 { 00440 //find a plane 00441 pcl::ModelCoefficients coefficients = findPlaneCoefficients<pcl::PointXYZRGB>(cloud, Eigen::Vector3f(0, -cos(M_PI/8), -sin(M_PI/8)), M_PI/4); 00442 00443 //we want to find the intersection of the z-axis with the plane. We'll use that as the center point for our cube 00444 double a = coefficients.values[0]; 00445 double b = coefficients.values[1]; 00446 double c = coefficients.values[2]; 00447 double d = coefficients.values[3]; 00448 00449 double u = d / (c * -1.0); 00450 00451 Eigen::Vector3f r = u * Eigen::Vector3f(0.0, 0.0, 1.0); 00452 printf("Intersection point: (%.2f, %.2f, %.2f)", r[0], r[1], r[2]); 00453 00454 Eigen::Vector3f proj(0.0, 0.0, 0.6); 00455 Eigen::Vector3f normal(a, b, c); 00456 00457 if(normal[2] > 0) 00458 normal = -1.0 * normal; 00459 00460 normal.normalize(); 00461 00462 Eigen::Vector3f plane_pt = proj - (proj - r).dot(normal) * normal; 00463 printf("Plane point: (%.2f, %.2f, %.2f)", plane_pt[0], plane_pt[1], plane_pt[2]); 00464 00465 //viz_.addSphere(pcl::PointXYZ(r[0], r[1], r[2]), 0.05, "sphere1"); 00466 //viz_.addSphere(pcl::PointXYZ(plane_pt[0], plane_pt[1], plane_pt[2]), 0.05, "sphere2"); 00467 00468 float rot_angle = atan2(normal[1], normal[2]); 00469 Eigen::Affine3f rot(Eigen::AngleAxisf(rot_angle, Eigen::Vector3f(-1, 0, 0))); 00470 00471 printf("Angle of rotation: %.2f\n", rot_angle); 00472 00473 Eigen::Translation3f trans(plane_pt); 00474 00475 return trans * rot; 00476 } 00477 00478 void keyPress(const pcl::visualization::KeyboardEvent& e) 00479 { 00480 if(e.keyUp()) 00481 { 00482 switch (e.getKeyCode()) 00483 { 00484 case 32: // SPACE 00485 take_snapshot_ = true; 00486 break; 00487 case 97: //a 00488 recompute_plane_ = true; 00489 break; 00490 } 00491 printf("Keycode %u\n", e.getKeyCode()); 00492 } 00493 } 00494 00495 dynamic_reconfigure::Server<simple_object_capture::CaptureConfig> dyn_conf_server_; 00496 simple_object_capture::CaptureConfig config_; 00497 00498 pcl::visualization::PCLVisualizer viz_; 00499 boost::shared_ptr<message_filters::Synchronizer<ApproxTimeSync> > sync_; 00500 boost::shared_ptr<message_filters::Subscriber<sensor_msgs::Image> > rgb_sub, depth_sub; 00501 boost::shared_ptr<message_filters::Subscriber<sensor_msgs::CameraInfo> > info_sub; 00502 boost::shared_ptr<message_filters::Subscriber<sensor_msgs::PointCloud2> > cloud_sub; 00503 00504 boost::mutex cloud_mutex_; 00505 bool has_new_cloud_; 00506 00507 boost::shared_ptr<pcl::PointCloud<pcl::PointXYZRGB> > cloud_; 00508 boost::shared_ptr<const sensor_msgs::Image> rgb_, depth_; 00509 boost::shared_ptr<const sensor_msgs::CameraInfo> camera_info_; 00510 00511 Eigen::Affine3f object_frame_; 00512 bool take_snapshot_, recompute_plane_, redraw_box_; 00513 00514 boost::filesystem::path output_directory_; 00515 00516 rosbag::Bag bag_; 00517 }; 00518 00519 // NEXT: keypress to trigger saving a point cloud 00520 00521 int main(int argc, char** argv) 00522 { 00523 ros::init(argc, argv, "simple_object_capture"); 00524 00525 std::string output_dir = "."; 00526 if(argc > 1) 00527 output_dir = argv[1]; 00528 00529 GrabBox gb(output_dir); 00530 gb.spin(); 00531 return 0; 00532 }