00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048 #include <stdio.h>
00049 #include <stdlib.h>
00050 #include <sstream>
00051 #include <iostream>
00052 #include <iomanip>
00053 #include <unistd.h>
00054 #include <math.h>
00055 #include <time.h>
00056
00057 #include <tf/tf.h>
00058 #include <tf/transform_broadcaster.h>
00059 #include <tf/transform_datatypes.h>
00060 #include <tf/transform_listener.h>
00061 #include "tf/LinearMath/Transform.h"
00062
00063 #include <pcl_ros/point_cloud.h>
00064 #include "pcl_ros/transforms.h"
00065 #include "pcl_ros/publisher.h"
00066 #include "pcl/io/io.h"
00067 #include "pcl/point_types.h"
00068 #include "pcl/point_cloud.h"
00069 #include "pcl/registration/ia_ransac.h"
00070 #include <pcl/point_types.h>
00071 #include <pcl/io/pcd_io.h>
00072
00073 #include <ros/ros.h>
00074 #include "ros/ros.h"
00075 #include "ros/package.h"
00076 #include "std_msgs/String.h"
00077 #include "sensor_msgs/PointCloud2.h"
00078 #include "geometry_msgs/Vector3.h"
00079 #include <visualization_msgs/Marker.h>
00080 #include <visualization_msgs/MarkerArray.h>
00081
00082 #include <actionlib/server/simple_action_server.h>
00083 #include <haf_grasping/CalcGraspPointsServerAction.h>
00084
00085
00086 #include <CIntImage_to_Featurevec.h>
00087
00088
00089 #define HEIGHT 56
00090 #define WIDTH 56
00091 #define PI 3.141592653
00092 #define ROLL_STEPS_DEGREE 15 //define in degree how different the tested rolls should be
00093 #define TILT_STEPS_DEGREE 40 //define in degree the angle for one tilt step
00094 #define TILT_STEPS 1 //define the number of tilt steps [not used anymore]
00095
00096
00097
00098 #define ROLL_MAX_DEGREE 190//190
00099
00100
00101 using namespace std;
00102 using namespace cv;
00103
00104 class CCalc_Grasppoints
00105 {
00106 protected:
00107
00108 ros::NodeHandle nh_;
00109
00110 actionlib::SimpleActionServer<haf_grasping::CalcGraspPointsServerAction> as_;
00111 std::string action_name_;
00112
00113 haf_grasping::CalcGraspPointsServerFeedback feedback_;
00114 haf_grasping::CalcGraspPointsServerResult result_;
00115
00116
00117 public:
00118 ros::Subscriber box_position_sub;
00119 ros::Subscriber pc_sub;
00120 ros::Publisher pubInputPCROS;
00121 ros::Publisher pubTransformedPCROS;
00122 ros::Publisher pubGraspPoints;
00123 ros::Publisher pubGraspPointsEval;
00124 ros::Publisher vis_pub;
00125 ros::Publisher vis_pub_ma;
00126 ros::Publisher vis_pub_ma_params;
00127 geometry_msgs::Point graspsearchcenter;
00128 float boxrot_angle_init;
00129 int grasp_search_area_size_x_dir;
00130 int grasp_search_area_size_y_dir;
00131 geometry_msgs::Vector3 approach_vector;
00132 float max_duration_for_grasp_calc;
00133 float heightsgridroll[ROLL_MAX_DEGREE/ROLL_STEPS_DEGREE][TILT_STEPS][HEIGHT][WIDTH];
00134 float integralimageroll[ROLL_MAX_DEGREE/ROLL_STEPS_DEGREE][TILT_STEPS][HEIGHT+1][WIDTH+1];
00135 bool point_inside_box_grid[ROLL_MAX_DEGREE/ROLL_STEPS_DEGREE][TILT_STEPS][HEIGHT][WIDTH];
00136 string outputpath_full;
00137 bool return_only_best_gp;
00138 string base_frame_id;
00139 int graspval_th;
00140 int graspval_top;
00141 int graspval_max_diff_for_pub;
00142
00143 int id_row_top_overall;
00144 int id_col_top_overall;
00145 int nr_roll_top_overall;
00146 int nr_tilt_top_overall;
00147 int topval_gp_overall;
00148 int marker_cnt;
00149 haf_grasping::GraspOutput gp_result;
00150 tf::TransformListener tf_listener;
00151 bool visualization;
00152 bool print_heights_bool;
00153 Eigen::Matrix4f av_trans_mat;
00154 float trans_z_after_pc_transform;
00155 tf::Quaternion quat_tf_to_tf_help;
00156 string feature_file_path;
00157 string range_file_path;
00158 string svmmodel_file_path;
00159 int nr_features_without_shaf;
00160 int gripper_opening_width;
00161
00162
00163 void print_heights(int nr_roll, int nr_tilt);
00164 void read_pc_cb(const haf_grasping::CalcGraspPointsServerGoalConstPtr &goal);
00165 void loop_control(pcl::PointCloud<pcl::PointXYZ> pcl_cloud_in);
00166 void generate_grid(int roll, int tilt, pcl::PointCloud<pcl::PointXYZ> pcl_cloud_in);
00167 void publish_transformed_pcl_cloud(int roll, int tilt, pcl::PointCloud<pcl::PointXYZ> pcl_cloud_in);
00168 void calc_intimage(int roll, int tilt);
00169 void calc_featurevectors(int roll, int tilt);
00170 void pnt_in_box(int nr_roll, int nr_tilt);
00171 void predict_bestgp_withsvm(bool svm_with_probability=false);
00172 void show_predicted_gps(int nr_roll, int tilt, bool svm_with_probability=false);
00173 void transform_gp_in_wcs_and_publish(int id_row_top_all, int id_col_top_all,int nr_roll_top_all, int nr_tilt_top_all, int scaled_gp_eval);
00174 void publish_grasp_grid(int nr_roll, int tilt, float graspsgrid[][WIDTH], int gripperwidth);
00175 void gp_to_marker(visualization_msgs::Marker *marker, float x, float y, float z, float green, bool pubmarker, int gripperwidth, int nr_roll, bool pub_grip_open_dir, bool pub_grid);
00176 void grasp_area_to_marker(visualization_msgs::Marker *marker, float x, float y, float z, int gripperwidth, int nr_roll, int param_id, bool top_grasp);
00177
00178 CCalc_Grasppoints(string name) :
00179 as_(nh_, name, boost::bind(&CCalc_Grasppoints::read_pc_cb, this, _1), false),
00180 action_name_(name)
00181 {
00182 this->pubGraspPointsEval = nh_.advertise<std_msgs::String>("/haf_grasping/grasp_hypothesis_with_eval", 1);
00183 this->vis_pub = nh_.advertise<visualization_msgs::Marker>( "visualization_marker", 1 );
00184 this->vis_pub_ma = nh_.advertise<visualization_msgs::MarkerArray>( "visualization_marker_array", 1 );
00185 this->vis_pub_ma_params = nh_.advertise<visualization_msgs::MarkerArray>( "visualization_marker_array_grasp_params", 1 );
00186 this->pubInputPCROS = nh_.advertise<sensor_msgs::PointCloud2>( "/haf_grasping/calc_gp_as_inputpcROS", 1);
00187 this->pubTransformedPCROS = nh_.advertise<sensor_msgs::PointCloud2>( "/haf_grasping/transformed_point_cloud",1);
00188 this->graspsearchcenter.x = 0;
00189 this->graspsearchcenter.y = 0;
00190 this->graspsearchcenter.z = 0;
00191 this->grasp_search_area_size_x_dir = 32;
00192 this->grasp_search_area_size_y_dir = 44;
00193 this->approach_vector.x = 0;
00194 this->approach_vector.y = 0;
00195 this->approach_vector.z = 1;
00196 this->max_duration_for_grasp_calc = 50;
00197 outputpath_full = "/tmp/features.txt";
00198 this->return_only_best_gp = false;
00199 graspval_th = 70;
00200 graspval_top = 119;
00201 graspval_max_diff_for_pub = 80;
00202 id_row_top_overall = -1;
00203 id_col_top_overall = -1;
00204 nr_roll_top_overall = -1;
00205 nr_tilt_top_overall = -1;
00206 topval_gp_overall = -1000;
00207 marker_cnt = 0;
00208 this->visualization = true;
00209 this->print_heights_bool = false;
00210 this->av_trans_mat = Eigen::Matrix4f::Identity();;
00211 this->trans_z_after_pc_transform = 0.15;
00212 this->gripper_opening_width = 1;
00213
00214
00215 this->feature_file_path = "";
00216 nh_.param("feature_file_path", this->feature_file_path, this->feature_file_path);
00217 this->range_file_path = "";
00218 nh_.param("range_file_path", this->range_file_path, this->range_file_path);
00219 this->svmmodel_file_path = "";
00220 nh_.param("svmmodel_file_path", this->svmmodel_file_path, this->svmmodel_file_path);
00221 this->nr_features_without_shaf = 302;
00222 nh_.param("nr_features_without_shaf", this->nr_features_without_shaf, this->nr_features_without_shaf);
00223
00224 as_.start();
00225 }
00226 };
00227
00228
00229
00230
00231 void CCalc_Grasppoints::print_heights(int nr_roll, int nr_tilt)
00232 {
00233
00234 cout << "\n CCalc_Grasppoints::print_heights: print heights matrix for roll number : " << nr_roll << "\t and tilt nr: "<< nr_tilt << endl;
00235 for (int i = 0; i < HEIGHT; i++){
00236 for (int j = 0; j < WIDTH; j++){
00237 cout << setw(5) << setprecision(2) << this->heightsgridroll[nr_roll][nr_tilt][HEIGHT-i-1][WIDTH-j-1];
00238 }
00239 cout << "\n";
00240 }
00241 }
00242
00243
00244
00245
00246
00247 void CCalc_Grasppoints::read_pc_cb(const haf_grasping::CalcGraspPointsServerGoalConstPtr &goal)
00248 {
00249 ROS_INFO("\n ==> calc_grasppoints_action_server.cpp: read_pc_cb() --> GRASP GOAL RECEIVED (incl. point cloud)");
00250
00251 pcl::PointCloud<pcl::PointXYZ> pcl_cloud_in;
00252 pcl::PointCloud<pcl::PointXYZ> pc_new_cs;
00253
00254
00255 this->graspsearchcenter.x = goal->graspinput.grasp_area_center.x;
00256 this->graspsearchcenter.y = goal->graspinput.grasp_area_center.y;
00257 this->graspsearchcenter.z = goal->graspinput.grasp_area_center.z;
00258
00259 cout << "************************************************************************************************************" << endl;
00260 cout << " --> SET NEW GRASP SEARCH CENTER: [x,y,z] = [" << this->graspsearchcenter.x << "," << this->graspsearchcenter.y << "," << this->graspsearchcenter.z << "]" << endl;
00261
00262
00263 this->grasp_search_area_size_x_dir = goal->graspinput.grasp_area_length_x;
00264 this->grasp_search_area_size_y_dir = goal->graspinput.grasp_area_length_y;
00265
00266
00267 float vector_length = sqrt(goal->graspinput.approach_vector.x*goal->graspinput.approach_vector.x+goal->graspinput.approach_vector.y*goal->graspinput.approach_vector.y+goal->graspinput.approach_vector.z*goal->graspinput.approach_vector.z);
00268 this->approach_vector.x = goal->graspinput.approach_vector.x/vector_length;
00269 this->approach_vector.y = goal->graspinput.approach_vector.y/vector_length;
00270 this->approach_vector.z = goal->graspinput.approach_vector.z/vector_length;
00271 cout << " --> SET APPROACH VECTOR TO: " << " [x,y,z] = [" << this->approach_vector.x << "," << this->approach_vector.y << "," << this->approach_vector.z << "]" << endl;
00272
00273
00274 this->max_duration_for_grasp_calc = (float) goal->graspinput.max_calculation_time.toSec();
00275 cout << " --> SET MAX. CALCULATION TIME TO: " << this->max_duration_for_grasp_calc << endl;
00276
00277
00278 this->gripper_opening_width = (float) goal->graspinput.gripper_opening_width;
00279
00280
00281 this->return_only_best_gp = (bool) goal->graspinput.show_only_best_grasp;
00282 cout << " --> SET show_only_best_grasp TO: " << this->return_only_best_gp << endl;
00283
00284
00285 string orig_tf = (string) goal->graspinput.input_pc.header.frame_id;
00286 cout << " --> FRAME_ID ORIGINAL Point Cloud: " << orig_tf << endl;
00287
00288 cout << "Fixed by now: this->trans_z_after_pc_transform: " << this->trans_z_after_pc_transform << endl;
00289
00290
00291 if (!goal->graspinput.goal_frame_id.empty())
00292 {
00293 this->base_frame_id = goal->graspinput.goal_frame_id;
00294 }
00295 else
00296 {
00297 this->base_frame_id = "/base_link";
00298 }
00299 cout << " --> BASE_FRAME_ID: " << this->base_frame_id << endl;
00300
00301 cout << "************************************************************************************************************" << endl;
00302
00303
00304 bool foundTransform = tf_listener.waitForTransform(this->base_frame_id, orig_tf, goal->graspinput.input_pc.header.stamp, ros::Duration(1.0));
00305 if (!foundTransform)
00306 {
00307 ROS_WARN(" ==> calc_grasppoints_action_server.cpp: read_pc_cb(): NO TRANSFORM FOR POINT CLOUD FOUND");
00308 }
00309
00310 pcl::PointCloud<pcl::PointXYZ> pcl_cloud_in_old_cs;
00311 pcl::fromROSMsg(goal->graspinput.input_pc, pcl_cloud_in_old_cs);
00312
00313 pcl_ros::transformPointCloud(this->base_frame_id, pcl_cloud_in_old_cs, pc_new_cs, tf_listener);
00314
00315
00316 this->pubInputPCROS.publish(goal->graspinput.input_pc);
00317
00318
00319 id_row_top_overall = -1;
00320 id_col_top_overall = -1;
00321 nr_roll_top_overall = -1;
00322 nr_tilt_top_overall = -1;
00323 topval_gp_overall = -1000;
00324
00325 loop_control(pc_new_cs);
00326 }
00327
00328
00329
00330
00331
00332 void CCalc_Grasppoints::loop_control(pcl::PointCloud<pcl::PointXYZ> pcl_cloud_in)
00333 {
00334 int time_for_calc_in_secs = this->max_duration_for_grasp_calc;
00335 time_t start,end;
00336 time (&start);
00337 double timedif;
00338 bool success = true;
00339
00340 for (int tilt = 0; tilt < TILT_STEPS; tilt++)
00341 {
00342 for (int roll = 0; roll < ROLL_MAX_DEGREE/ROLL_STEPS_DEGREE; roll++)
00343 {
00344
00345 feedback_.feedback.data = "this->topval_gp_overall";
00346
00347 if (as_.isPreemptRequested() || !ros::ok() || success == false)
00348 {
00349 ROS_INFO("%s: Preempted", action_name_.c_str());
00350
00351 as_.setPreempted();
00352 success = false;
00353 break;
00354 }
00355
00356 as_.publishFeedback(feedback_);
00357
00358
00359 if (this->return_only_best_gp and (this->topval_gp_overall >= this->graspval_top)){
00360 cout << "Top grasp already found\n";
00361 break;
00362 }
00363
00364
00365 time (&end);
00366 timedif = difftime (end,start);
00367 cout << "\n ===> TEST ROTATION: " << roll*ROLL_STEPS_DEGREE << "\nRuntime so far (in sec): " << timedif << endl;
00368 if (timedif > time_for_calc_in_secs) {
00369 cout << "\n Calculation time is over, stop calculation of grasp points!!\n";
00370 break;
00371 }
00372
00373 generate_grid(roll, tilt, pcl_cloud_in);
00374 if (this->print_heights_bool){
00375 print_heights(roll,tilt);
00376 }
00377 calc_intimage(roll, tilt);
00378 calc_featurevectors(roll, tilt);
00379
00380 bool svm_with_probability = false;
00381 predict_bestgp_withsvm(svm_with_probability);
00382 show_predicted_gps(roll, tilt, svm_with_probability);
00383 }
00384 }
00385
00386 publish_transformed_pcl_cloud(0, 0, pcl_cloud_in);
00387 transform_gp_in_wcs_and_publish(this->id_row_top_overall, this->id_col_top_overall, this->nr_roll_top_overall,this->nr_tilt_top_overall, this->topval_gp_overall-20);
00388
00389 time (&end);
00390 timedif = difftime (end,start);
00391 cout << "\n Gesamtzeit fuer Loop: " << timedif << endl;
00392
00393 if(success)
00394 {
00395 result_.graspOutput = this->gp_result;
00396 ROS_INFO_STREAM("Succeeded:\n" << this->gp_result);
00397 as_.setSucceeded(result_);
00398 }
00399 }
00400
00401
00402
00403 void CCalc_Grasppoints::generate_grid(int roll, int tilt, pcl::PointCloud<pcl::PointXYZ> pcl_cloud_in)
00404 {
00405 pcl::PointCloud<pcl::PointXYZ> pcl_cloud_transformed;
00406 int nr_rows = HEIGHT, nr_cols = WIDTH;
00407 float r_col_m = (0.5 * (float)nr_cols)/100.0;
00408 float r_row_m = (0.5 * (float)nr_rows)/100.0;
00409 float rot_about_z;
00410 float rot_about_x = 0;
00411 pcl::PointXYZ pnt;
00412 pcl::PointXYZ *av = new pcl::PointXYZ(0,0,-1);
00413
00414
00415 av->x = this->approach_vector.x;
00416 av->y = this->approach_vector.y;
00417 av->z = this->approach_vector.z;
00418
00419
00420 Eigen::Matrix4f mat_sh_to_orig = Eigen::Matrix4f::Identity();
00421 Eigen::Matrix4f mat_rot_z_axis = Eigen::Matrix4f::Identity();
00422 Eigen::Matrix4f mat_rot_x_axis = Eigen::Matrix4f::Identity();
00423 Eigen::Matrix4f mat_sh_from_orig = Eigen::Matrix4f::Identity();
00424 Eigen::Matrix4f mat_rot = Eigen::Matrix4f::Identity();
00425 Eigen::Matrix4f mat_scale_x_dir = Eigen::Matrix4f::Identity();
00426
00427 Eigen::Matrix4f mat_transform = Eigen::Matrix4f::Identity();
00428
00429
00430 mat_scale_x_dir(0,0) = this->gripper_opening_width;
00431
00432 mat_sh_to_orig(0,3) = -this->graspsearchcenter.x;
00433 mat_sh_to_orig(1,3) = -this->graspsearchcenter.y;
00434 mat_sh_to_orig(2,3) = -this->graspsearchcenter.z;
00435
00436 mat_sh_from_orig(0,3) = 0;
00437 mat_sh_from_orig(1,3) = 0;
00438 mat_sh_from_orig(2,3) = 0 + this->trans_z_after_pc_transform;
00439
00440
00441 if (av->y == 0 and av->x == 0){
00442 rot_about_z = 0;
00443 if (av->z >= 0) {
00444 rot_about_x = 0;
00445 } else {
00446 rot_about_x = PI;
00447 }
00448 } else {
00449 rot_about_z = 90*PI/180.0 - atan2(av->y, av->x);
00450 rot_about_x = 90*PI/180.0 - atan2( av->z, sqrt(av->y*av->y + av->x*av->x) );
00451 }
00452
00453
00454
00455
00456
00457
00458
00459 float angle = roll*ROLL_STEPS_DEGREE*PI/180;
00460 mat_rot(0,0) = cos(angle);
00461 mat_rot(0,1) = -sin(angle);
00462 mat_rot(1,0) = sin(angle);
00463 mat_rot(1,1) = cos(angle);
00464
00465
00466 mat_rot_z_axis(0,0) = cos(rot_about_z);
00467 mat_rot_z_axis(0,1) = -sin(rot_about_z);
00468 mat_rot_z_axis(1,0) = sin(rot_about_z);
00469 mat_rot_z_axis(1,1) = cos(rot_about_z);
00470
00471
00472
00473 mat_rot_x_axis(1,1) = cos(rot_about_x);
00474 mat_rot_x_axis(1,2) = -sin(rot_about_x);
00475 mat_rot_x_axis(2,1) = sin(rot_about_x);
00476 mat_rot_x_axis(2,2) = cos(rot_about_x);
00477
00478
00479
00480 mat_transform = mat_scale_x_dir * mat_rot* mat_sh_from_orig * mat_rot_x_axis * mat_rot_z_axis * mat_sh_to_orig;
00481 this->av_trans_mat = mat_transform;
00482
00483
00484 pcl::copyPointCloud(pcl_cloud_in, pcl_cloud_transformed);
00485 pcl::transformPointCloud(pcl_cloud_in, pcl_cloud_transformed, mat_transform);
00486
00487
00488
00489 if (this->visualization)
00490 {
00491 cout << "Publish transformed point cloud! \n";
00492 this->pubTransformedPCROS.publish(pcl_cloud_transformed);
00493 }
00494
00495
00496 for (int i = 0; i < nr_rows; i++)
00497 for (int j = 0; j < nr_cols; j++)
00498 this->heightsgridroll[roll][tilt][i][j]= -1.0;
00499
00500
00501 for (size_t i = 0; i < pcl_cloud_transformed.points.size(); ++i)
00502 {
00503
00504
00505 int idx_x = -1, idx_y = -1;
00506 pnt = pcl_cloud_transformed.points[i];
00507 if ((pnt.x > -r_row_m) and (pnt.x < r_row_m) and
00508 (pnt.y > -r_col_m) and (pnt.y < r_col_m))
00509 {
00510 idx_x = (int) (floor (100*(pnt.x - ( - r_row_m))));
00511 idx_y = (int) (floor (100*(pnt.y - ( - r_col_m))));;
00512 if (heightsgridroll[roll][tilt][idx_x][idx_y] < pnt.z)
00513 {
00514 heightsgridroll[roll][tilt][idx_x][idx_y] = pnt.z;
00515 }
00516 }
00517 }
00518
00519 for (int i = 0; i < nr_rows; i++){
00520 for (int j = 0; j < nr_cols; j++){
00521 if (this->heightsgridroll[roll][tilt][i][j] < -0.99){
00522 this->heightsgridroll[roll][tilt][i][j] = 0;
00523 }
00524 }
00525 }
00526 }
00527
00528
00529
00530 void CCalc_Grasppoints::publish_transformed_pcl_cloud(int roll, int tilt, pcl::PointCloud<pcl::PointXYZ> pcl_cloud_in)
00531 {
00532 pcl::PointCloud<pcl::PointXYZ> pcl_cloud_transformed;
00533
00534 Eigen::Matrix4f mat_sh_orig = Eigen::Matrix4f::Identity();
00535 Eigen::Matrix4f mat_rot = Eigen::Matrix4f::Identity();
00536 Eigen::Matrix4f mat_tilt = Eigen::Matrix4f::Identity();
00537 Eigen::Matrix4f mat_sh_from_orig = Eigen::Matrix4f::Identity();
00538 Eigen::Matrix4f mat_transform = Eigen::Matrix4f::Identity();
00539
00540 mat_sh_orig(0,3) = -this->graspsearchcenter.x;
00541 mat_sh_orig(1,3) = -this->graspsearchcenter.y;
00542 mat_sh_from_orig(0,3) = this->graspsearchcenter.x;
00543 mat_sh_from_orig(1,3) = this->graspsearchcenter.y;
00544
00545
00546
00547
00548 float angle = roll*ROLL_STEPS_DEGREE*PI/180 + this->boxrot_angle_init;
00549 mat_rot(0,0) = cos(angle);
00550 mat_rot(0,1) = -sin(angle);
00551 mat_rot(1,0) = sin(angle);
00552 mat_rot(1,1) = cos(angle);
00553
00554 float beta = -tilt*TILT_STEPS_DEGREE*PI/180;
00555 mat_tilt(0,0) = cos(beta);
00556 mat_tilt(0,2) = -sin(beta);
00557 mat_tilt(2,0) = sin(beta);
00558 mat_tilt(2,2) = cos(beta);
00559
00560 mat_transform = mat_sh_from_orig*mat_tilt*mat_rot*mat_sh_orig;
00561
00562 pcl::copyPointCloud(pcl_cloud_in, pcl_cloud_transformed);
00563 pcl::transformPointCloud(pcl_cloud_in, pcl_cloud_transformed, mat_transform);
00564
00565
00566
00567 this->pubTransformedPCROS.publish(pcl_cloud_transformed);
00568 }
00569
00570
00571
00572
00573
00574 void CCalc_Grasppoints::calc_intimage(int roll, int tilt)
00575 {
00576 Mat heightsIntegral;
00577 heightsIntegral = Mat(HEIGHT+1, WIDTH+1, CV_64FC1);
00578
00579
00580 double *TempHeights = (double *)malloc(HEIGHT * WIDTH * sizeof(double));
00581
00582 int k = 0;
00583 for(int i = 0; i < HEIGHT; i++ )
00584 for(int j = 0; j < WIDTH; j++ )
00585 {
00586 TempHeights[k] = this->heightsgridroll[roll][tilt][i][j];
00587 k++;
00588 }
00589
00590 Mat const cvheightsmat = Mat(HEIGHT, WIDTH, CV_64FC1, TempHeights);
00591
00592 integral(cvheightsmat, heightsIntegral,CV_64FC1);
00593
00594
00595
00596 for (int row = 0; row < 1+HEIGHT; row++)
00597 for (int col = 0; col < 1+WIDTH; col++)
00598 this->integralimageroll[roll][tilt][row][col] = ((double*)(heightsIntegral.ptr() + heightsIntegral.step*row))[col];
00599
00600
00601
00602
00603
00604
00605
00606
00607
00608
00609 free(TempHeights);
00610 }
00611
00612
00613 void CCalc_Grasppoints::calc_featurevectors(int roll, int tilt)
00614 {
00615
00616
00617
00618 CIntImage_to_Featurevec * ii_to_fv = new CIntImage_to_Featurevec();
00619
00620 string pkg_path = ros::package::getPath("haf_grasping");
00621
00622
00623 if (this->feature_file_path == ""){
00624 this->feature_file_path = pkg_path + "/data/Features.txt";
00625 }
00626 ii_to_fv->read_features(this->feature_file_path);
00627
00628
00629 ofstream output_fv_file(outputpath_full.c_str());
00630
00631
00632 pnt_in_box(roll, tilt);
00633
00634 for (int row = 0; row < HEIGHT - 14; row++){
00635 for (int col = 0; col < WIDTH -14; col++)
00636 {
00637
00638 if (!this->point_inside_box_grid[roll][tilt][row+7][col+7]){
00639 continue;
00640 }
00641
00642
00643 for (int i = 0; i < 15; i++){
00644 for (int j = 0; j < 15; j++){
00645 ii_to_fv->intimagemat[i][j] = this->integralimageroll[roll][tilt][row+i][col+j];
00646 }
00647 }
00648
00649
00650 ii_to_fv->write_featurevector(outputpath_full.c_str(), this->nr_features_without_shaf);
00651 }
00652 }
00653 }
00654
00655
00656
00657
00658
00659
00660
00661
00662
00663 void CCalc_Grasppoints::pnt_in_box(int nr_roll, int nr_tilt){
00664
00665 bool print_pnt_in_box = false;
00666
00667
00668
00669
00670
00671
00672
00673
00674
00675
00676 float alpha_deg = -nr_roll*ROLL_STEPS_DEGREE - this->boxrot_angle_init * 180/PI;
00677 float alpha = alpha_deg*PI/180;
00678 float cx = HEIGHT/2;
00679 float cy = HEIGHT/2;
00680 float cx1,cy1,cx2,cy2,cx3,cy3,cx4,cy4;
00681
00682
00683 float boarder = 7.0;
00684 float height_r = this->grasp_search_area_size_x_dir/2 - boarder;
00685 float width_r = this->grasp_search_area_size_y_dir/2 - boarder;
00686 cx1 = cx - sin(alpha)*height_r;
00687 cy1 = cy + cos(alpha)*height_r;
00688 cx2 = cx + sin(alpha)*height_r;
00689 cy2 = cy - cos(alpha)*height_r;
00690 cx3 = cx - sin(alpha+PI/2)*width_r;
00691 cy3 = cy + cos(alpha+PI/2)*width_r;
00692 cx4 = cx + sin(alpha+PI/2)*width_r;
00693 cy4 = cy - cos(alpha+PI/2)*width_r;
00694
00695 if (print_pnt_in_box)
00696 cout << cx1 << "\t" << cy1 << "\n" << cx2 << "\t" << cy2 << "\n" << cx3 << "\t" << cy3 << "\n" << cx4 << "\t" << cy4 << "\n\n";
00697 int cnt_all = 0;
00698 int cnt_in = 0;
00699 int cnt_out = 0;
00700
00701 for (int i = 0; i < HEIGHT; i++){
00702 for (int j = 0; j < HEIGHT; j++){
00703 ++cnt_all;
00704
00705
00706 int th_empty_r = 4;
00707 float ii_th_in_r = 0.03;
00708
00709
00710 if ((i>6 and i < HEIGHT-7 and j>6 and j<HEIGHT-7) and
00711 (this->integralimageroll[nr_roll][nr_tilt][i+th_empty_r][j+th_empty_r]-
00712 this->integralimageroll[nr_roll][nr_tilt][i-th_empty_r-1][j+th_empty_r]-
00713 this->integralimageroll[nr_roll][nr_tilt][i+th_empty_r][j-th_empty_r-1]+
00714 this->integralimageroll[nr_roll][nr_tilt][i-th_empty_r-1][j-th_empty_r-1] > ii_th_in_r) and
00715 (-sin(alpha)*(-cx1+j) + cos(alpha)*(-cy1+i) < 0.00001) and
00716 (-sin(alpha)*(-cx2+j) + cos(alpha)*(-cy2+i) > -0.00001) and
00717 ( cos(alpha)*(-cx3+j) + sin(alpha)*(-cy3+i) > -0.00001) and
00718 ( cos(alpha)*(-cx4+j) + sin(alpha)*(-cy4+i) < 0.00001)){
00719
00720
00721 this->point_inside_box_grid[nr_roll][nr_tilt][i][j] = true;
00722 cnt_in++;
00723 } else {
00724
00725
00726 this->point_inside_box_grid[nr_roll][nr_tilt][i][j] = false;
00727 cnt_out++;
00728 }
00729 }
00730 }
00731
00732
00733 if (print_pnt_in_box){
00734 cout << "points_all: " << cnt_all << " points in: " << cnt_in << " and points out: " << cnt_out << endl;
00735 for (int i = HEIGHT-1; i >= 0; i--){
00736 for (int j = HEIGHT-1; j >= 0; j--){
00737 if (this->point_inside_box_grid[nr_roll][nr_tilt][i][j] == true){
00738 cout << " + ";
00739 } else {
00740 cout << " - ";
00741 }
00742 }
00743 cout << endl;
00744 }
00745 }
00746 }
00747
00748
00749
00750
00751 void CCalc_Grasppoints::predict_bestgp_withsvm(bool svm_with_probability){
00752
00753
00754
00755
00756 try{
00757 string pkg_path = ros::package::getPath("haf_grasping");
00758
00759
00760 stringstream ss, ss2;
00761
00762
00763
00764 if (this->range_file_path == ""){
00765 this->range_file_path = pkg_path + "/data/range21062012_allfeatures";
00766 }
00767
00768 if (this->svmmodel_file_path == ""){
00769 this->svmmodel_file_path = pkg_path + "/data/all_features.txt.scale.model";
00770 }
00771
00772 ss << pkg_path << "/libsvm-3.12/svm-scale -r " << this->range_file_path << " /tmp/features.txt > /tmp/features.txt.scale";
00773 string command = ss.str();
00774 int i = system(command.c_str());
00775 if (i != 0){
00776 ROS_WARN(" CCalc_Grasppoints::predict_bestgp_withsvm() SCALING OF FEATURES WAS NOT EXECUTED AS IT SHOULD (Was SVM code compiled?) ");
00777 cout << "===> CCalc_Grasppoints::predict_bestgp_withsvm: System return value for scaling features is: " << i << endl;
00778 }
00779
00780
00781 if (!svm_with_probability){
00782
00783 ss2 << pkg_path << "/libsvm-3.12/svm-predict /tmp/features.txt.scale " << this->svmmodel_file_path << " /tmp/output_calc_gp.txt";
00784 string command2 = ss2.str();
00785 i = system(command2.c_str());
00786 } else {
00787
00788 i = system("/usr/lib/libsvm/libsvm-3.1/svm-predict -b 1 /tmp/features.txt.scale /usr/lib/libsvm/libsvm-3.1/tools/allmanualfeatures.txt.scale.p.model /tmp/output_calc_gp.txt");
00789 }
00790 if (i != 0){
00791 ROS_WARN(" CCalc_Grasppoints::predict_bestgp_withsvm() GRASP PREDICTION FROM FEATURES WAS NOT EXECUTED AS IT SHOULD (Was SVM code compiled?) ");
00792 cout << "===> CCalc_Grasppoints::predict_bestgp_withsvm: System return value for execution of grasp prediction with SVM: " << i << endl;
00793 }
00794 } catch (int j) {
00795 cerr << "ERROR in calc_grasppoints.cpp: predict_bestgp_withsvm()" << endl;
00796 }
00797 }
00798
00799
00800 void CCalc_Grasppoints::show_predicted_gps(int nr_roll, int tilt, bool svm_with_probability){
00801
00802 string path_svm_output = "/tmp/output_calc_gp.txt";
00803
00804
00805 ifstream file_in(path_svm_output.c_str());
00806
00807
00808 int id_row_top_all = -1;
00809 int id_col_top_all = -1;
00810 int nr_roll_top_all = -1;
00811 int nr_tilt_top_all = -1;
00812 int topval_gp_all = -1000;
00813
00814 string line;
00815 getline(file_in, line);
00816
00817 bool printgraspsgrid = false;
00818 bool printgraspseval = false;
00819 float graspsgrid[HEIGHT][WIDTH];
00820 float graspseval[HEIGHT][WIDTH];
00821
00822 for (int row = 0; row < HEIGHT; row++){
00823 for (int col = 0; col < WIDTH; col++){
00824
00825 if (this->point_inside_box_grid[nr_roll][tilt][row][col] == false){
00826 graspsgrid[row][col] = -1;
00827 } else {
00828 if (svm_with_probability){
00829 int start=0,end=0, res;
00830 res = atof(line.substr(0,2).c_str());
00831 start = line.find(" ",0);
00832 end = line.find(" ",start+1);
00833 if (res>0){
00834 start = end;
00835 end = line.find(" ", start+1);
00836 }
00837 float prob = atof(line.substr(start,end).c_str());
00838 graspsgrid[row][col] = res*prob;
00839 } else {
00840 graspsgrid[row][col] = atoi(line.substr(0,2).c_str());
00841 }
00842
00843 getline(file_in, line);
00844 }
00845 }
00846 }
00847
00848
00849 if (printgraspsgrid){
00850 cout << "\n Graspsgrid: intuitiv! \n";
00851 for (int row = HEIGHT-1; row >= 0; row--){
00852 cout << row << ") \t";
00853 for (int col = WIDTH-1; col >= 0; col--){
00854 cout << graspsgrid[row][col] << "\t";
00855 }
00856 cout << "\n";
00857 }
00858 }
00859
00860
00861 if (printgraspseval) cout << "graspseval[row][col]" << "\n\n";
00862 int w1=1, w2=2,w3=3,w4=4,w5=55;
00863 int topval_gp = -1000;
00864 int id_row_top = -1, id_col_top = -1;
00865 for (int row = 0; row < HEIGHT; row++){
00866 for (int col = 0; col < WIDTH; col++){
00867 if ( graspsgrid[row][col] < 0 ){
00868 graspseval[row][col] = 0;
00869 } else {
00870 graspseval[row][col] =
00871 w1*graspsgrid[row-2][col-2]+w2*graspsgrid[row-2][col-1]+w3*graspsgrid[row-2][col]+w2*graspsgrid[row-2][col+1]+w1*graspsgrid[row-2][col+2]+
00872 w2*graspsgrid[row-1][col-2]+w3*graspsgrid[row-1][col-1]+w4*graspsgrid[row-1][col]+w3*graspsgrid[row-1][col+1]+w2*graspsgrid[row-1][col+2]+
00873 w2*graspsgrid[row][col-4] + w2*graspsgrid[row][col-3] + w3*graspsgrid[row][col-2] + w4*graspsgrid[row][col-1] + w5*graspsgrid[row][col] + w4*graspsgrid[row][col+1] + w3*graspsgrid[row][col+2] + w2*graspsgrid[row][col+3] +w2*graspsgrid[row][col+4] +
00874 w2*graspsgrid[row+1][col-2]+w3*graspsgrid[row+1][col-1]+w4*graspsgrid[row+1][col]+w3*graspsgrid[row+1][col+1]+w2*graspsgrid[row+1][col+2]+
00875 w1*graspsgrid[row+2][col-2]+w2*graspsgrid[row+2][col-1]+w3*graspsgrid[row+2][col]+w2*graspsgrid[row+2][col+1]+w1*graspsgrid[row+2][col+2];
00876
00877 }
00878 if (printgraspseval) cout << graspseval[row][col] << "\t";
00879 if (graspseval[row][col] > topval_gp){
00880 topval_gp = graspseval[row][col];
00881 id_row_top = row;
00882 id_col_top = col;
00883 if (topval_gp > topval_gp_all){
00884 cout << "New overall grasp evaluation with value: " << topval_gp << " in row,col: [" << id_row_top << ", " << id_col_top <<"] and rotation: " << nr_roll*ROLL_STEPS_DEGREE << endl;
00885 id_row_top_all = id_row_top;
00886 id_col_top_all = id_col_top;
00887 nr_roll_top_all = nr_roll;
00888 nr_tilt_top_all = tilt;
00889 topval_gp_all = topval_gp;
00890 }
00891 }
00892 }
00893 if (printgraspseval) cout << "\n";
00894 }
00895
00896
00897
00898 marker_cnt = 1;
00899 publish_grasp_grid(nr_roll, tilt, graspseval, 1);
00900
00901
00902 int best_topval_row = -1, best_topval_col = -1;
00903 int longest_topval_len = 0;
00904 int cur_topval_len = 0;
00905 bool count_topval_len = false;
00906 for (int row = 0; row < HEIGHT; row++){
00907 cur_topval_len = 0;
00908 count_topval_len = false;
00909 for (int col = 0; col < WIDTH; col++){
00910 if (graspseval[row][col] == topval_gp){
00911 count_topval_len = true;
00912 cur_topval_len++;
00913 if (cur_topval_len > longest_topval_len){
00914 longest_topval_len = cur_topval_len;
00915 best_topval_row = row;
00916 best_topval_col = col - cur_topval_len/2;
00917 if (topval_gp == topval_gp_all){
00918 cout << "Better topval gp still with topval: " << topval_gp << " in row,col: [" << best_topval_row << ", " << best_topval_col <<"] and rotation: " << nr_roll*ROLL_STEPS_DEGREE << endl;
00919 id_row_top_all = best_topval_row;
00920 id_col_top_all = best_topval_col;
00921 }
00922 }
00923 }
00924 else {
00925 count_topval_len = false;
00926 cur_topval_len = 0;
00927 }
00928 }
00929 }
00930
00931
00932
00933 if (printgraspseval) {
00934 cout << "\n Grasps predicted more intuitively: \n";
00935 for (int row = HEIGHT-1; row >= 0; row--){
00936 for (int col = WIDTH-1; col >= 0; col--){
00937 cout << setw(3) << setprecision(3) <<graspseval[row][col];
00938 if (col > 6 and col < WIDTH-7 )
00939 cout << " ";
00940 }
00941 if (row > 7 and row < HEIGHT - 7)
00942 cout << "\n";
00943 cout << endl;
00944 }
00945 }
00946 cout << "\n Best grasp value for currently tested roll: " << topval_gp_all << endl;
00947
00948 file_in.close();
00949
00950 if (topval_gp_all > this->topval_gp_overall){
00951 cout << "\n New overall (overall!) grasp evaluation with value: " << topval_gp_all << " in row,col: [" << id_row_top_all << ", " << id_col_top_all <<"] and rotation: " << nr_roll*ROLL_STEPS_DEGREE << endl;
00952 this->id_row_top_overall = id_row_top_all;
00953 this->id_col_top_overall = id_col_top_all;
00954 this->nr_roll_top_overall = nr_roll_top_all;
00955 this->nr_tilt_top_overall = nr_tilt_top_all;
00956 this->topval_gp_overall = topval_gp_all;
00957 }
00958
00959 if (this->return_only_best_gp){
00960 cout << "\n Grasp detection for one roll finished. Only best grasp is published after full gp calculation! \n";
00961 } else if ((topval_gp_all > this->graspval_th) ){
00962
00963
00964 int scaled_gp_eval = topval_gp_all-20;
00965 if (scaled_gp_eval < 10) scaled_gp_eval = 10;
00966 transform_gp_in_wcs_and_publish(id_row_top_all, id_col_top_all,nr_roll_top_all, nr_tilt_top_all, scaled_gp_eval);
00967 } else {
00968 cout << "\n For current roll no grasp point had an evaluation above threshold for publishing! \n";
00969 }
00970 }
00971
00972
00973
00974
00975
00976 void CCalc_Grasppoints::publish_grasp_grid(int nr_roll, int tilt, float graspsgrid[][WIDTH], int gripperwidth=1){
00977 visualization_msgs::MarkerArray ma;
00978 visualization_msgs::MarkerArray ma_params;
00979 visualization_msgs::Marker marker;
00980 visualization_msgs::Marker marker_graps_params;
00981 cout << "publish_grasp_grid: input parameter gripperwidth: " << gripperwidth << endl;
00982 float x,y,z;
00983 x = this->graspsearchcenter.x - 0.01*HEIGHT/2/gripperwidth;
00984 y = this->graspsearchcenter.y - 0.01*WIDTH/2;
00985 z = this->graspsearchcenter.z + this->trans_z_after_pc_transform;
00986
00987
00988
00989 for (int row = 0; row <= HEIGHT-1; row++){
00990 for (int col = 0; col <= WIDTH-1; col++){
00991 if (this->point_inside_box_grid[nr_roll][tilt][row][col] == true){
00992 gp_to_marker(&marker, x+0.01/gripperwidth*row,y+0.01*col,z, graspsgrid[row][col], false, gripperwidth, nr_roll, false, true);
00993 ma.markers.push_back(marker);
00994 }
00995 }
00996 }
00997
00998
00999
01000 for (int i = 1; i <= 3; i++){
01001 grasp_area_to_marker(&marker_graps_params, this->graspsearchcenter.x,this->graspsearchcenter.y, z, gripperwidth, nr_roll, i , false );
01002 ma_params.markers.push_back(marker_graps_params);
01003 }
01004
01005
01006
01007 gp_to_marker(&marker, this->graspsearchcenter.x,this->graspsearchcenter.y,z, graspsgrid[0][0], false, gripperwidth, nr_roll, true, true);
01008 ma.markers.push_back(marker);
01009
01010 vis_pub_ma.publish(ma);
01011 vis_pub_ma_params.publish(ma_params);
01012
01013 }
01014
01015
01016
01017 void CCalc_Grasppoints::gp_to_marker(visualization_msgs::Marker *marker, float x, float y, float z, float green, bool pubmarker, int gripperwidth=1, int nr_roll=0,bool pub_grip_open_dir=false, bool pub_grid=true){
01018
01019
01020 string tmp_tf_help = "tf_help";
01021 static tf::TransformBroadcaster br;
01022
01023
01024 float rot_z, rot_x;
01025
01026 if (this->approach_vector.y == 0 and this->approach_vector.x == 0){
01027 rot_z = 0;
01028 if (this->approach_vector.z >= 0) {
01029 rot_x = 0;
01030 } else {
01031 rot_x = PI;
01032 }
01033 } else {
01034 rot_z = 90*PI/180.0 - atan2(this->approach_vector.y, this->approach_vector.x);
01035 rot_x = 90*PI/180.0 - atan2( this->approach_vector.z, sqrt(this->approach_vector.y*this->approach_vector.y + this->approach_vector.x*this->approach_vector.x) );
01036 }
01037
01038
01039
01040
01041
01042
01043 Eigen::Matrix4f mat_sh_to_orig = Eigen::Matrix4f::Identity();
01044 Eigen::Matrix4f mat_rot = Eigen::Matrix4f::Identity();
01045 Eigen::Matrix4f mat_sh_from_orig = Eigen::Matrix4f::Identity();
01046 Eigen::Matrix4f mat_transform = Eigen::Matrix4f::Identity();
01047 Eigen::Matrix3f mat_rot_for_appr_vec = Eigen::Matrix3f::Identity();
01048
01049 Eigen::Matrix4f mat_rot_z_axis = Eigen::Matrix4f::Identity();
01050 Eigen::Matrix4f mat_rot_x_axis = Eigen::Matrix4f::Identity();
01051
01052
01053 mat_sh_to_orig(0,3) = -this->graspsearchcenter.x;
01054 mat_sh_to_orig(1,3) = -this->graspsearchcenter.y;
01055 mat_sh_to_orig(2,3) = -this->graspsearchcenter.z;
01056 mat_sh_from_orig(0,3) = 0;
01057 mat_sh_from_orig(1,3) = 0;
01058 mat_sh_from_orig(2,3) = 0 + this->trans_z_after_pc_transform;
01059
01060
01061
01062
01063 float angle = nr_roll*ROLL_STEPS_DEGREE*PI/180;
01064 mat_rot(0,0) = cos(angle);
01065 mat_rot(0,1) = -sin(angle);
01066 mat_rot(1,0) = sin(angle);
01067 mat_rot(1,1) = cos(angle);
01068
01069
01070 mat_rot_z_axis(0,0) = cos(rot_z);
01071 mat_rot_z_axis(0,1) = -sin(rot_z);
01072 mat_rot_z_axis(1,0) = sin(rot_z);
01073 mat_rot_z_axis(1,1) = cos(rot_z);
01074
01075
01076
01077 mat_rot_x_axis(1,1) = cos(rot_x);
01078 mat_rot_x_axis(1,2) = -sin(rot_x);
01079 mat_rot_x_axis(2,1) = sin(rot_x);
01080 mat_rot_x_axis(2,2) = cos(rot_x);
01081
01082
01083 mat_transform = mat_rot*mat_sh_from_orig*mat_rot_x_axis*mat_rot_z_axis*mat_sh_to_orig;
01084
01085
01086
01087 Eigen::Matrix4f Tm;
01088 Tm = mat_transform.inverse();
01089 tf::Vector3 origin;
01090 origin.setValue(static_cast<double>(Tm(0,3)),static_cast<double>(Tm(1,3)),static_cast<double>(Tm(2,3)));
01091 tf::Matrix3x3 tf3d;
01092 tf3d.setValue(static_cast<double>(Tm(0,0)), static_cast<double>(Tm(0,1)), static_cast<double>(Tm(0,2)),
01093 static_cast<double>(Tm(1,0)), static_cast<double>(Tm(1,1)), static_cast<double>(Tm(1,2)),
01094 static_cast<double>(Tm(2,0)), static_cast<double>(Tm(2,1)), static_cast<double>(Tm(2,2)));
01095
01096 tf::Quaternion tfqt;
01097 tf3d.getRotation(tfqt);
01098 this->quat_tf_to_tf_help = tfqt;
01099 tf::Transform transform;
01100 transform.setOrigin(origin);
01101 transform.setRotation(tfqt);
01102
01103 br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), this->base_frame_id, tmp_tf_help));
01104
01105 if (pub_grid){
01106 std::stringstream ss;
01107 ss << tmp_tf_help ;
01108 (*marker).header.frame_id = ss.str();
01109 (*marker).header.stamp = ros::Time();
01110 (*marker).ns = "my_namespace";
01111 (*marker).id = marker_cnt++;
01112 (*marker).type = visualization_msgs::Marker::SPHERE;
01113 (*marker).action = visualization_msgs::Marker::ADD;
01114 (*marker).pose.position.x = x-this->graspsearchcenter.x;
01115 (*marker).pose.position.y = y-this->graspsearchcenter.y;
01116 (*marker).pose.position.z = z;
01117 (*marker).pose.orientation.x = 0.0;
01118 (*marker).pose.orientation.y = 0.0;
01119 (*marker).pose.orientation.z = 0.0;
01120 (*marker).pose.orientation.w = 1.0;
01121 (*marker).scale.x = 0.002;
01122 (*marker).lifetime = ros::Duration(1);
01123 (*marker).scale.y = 0.002;
01124 (*marker).scale.z = 0.002;
01125 (*marker).color.a = 1.0;
01126 if (green > 0){
01127 (*marker).color.r = 0.0;
01128 (*marker).color.g = 1.0;
01129 (*marker).scale.x = 0.005;
01130 (*marker).scale.y = 0.005;
01131 (*marker).scale.z = 0.001*green;
01132 (*marker).pose.position.z = z+(*marker).scale.z/2;
01133 } else {
01134 (*marker).color.r = 1.0;
01135 (*marker).color.g = 0.0;
01136 }
01137 (*marker).color.b = 0.0;
01138 }
01139 }
01140
01141
01142 void CCalc_Grasppoints::grasp_area_to_marker(visualization_msgs::Marker *marker, float x, float y, float z, int gripperwidth=1, int nr_roll=0, int param_id=1, bool top_grasp=false){
01143
01144 int fix_marker_id_gripper_dir = 10000;
01145 int fix_marker_id_gripper_appr_dir = 10001;
01146 int fix_marker_id_grasp_search_area = 10002;
01147 int fix_marker_id_grasp_search_area2 = 10003;
01148
01149 (*marker).header.frame_id = "tf_help";
01150 (*marker).header.stamp = ros::Time::now();
01151 (*marker).ns = "haf_grasping_parameters";
01152
01153
01154 switch(param_id) {
01155 case 1 : {
01156 (*marker).id = fix_marker_id_grasp_search_area;
01157 (*marker).type = visualization_msgs::Marker::CUBE;
01158 (*marker).action = visualization_msgs::Marker::ADD;
01159 (*marker).color.a = 0.05;
01160 (*marker).color.r = 0.4;
01161 (*marker).color.g = 0.4;
01162 (*marker).color.b = 0.4;
01163 (*marker).pose.position.x = 0;
01164 (*marker).pose.position.y = 0;
01165 (*marker).pose.position.z = z;
01166
01167 tf::Vector3 zaxis(0, 0, 1);
01168 tf::Quaternion qt_compensate_rot(zaxis, nr_roll*ROLL_STEPS_DEGREE*PI/180);
01169 geometry_msgs::Quaternion quat_msg_compensate_rot;
01170 tf::quaternionTFToMsg(qt_compensate_rot, quat_msg_compensate_rot);
01171 (*marker).pose.orientation = quat_msg_compensate_rot;
01172 (*marker).scale.x = 0.01*this->grasp_search_area_size_x_dir/ gripperwidth;
01173 (*marker).scale.y = 0.01*this->grasp_search_area_size_y_dir;
01174 (*marker).scale.z = 0.001;
01175 (*marker).lifetime = ros::Duration();
01176 break;
01177 }
01178
01179 case 2 : {
01180 (*marker).id = fix_marker_id_grasp_search_area2;
01181 (*marker).type = visualization_msgs::Marker::CUBE;
01182 (*marker).action = visualization_msgs::Marker::ADD;
01183 (*marker).color.a = 0.4;
01184 (*marker).color.r = 0.2;
01185 (*marker).color.g = 0.2;
01186 (*marker).color.b = 0.2;
01187 (*marker).pose.position.x = 0;
01188 (*marker).pose.position.y = 0;
01189 (*marker).pose.position.z = z;
01190
01191 tf::Vector3 zaxis(0, 0, 1);
01192 tf::Quaternion qt_compensate_rot(zaxis, nr_roll*ROLL_STEPS_DEGREE*PI/180);
01193 geometry_msgs::Quaternion quat_msg_compensate_rot;
01194 tf::quaternionTFToMsg(qt_compensate_rot, quat_msg_compensate_rot);
01195 (*marker).pose.orientation = quat_msg_compensate_rot;
01196
01197 (*marker).scale.x = 0.01*(this->grasp_search_area_size_x_dir-14)/ gripperwidth;
01198 (*marker).scale.y = 0.01*(this->grasp_search_area_size_y_dir-14);
01199 (*marker).scale.z = 0.001;
01200 (*marker).lifetime = ros::Duration();
01201 break;
01202 }
01203 case 3 : {
01204 (*marker).id = fix_marker_id_gripper_dir;
01205 (*marker).type = visualization_msgs::Marker::CUBE;
01206 (*marker).action = visualization_msgs::Marker::ADD;
01207 (*marker).color.a = 0.8;
01208 (*marker).color.r = 1.0;
01209 (*marker).color.g = 0.0;
01210 (*marker).color.b = 0.0;
01211 if (top_grasp){
01212 (*marker).pose.position.x = x;
01213 (*marker).pose.position.y = y;
01214 (*marker).pose.position.z = z;
01215 (*marker).scale.x = 0.5 * 1 / gripperwidth;
01216 (*marker).scale.y = 0.002;
01217 (*marker).scale.z = 0.002;
01218
01219
01220 visualization_msgs::Marker markerdummy;
01221 gp_to_marker(&markerdummy, this->graspsearchcenter.x,this->graspsearchcenter.y,this->graspsearchcenter.z, 1, false, 1, nr_roll, false, false);
01222 } else {
01223 (*marker).pose.position.x = 0;
01224 (*marker).pose.position.y = 0;
01225 (*marker).pose.position.z = z;
01226 (*marker).scale.x = 0.5 * 1 / gripperwidth;
01227 (*marker).scale.y = 0.002;
01228 (*marker).scale.z = 0.002;
01229 (*marker).lifetime = ros::Duration(3);
01230 tf::Vector3 marker_gripper_open_dir_axis(0, 0, 1);
01231 tf::Quaternion qt_gripper_open_dir(marker_gripper_open_dir_axis, 0*(-nr_roll)*ROLL_STEPS_DEGREE*PI/180);
01232 geometry_msgs::Quaternion quat_msg_gripper_open_dir;
01233 tf::quaternionTFToMsg(qt_gripper_open_dir, quat_msg_gripper_open_dir);
01234 (*marker).pose.orientation = quat_msg_gripper_open_dir;
01235 }
01236 (*marker).lifetime = ros::Duration();
01237 break;
01238 }
01239 case 4 : {
01240 (*marker).header.frame_id = this->base_frame_id;
01241 (*marker).id = fix_marker_id_gripper_appr_dir;
01242 (*marker).type = visualization_msgs::Marker::ARROW;
01243 (*marker).action = visualization_msgs::Marker::ADD;
01244 (*marker).color.a = 0.8;
01245 (*marker).color.r = 0.0;
01246 (*marker).color.g = 0.0;
01247 (*marker).color.b = 0.0;
01248 float markerlength = 0.1;
01249 (*marker).pose.position.x = x + markerlength*this->approach_vector.x;
01250 (*marker).pose.position.y = y + markerlength*this->approach_vector.y;
01251 (*marker).pose.position.z = z + markerlength*this->approach_vector.z;
01252 (*marker).scale.x = markerlength;
01253 (*marker).scale.y = 0.003;
01254 (*marker).scale.z = 0.003;
01255 (*marker).lifetime = ros::Duration(3);
01256 tf::Vector3 marker_axis(0, 1, 0);
01257 tf::Quaternion qt(marker_axis, PI/2);
01258 geometry_msgs::Quaternion quat_msg;
01259 tf::quaternionTFToMsg( (this->quat_tf_to_tf_help)*qt, quat_msg);
01260 (*marker).pose.orientation = quat_msg;
01261 (*marker).lifetime = ros::Duration();
01262 break;
01263 }
01264 default: cout << "CCalc_Grasppoints::grasp_area_to_marker: WRONG INPUT FOR param_id " << endl;
01265 break;
01266 }
01267 }
01268
01269
01270
01271 void CCalc_Grasppoints::transform_gp_in_wcs_and_publish(int id_row_top_all, int id_col_top_all,int nr_roll_top_all, int nr_tilt_top_all, int scaled_gp_eval){
01272 cout << "\n ===> transform_gp_in_wcs_and_publish(): TRANSFORM FOUND GRASP" << endl;
01273 Eigen::Matrix4f mat_sh_to_orig = Eigen::Matrix4f::Identity();
01274 Eigen::Matrix4f mat_rot_z_axis = Eigen::Matrix4f::Identity();
01275 Eigen::Matrix4f mat_rot_x_axis = Eigen::Matrix4f::Identity();
01276 Eigen::Matrix4f mat_sh_from_orig = Eigen::Matrix4f::Identity();
01277 Eigen::Matrix4f mat_rot = Eigen::Matrix4f::Identity();
01278 Eigen::Matrix4f mat_scale_x_dir = Eigen::Matrix4f::Identity();
01279
01280 Eigen::Matrix4f mat_transform = Eigen::Matrix4f::Identity();
01281
01282 Eigen::Matrix3f mat_rot_for_appr_vec = Eigen::Matrix3f::Identity();
01283
01284 float rot_about_z;
01285 float rot_about_x = 0;
01286
01287 mat_scale_x_dir(0,0) = this->gripper_opening_width;
01288
01289 mat_sh_to_orig(0,3) = -this->graspsearchcenter.x;
01290 mat_sh_to_orig(1,3) = -this->graspsearchcenter.y;
01291 mat_sh_to_orig(2,3) = -this->graspsearchcenter.z;
01292
01293 mat_sh_from_orig(0,3) = 0;
01294 mat_sh_from_orig(1,3) = 0;
01295 mat_sh_from_orig(2,3) = 0 + this->trans_z_after_pc_transform;
01296
01297 if (this->approach_vector.y == 0 and this->approach_vector.x == 0){
01298 rot_about_z = 0;
01299 if (this->approach_vector.z >= 0) {
01300 rot_about_x = 0;
01301 } else {
01302 rot_about_x = PI;
01303 }
01304 } else {
01305 rot_about_z = 90*PI/180.0 - atan2(this->approach_vector.y, this->approach_vector.x);
01306 rot_about_x = 90*PI/180.0 - atan2( this->approach_vector.z, sqrt(this->approach_vector.y*this->approach_vector.y + this->approach_vector.x*this->approach_vector.x) );
01307 }
01308
01309
01310
01311
01312 float angle = nr_roll_top_all*ROLL_STEPS_DEGREE*PI/180;
01313 mat_rot(0,0) = cos(angle);
01314 mat_rot(0,1) = -sin(angle);
01315 mat_rot(1,0) = sin(angle);
01316 mat_rot(1,1) = cos(angle);
01317
01318
01319 mat_rot_z_axis(0,0) = cos(rot_about_z);
01320 mat_rot_z_axis(0,1) = -sin(rot_about_z);
01321 mat_rot_z_axis(1,0) = sin(rot_about_z);
01322 mat_rot_z_axis(1,1) = cos(rot_about_z);
01323
01324
01325 mat_rot_x_axis(1,1) = cos(rot_about_x);
01326 mat_rot_x_axis(1,2) = -sin(rot_about_x);
01327 mat_rot_x_axis(2,1) = sin(rot_about_x);
01328 mat_rot_x_axis(2,2) = cos(rot_about_x);
01329
01330
01331 mat_transform = mat_scale_x_dir * mat_rot * mat_sh_from_orig * mat_rot_x_axis * mat_rot_z_axis * mat_sh_to_orig;
01332
01333
01334 cout << " ---> id_row_top_all: " << id_row_top_all << "\t" << "id_col_top_all: " << id_col_top_all << "\t and rotation: " << nr_roll_top_all*ROLL_STEPS_DEGREE << " tilt_top: " << nr_tilt_top_all <<endl;
01335
01336 float x_gp_roll = - ((float)(HEIGHT/2 - id_row_top_all))/100;
01337 float y_gp_roll = - ((float)(WIDTH/2 - id_col_top_all))/100;
01338
01339 float h_locmax_roll = -10;
01340 for (int row_z = -4; row_z < 5; row_z++){
01341 for (int col_z = -4; col_z < 4; col_z++){
01342
01343 if (id_row_top_all+row_z >= 0 and id_col_top_all+col_z>=0 and h_locmax_roll < this->heightsgridroll[nr_roll_top_all][nr_tilt_top_all][id_row_top_all+row_z][id_col_top_all+col_z]){
01344 h_locmax_roll = this->heightsgridroll[nr_roll_top_all][nr_tilt_top_all][id_row_top_all+row_z][id_col_top_all+col_z];
01345
01346 }
01347 }
01348 }
01349
01350
01351 h_locmax_roll -= 0.01;
01352 float z_gp_roll = h_locmax_roll;
01353 cout << " ---> x_roll: "<< x_gp_roll << "\t y_roll: " << y_gp_roll << "\t z_gp_roll: " << z_gp_roll << endl;
01354
01355
01356
01357 float x_gp_dis = 0.03;
01358
01359 Eigen::Vector4f gp1(x_gp_roll-x_gp_dis, y_gp_roll,z_gp_roll,1.0);
01360 Eigen::Vector4f gp2(x_gp_roll+x_gp_dis, y_gp_roll,z_gp_roll,1.0);
01361 Eigen::Vector4f gp1_wcs, gp2_wcs;
01362 Eigen::Vector3f appr_vec(0,0,1);
01363
01364 gp1_wcs = mat_transform.inverse()*gp1;
01365 gp2_wcs = mat_transform.inverse()*gp2;
01366
01367 mat_rot_for_appr_vec << this->av_trans_mat(0,0),this->av_trans_mat(1,0),this->av_trans_mat(2,0),
01368 this->av_trans_mat(0,1),this->av_trans_mat(1,1),this->av_trans_mat(2,1),
01369 this->av_trans_mat(0,2),this->av_trans_mat(1,2),this->av_trans_mat(2,2);
01370
01371 appr_vec = mat_rot_for_appr_vec*appr_vec;
01372
01373 cout << " ---> GP_1: x_roll_wcs: "<< gp1_wcs[0] << "\t y_roll_wcs: " << gp1_wcs[1] << "\t z_roll_wcs: " << gp1_wcs[2] << endl;
01374 cout << " ---> GP_2: x_roll_wcs: "<< gp2_wcs[0] << "\t y_roll_wcs: " << gp2_wcs[1] << "\t z_roll_wcs: " << gp2_wcs[2] << endl;
01375
01376
01377
01378 std_msgs::String msgStrPoints;
01379 std::stringstream ss;
01380
01381 ss << scaled_gp_eval << " " << gp1_wcs[0] <<" "<< gp1_wcs[1] << " "<< gp1_wcs[2] << " "<< gp2_wcs[0] << " " << gp2_wcs[1] << " " << gp2_wcs[2] << " "<< appr_vec(0) << " "<< appr_vec(1) << " "<< appr_vec(2) << " " << (gp1_wcs[0]+gp2_wcs[0])/2.0 <<" " << (gp1_wcs[1]+gp2_wcs[1])/2.0 <<" " << (gp1_wcs[2]+gp2_wcs[2])/2.0 <<" " << nr_roll_top_all*ROLL_STEPS_DEGREE;
01382 msgStrPoints.data = ss.str();
01383 this->gp_result.header.stamp = ros::Time::now();
01384 this->gp_result.header.frame_id = this->base_frame_id;
01385 this->gp_result.eval = scaled_gp_eval;
01386 this->gp_result.graspPoint1.x = gp1_wcs[0];
01387 this->gp_result.graspPoint1.y = gp1_wcs[1];
01388 this->gp_result.graspPoint1.z = gp1_wcs[2];
01389 this->gp_result.graspPoint2.x = gp2_wcs[0];
01390 this->gp_result.graspPoint2.y = gp2_wcs[1];
01391 this->gp_result.graspPoint2.z = gp2_wcs[2];
01392 this->gp_result.averagedGraspPoint.x = (gp1_wcs[0]+gp2_wcs[0])/2.0;
01393 this->gp_result.averagedGraspPoint.y = (gp1_wcs[1]+gp2_wcs[1])/2.0;
01394 this->gp_result.averagedGraspPoint.z = (gp1_wcs[2]+gp2_wcs[2])/2.0;
01395 this->gp_result.approachVector.x = appr_vec(0);
01396 this->gp_result.approachVector.y = appr_vec(1);
01397 this->gp_result.approachVector.z = appr_vec(2);
01398 this->gp_result.roll = (nr_roll_top_all * ROLL_STEPS_DEGREE * PI) / 180;
01399
01400
01401 visualization_msgs::Marker marker_best_params;
01402 visualization_msgs::MarkerArray ma_best_params;
01403
01404 for (int i = 3; i <= 3; i++){
01405 grasp_area_to_marker(&marker_best_params, (gp1[0]+gp2[0])/2,(gp1[1]+gp2[1])/2,(gp1[2]+gp2[2])/2, this->gripper_opening_width , nr_roll_top_all, i , true );
01406 ma_best_params.markers.push_back(marker_best_params);
01407 }
01408 for (int i = 4; i <= 4; i++){
01409 grasp_area_to_marker(&marker_best_params, (gp1_wcs[0]+gp2_wcs[0])/2,(gp1_wcs[1]+gp2_wcs[1])/2,(gp1_wcs[2]+gp2_wcs[2])/2, this->gripper_opening_width , nr_roll_top_all, i , true );
01410 ma_best_params.markers.push_back(marker_best_params);
01411 }
01412 vis_pub_ma_params.publish(ma_best_params);
01413
01414
01415 cout << " ---> Scaled GP Evaluation (-20-99) [-20 <=> no GP found]: " << scaled_gp_eval << endl;
01416 pubGraspPointsEval.publish(msgStrPoints);
01417
01418 }
01419
01420
01421
01422 int main (int argc, char** argv)
01423 {
01424 ROS_INFO("ROS NODE calc_grasppoints_svm_action_server (from package haf_grasping) started");
01425 ros::init(argc, argv, "calc_grasppoints_svm_action_server");
01426 CCalc_Grasppoints * calc_gps = new CCalc_Grasppoints(ros::this_node::getName());
01427 ros::spin();
01428 return (0);
01429 }
01430