find_grasps.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 
00003 #include <agile_grasp/Grasp.h>
00004 #include <agile_grasp/grasp_localizer.h>
00005 
00006 
00007 const std::string CLOUD_TOPIC = "input_cloud";
00008 const std::string CLOUD_FRAME = "camera_rgb_optical_frame";
00009 const std::string SVM_FILE_NAME = "/home/baxter/svm";
00010 const int NUM_THREADS = 1;
00011 const int NUM_SAMPLES = 1000;
00012 const int NUM_CLOUDS = 2;
00013 const double FINGER_WIDTH = 0.01;
00014 const double HAND_OUTER_DIAMETER = 0.09;
00015 const double HAND_DEPTH = 0.06;
00016 const double INIT_BITE = 0.01;
00017 const double HAND_HEIGHT = 0.02;
00018 const double WORKSPACE[6] = {0.65, 0.9, -0.2, 0.07, -0.3, 1.0};
00019 const int MIN_HANDLE_INLIERS = 3;
00020 const int CLOUD_TYPE = 0;
00021 const std::string CLOUD_TYPES[2] = {"sensor_msgs/PointCloud2", "grasp_affordances/CloudSized"};
00022 
00023 
00024 int main(int argc, char** argv)
00025 {
00026   // initialize ROS
00027   ros::init(argc, argv, "find_grasps");
00028   ros::NodeHandle node("~");
00029   
00030   GraspLocalizer::Parameters params;
00031   
00032   // camera transforms (poses)
00033   Eigen::Matrix4d base_tf, sqrt_tf;
00034   base_tf <<  0, 0.445417, 0.895323, 0.215, 
00035               1, 0, 0, -0.015, 
00036               0, 0.895323, -0.445417, 0.23, 
00037               0, 0, 0, 1;
00038   sqrt_tf <<  0.9366, -0.0162, 0.3500, -0.2863, 
00039               0.0151, 0.9999, 0.0058, 0.0058, 
00040               -0.3501, -0.0002, 0.9367, 0.0554, 
00041               0, 0, 0, 1;
00042   params.cam_tf_left_ = base_tf * sqrt_tf.inverse();
00043   params.cam_tf_right_ = base_tf * sqrt_tf;
00044 
00045   // read ROS parameters
00046   std::string cloud_topic;
00047   std::string cloud_frame;
00048   std::string svm_file_name;
00049   std::vector<double> workspace;
00050   std::vector<double> camera_pose;
00051   int cloud_type;
00052   node.param("cloud_topic", cloud_topic, CLOUD_TOPIC);
00053   node.param("cloud_frame", cloud_frame, CLOUD_FRAME);
00054   node.param("cloud_type", cloud_type, CLOUD_TYPE);
00055   node.param("svm_file_name", svm_file_name, SVM_FILE_NAME);
00056   node.param("num_threads", params.num_threads_, NUM_THREADS);
00057   node.param("num_samples", params.num_samples_, NUM_SAMPLES); 
00058   node.param("num_clouds", params.num_clouds_, NUM_CLOUDS);
00059   node.param("finger_width", params.finger_width_, FINGER_WIDTH);
00060   node.param("hand_outer_diameter", params.hand_outer_diameter_, HAND_OUTER_DIAMETER);
00061   node.param("hand_depth", params.hand_depth_, HAND_DEPTH);
00062   node.param("init_bite", params.init_bite_, INIT_BITE);
00063   node.param("hand_height", params.hand_height_, HAND_HEIGHT);
00064   node.param("min_inliers", params.min_inliers_, MIN_HANDLE_INLIERS);
00065   node.getParam("workspace", workspace);
00066   node.getParam("camera_pose", camera_pose);
00067   node.param("plots", params.plots_hands_, false);
00068 
00069   Eigen::Matrix4d R;
00070   for (int i=0; i < R.rows(); i++)
00071     R.row(i) << camera_pose[i*R.cols()], camera_pose[i*R.cols() + 1], camera_pose[i*R.cols() + 2], camera_pose[i*R.cols() + 3];  
00072     
00073   Eigen::VectorXd ws(6);
00074   ws << workspace[0], workspace[1], workspace[2], workspace[3], workspace[4], workspace[5];
00075   params.workspace_ = ws;
00076   
00077   std::cout << "-- Parameters --\n";
00078   std::cout << " Input\n";
00079   std::cout << "  cloud_topic: " << cloud_topic << "\n";
00080   std::cout << "  cloud_frame: " << cloud_frame << "\n";
00081   std::cout << "  cloud_type: " << CLOUD_TYPES[cloud_type] << "\n";
00082   std::cout << " Hand Search\n";  
00083   std::cout << "  workspace: " << ws.transpose() << "\n";
00084   std::cout << "  num_samples: " << params.num_samples_ << "\n";
00085   std::cout << "  num_threads: " << params.num_threads_ << "\n";
00086   std::cout << "  num_clouds: " << params.num_clouds_ << "\n";
00087   std::cout << "  plots: " << params.plots_hands_ << "\n";
00088   std::cout << "  camera pose:\n" << R << std::endl;
00089   std::cout << " Robot Hand Model\n";
00090   std::cout << "  finger_width: " << params.finger_width_ << "\n";
00091   std::cout << "  hand_outer_diameter: " << params.hand_outer_diameter_ << "\n";
00092   std::cout << "  hand_depth: " << params.finger_width_ << "\n";
00093   std::cout << "  init_bite: " << params.finger_width_ << "\n";
00094   std::cout << "  hand_height: " << params.finger_width_ << "\n";
00095   std::cout << " Antipodal Grasps Prediction\n";
00096   std::cout << "  svm_file_name: " << svm_file_name << "\n";
00097   std::cout << " Handle Search\n";
00098   std::cout << "  min_inliers: " << params.min_inliers_ << "\n";
00099   
00100   GraspLocalizer loc(node, cloud_topic, cloud_frame, cloud_type, svm_file_name, params);
00101   loc.localizeGrasps();
00102   
00103         return 0;
00104 }


agile_grasp
Author(s):
autogenerated on Thu Aug 27 2015 12:01:28