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 #include "graspit_interface/ros_graspit_interface.h"
00036
00037 #include <boost/foreach.hpp>
00038 #include <cmath>
00039 #include <Inventor/actions/SoGetBoundingBoxAction.h>
00040
00041 #include <src/DBase/DBPlanner/ros_database_manager.h>
00042 #include <src/DBase/graspit_db_model.h>
00043 #include <src/Collision/collisionStructures.h>
00044 #include <include/EGPlanner/searchEnergy.h>
00045 #include <include/mytools.h>
00046 #include <include/world.h>
00047 #include <include/body.h>
00048 #include <include/graspitGUI.h>
00049 #include <include/ivmgr.h>
00050 #include <include/scanSimulator.h>
00051 #include <include/pr2Gripper.h>
00052
00053 #include <sensor_msgs/PointCloud.h>
00054 #include <sensor_msgs/point_cloud_conversion.h>
00055
00056 template<typename T>
00057 inline T mean(const std::vector<T> &input)
00058 {
00059 T total = 0.0;
00060 BOOST_FOREACH(const T &val, input)
00061 {
00062 total += val;
00063 }
00064 return total / input.size();
00065 }
00066 ;
00067
00068 template<typename T>
00069 inline T stddev(const std::vector<T> &input)
00070 {
00071 T m = mean(input);
00072 T total_err = 0.0;
00073 BOOST_FOREACH(const T &val, input)
00074 {
00075 total_err += std::pow(m - val, 2);
00076 }
00077
00078 total_err /= input.size();
00079
00080 return std::sqrt(total_err);
00081 }
00082
00083 namespace graspit_interface
00084 {
00085
00086 transf poseToTransf(const geometry_msgs::Pose &pose)
00087 {
00088 return transf(Quaternion(pose.orientation.w, pose.orientation.x, pose.orientation.y, pose.orientation.z),
00089 vec3(1000 * pose.position.x, 1000 * pose.position.y, 1000 * pose.position.z));
00090 }
00091
00092 geometry_msgs::Pose transfToPose(const transf &tr)
00093 {
00094 geometry_msgs::Pose pose;
00095 return pose;
00096 }
00097
00098 inline void getSbBoxDimension(SbBox3f& bbx, vec3& dimension)
00099 {
00100
00101 float xmin, ymin, zmin, xmax, ymax, zmax;
00102 bbx.getBounds(xmin, ymin, zmin, xmax, ymax, zmax);
00103 dimension.set(xmax - xmin, ymax - ymin, zmax - zmin);
00104 ROS_INFO("Boundind box: (%.3lf, %.3lf, %.3lf), (%.3lf, %.3lf, %.3lf) ", xmin, ymin, zmin, xmax, ymax, zmax);
00105 }
00106
00107 inline bool smallerThanSbVec3f(const SbVec3f& b1, const SbVec3f& b2)
00108 {
00109 float x1, y1, z1, x2, y2, z2;
00110 b1.getValue(x1, y1, z1);
00111 b2.getValue(x2, y2, z2);
00112
00113 if (x1 <= x2 && y1 <= y2 && z1 <= z2)
00114 return true;
00115 else
00116 return false;
00117 }
00118
00119 inline bool biggerThanSbVec3f(const SbVec3f& b1, const SbVec3f& b2)
00120 {
00121 float x1, y1, z1, x2, y2, z2;
00122 b1.getValue(x1, y1, z1);
00123 b2.getValue(x2, y2, z2);
00124
00125 if (x1 >= x2 && y1 >= y2 && z1 >= z2)
00126 return true;
00127 else
00128 return false;
00129 }
00130
00131 inline double randomUniformReal(double min, double max)
00132 {
00133 return ((1.0 * rand() / RAND_MAX) * (max - min) + min);
00134 }
00135
00136 void randomPoseGenerate(SbBox3f &bb_space, geometry_msgs::Pose& grasp_random_pose)
00137 {
00138
00139 float xmin, ymin, zmin, xmax, ymax, zmax;
00140 bb_space.getBounds(xmin, ymin, zmin, xmax, ymax, zmax);
00141
00142
00143 grasp_random_pose.position.x = randomUniformReal(xmin, xmax);
00144 grasp_random_pose.position.y = randomUniformReal(ymin, ymax);
00145 grasp_random_pose.position.z = randomUniformReal(zmin, zmax);
00146
00147
00148 double angle = randomUniformReal(0, 2.0 * M_PI);
00149 vec3 axis(randomUniformReal(0 + 0.0001, 1), randomUniformReal(0, 1), randomUniformReal(0, 1));
00150 Quaternion orientation(angle, axis);
00151
00152 grasp_random_pose.orientation.w = orientation.w;
00153 grasp_random_pose.orientation.x = orientation.x;
00154 grasp_random_pose.orientation.y = orientation.y;
00155 grasp_random_pose.orientation.z = orientation.z;
00156 }
00157
00158 RosGraspitInterface::RosGraspitInterface() :
00159 root_nh_(NULL), priv_nh_(NULL), db_mgr_(NULL)
00160 {
00161 default_energy_threshold_ = 68.6;
00162 }
00163
00164 RosGraspitInterface::~RosGraspitInterface()
00165 {
00166 ROS_INFO("ROS GraspIt node stopping");
00167 ros::shutdown();
00168 delete root_nh_;
00169 delete priv_nh_;
00170 delete db_mgr_;
00171 }
00172
00173 int RosGraspitInterface::init(int argc, char **argv)
00174 {
00175
00176 int ros_argc = argc;
00177 char** ros_argv = new char*[argc];
00178 for (int i = 0; i < argc; i++)
00179 {
00180 ros_argv[i] = new char[strlen(argv[i])];
00181 strcpy(ros_argv[i], argv[i]);
00182 }
00183
00184 std::string node_name("ros_graspit_interface");
00185 for (int i = 0; i < argc - 1; i++)
00186 {
00187
00188 if (!strcmp(argv[i], "_name"))
00189 {
00190 node_name = argv[i + 1];
00191 }
00192 }
00193
00194 ros::init(ros_argc, ros_argv, node_name.c_str());
00195
00196
00197 for (int i = 0; i < argc; i++)
00198 {
00199 delete ros_argv[i];
00200 }
00201 delete ros_argv;
00202
00203 root_nh_ = new ros::NodeHandle("");
00204 priv_nh_ = new ros::NodeHandle("~");
00205
00206 load_model_srv_ = priv_nh_->advertiseService("load_database_model", &RosGraspitInterface::loadModelCB, this);
00207 load_obstacle_srv_ = priv_nh_->advertiseService("load_obstacle", &RosGraspitInterface::loadObstacleCB, this);
00208 clear_bodies_srv_ = priv_nh_->advertiseService("clear_bodies", &RosGraspitInterface::clearBodiesCB, this);
00209 simulate_scan_srv_ = priv_nh_->advertiseService("simulate_scan", &RosGraspitInterface::simulateScanCB, this);
00210 test_grasp_srv_ = priv_nh_->advertiseService("test_grasp", &RosGraspitInterface::testGraspCB, this);
00211 grasp_planning_srv_ = priv_nh_->advertiseService("grasp_planning", &RosGraspitInterface::graspPlanningCB, this);
00212
00213 generate_grasp_srv_ = priv_nh_->advertiseService("generate_grasp", &RosGraspitInterface::generateGraspCB, this);
00214
00215 scan_publisher_ = priv_nh_->advertise<sensor_msgs::PointCloud2> ("simulated_scans", 5);
00216
00217 verify_grasp_srv_ = priv_nh_->advertiseService("verify_grasp", &RosGraspitInterface::verifyGraspCB, this);
00218
00219 srand(1);
00220
00221
00222 db_mgr_ = new db_planner::RosDatabaseManager("wgs36", "5432", "willow", "willow", "household_objects", NULL, NULL);
00223
00224 GeomGraspitDBModelAllocator* allocator = new GeomGraspitDBModelAllocator(db_mgr_);
00225 db_mgr_->SetModelAllocator(allocator);
00226 gripper_ = NULL;
00227 if (!db_mgr_->isConnected())
00228 {
00229 ROS_ERROR("Failed to connect to database");
00230 return -1;
00231 }
00232 ROS_INFO("ROS GraspIt node ready");
00233 return 0;
00234 }
00235
00236 int RosGraspitInterface::mainLoop()
00237 {
00238 ros::spinOnce();
00239 return 0;
00240 }
00241
00246 GraspitDBModel* RosGraspitInterface::getModel(int model_id)
00247 {
00248 std::map<int, GraspitDBModel*>::iterator it = models_.find(model_id);
00249 if (it != models_.end())
00250 return it->second;
00251
00252
00253 db_planner::Model* db_model;
00254 if (!db_mgr_->ScaledModel(db_model, model_id))
00255 {
00256 ROS_ERROR("Failed to load database model with id %d", model_id);
00257 return NULL;
00258 }
00259 GraspitDBModel *model = static_cast<GraspitDBModel*> (db_model);
00260 models_.insert(std::pair<int, GraspitDBModel*>(model_id, model));
00261 return model;
00262 }
00263
00264 bool RosGraspitInterface::loadGripper()
00265 {
00266 World *world = graspItGUI->getIVmgr()->getWorld();
00267 if (gripper_)
00268 {
00269 ROS_WARN("Gripper load requested, but gripper already present. Re-loading.");
00270 world->removeRobot(gripper_);
00271 }
00272 std::string hand_path("/models/robots/pr2_gripper/pr2_gripper_2010.xml");
00273 hand_path = getenv("GRASPIT") + hand_path;
00274 gripper_ = static_cast<Pr2Gripper2010*> (world->importRobot(QString(hand_path.c_str())));
00275 if (!gripper_)
00276 {
00277 ROS_ERROR("Failed to load PR2 gripper from file %s", hand_path.c_str());
00278 return false;
00279 }
00280 return true;
00281 }
00282
00283 bool RosGraspitInterface::loadModelCB(graspit_interface_msgs::LoadDatabaseModel::Request &request,
00284 graspit_interface_msgs::LoadDatabaseModel::Response &response)
00285 {
00286
00287 GraspitDBModel *model = getModel(request.model_id);
00288 if (!model)
00289 {
00290 response.result = response.LOAD_FAILURE;
00291 return true;
00292 }
00293
00294
00295 World *world = graspItGUI->getIVmgr()->getWorld();
00296 if (!model->geometryLoaded())
00297 {
00298 if (model->load(world) != SUCCESS)
00299 {
00300 ROS_ERROR("Failed to load geometry for database model with id %d", request.model_id);
00301 response.result = response.LOAD_FAILURE;
00302 return true;
00303 }
00304 }
00305
00306
00307 if (request.clear_other_models)
00308 {
00309 bool done = false;
00310 while (!done)
00311 {
00312 done = true;
00313 for (int i = 0; i < world->getNumGB(); i++)
00314 {
00315 if (world->getGB(i) != model->getGraspableBody())
00316 {
00317 world->destroyElement(world->getGB(i), false);
00318 done = false;
00319 break;
00320 }
00321 }
00322 }
00323 }
00324
00325
00326 if (world->getIVRoot()->findChild(model->getGraspableBody()->getIVRoot()) == -1)
00327 {
00328 model->getGraspableBody()->addToIvc();
00329 world->addBody(model->getGraspableBody());
00330 }
00331
00332
00333 model->getGraspableBody()->setTran(poseToTransf(request.model_pose));
00334 model->getGraspableBody()->showAxes(false);
00335 response.result = response.LOAD_SUCCESS;
00336 return true;
00337 }
00338
00339 bool RosGraspitInterface::clearBodiesCB(graspit_interface_msgs::ClearBodies::Request &request,
00340 graspit_interface_msgs::ClearBodies::Response &response)
00341 {
00342 World *world = graspItGUI->getIVmgr()->getWorld();
00343 if (request.which_bodies == request.GRASPABLE_BODIES || request.which_bodies == request.ALL_BODIES)
00344 {
00345 while (world->getNumGB() > 0)
00346 {
00347
00348
00349
00350 world->destroyElement(world->getGB(0), false);
00351 }
00352 ROS_INFO("Cleared graspable bodies");
00353 }
00354 if (request.which_bodies == request.OBSTACLES || request.which_bodies == request.ALL_BODIES)
00355 {
00356 bool removal = true;
00357 while (removal)
00358 {
00359 removal = false;
00360 for (int i = 0; i < world->getNumBodies(); i++)
00361 {
00362 if (!world->getBody(i)->inherits("DynamicBody"))
00363 {
00364
00365 world->destroyElement(world->getBody(i), true);
00366 removal = true;
00367 break;
00368 }
00369 }
00370 }
00371 ROS_INFO("Cleared obstacles bodies");
00372 }
00373 return true;
00374 }
00375
00376 bool RosGraspitInterface::loadObstacleCB(graspit_interface_msgs::LoadObstacle::Request &request,
00377 graspit_interface_msgs::LoadObstacle::Response &response)
00378 {
00379 std::string filename = getenv("GRASPIT") + std::string("/") + request.file_name;
00380 World *world = graspItGUI->getIVmgr()->getWorld();
00381 Body *body = world->importBody("Body", QString(filename.c_str()));
00382 if (!body)
00383 {
00384 ROS_ERROR("Failed to import obstacle from file %s", filename.c_str());
00385 response.result = response.LOAD_FAILURE;
00386 return true;
00387 }
00388
00389
00390 body->setTran(poseToTransf(request.obstacle_pose));
00391 response.result = response.LOAD_SUCCESS;
00392 return true;
00393 }
00394
00395 bool RosGraspitInterface::simulateScanCB(graspit_interface_msgs::SimulateScan::Request &request,
00396 graspit_interface_msgs::SimulateScan::Response &response)
00397 {
00398 ScanSimulator scan_sim;
00399 scan_sim.setType(ScanSimulator::SCANNER_COORDINATES);
00400 scan_sim.setPosition(poseToTransf(request.scanner_pose), ScanSimulator::STEREO_CAMERA);
00401
00402 double horiz_fov = 45;
00403
00404 double horiz_res = 640;
00405 double vertical_res = 480;
00406 double vertical_fov = horiz_fov * vertical_res / horiz_res;
00407 scan_sim.setOptics(-horiz_fov / 2.0, horiz_fov / 2.0, horiz_res, -vertical_fov / 2.0, vertical_fov / 2.0,
00408 vertical_res);
00409
00410
00411 World *world = graspItGUI->getIVmgr()->getWorld();
00412 if (gripper_)
00413 {
00414 world->removeElementFromSceneGraph(gripper_);
00415 }
00416
00417 std::vector<position> cloud;
00418 ROS_INFO("Simulating scan...");
00419
00420 if (request.request_ray_directions)
00421 {
00422 std::vector<RawScanPoint> rawData;
00423 scan_sim.scan(&cloud, &rawData);
00424 ROS_INFO("Simulated scan has %d points, %d rays", (int)cloud.size(), (int)rawData.size());
00425
00426 response.missing_ray_directions.reserve(rawData.size());
00427 for (size_t j = 0; j < rawData.size(); j++)
00428 {
00429 if (rawData[j].distance < -0.9)
00430 {
00431 geometry_msgs::Point32 dir;
00432 dir.x = rawData[j].dx;
00433 dir.y = rawData[j].dy;
00434 dir.z = rawData[j].dz;
00435 response.missing_ray_directions.push_back(dir);
00436 }
00437 }
00438 }
00439 else
00440 {
00441 scan_sim.scan(&cloud);
00442 ROS_INFO("Simulated scan has %d points", (int)cloud.size());
00443 }
00444 if (gripper_)
00445 {
00446 world->addElementToSceneGraph(gripper_);
00447 }
00448
00449
00450
00451
00452 ROS_INFO("Converting scan to ROS format");
00453 sensor_msgs::PointCloud point_cloud;
00454 for (size_t i = 0; i < cloud.size(); i++)
00455 {
00456 geometry_msgs::Point32 point;
00457 point.x = 1.0e-3 * cloud[i].x();
00458 point.y = 1.0e-3 * cloud[i].y();
00459 point.z = 1.0e-3 * cloud[i].z();
00460 point_cloud.points.push_back(point);
00461 }
00462 point_cloud.header.frame_id = "graspit_scanner_frame";
00463 point_cloud.header.stamp = ros::Time::now();
00464
00465 sensor_msgs::convertPointCloudToPointCloud2(point_cloud, response.scan);
00466 response.scan.header.stamp = ros::Time::now();
00467
00468
00469 ROS_INFO("Publishing scan");
00470 scan_publisher_.publish(response.scan);
00471
00472 return true;
00473 }
00474
00475 void RosGraspitInterface::gripperCollisionCheck(const Body *object,
00476 graspit_interface_msgs::TestGrasp::Response &response)
00477 {
00478 response.hand_environment_collision = false;
00479 response.hand_object_collision = false;
00480 std::vector<DynamicBody*> gripper_link_list;
00481 gripper_->getAllLinks(gripper_link_list);
00482 std::vector<Body*> interest_list;
00483 for (size_t i = 0; i < gripper_link_list.size(); i++)
00484 {
00485 interest_list.push_back(gripper_link_list[i]);
00486 }
00487 CollisionReport collision_report;
00488 World *world = graspItGUI->getIVmgr()->getWorld();
00489 world->getCollisionReport(&collision_report, &interest_list);
00490 for (size_t i = 0; i < collision_report.size(); i++)
00491 {
00492
00493 Body *collision_body = collision_report[i].first;
00494 if (collision_body->getOwner() == gripper_)
00495 {
00496 collision_body = collision_report[i].second;
00497 }
00498 if (collision_body == object)
00499 response.hand_object_collision = true;
00500 else
00501 response.hand_environment_collision = true;
00502 }
00503 }
00504
00505 void RosGraspitInterface::computeEnergy(Body *object, graspit_interface_msgs::TestGrasp::Response &response)
00506 {
00507 SearchEnergy energy_calculator;
00508 energy_calculator.setType(ENERGY_CONTACT);
00509 energy_calculator.setContactType(CONTACT_PRESET);
00510 bool legal;
00511 double energy;
00512 energy_calculator.analyzeCurrentPosture(gripper_, object, legal, energy, false);
00513 if (!legal)
00514 {
00515
00516 ROS_WARN("Energy calculator reports illegal state");
00517 response.test_result = response.HAND_COLLISION;
00518 response.energy_value = -1.0;
00519 return;
00520 }
00521 response.energy_value = energy;
00522
00523 if (energy < 10.0)
00524 response.test_result = response.GRASP_SUCCESS;
00525 else
00526 response.test_result = response.GRASP_FAILURE;
00527 }
00528
00529 bool RosGraspitInterface::verifyGraspCB(graspit_interface_msgs::VerifyGrasp::Request &request,
00530 graspit_interface_msgs::VerifyGrasp::Response &response)
00531 {
00532 response.hand_environment_collision = false;
00533 response.hand_object_collision = false;
00534
00535
00536
00537 graspit_interface_msgs::LoadDatabaseModel::Request req_load_object;
00538 graspit_interface_msgs::LoadDatabaseModel::Response res_load_object;
00539
00540 World *world_p = graspItGUI->getIVmgr()->getWorld();
00541 GraspableBody *object = NULL;
00542 Body *obstacle = NULL;
00543
00544 std::string filename = getenv("GRASPIT") + std::string("/") + request.table_file_name;
00545
00546 req_load_object.model_id = request.scaled_model_id;
00547 req_load_object.model_pose = geometry_msgs::Pose();
00548 req_load_object.model_pose.orientation.w = 1.0;
00549 req_load_object.clear_other_models = true;
00550
00551 loadModelCB(req_load_object, res_load_object);
00552
00553 if (res_load_object.result == graspit_interface_msgs::LoadDatabaseModel::Response::LOAD_FAILURE)
00554 {
00555 response.result = graspit_interface_msgs::VerifyGrasp::Response::LOAD_OBJECT_FAILURE;
00556 ROS_WARN_STREAM("Object load failed!");
00557 return true;
00558 }
00559
00560 object = world_p->getGB(0);
00561
00562
00563 SoGetBoundingBoxAction bboxAction(graspItGUI->getIVmgr()->getViewer()->getViewportRegion());
00564 bboxAction.apply(object->getIVRoot());
00565 SbBox3f object_bbx = bboxAction.getBoundingBox();
00566 vec3 obj_bbx_dim;
00567 SbVec3f object_bbx_min, object_bbx_max;
00568 object_bbx.getBounds(object_bbx_min, object_bbx_max);
00569 getSbBoxDimension(object_bbx, obj_bbx_dim);
00570
00571
00572
00573 for (int i = 0; i < world_p->getNumBodies(); i++)
00574 {
00575 if (world_p->getBody(i)->getFilename().compare(QString(request.table_file_name.c_str())) == 0)
00576 {
00577 obstacle = world_p->getBody(i);
00578 break;
00579 }
00580 }
00581
00582 graspit_interface_msgs::LoadObstacle::Request req_load_obstacle;
00583 req_load_obstacle.file_name = request.table_file_name;
00584 req_load_obstacle.obstacle_pose = geometry_msgs::Pose();
00585 req_load_obstacle.obstacle_pose.orientation.w = 1.0;
00586 if (obstacle == NULL)
00587 {
00588 graspit_interface_msgs::LoadObstacle::Response res_load_obstacle;
00589
00590 loadObstacleCB(req_load_obstacle, res_load_obstacle);
00591
00592 if (res_load_obstacle.result == graspit_interface_msgs::LoadObstacle::Response::LOAD_FAILURE)
00593 {
00594 response.result = graspit_interface_msgs::VerifyGrasp::Response::LOAD_OBSTACLE_FAILURE;
00595 ROS_WARN_STREAM("Tabletop load failed!");
00596 return true;
00597 }
00598
00599 for (int i = 0; i < world_p->getNumBodies(); i++)
00600 {
00601 if (world_p->getBody(i)->getFilename().compare(QString(request.table_file_name.c_str())) == 0)
00602 {
00603 obstacle = world_p->getBody(i);
00604 break;
00605 }
00606 }
00607 }
00608
00609
00610 bboxAction.apply(obstacle->getIVRoot());
00611 SbBox3f obstacle_bbx = bboxAction.getBoundingBox();
00612 vec3 obstacle_bbx_dim;
00613 SbVec3f obstacle_bbx_min, obstacle_bbx_max;
00614 obstacle_bbx.getBounds(obstacle_bbx_min, obstacle_bbx_max);
00615 ROS_INFO("Tabletop");
00616 getSbBoxDimension(obstacle_bbx, obstacle_bbx_dim);
00617
00618 float obstacle_current_z = obstacle->getTran().translation().z();
00619 float obstacle_top_z = obstacle_bbx_max[2];
00620 float object_bottom_z = object_bbx_min[2];
00621 float new_obstacle_z = obstacle_current_z + object_bottom_z - obstacle_top_z;
00622 req_load_obstacle.obstacle_pose.position.z = new_obstacle_z * 0.001;
00623 obstacle->setTran(poseToTransf(req_load_obstacle.obstacle_pose));
00624
00625 bboxAction.apply(obstacle->getIVRoot());
00626 SbBox3f obstacle_bbx_new = bboxAction.getBoundingBox();
00627 obstacle_bbx_new.getBounds(obstacle_bbx_min, obstacle_bbx_max);
00628 getSbBoxDimension(obstacle_bbx_new, obstacle_bbx_dim);
00629
00630
00631 if (!gripper_ && !loadGripper())
00632 {
00633 response.result = graspit_interface_msgs::VerifyGrasp::Response::LOAD_GRIPPER_FAILURE;
00634 ROS_WARN_STREAM("Gripper load failed!");
00635 return true;
00636 }
00637
00638
00639 response.result = graspit_interface_msgs::VerifyGrasp::Response::CHECK_SUCCESS;
00640
00641 gripper_->setTran(poseToTransf(request.grasp_pose));
00642
00643 gripper_->forceDOFVal(0, request.grasp_joint_angle);
00644
00645 graspit_interface_msgs::TestGrasp::Response test_collision_response;
00646
00647 response.gripper_tabletop_clearance = world_p->getDist(gripper_, obstacle);
00648 response.gripper_object_distance = world_p->getDist(gripper_, object);
00649 gripperCollisionCheck(object, test_collision_response);
00650
00651 bool any_collision = false;
00652
00653 if (test_collision_response.hand_environment_collision)
00654 {
00655 response.hand_environment_collision = true;
00656 ROS_WARN_STREAM("Collision with environment detected!");
00657 any_collision = true;
00658 }
00659 if (test_collision_response.hand_object_collision)
00660 {
00661 response.hand_object_collision = true;
00662 ROS_WARN_STREAM("Collision with object detected!");
00663 any_collision = true;
00664 }
00665
00666 if (request.grasp_pose.position.z < 0.0 && !test_collision_response.hand_environment_collision)
00667 {
00668 ROS_WARN_STREAM("Gripper under desktop, hack the collision result");
00669 response.hand_environment_collision = true;
00670 response.gripper_tabletop_clearance = -1.0;
00671 any_collision = true;
00672 }
00673
00674 if (!any_collision)
00675 ROS_WARN_STREAM("No Collision detected!");
00676 return true;
00677 }
00678
00679 bool RosGraspitInterface::generateGraspCB(graspit_interface_msgs::GenerateGrasp::Request &request,
00680 graspit_interface_msgs::GenerateGrasp::Response &response)
00681 {
00682
00683
00684 response.result = response.GENERATE_FAILURE;
00685
00686
00687 graspit_interface_msgs::LoadDatabaseModel::Request req_load_object;
00688 graspit_interface_msgs::LoadDatabaseModel::Response res_load_object;
00689
00690 static int last_model_id = 0;
00691 static int acc_count = 1;
00692
00693
00694 req_load_object.model_id = request.model_id;
00695 req_load_object.model_pose = geometry_msgs::Pose();
00696 req_load_object.model_pose.orientation.w = 1.0;
00697 req_load_object.clear_other_models = true;
00698
00699 loadModelCB(req_load_object, res_load_object);
00700
00701 if (res_load_object.result == res_load_object.LOAD_FAILURE)
00702 {
00703 response.result = response.GENERATE_FAILURE;
00704 ROS_INFO_STREAM("Object loaded failed!");
00705 return true;
00706 }
00707
00708
00709
00710
00711
00712 GraspitDBModel *model = getModel(request.model_id);
00713 if (!model)
00714 {
00715 response.result = response.GENERATE_FAILURE;
00716 return true;
00717 }
00718
00719
00720 if (!gripper_ && !loadGripper())
00721 {
00722 response.result = response.GENERATE_FAILURE;
00723 return true;
00724 }
00725
00726
00727
00728
00729 SoGetBoundingBoxAction bboxAction(graspItGUI->getIVmgr()->getViewer()->getViewportRegion());
00730 bboxAction.apply(model->getGraspableBody()->getIVRoot());
00731 SbBox3f object_bbx = bboxAction.getBoundingBox();
00732
00733 gripper_->setTran(transf());
00734
00735 gripper_->forceDOFVal(0, 0.26);
00736 bboxAction.apply(gripper_->getIVRoot());
00737 SbBox3f gripper_bbx = bboxAction.getBoundingBox();
00738
00739
00740 vec3 gripper_bbx_dim, obj_bbx_dim, bbs_dim;
00741
00742 getSbBoxDimension(gripper_bbx, gripper_bbx_dim);
00743
00744 double gripper_box_xdim = gripper_bbx_dim.x();
00745
00746 SbVec3f object_bbx_min, object_bbx_max;
00747 object_bbx.getBounds(object_bbx_min, object_bbx_max);
00748
00749 getSbBoxDimension(object_bbx, obj_bbx_dim);
00750
00751 SbBox3f bb_space;
00752 SbVec3f offset(30, 30, 0);
00753 SbVec3f offset2(30, 30, 30);
00754 if (last_model_id == request.model_id)
00755 {
00756 acc_count = (acc_count+1)%2;
00757 }
00758 else
00759 {
00760 acc_count = 0;
00761 }
00762 last_model_id = request.model_id;
00763 SbVec3f bb_min, bb_max;
00764 bb_min = object_bbx_min - SbVec3f(gripper_box_xdim, gripper_box_xdim, 0) + acc_count * offset;
00765 bb_max = object_bbx_max + SbVec3f(gripper_box_xdim, gripper_box_xdim, gripper_box_xdim) - acc_count * offset2;
00766
00767 bb_space.setBounds(bb_min, bb_max);
00768
00769 getSbBoxDimension(bb_space, bbs_dim);
00770
00771
00772 ROS_ASSERT(gripper_->getNumChains() == 2);
00773
00774
00775 geometry_msgs::Pose grasp_random_pose;
00776 graspit_interface_msgs::TestGrasp::Response test_grasp_res;
00777 std::vector<Body*> interest_list;
00778 interest_list.push_back(gripper_->getBase());
00779 interest_list.push_back(gripper_->getChain(0)->getLink(0));
00780 interest_list.push_back(gripper_->getChain(1)->getLink(0));
00781 if (request.reject_fingertip_collision)
00782 {
00783 interest_list.push_back(gripper_->getChain(0)->getLink(1));
00784 interest_list.push_back(gripper_->getChain(1)->getLink(1));
00785 }
00786
00787 World *world = graspItGUI->getIVmgr()->getWorld();
00788 Body *obstacle = NULL;
00789
00790 if (request.request_tabletop)
00791 {
00792 std::string filename = getenv("GRASPIT") + std::string("/") + request.tabletop_file_name;
00793
00794 for (int i = 0; i < world->getNumBodies(); i++)
00795 {
00796 if (world->getBody(i)->getFilename().compare(QString(request.tabletop_file_name.c_str())) == 0)
00797 {
00798 obstacle = world->getBody(i);
00799 break;
00800 }
00801 }
00802
00803 graspit_interface_msgs::LoadObstacle::Request req_load_obstacle;
00804 req_load_obstacle.file_name = request.tabletop_file_name;
00805 req_load_obstacle.obstacle_pose = geometry_msgs::Pose();
00806 req_load_obstacle.obstacle_pose.orientation.w = 1.0;
00807
00808 if (obstacle == NULL)
00809 {
00810 graspit_interface_msgs::LoadObstacle::Response res_load_obstacle;
00811 loadObstacleCB(req_load_obstacle, res_load_obstacle);
00812
00813 if (res_load_obstacle.result == graspit_interface_msgs::LoadObstacle::Response::LOAD_FAILURE)
00814 {
00815 response.result = response.GENERATE_FAILURE;
00816 ROS_WARN_STREAM("Tabletop load failed!");
00817 return true;
00818 }
00819 for (int i = 0; i < world->getNumBodies(); i++)
00820 {
00821 if (world->getBody(i)->getFilename().compare(QString(request.tabletop_file_name.c_str())) == 0)
00822 {
00823 obstacle = world->getBody(i);
00824 break;
00825 }
00826 }
00827 }
00828
00829
00830 bboxAction.apply(obstacle->getIVRoot());
00831 SbBox3f obstacle_bbx = bboxAction.getBoundingBox();
00832 vec3 obstacle_bbx_dim;
00833 SbVec3f obstacle_bbx_min, obstacle_bbx_max;
00834 obstacle_bbx.getBounds(obstacle_bbx_min, obstacle_bbx_max);
00835 getSbBoxDimension(obstacle_bbx, obstacle_bbx_dim);
00836
00837 float obstacle_current_z = obstacle->getTran().translation().z();
00838 float obstacle_top_height = obstacle_bbx_max[2];
00839 float object_bottom_height = object_bbx_min[2];
00840 float new_obstacle_height = obstacle_current_z + object_bottom_height - obstacle_top_height;
00841 req_load_obstacle.obstacle_pose.position.z = new_obstacle_height * 0.001;
00842 obstacle->setTran(poseToTransf(req_load_obstacle.obstacle_pose));
00843
00844 bboxAction.apply(obstacle->getIVRoot());
00845 SbBox3f obstacle_bbx_new = bboxAction.getBoundingBox();
00846 obstacle_bbx_new.getBounds(obstacle_bbx_min, obstacle_bbx_max);
00847 getSbBoxDimension(obstacle_bbx_new, obstacle_bbx_dim);
00848 }
00849
00850 int test_count = 1;
00851 double gripper_tabletop_clearance = -1;
00852 double gripper_object_distance = -1;
00853 while (true)
00854 {
00855
00856 test_count++;
00857
00858 randomPoseGenerate(bb_space, grasp_random_pose);
00859
00860
00861 grasp_random_pose.position.x = grasp_random_pose.position.x * 1.0e-3;
00862 grasp_random_pose.position.y = grasp_random_pose.position.y * 1.0e-3;
00863 grasp_random_pose.position.z = grasp_random_pose.position.z * 1.0e-3;
00864
00865
00866 gripper_->setTran(poseToTransf(grasp_random_pose));
00867
00868 gripper_->forceDOFVal(0, 0.523);
00869
00870 gripper_->autoGrasp(false, 0.5, true);
00871
00872
00873
00874 gripper_object_distance = world->getDist(gripper_, model->getGraspableBody());
00875 if (request.request_tabletop)
00876 {
00877 gripper_tabletop_clearance = world->getDist(gripper_, obstacle);
00878 graspit_interface_msgs::TestGrasp::Response test_collision_response;
00879
00880 gripperCollisionCheck(model->getGraspableBody(), test_collision_response);
00881
00882 if (test_collision_response.hand_environment_collision)
00883 {
00884
00885 continue;
00886 }
00887
00888 if (grasp_random_pose.position.z < 0.0)
00889 {
00890 gripper_tabletop_clearance = -1.0;
00891 continue;
00892 }
00893 }
00894
00895
00896
00897 CollisionReport collision_report;
00898 world->getCollisionReport(&collision_report, &interest_list);
00899 if (collision_report.size() > 0)
00900 {
00901
00902
00903
00904
00905
00906 continue;
00907 }
00908
00909
00910
00911
00912 computeEnergy(model->getGraspableBody(), test_grasp_res);
00913
00914 if (test_grasp_res.test_result == test_grasp_res.HAND_COLLISION)
00915
00916 {
00917 if (request.reject_fingertip_collision)
00918 {
00919 ROS_INFO_STREAM("Collision exists between fingertip and the object, reject it and this should not happen");
00920 continue;
00921 }
00922 else
00923 {
00924 response.hand_object_collision = true;
00925 ROS_INFO_STREAM("Collision exists between fingertip and the object, accept it");
00926 break;
00927 }
00928 }
00929
00930 if (test_grasp_res.energy_value > request.energy_high_threshold || test_grasp_res.energy_value
00931 < request.energy_low_threshold)
00932 {
00933
00934
00935
00936
00937
00938 continue;
00939
00940 }
00941 if (request.reject_fingertip_collision)
00942
00943 {
00944 ROS_INFO_STREAM("Bad grasp we found, accept it");
00945 response.hand_object_collision = false;
00946 break;
00947 }
00948 else
00949
00950 {
00951 continue;
00952 }
00953 }
00954
00955 ROS_INFO_STREAM( "Random grasp pose:" << grasp_random_pose << " grasp joint angle " << gripper_->getDOF(0)->getVal() <<" energy " << test_grasp_res.energy_value );
00956 ROS_INFO_STREAM("Number of objects "<<world->getNumBodies());
00957 response.grasp_pose = grasp_random_pose;
00958 response.grasp_energy = test_grasp_res.energy_value;
00959 response.grasp_joint_angle = gripper_->getDOF(0)->getVal();
00960 response.gripper_tabletop_clearance = gripper_tabletop_clearance;
00961 response.gripper_object_distance = gripper_object_distance;
00962 response.result = response.GENERATE_SUCCESS;
00963 return true;
00964
00965 }
00966
00967 void RosGraspitInterface::testGraspDirect(const object_manipulation_msgs::Grasp &grasp, GraspableBody *object,
00968 graspit_interface_msgs::TestGrasp::Response &response)
00969 {
00970
00971 gripper_->setTran(poseToTransf(grasp.grasp_pose));
00972
00973 gripper_->forceDOFVal(0, 0.523);
00974 gripper_->autoGrasp(false, 0.5, true);
00975
00976 gripperCollisionCheck(object, response);
00977
00978 if (response.hand_object_collision || response.hand_environment_collision)
00979 {
00980 response.test_result = response.HAND_COLLISION;
00981 return;
00982 }
00983
00984 computeEnergy(object, response);
00985 }
00986
00987 void RosGraspitInterface::testGraspCompliant(const object_manipulation_msgs::Grasp &grasp, GraspableBody *object,
00988 graspit_interface_msgs::TestGrasp::Response &response)
00989 {
00990
00991 gripper_->setTran(poseToTransf(grasp.grasp_pose));
00992
00993 gripper_->forceDOFVal(0, grasp.pre_grasp_posture.position[0]);
00994
00995 gripperCollisionCheck(object, response);
00996
00997 if (response.hand_object_collision || response.hand_environment_collision)
00998 {
00999 response.test_result = response.HAND_COLLISION;
01000 return;
01001 }
01002
01003 gripper_->compliantClose();
01004
01005 computeEnergy(object, response);
01006 }
01007
01008 void RosGraspitInterface::testGraspReactive(const object_manipulation_msgs::Grasp &grasp, GraspableBody *object,
01009 graspit_interface_msgs::TestGrasp::Response &response)
01010 {
01011
01012 transf pre_grasp = poseToTransf(grasp.grasp_pose);
01013 double moveDist = 100;
01014 pre_grasp = translate_transf(vec3(0, 0, -moveDist) * gripper_->getApproachTran()) * pre_grasp;
01015 gripper_->setTran(pre_grasp);
01016
01017 gripper_->forceDOFVal(0, 0.523);
01018
01019 gripperCollisionCheck(object, response);
01020
01021 if (response.hand_object_collision || response.hand_environment_collision)
01022 {
01023 response.test_result = response.HAND_COLLISION;
01024 return;
01025 }
01026
01027 gripper_->approachToContact(moveDist, false);
01028
01029 gripper_->compliantClose();
01030
01031 computeEnergy(object, response);
01032 response.energy_value_list.push_back(response.energy_value);
01033 }
01034
01035 void RosGraspitInterface::testGraspRobustReactive(const object_manipulation_msgs::Grasp &grasp, GraspableBody *object,
01036 graspit_interface_msgs::TestGrasp::Response &response)
01037 {
01038
01039 transf orig_pre_grasp = poseToTransf(grasp.grasp_pose);
01040 double moveDist = 100;
01041 const int n_tsteps = 3;
01042
01043 double t_steps[n_tsteps] = {-10, 0, 10};
01044 for (int x_step = 0; x_step < n_tsteps; x_step++)
01045 {
01046 transf pre_grasp = translate_transf(vec3(t_steps[x_step], 0, -moveDist) * gripper_->getApproachTran())
01047 * orig_pre_grasp;
01048 gripper_->setTran(pre_grasp);
01049
01050 gripper_->forceDOFVal(0, 0.523);
01051
01052 gripperCollisionCheck(object, response);
01053
01054 if (response.hand_object_collision || response.hand_environment_collision)
01055 {
01056 response.energy_value_list.push_back(100);
01057 }
01058 else
01059 {
01060
01061 gripper_->approachToContact(moveDist, false);
01062
01063 gripper_->compliantClose();
01064
01065 computeEnergy(object, response);
01066 response.energy_value_list.push_back(response.energy_value);
01067 }
01068 }
01069
01070 for (int y_step = 0; y_step < n_tsteps; y_step++)
01071 {
01072 transf pre_grasp = translate_transf(vec3(0, t_steps[y_step], -moveDist) * gripper_->getApproachTran())
01073 * orig_pre_grasp;
01074 gripper_->setTran(pre_grasp);
01075
01076 gripper_->forceDOFVal(0, 0.523);
01077
01078 gripperCollisionCheck(object, response);
01079
01080 if (response.hand_object_collision || response.hand_environment_collision)
01081 {
01082 response.energy_value_list.push_back(100);
01083 }
01084 else
01085 {
01086
01087 gripper_->approachToContact(moveDist, false);
01088
01089 gripper_->compliantClose();
01090
01091
01092 computeEnergy(object, response);
01093 response.energy_value_list.push_back(response.energy_value);
01094 }
01095 }
01096
01097 for (int z_step = 0; z_step < n_tsteps; z_step++)
01098 {
01099 transf pre_grasp = translate_transf(vec3(0, 0, t_steps[z_step] - moveDist) * gripper_->getApproachTran())
01100 * orig_pre_grasp;
01101 gripper_->setTran(pre_grasp);
01102
01103 gripper_->forceDOFVal(0, 0.523);
01104
01105 gripperCollisionCheck(object, response);
01106
01107 if (response.hand_object_collision || response.hand_environment_collision)
01108 {
01109 response.energy_value_list.push_back(100);
01110 }
01111 else
01112 {
01113
01114 gripper_->approachToContact(moveDist, false);
01115
01116 gripper_->compliantClose();
01117
01118
01119 computeEnergy(object, response);
01120 response.energy_value_list.push_back(response.energy_value);
01121 }
01122 }
01123
01124 double m_energy = mean(response.energy_value_list);
01125 double stddev_energy = stddev(response.energy_value_list);
01126 response.energy_value = m_energy + stddev_energy;
01127 }
01128
01129 bool RosGraspitInterface::testGraspCB(graspit_interface_msgs::TestGrasp::Request &request,
01130 graspit_interface_msgs::TestGrasp::Response &response)
01131 {
01132 response.test_performed = response.TEST_WAS_NOT_PERFORMED;
01133
01134 if (!gripper_ && !loadGripper())
01135 return true;
01136
01137
01138 World *world = graspItGUI->getIVmgr()->getWorld();
01139 if (!world->getNumGB())
01140 {
01141 ROS_ERROR("No graspable object loaded");
01142 return true;
01143 }
01144 GraspableBody *object = world->getGB(0);
01145
01146 if (request.grasp.grasp_posture.position.empty() || request.grasp.pre_grasp_posture.position.empty())
01147 {
01148 ROS_ERROR("Gripper DOF not specified in grasp or pre-grasp");
01149 return true;
01150 }
01151
01152 response.test_performed = response.TEST_WAS_PERFORMED;
01153 if (request.test_type == request.DIRECT)
01154 {
01155 testGraspDirect(request.grasp, object, response);
01156 }
01157 else if (request.test_type == request.COMPLIANT_CLOSE)
01158 {
01159 testGraspCompliant(request.grasp, object, response);
01160 }
01161 else if (request.test_type == request.REACTIVE_GRASP)
01162 {
01163 testGraspReactive(request.grasp, object, response);
01164 }
01165 else if (request.test_type == request.ROBUST_REACTIVE_GRASP)
01166 {
01167 testGraspReactive(request.grasp, object, response);
01168 }
01169 else
01170 {
01171 ROS_ERROR("Unknown test type requested");
01172 response.test_performed = response.TEST_WAS_NOT_PERFORMED;
01173 }
01174 return true;
01175 }
01176
01177 bool RosGraspitInterface::graspPlanningCB(object_manipulation_msgs::GraspPlanning::Request &request,
01178 object_manipulation_msgs::GraspPlanning::Response &response)
01179 {
01180 response.error_code.value = response.error_code.OTHER_ERROR;
01181 if (!gripper_ && !loadGripper())
01182 {
01183 ROS_ERROR("Failed to load gripper for grasp planning");
01184 return true;
01185 }
01186 if (request.target.potential_models.empty())
01187 {
01188 ROS_ERROR("Graspit can only evaluate grasps on database objects");
01189 return true;
01190 }
01191 if (request.target.potential_models.size() != 1)
01192 {
01193 ROS_WARN("Graspit can only evaluate grasps on the first potential model in the list");
01194 }
01195 if (request.grasps_to_evaluate.empty())
01196 {
01197 ROS_ERROR("For now, graspit will test grasps on-line, but not plan new grasps");
01198 return true;
01199 }
01200 graspit_interface_msgs::LoadDatabaseModel load_srv;
01201 load_srv.request.model_id = request.target.potential_models[0].model_id;
01202 load_srv.request.clear_other_models = true;
01203 loadModelCB(load_srv.request, load_srv.response);
01204 if (load_srv.response.result != load_srv.response.LOAD_SUCCESS)
01205 {
01206 ROS_ERROR("Failed to load database model for graspit grasp testing");
01207 return true;
01208 }
01209 GraspableBody *object = graspItGUI->getIVmgr()->getWorld()->getGB(0);
01210
01211
01212 response.error_code.value = 0;
01213
01214 BOOST_FOREACH(object_manipulation_msgs::Grasp grasp, request.grasps_to_evaluate)
01215 {
01216 if (grasp.grasp_posture.position.empty() || grasp.pre_grasp_posture.position.empty())
01217 {
01218 ROS_ERROR("Gripper DOF not specified in grasp or pre-grasp");
01219 response.error_code.value = response.error_code.OTHER_ERROR;
01220 return true;
01221 }
01222
01223 graspit_interface_msgs::TestGrasp test_srv;
01224 if (default_grasp_test_type_ == test_srv.request.DIRECT)
01225 {
01226 testGraspDirect(grasp, object, test_srv.response);
01227 }
01228 else if (default_grasp_test_type_ == test_srv.request.COMPLIANT_CLOSE)
01229 {
01230 testGraspCompliant(grasp, object, test_srv.response);
01231 }
01232 else if (default_grasp_test_type_ == test_srv.request.REACTIVE_GRASP)
01233 {
01234 testGraspReactive(grasp, object, test_srv.response);
01235 }
01236 else if (default_grasp_test_type_ == test_srv.request.ROBUST_REACTIVE_GRASP)
01237 {
01238 testGraspReactive(grasp, object, test_srv.response);
01239 }
01240 if (test_srv.response.test_performed != test_srv.response.TEST_WAS_PERFORMED)
01241 {
01242 ROS_ERROR("Failed to test grasp");
01243 response.error_code.value = response.error_code.OTHER_ERROR;
01244 return true;
01245 }
01246
01247
01248 double probability;
01249
01250 if (test_srv.response.test_result == test_srv.response.HAND_COLLISION)
01251 probability = 0.0;
01252
01253 if (default_grasp_test_type_ == test_srv.request.ROBUST_REACTIVE_GRASP)
01254 {
01255
01256 }
01257 probability = std::max(0.0, 1 - (test_srv.response.energy_value / default_energy_threshold_));
01258 grasp.success_probability = probability;
01259
01260 response.grasps.push_back(grasp);
01261 }
01262
01263 return true;
01264 }
01265
01266 }