$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 #include "graspit_ros_planning/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 //------------------------- Convenience functions ------------------------------- 00057 00058 template<typename T> 00059 inline T mean(const std::vector<T> &input) 00060 { 00061 T total = 0.0; 00062 BOOST_FOREACH(const T &val, input) 00063 { 00064 total += val; 00065 } 00066 return total / input.size(); 00067 } 00068 ; 00069 00070 template<typename T> 00071 inline T stddev(const std::vector<T> &input) 00072 { 00073 T m = mean(input); 00074 T total_err = 0.0; 00075 BOOST_FOREACH(const T &val, input) 00076 { 00077 total_err += std::pow(m - val, 2); 00078 } 00079 00080 total_err /= input.size(); 00081 00082 return std::sqrt(total_err); 00083 } 00084 00085 namespace graspit_ros_planning 00086 { 00087 00088 transf poseToTransf(const geometry_msgs::Pose &pose) 00089 { 00090 return transf(Quaternion(pose.orientation.w, pose.orientation.x, pose.orientation.y, pose.orientation.z), 00091 vec3(1000 * pose.position.x, 1000 * pose.position.y, 1000 * pose.position.z)); 00092 } 00093 00094 geometry_msgs::Pose transfToPose(const transf &tr) 00095 { 00096 geometry_msgs::Pose pose; 00097 return pose; 00098 } 00099 00100 inline void getSbBoxDimension(SbBox3f& bbx, vec3& dimension) 00101 { 00102 // SbBox3f is axis aligned, so the dimension of the box can be easily computed 00103 float xmin, ymin, zmin, xmax, ymax, zmax; 00104 bbx.getBounds(xmin, ymin, zmin, xmax, ymax, zmax); 00105 dimension.set(xmax - xmin, ymax - ymin, zmax - zmin); 00106 ROS_INFO("Boundind box: (%.3lf, %.3lf, %.3lf), (%.3lf, %.3lf, %.3lf) ", xmin, ymin, zmin, xmax, ymax, zmax); 00107 } 00108 00109 inline bool smallerThanSbVec3f(const SbVec3f& b1, const SbVec3f& b2) 00110 { 00111 float x1, y1, z1, x2, y2, z2; 00112 b1.getValue(x1, y1, z1); 00113 b2.getValue(x2, y2, z2); 00114 00115 if (x1 <= x2 && y1 <= y2 && z1 <= z2) 00116 return true; 00117 else 00118 return false; 00119 } 00120 00121 inline bool biggerThanSbVec3f(const SbVec3f& b1, const SbVec3f& b2) 00122 { 00123 float x1, y1, z1, x2, y2, z2; 00124 b1.getValue(x1, y1, z1); 00125 b2.getValue(x2, y2, z2); 00126 00127 if (x1 >= x2 && y1 >= y2 && z1 >= z2) 00128 return true; 00129 else 00130 return false; 00131 } 00132 00133 inline double randomUniformReal(double min, double max) 00134 { 00135 return ((1.0 * rand() / RAND_MAX) * (max - min) + min); 00136 } 00137 00138 void randomPoseGenerate(SbBox3f &bb_space, geometry_msgs::Pose& grasp_random_pose) 00139 { 00140 00141 float xmin, ymin, zmin, xmax, ymax, zmax; 00142 bb_space.getBounds(xmin, ymin, zmin, xmax, ymax, zmax); 00143 00144 // Generate a random position within the bounding space first 00145 grasp_random_pose.position.x = randomUniformReal(xmin, xmax); 00146 grasp_random_pose.position.y = randomUniformReal(ymin, ymax); 00147 grasp_random_pose.position.z = randomUniformReal(zmin, zmax); 00148 00149 // Generate a random orientation then 00150 double angle = randomUniformReal(0, 2.0 * M_PI); 00151 vec3 axis(randomUniformReal(0 + 0.0001, 1), randomUniformReal(0, 1), randomUniformReal(0, 1)); //make sure axis valid 00152 Quaternion orientation(angle, axis); 00153 00154 grasp_random_pose.orientation.w = orientation.w; 00155 grasp_random_pose.orientation.x = orientation.x; 00156 grasp_random_pose.orientation.y = orientation.y; 00157 grasp_random_pose.orientation.z = orientation.z; 00158 } 00159 00160 RosGraspitInterface::RosGraspitInterface() : 00161 root_nh_(NULL), priv_nh_(NULL), db_mgr_(NULL) 00162 { 00163 default_energy_threshold_ = 68.6; 00164 } 00165 00166 RosGraspitInterface::~RosGraspitInterface() 00167 { 00168 ROS_INFO("ROS GraspIt node stopping"); 00169 ros::shutdown(); 00170 delete root_nh_; 00171 delete priv_nh_; 00172 delete db_mgr_; 00173 } 00174 00175 //------------------------- Main class ------------------------------- 00176 00177 int RosGraspitInterface::init(int argc, char **argv) 00178 { 00179 //copy the arguments somewhere else so we can pass them to ROS 00180 int ros_argc = argc; 00181 char** ros_argv = new char*[argc]; 00182 for (int i = 0; i < argc; i++) 00183 { 00184 ros_argv[i] = new char[strlen(argv[i])]; 00185 strcpy(ros_argv[i], argv[i]); 00186 } 00187 //see if a node name was requested 00188 std::string node_name("ros_graspit_interface"); 00189 for (int i = 0; i < argc - 1; i++) 00190 { 00191 //std::cerr << argv[i] << "\n"; 00192 if (!strcmp(argv[i], "_name")) 00193 { 00194 node_name = argv[i + 1]; 00195 } 00196 } 00197 //init ros 00198 ros::init(ros_argc, ros_argv, node_name.c_str()); 00199 //ROS_INFO("Using node name %s", node_name.c_str()); 00200 //clean up ros arguments 00201 for (int i = 0; i < argc; i++) 00202 { 00203 delete ros_argv[i]; 00204 } 00205 delete ros_argv; 00206 //init node handles 00207 root_nh_ = new ros::NodeHandle(""); 00208 priv_nh_ = new ros::NodeHandle("~"); 00209 //advertise service in private namespace 00210 load_model_srv_ = priv_nh_->advertiseService("load_database_model", &RosGraspitInterface::loadModelCB, this); 00211 load_obstacle_srv_ = priv_nh_->advertiseService("load_obstacle", &RosGraspitInterface::loadObstacleCB, this); 00212 clear_bodies_srv_ = priv_nh_->advertiseService("clear_bodies", &RosGraspitInterface::clearBodiesCB, this); 00213 simulate_scan_srv_ = priv_nh_->advertiseService("simulate_scan", &RosGraspitInterface::simulateScanCB, this); 00214 test_grasp_srv_ = priv_nh_->advertiseService("test_grasp", &RosGraspitInterface::testGraspCB, this); 00215 grasp_planning_srv_ = priv_nh_->advertiseService("grasp_planning", &RosGraspitInterface::graspPlanningCB, this); 00216 00217 generate_grasp_srv_ = priv_nh_->advertiseService("generate_grasp", &RosGraspitInterface::generateGraspCB, this); 00218 00219 scan_publisher_ = priv_nh_->advertise<sensor_msgs::PointCloud2> ("simulated_scans", 5); 00220 00221 verify_grasp_srv_ = priv_nh_->advertiseService("verify_grasp", &RosGraspitInterface::verifyGraspCB, this); 00222 00223 srand(1); 00224 //initialize database connection 00225 //careful: we pass a null for the grasp allocator as we don't know yet which hand we'll be using 00226 db_mgr_ = new db_planner::RosDatabaseManager("wgs36", "5432", "willow", "willow", "household_objects", NULL, NULL); 00227 //use the special allocator for models that get geometry directly from the database 00228 GeomGraspitDBModelAllocator* allocator = new GeomGraspitDBModelAllocator(db_mgr_); 00229 db_mgr_->SetModelAllocator(allocator); 00230 gripper_ = NULL; 00231 if (!db_mgr_->isConnected()) 00232 { 00233 ROS_ERROR("Failed to connect to database"); 00234 return -1; 00235 } 00236 ROS_INFO("ROS GraspIt node ready"); 00237 return 0; 00238 } 00239 00240 int RosGraspitInterface::mainLoop() 00241 { 00242 ros::spinOnce(); 00243 return 0; 00244 } 00245 00250 GraspitDBModel* RosGraspitInterface::getModel(int model_id) 00251 { 00252 std::map<int, GraspitDBModel*>::iterator it = models_.find(model_id); 00253 if (it != models_.end()) 00254 return it->second; 00255 00256 //retrieve the model from the database 00257 db_planner::Model* db_model; 00258 if (!db_mgr_->ScaledModel(db_model, model_id)) 00259 { 00260 ROS_ERROR("Failed to load database model with id %d", model_id); 00261 return NULL; 00262 } 00263 GraspitDBModel *model = static_cast<GraspitDBModel*> (db_model); 00264 models_.insert(std::pair<int, GraspitDBModel*>(model_id, model)); 00265 return model; 00266 } 00267 00268 bool RosGraspitInterface::loadGripper() 00269 { 00270 World *world = graspItGUI->getIVmgr()->getWorld(); 00271 if (gripper_) 00272 { 00273 ROS_WARN("Gripper load requested, but gripper already present. Re-loading."); 00274 world->removeRobot(gripper_); 00275 } 00276 std::string hand_path("/models/robots/pr2_gripper/pr2_gripper_2010.xml"); 00277 hand_path = getenv("GRASPIT") + hand_path; 00278 gripper_ = static_cast<Pr2Gripper2010*> (world->importRobot(QString(hand_path.c_str()))); 00279 if (!gripper_) 00280 { 00281 ROS_ERROR("Failed to load PR2 gripper from file %s", hand_path.c_str()); 00282 return false; 00283 } 00284 return true; 00285 } 00286 00287 bool RosGraspitInterface::loadModelCB(graspit_ros_planning_msgs::LoadDatabaseModel::Request &request, 00288 graspit_ros_planning_msgs::LoadDatabaseModel::Response &response) 00289 { 00290 //retrieve model from database, if not already retrieved 00291 GraspitDBModel *model = getModel(request.model_id); 00292 if (!model) 00293 { 00294 response.result = response.LOAD_FAILURE; 00295 return true; 00296 } 00297 00298 //load the geometry, if not already loaded 00299 World *world = graspItGUI->getIVmgr()->getWorld(); 00300 if (!model->geometryLoaded()) 00301 { 00302 if (model->load(world) != SUCCESS) 00303 { 00304 ROS_ERROR("Failed to load geometry for database model with id %d", request.model_id); 00305 response.result = response.LOAD_FAILURE; 00306 return true; 00307 } 00308 } 00309 00310 //if requested, if there are any models in the world that are not this one, remove them 00311 if (request.clear_other_models) 00312 { 00313 bool done = false; 00314 while (!done) 00315 { 00316 done = true; 00317 for (int i = 0; i < world->getNumGB(); i++) 00318 { 00319 if (world->getGB(i) != model->getGraspableBody()) 00320 { 00321 world->destroyElement(world->getGB(i), false); 00322 done = false; 00323 break; 00324 } 00325 } 00326 } 00327 } 00328 00329 //add the model to the world, if not already there 00330 if (world->getIVRoot()->findChild(model->getGraspableBody()->getIVRoot()) == -1) 00331 { 00332 model->getGraspableBody()->addToIvc(); 00333 world->addBody(model->getGraspableBody()); 00334 } 00335 00336 //set the correct transform 00337 model->getGraspableBody()->setTran(poseToTransf(request.model_pose)); 00338 model->getGraspableBody()->showAxes(false); 00339 response.result = response.LOAD_SUCCESS; 00340 return true; 00341 } 00342 00343 bool RosGraspitInterface::clearBodiesCB(graspit_ros_planning_msgs::ClearBodies::Request &request, 00344 graspit_ros_planning_msgs::ClearBodies::Response &response) 00345 { 00346 World *world = graspItGUI->getIVmgr()->getWorld(); 00347 if (request.which_bodies == request.GRASPABLE_BODIES || request.which_bodies == request.ALL_BODIES) 00348 { 00349 while (world->getNumGB() > 0) 00350 { 00351 //careful, we remove it from the world here but do not delete it 00352 //all geometry stays in place if we need it in the future, it just gets disconnected 00353 //from the scene graph and the collision engine 00354 world->destroyElement(world->getGB(0), false); 00355 } 00356 ROS_INFO("Cleared graspable bodies"); 00357 } 00358 if (request.which_bodies == request.OBSTACLES || request.which_bodies == request.ALL_BODIES) 00359 { 00360 bool removal = true; 00361 while (removal) 00362 { 00363 removal = false; 00364 for (int i = 0; i < world->getNumBodies(); i++) 00365 { 00366 if (!world->getBody(i)->inherits("DynamicBody")) 00367 { 00368 //obstacles get deleted for good as we don't keep track of them here 00369 world->destroyElement(world->getBody(i), true); 00370 removal = true; 00371 break; 00372 } 00373 } 00374 } 00375 ROS_INFO("Cleared obstacles bodies"); 00376 } 00377 return true; 00378 } 00379 00380 bool RosGraspitInterface::loadObstacleCB(graspit_ros_planning_msgs::LoadObstacle::Request &request, 00381 graspit_ros_planning_msgs::LoadObstacle::Response &response) 00382 { 00383 std::string filename = getenv("GRASPIT") + std::string("/") + request.file_name; 00384 World *world = graspItGUI->getIVmgr()->getWorld(); 00385 Body *body = world->importBody("Body", QString(filename.c_str())); 00386 if (!body) 00387 { 00388 ROS_ERROR("Failed to import obstacle from file %s", filename.c_str()); 00389 response.result = response.LOAD_FAILURE; 00390 return true; 00391 } 00392 00393 //set the correct transform 00394 body->setTran(poseToTransf(request.obstacle_pose)); 00395 response.result = response.LOAD_SUCCESS; 00396 return true; 00397 } 00398 00399 bool RosGraspitInterface::simulateScanCB(graspit_ros_planning_msgs::SimulateScan::Request &request, 00400 graspit_ros_planning_msgs::SimulateScan::Response &response) 00401 { 00402 ScanSimulator scan_sim; 00403 scan_sim.setType(ScanSimulator::SCANNER_COORDINATES); 00404 scan_sim.setPosition(poseToTransf(request.scanner_pose), ScanSimulator::STEREO_CAMERA); 00405 //for now, we hard-code this in for the stereo camera, but they could be in the message 00406 double horiz_fov = 45; 00407 //half resolution to speed things up 00408 double horiz_res = 640; 00409 double vertical_res = 480; 00410 double vertical_fov = horiz_fov * vertical_res / horiz_res; 00411 scan_sim.setOptics(-horiz_fov / 2.0, horiz_fov / 2.0, horiz_res, -vertical_fov / 2.0, vertical_fov / 2.0, 00412 vertical_res); 00413 00414 //if the gripper is there, get it out of the scene graph so it does not show up in the scan 00415 World *world = graspItGUI->getIVmgr()->getWorld(); 00416 if (gripper_) 00417 { 00418 world->removeElementFromSceneGraph(gripper_); 00419 } 00420 //get the scan (without the raw data) 00421 std::vector<position> cloud; 00422 ROS_INFO("Simulating scan..."); 00423 00424 if (request.request_ray_directions) 00425 { 00426 std::vector<RawScanPoint> rawData; 00427 scan_sim.scan(&cloud, &rawData); 00428 ROS_INFO("Simulated scan has %d points, %d rays", (int)cloud.size(), (int)rawData.size()); 00429 // Also publish the direction of the rays that doesn't hit any object 00430 response.missing_ray_directions.reserve(rawData.size()); 00431 for (size_t j = 0; j < rawData.size(); j++) 00432 { 00433 if (rawData[j].distance < -0.9) // If the ray doesn't hit anything, the distance is set to -1 00434 { 00435 geometry_msgs::Point32 dir; 00436 dir.x = rawData[j].dx; 00437 dir.y = rawData[j].dy; 00438 dir.z = rawData[j].dz; 00439 response.missing_ray_directions.push_back(dir); 00440 } 00441 } 00442 } 00443 else 00444 { 00445 scan_sim.scan(&cloud); 00446 ROS_INFO("Simulated scan has %d points", (int)cloud.size()); 00447 } 00448 if (gripper_) 00449 { 00450 world->addElementToSceneGraph(gripper_); 00451 } 00452 //world->getIVRoot()->addChild(scan_sim.getVisualIndicator()); 00453 00454 //convert it to a PointCloud2 00455 //convert to a PointCloud first 00456 ROS_INFO("Converting scan to ROS format"); 00457 sensor_msgs::PointCloud point_cloud; 00458 for (size_t i = 0; i < cloud.size(); i++) 00459 { 00460 geometry_msgs::Point32 point; 00461 point.x = 1.0e-3 * cloud[i].x(); 00462 point.y = 1.0e-3 * cloud[i].y(); 00463 point.z = 1.0e-3 * cloud[i].z(); 00464 point_cloud.points.push_back(point); 00465 } 00466 point_cloud.header.frame_id = "graspit_scanner_frame"; 00467 point_cloud.header.stamp = ros::Time::now(); 00468 //convert to a PointCloud2 00469 ROS_INFO("Converting scan to point cloud 2"); 00470 sensor_msgs::convertPointCloudToPointCloud2(point_cloud, response.scan); 00471 response.scan.header.stamp = ros::Time::now(); 00472 00473 //publish it on our internal topic 00474 ROS_INFO("Publishing scan"); 00475 scan_publisher_.publish(response.scan); 00476 00477 ROS_INFO("Done"); 00478 return true; 00479 } 00480 00481 void RosGraspitInterface::gripperCollisionCheck(const Body *object, 00482 graspit_ros_planning_msgs::TestGrasp::Response &response) 00483 { 00484 response.hand_environment_collision = false; 00485 response.hand_object_collision = false; 00486 std::vector<DynamicBody*> gripper_link_list; 00487 gripper_->getAllLinks(gripper_link_list); 00488 std::vector<Body*> interest_list; 00489 for (size_t i = 0; i < gripper_link_list.size(); i++) 00490 { 00491 interest_list.push_back(gripper_link_list[i]); 00492 } 00493 CollisionReport collision_report; 00494 World *world = graspItGUI->getIVmgr()->getWorld(); 00495 world->getCollisionReport(&collision_report, &interest_list); 00496 for (size_t i = 0; i < collision_report.size(); i++) 00497 { 00498 //figure out what the other body we are colliding with is 00499 Body *collision_body = collision_report[i].first; 00500 if (collision_body->getOwner() == gripper_) 00501 { 00502 collision_body = collision_report[i].second; 00503 } 00504 if (collision_body == object) 00505 response.hand_object_collision = true; 00506 else 00507 response.hand_environment_collision = true; 00508 } 00509 } 00510 00511 void RosGraspitInterface::computeEnergy(Body *object, graspit_ros_planning_msgs::TestGrasp::Response &response) 00512 { 00513 SearchEnergy energy_calculator; 00514 energy_calculator.setType(ENERGY_CONTACT); 00515 energy_calculator.setContactType(CONTACT_PRESET); 00516 bool legal; 00517 double energy; 00518 energy_calculator.analyzeCurrentPosture(gripper_, object, legal, energy, false); 00519 if (!legal) 00520 { 00521 //this should not really happen, as we've checked for collisions already 00522 ROS_WARN("Energy calculator reports illegal state"); 00523 response.test_result = response.HAND_COLLISION; 00524 response.energy_value = -1.0; 00525 return; 00526 } 00527 response.energy_value = energy; 00528 //hard-coded threshold for now, will make it into a parameter 00529 if (energy < 10.0) 00530 response.test_result = response.GRASP_SUCCESS; 00531 else 00532 response.test_result = response.GRASP_FAILURE; 00533 } 00534 00535 bool RosGraspitInterface::verifyGraspCB(graspit_ros_planning_msgs::VerifyGrasp::Request &request, 00536 graspit_ros_planning_msgs::VerifyGrasp::Response &response) 00537 { 00538 response.hand_environment_collision = false; 00539 response.hand_object_collision = false; 00540 00541 // static int last_object_id = 0; 00542 00543 graspit_ros_planning_msgs::LoadDatabaseModel::Request req_load_object; 00544 graspit_ros_planning_msgs::LoadDatabaseModel::Response res_load_object; 00545 00546 World *world_p = graspItGUI->getIVmgr()->getWorld(); 00547 GraspableBody *object = NULL; 00548 Body *obstacle = NULL; 00549 00550 std::string filename = getenv("GRASPIT") + std::string("/") + request.table_file_name; 00551 00552 req_load_object.model_id = request.scaled_model_id; 00553 req_load_object.model_pose = geometry_msgs::Pose(); 00554 req_load_object.model_pose.orientation.w = 1.0; 00555 req_load_object.clear_other_models = true; 00556 00557 loadModelCB(req_load_object, res_load_object); 00558 00559 if (res_load_object.result == graspit_ros_planning_msgs::LoadDatabaseModel::Response::LOAD_FAILURE) 00560 { 00561 response.result = graspit_ros_planning_msgs::VerifyGrasp::Response::LOAD_OBJECT_FAILURE; 00562 ROS_WARN_STREAM("Object load failed!"); 00563 return true; 00564 } 00565 00566 object = world_p->getGB(0); 00567 00568 //Get the bounding box of the object 00569 SoGetBoundingBoxAction bboxAction(graspItGUI->getIVmgr()->getViewer()->getViewportRegion()); 00570 bboxAction.apply(object->getIVRoot()); 00571 SbBox3f object_bbx = bboxAction.getBoundingBox(); 00572 vec3 obj_bbx_dim; 00573 SbVec3f object_bbx_min, object_bbx_max; 00574 object_bbx.getBounds(object_bbx_min, object_bbx_max); 00575 getSbBoxDimension(object_bbx, obj_bbx_dim); 00576 00577 // Load the tabletop 00578 // ROS_INFO_STREAM("Number of objects in the world " << world_p->getNumBodies()); 00579 for (int i = 0; i < world_p->getNumBodies(); i++) 00580 { 00581 if (world_p->getBody(i)->getFilename().compare(QString(request.table_file_name.c_str())) == 0) 00582 { 00583 obstacle = world_p->getBody(i); 00584 break; 00585 } 00586 } 00587 00588 graspit_ros_planning_msgs::LoadObstacle::Request req_load_obstacle; 00589 req_load_obstacle.file_name = request.table_file_name; 00590 req_load_obstacle.obstacle_pose = geometry_msgs::Pose(); 00591 req_load_obstacle.obstacle_pose.orientation.w = 1.0; 00592 if (obstacle == NULL) 00593 { 00594 graspit_ros_planning_msgs::LoadObstacle::Response res_load_obstacle; 00595 00596 loadObstacleCB(req_load_obstacle, res_load_obstacle); 00597 00598 if (res_load_obstacle.result == graspit_ros_planning_msgs::LoadObstacle::Response::LOAD_FAILURE) 00599 { 00600 response.result = graspit_ros_planning_msgs::VerifyGrasp::Response::LOAD_OBSTACLE_FAILURE; 00601 ROS_WARN_STREAM("Tabletop load failed!"); 00602 return true; 00603 } 00604 00605 for (int i = 0; i < world_p->getNumBodies(); i++) 00606 { 00607 if (world_p->getBody(i)->getFilename().compare(QString(request.table_file_name.c_str())) == 0) 00608 { 00609 obstacle = world_p->getBody(i); 00610 break; 00611 } 00612 } 00613 } 00614 00615 //Get the bounding box of the obstacle 00616 bboxAction.apply(obstacle->getIVRoot()); 00617 SbBox3f obstacle_bbx = bboxAction.getBoundingBox(); 00618 vec3 obstacle_bbx_dim; 00619 SbVec3f obstacle_bbx_min, obstacle_bbx_max; 00620 obstacle_bbx.getBounds(obstacle_bbx_min, obstacle_bbx_max); 00621 ROS_INFO("Tabletop"); 00622 getSbBoxDimension(obstacle_bbx, obstacle_bbx_dim); 00623 00624 float obstacle_current_z = obstacle->getTran().translation().z(); 00625 float obstacle_top_z = obstacle_bbx_max[2]; 00626 float object_bottom_z = object_bbx_min[2]; 00627 float new_obstacle_z = obstacle_current_z + object_bottom_z - obstacle_top_z; 00628 req_load_obstacle.obstacle_pose.position.z = new_obstacle_z * 0.001; // 00629 obstacle->setTran(poseToTransf(req_load_obstacle.obstacle_pose)); 00630 00631 bboxAction.apply(obstacle->getIVRoot()); 00632 SbBox3f obstacle_bbx_new = bboxAction.getBoundingBox(); 00633 obstacle_bbx_new.getBounds(obstacle_bbx_min, obstacle_bbx_max); 00634 getSbBoxDimension(obstacle_bbx_new, obstacle_bbx_dim); 00635 00636 // Load gripper to the scene 00637 if (!gripper_ && !loadGripper()) 00638 { 00639 response.result = graspit_ros_planning_msgs::VerifyGrasp::Response::LOAD_GRIPPER_FAILURE; 00640 ROS_WARN_STREAM("Gripper load failed!"); 00641 return true; 00642 } 00643 00644 // Result valid 00645 response.result = graspit_ros_planning_msgs::VerifyGrasp::Response::CHECK_SUCCESS; 00646 //place the hand in the right pose 00647 gripper_->setTran(poseToTransf(request.grasp_pose)); 00648 //set the gripper dof 00649 gripper_->forceDOFVal(0, request.grasp_joint_angle); 00650 00651 graspit_ros_planning_msgs::TestGrasp::Response test_collision_response; 00652 00653 response.gripper_tabletop_clearance = world_p->getDist(gripper_, obstacle); 00654 response.gripper_object_distance = world_p->getDist(gripper_, object); 00655 gripperCollisionCheck(object, test_collision_response); 00656 00657 bool any_collision = false; 00658 00659 if (test_collision_response.hand_environment_collision) 00660 { 00661 response.hand_environment_collision = true; 00662 ROS_WARN_STREAM("Collision with environment detected!"); 00663 any_collision = true; 00664 } 00665 if (test_collision_response.hand_object_collision) 00666 { 00667 response.hand_object_collision = true; 00668 ROS_WARN_STREAM("Collision with object detected!"); 00669 any_collision = true; 00670 } 00671 00672 if (request.grasp_pose.position.z < 0.0 && !test_collision_response.hand_environment_collision) 00673 { 00674 ROS_WARN_STREAM("Gripper under desktop, hack the collision result"); 00675 response.hand_environment_collision = true; 00676 response.gripper_tabletop_clearance = -1.0; 00677 any_collision = true; 00678 } 00679 00680 if (!any_collision) 00681 ROS_WARN_STREAM("No Collision detected!"); 00682 return true; 00683 } 00684 00685 bool RosGraspitInterface::generateGraspCB(graspit_ros_planning_msgs::GenerateGrasp::Request &request, 00686 graspit_ros_planning_msgs::GenerateGrasp::Response &response) 00687 { 00688 // The resulted grasp pose doesn't guarantee that the object will be reasonably close to the gripper. (Generating voxelgrid using this grasp pose might get a completedly free voxelgrid) 00689 00690 response.result = response.GENERATE_FAILURE; 00691 00692 // Load the requested object to graspit and clear other objects 00693 graspit_ros_planning_msgs::LoadDatabaseModel::Request req_load_object; 00694 graspit_ros_planning_msgs::LoadDatabaseModel::Response res_load_object; 00695 00696 static int last_model_id = 0; 00697 static int acc_count = 1; 00698 00699 // object's pose will coincides with world frame, to simplify everything 00700 req_load_object.model_id = request.model_id; 00701 req_load_object.model_pose = geometry_msgs::Pose(); 00702 req_load_object.model_pose.orientation.w = 1.0; 00703 req_load_object.clear_other_models = true; 00704 00705 loadModelCB(req_load_object, res_load_object); 00706 00707 if (res_load_object.result == res_load_object.LOAD_FAILURE) 00708 { 00709 response.result = response.GENERATE_FAILURE; 00710 ROS_INFO_STREAM("Object loaded failed!"); 00711 return true; 00712 } 00713 00714 //ROS_INFO_STREAM("Object loaded successful!"); 00715 00716 00717 // Get a pointer to the object 00718 GraspitDBModel *model = getModel(request.model_id); 00719 if (!model) 00720 { 00721 response.result = response.GENERATE_FAILURE; 00722 return true; 00723 } 00724 00725 // Load gripper to the scene 00726 if (!gripper_ && !loadGripper()) 00727 { 00728 response.result = response.GENERATE_FAILURE; 00729 return true; 00730 } 00731 00732 // ROS_INFO_STREAM("Gripper loaded successful!"); 00733 00734 // Calculate bounding box sizes of both the object and gripper 00735 SoGetBoundingBoxAction bboxAction(graspItGUI->getIVmgr()->getViewer()->getViewportRegion()); 00736 bboxAction.apply(model->getGraspableBody()->getIVRoot()); 00737 SbBox3f object_bbx = bboxAction.getBoundingBox(); 00738 00739 gripper_->setTran(transf()); 00740 //set the gripper dof (for the moment all the way open) 00741 gripper_->forceDOFVal(0, 0.26); 00742 bboxAction.apply(gripper_->getIVRoot()); 00743 SbBox3f gripper_bbx = bboxAction.getBoundingBox(); 00744 00745 // Define the bounding space for randomly selecting the gripper 00746 vec3 gripper_bbx_dim, obj_bbx_dim, bbs_dim; 00747 //ROS_INFO("Gripper"); 00748 getSbBoxDimension(gripper_bbx, gripper_bbx_dim); 00749 // double gripper_bbx_diag = sqrt(gripper_bbx_dim.len_sq()); 00750 double gripper_box_xdim = gripper_bbx_dim.x(); 00751 00752 SbVec3f object_bbx_min, object_bbx_max; 00753 object_bbx.getBounds(object_bbx_min, object_bbx_max); 00754 // ROS_INFO("Object"); 00755 getSbBoxDimension(object_bbx, obj_bbx_dim); 00756 00757 SbBox3f bb_space; 00758 SbVec3f offset(30, 30, 0); 00759 SbVec3f offset2(30, 30, 30); 00760 if (last_model_id == request.model_id) 00761 { 00762 acc_count = (acc_count+1)%2; // acc_count != 0 and acc_count will accumulate 00763 } 00764 else 00765 { 00766 acc_count = 0; 00767 } 00768 last_model_id = request.model_id; 00769 SbVec3f bb_min, bb_max; 00770 bb_min = object_bbx_min - SbVec3f(gripper_box_xdim, gripper_box_xdim, 0) + acc_count * offset; 00771 bb_max = object_bbx_max + SbVec3f(gripper_box_xdim, gripper_box_xdim, gripper_box_xdim) - acc_count * offset2; 00772 00773 bb_space.setBounds(bb_min, bb_max); 00774 //ROS_INFO("Bounding space"); 00775 getSbBoxDimension(bb_space, bbs_dim); 00776 00777 // PressEnterToContinue(); 00778 ROS_ASSERT(gripper_->getNumChains() == 2); // Pr2 gripper should have two kinematic chains 00779 00780 // Randomly generate grasp pose within the bounding space 00781 geometry_msgs::Pose grasp_random_pose; 00782 graspit_ros_planning_msgs::TestGrasp::Response test_grasp_res; 00783 std::vector<Body*> interest_list; 00784 interest_list.push_back(gripper_->getBase()); // palm 00785 interest_list.push_back(gripper_->getChain(0)->getLink(0)); //upper finger 00786 interest_list.push_back(gripper_->getChain(1)->getLink(0)); //another upper finger 00787 if (request.reject_fingertip_collision) 00788 { 00789 interest_list.push_back(gripper_->getChain(0)->getLink(1)); //fingertip 00790 interest_list.push_back(gripper_->getChain(1)->getLink(1)); //fingertip 00791 } 00792 00793 World *world = graspItGUI->getIVmgr()->getWorld(); 00794 Body *obstacle = NULL; 00795 00796 if (request.request_tabletop) 00797 { 00798 std::string filename = getenv("GRASPIT") + std::string("/") + request.tabletop_file_name; 00799 00800 for (int i = 0; i < world->getNumBodies(); i++) 00801 { 00802 if (world->getBody(i)->getFilename().compare(QString(request.tabletop_file_name.c_str())) == 0) 00803 { 00804 obstacle = world->getBody(i); 00805 break; 00806 } 00807 } 00808 00809 graspit_ros_planning_msgs::LoadObstacle::Request req_load_obstacle; 00810 req_load_obstacle.file_name = request.tabletop_file_name; 00811 req_load_obstacle.obstacle_pose = geometry_msgs::Pose(); 00812 req_load_obstacle.obstacle_pose.orientation.w = 1.0; 00813 00814 if (obstacle == NULL) 00815 { 00816 graspit_ros_planning_msgs::LoadObstacle::Response res_load_obstacle; 00817 loadObstacleCB(req_load_obstacle, res_load_obstacle); 00818 00819 if (res_load_obstacle.result == graspit_ros_planning_msgs::LoadObstacle::Response::LOAD_FAILURE) 00820 { 00821 response.result = response.GENERATE_FAILURE; 00822 ROS_WARN_STREAM("Tabletop load failed!"); 00823 return true; 00824 } 00825 for (int i = 0; i < world->getNumBodies(); i++) 00826 { 00827 if (world->getBody(i)->getFilename().compare(QString(request.tabletop_file_name.c_str())) == 0) 00828 { 00829 obstacle = world->getBody(i); 00830 break; 00831 } 00832 } 00833 } 00834 00835 //Get the bounding box of the obstacle 00836 bboxAction.apply(obstacle->getIVRoot()); 00837 SbBox3f obstacle_bbx = bboxAction.getBoundingBox(); 00838 vec3 obstacle_bbx_dim; 00839 SbVec3f obstacle_bbx_min, obstacle_bbx_max; 00840 obstacle_bbx.getBounds(obstacle_bbx_min, obstacle_bbx_max); 00841 getSbBoxDimension(obstacle_bbx, obstacle_bbx_dim); 00842 00843 float obstacle_current_z = obstacle->getTran().translation().z(); 00844 float obstacle_top_height = obstacle_bbx_max[2]; 00845 float object_bottom_height = object_bbx_min[2]; 00846 float new_obstacle_height = obstacle_current_z + object_bottom_height - obstacle_top_height; 00847 req_load_obstacle.obstacle_pose.position.z = new_obstacle_height * 0.001; // 00848 obstacle->setTran(poseToTransf(req_load_obstacle.obstacle_pose)); 00849 00850 bboxAction.apply(obstacle->getIVRoot()); 00851 SbBox3f obstacle_bbx_new = bboxAction.getBoundingBox(); 00852 obstacle_bbx_new.getBounds(obstacle_bbx_min, obstacle_bbx_max); 00853 getSbBoxDimension(obstacle_bbx_new, obstacle_bbx_dim); 00854 } 00855 00856 int test_count = 1; 00857 double gripper_tabletop_clearance = -1; 00858 double gripper_object_distance = -1; 00859 while (true/*test_count > 0*/) 00860 { 00861 // ROS_INFO_STREAM("Trial " << test_count); 00862 test_count++; 00863 00864 randomPoseGenerate(bb_space, grasp_random_pose); // Generate a random gripper pose in the bounding space 00865 // ROS_INFO_STREAM( " Random grasp pose:" << grasp_random_pose); 00866 // PressEnterToContinue(); 00867 grasp_random_pose.position.x = grasp_random_pose.position.x * 1.0e-3; //Convert to meters 00868 grasp_random_pose.position.y = grasp_random_pose.position.y * 1.0e-3; 00869 grasp_random_pose.position.z = grasp_random_pose.position.z * 1.0e-3; 00870 00871 //place the hand in the right pose 00872 gripper_->setTran(poseToTransf(grasp_random_pose)); 00873 //set the gripper dof (for the moment all the way open) 00874 gripper_->forceDOFVal(0, 0.523); 00875 // Let the gripper automatically hold to the object 00876 gripper_->autoGrasp(false, 0.5, true); 00877 00878 //ROS_INFO_STREAM( " Random grasp pose:" << grasp_random_pose << " grasp joint angle " << gripper_->getDOF(0)->getVal() ); 00879 00880 gripper_object_distance = world->getDist(gripper_, model->getGraspableBody()); 00881 if (request.request_tabletop) 00882 { 00883 gripper_tabletop_clearance = world->getDist(gripper_, obstacle); 00884 graspit_ros_planning_msgs::TestGrasp::Response test_collision_response; 00885 00886 gripperCollisionCheck(model->getGraspableBody(), test_collision_response); 00887 00888 if (test_collision_response.hand_environment_collision) 00889 { 00890 // ROS_WARN_STREAM("Collision with environment detected!, reject it!"); 00891 continue; 00892 } 00893 00894 if (grasp_random_pose.position.z < 0.0) 00895 { 00896 gripper_tabletop_clearance = -1.0; 00897 continue; 00898 } 00899 } 00900 00901 // For every grasp pose, detect collision between gripper palm, two gripper upper fingers (i.e. all gripper parts except fingertips) and the object 00902 // If collision exists, reject this grasp pose 00903 CollisionReport collision_report; 00904 world->getCollisionReport(&collision_report, &interest_list); 00905 if (collision_report.size() > 0) 00906 { 00907 // if (request.reject_fingertip_collision) 00908 // ROS_INFO_STREAM("Collision exists between the gripper and the object, reject it"); 00909 // else 00910 // ROS_INFO_STREAM("Collision exists between the gripper bottom part and the object, reject it"); 00911 00912 continue; //if collision exists, then continue to the next grasp pose 00913 } 00914 00915 // ROS_INFO_STREAM("No collision exists between the gripper bottom part and the object"); 00916 00917 // Compute grasp energy 00918 computeEnergy(model->getGraspableBody(), test_grasp_res); 00919 00920 if (test_grasp_res.test_result == test_grasp_res.HAND_COLLISION) // collision exists, which should be with the fingertip, we found a bad grasp 00921 00922 { 00923 if (request.reject_fingertip_collision) 00924 { 00925 ROS_INFO_STREAM("Collision exists between fingertip and the object, reject it and this should not happen"); 00926 continue; 00927 } 00928 else 00929 { 00930 response.hand_object_collision = true; 00931 ROS_INFO_STREAM("Collision exists between fingertip and the object, accept it"); 00932 break; 00933 } 00934 } 00935 00936 if (test_grasp_res.energy_value > request.energy_high_threshold || test_grasp_res.energy_value 00937 < request.energy_low_threshold) 00938 { 00939 00940 // if (test_grasp_res.energy_value > request.energy_high_threshold) 00941 // ROS_INFO_STREAM("Too high grasp energy, reject it"); 00942 // if (test_grasp_res.energy_value < request.energy_low_threshold) 00943 // ROS_INFO_STREAM("Too low grasp energy , reject it"); 00944 continue; // if energy too high or too low, reject 00945 // too high could be because object too far away from the gripper, too low is not bad grasp as we want 00946 } 00947 if (request.reject_fingertip_collision) // Only accept grasp with a grasp energy between two thresholds 00948 00949 { 00950 ROS_INFO_STREAM("Bad grasp we found, accept it"); 00951 response.hand_object_collision = false; 00952 break; 00953 } 00954 else // Only accept bad grasp that involves fingertip collision with the object 00955 00956 { 00957 continue; 00958 } 00959 } 00960 00961 ROS_INFO_STREAM( "Random grasp pose:" << grasp_random_pose << " grasp joint angle " << gripper_->getDOF(0)->getVal() <<" energy " << test_grasp_res.energy_value ); 00962 ROS_INFO_STREAM("Number of objects "<<world->getNumBodies()); 00963 response.grasp_pose = grasp_random_pose; 00964 response.grasp_energy = test_grasp_res.energy_value; 00965 response.grasp_joint_angle = gripper_->getDOF(0)->getVal(); 00966 response.gripper_tabletop_clearance = gripper_tabletop_clearance; 00967 response.gripper_object_distance = gripper_object_distance; 00968 response.result = response.GENERATE_SUCCESS; 00969 return true; 00970 00971 } 00972 00973 void RosGraspitInterface::testGraspDirect(const object_manipulation_msgs::Grasp &grasp, GraspableBody *object, 00974 graspit_ros_planning_msgs::TestGrasp::Response &response) 00975 { 00976 //place the hand in the right pose 00977 gripper_->setTran(poseToTransf(grasp.grasp_pose)); 00978 //set the gripper dof (for the moment all the way open) 00979 gripper_->forceDOFVal(0, 0.523);//request.grasp.grasp_posture.position[0]); 00980 gripper_->autoGrasp(false, 0.5, true); 00981 //check for collisions 00982 gripperCollisionCheck(object, response); 00983 //if we find a collision, we are done 00984 if (response.hand_object_collision || response.hand_environment_collision) 00985 { 00986 response.test_result = response.HAND_COLLISION; 00987 return; 00988 } 00989 //compute the energy value 00990 computeEnergy(object, response); 00991 } 00992 00993 void RosGraspitInterface::testGraspCompliant(const object_manipulation_msgs::Grasp &grasp, GraspableBody *object, 00994 graspit_ros_planning_msgs::TestGrasp::Response &response) 00995 { 00996 //place the hand in the right pose 00997 gripper_->setTran(poseToTransf(grasp.grasp_pose)); 00998 //set the gripper dof in the pre-grasp 00999 gripper_->forceDOFVal(0, grasp.pre_grasp_posture.position[0]); 01000 //check for collisions 01001 gripperCollisionCheck(object, response); 01002 //if we find a collision, we are done 01003 if (response.hand_object_collision || response.hand_environment_collision) 01004 { 01005 response.test_result = response.HAND_COLLISION; 01006 return; 01007 } 01008 //perform the compliant close 01009 gripper_->compliantClose(); 01010 //compute the energy value 01011 computeEnergy(object, response); 01012 } 01013 01014 void RosGraspitInterface::testGraspReactive(const object_manipulation_msgs::Grasp &grasp, GraspableBody *object, 01015 graspit_ros_planning_msgs::TestGrasp::Response &response) 01016 { 01017 // put hand in pre-grasp pose 01018 transf pre_grasp = poseToTransf(grasp.grasp_pose); 01019 double moveDist = 100; 01020 pre_grasp = translate_transf(vec3(0, 0, -moveDist) * gripper_->getApproachTran()) * pre_grasp; 01021 gripper_->setTran(pre_grasp); 01022 // Open hand all the way up 01023 gripper_->forceDOFVal(0, 0.523); 01024 // check for collisions 01025 gripperCollisionCheck(object, response); 01026 //if we find a collision, we are done 01027 if (response.hand_object_collision || response.hand_environment_collision) 01028 { 01029 response.test_result = response.HAND_COLLISION; 01030 return; 01031 } 01032 // move hand forward until it contacts 01033 gripper_->approachToContact(moveDist, false); 01034 // Execute a compliant close 01035 gripper_->compliantClose(); 01036 //Compute the score for the resulting grasp 01037 computeEnergy(object, response); 01038 response.energy_value_list.push_back(response.energy_value); 01039 } 01040 01041 void RosGraspitInterface::testGraspRobustReactive(const object_manipulation_msgs::Grasp &grasp, GraspableBody *object, 01042 graspit_ros_planning_msgs::TestGrasp::Response &response) 01043 { 01044 // put hand in pre-grasp pose 01045 transf orig_pre_grasp = poseToTransf(grasp.grasp_pose); 01046 double moveDist = 100; 01047 const int n_tsteps = 3; 01048 //double t_steps[n_tsteps] = {-15,-10,-5,0,5,10,15}; 01049 double t_steps[n_tsteps] = {-10, 0, 10}; 01050 for (int x_step = 0; x_step < n_tsteps; x_step++) 01051 { 01052 transf pre_grasp = translate_transf(vec3(t_steps[x_step], 0, -moveDist) * gripper_->getApproachTran()) 01053 * orig_pre_grasp; 01054 gripper_->setTran(pre_grasp); 01055 // Open hand all the way up 01056 gripper_->forceDOFVal(0, 0.523); 01057 // check for collisions 01058 gripperCollisionCheck(object, response); 01059 //if we find a collision, we are done 01060 if (response.hand_object_collision || response.hand_environment_collision) 01061 { 01062 response.energy_value_list.push_back(100); 01063 } 01064 else 01065 { 01066 // move hand forward until it contacts 01067 gripper_->approachToContact(moveDist, false); 01068 // Execute a compliant close 01069 gripper_->compliantClose(); 01070 //Compute the score for the resulting grasp 01071 computeEnergy(object, response); 01072 response.energy_value_list.push_back(response.energy_value); 01073 } 01074 } 01075 01076 for (int y_step = 0; y_step < n_tsteps; y_step++) 01077 { 01078 transf pre_grasp = translate_transf(vec3(0, t_steps[y_step], -moveDist) * gripper_->getApproachTran()) 01079 * orig_pre_grasp; 01080 gripper_->setTran(pre_grasp); 01081 // Open hand all the way up 01082 gripper_->forceDOFVal(0, 0.523); 01083 // check for collisions 01084 gripperCollisionCheck(object, response); 01085 //if we find a collision, we are done 01086 if (response.hand_object_collision || response.hand_environment_collision) 01087 { 01088 response.energy_value_list.push_back(100); 01089 } 01090 else 01091 { 01092 // move hand forward until it contacts 01093 gripper_->approachToContact(moveDist, false); 01094 // Execute a compliant close 01095 gripper_->compliantClose(); 01096 01097 //Compute the score for the resulting grasp 01098 computeEnergy(object, response); 01099 response.energy_value_list.push_back(response.energy_value); 01100 } 01101 } 01102 01103 for (int z_step = 0; z_step < n_tsteps; z_step++) 01104 { 01105 transf pre_grasp = translate_transf(vec3(0, 0, t_steps[z_step] - moveDist) * gripper_->getApproachTran()) 01106 * orig_pre_grasp; 01107 gripper_->setTran(pre_grasp); 01108 // Open hand all the way up 01109 gripper_->forceDOFVal(0, 0.523); 01110 // check for collisions 01111 gripperCollisionCheck(object, response); 01112 //if we find a collision, we are done 01113 if (response.hand_object_collision || response.hand_environment_collision) 01114 { 01115 response.energy_value_list.push_back(100); 01116 } 01117 else 01118 { 01119 // move hand forward until it contacts 01120 gripper_->approachToContact(moveDist, false); 01121 // Execute a compliant close 01122 gripper_->compliantClose(); 01123 01124 //Compute the score for the resulting grasp 01125 computeEnergy(object, response); 01126 response.energy_value_list.push_back(response.energy_value); 01127 } 01128 } 01129 01130 double m_energy = mean(response.energy_value_list); 01131 double stddev_energy = stddev(response.energy_value_list); 01132 response.energy_value = m_energy + stddev_energy; 01133 } 01134 01135 bool RosGraspitInterface::testGraspCB(graspit_ros_planning_msgs::TestGrasp::Request &request, 01136 graspit_ros_planning_msgs::TestGrasp::Response &response) 01137 { 01138 response.test_performed = response.TEST_WAS_NOT_PERFORMED; 01139 //check if we have a gripper 01140 if (!gripper_ && !loadGripper()) 01141 return true; 01142 //check if we have an object 01143 //by default (for now) we only test against the first graspable object in the world 01144 World *world = graspItGUI->getIVmgr()->getWorld(); 01145 if (!world->getNumGB()) 01146 { 01147 ROS_ERROR("No graspable object loaded"); 01148 return true; 01149 } 01150 GraspableBody *object = world->getGB(0); 01151 //check is grasp is correctly specified 01152 if (request.grasp.grasp_posture.position.empty() || request.grasp.pre_grasp_posture.position.empty()) 01153 { 01154 ROS_ERROR("Gripper DOF not specified in grasp or pre-grasp"); 01155 return true; 01156 } 01157 01158 response.test_performed = response.TEST_WAS_PERFORMED; 01159 if (request.test_type == request.DIRECT) 01160 { 01161 testGraspDirect(request.grasp, object, response); 01162 } 01163 else if (request.test_type == request.COMPLIANT_CLOSE) 01164 { 01165 testGraspCompliant(request.grasp, object, response); 01166 } 01167 else if (request.test_type == request.REACTIVE_GRASP) 01168 { 01169 testGraspReactive(request.grasp, object, response); 01170 } 01171 else if (request.test_type == request.ROBUST_REACTIVE_GRASP) 01172 { 01173 testGraspReactive(request.grasp, object, response); 01174 } 01175 else 01176 { 01177 ROS_ERROR("Unknown test type requested"); 01178 response.test_performed = response.TEST_WAS_NOT_PERFORMED; 01179 } 01180 return true; 01181 } 01182 01183 bool RosGraspitInterface::graspPlanningCB(object_manipulation_msgs::GraspPlanning::Request &request, 01184 object_manipulation_msgs::GraspPlanning::Response &response) 01185 { 01186 response.error_code.value = response.error_code.OTHER_ERROR; 01187 if (!gripper_ && !loadGripper()) 01188 { 01189 ROS_ERROR("Failed to load gripper for grasp planning"); 01190 return true; 01191 } 01192 if (request.target.potential_models.empty()) 01193 { 01194 ROS_ERROR("Graspit can only evaluate grasps on database objects"); 01195 return true; 01196 } 01197 if (request.target.potential_models.size() != 1) 01198 { 01199 ROS_WARN("Graspit can only evaluate grasps on the first potential model in the list"); 01200 } 01201 if (request.grasps_to_evaluate.empty()) 01202 { 01203 ROS_ERROR("For now, graspit will test grasps on-line, but not plan new grasps"); 01204 return true; 01205 } 01206 graspit_ros_planning_msgs::LoadDatabaseModel load_srv; 01207 load_srv.request.model_id = request.target.potential_models[0].model_id; 01208 load_srv.request.clear_other_models = true; 01209 loadModelCB(load_srv.request, load_srv.response); 01210 if (load_srv.response.result != load_srv.response.LOAD_SUCCESS) 01211 { 01212 ROS_ERROR("Failed to load database model for graspit grasp testing"); 01213 return true; 01214 } 01215 GraspableBody *object = graspItGUI->getIVmgr()->getWorld()->getGB(0); 01216 01217 //have to hardcode SUCCESS as graspit defines over it... 01218 response.error_code.value = 0; 01219 01220 BOOST_FOREACH(object_manipulation_msgs::Grasp grasp, request.grasps_to_evaluate) 01221 { 01222 if (grasp.grasp_posture.position.empty() || grasp.pre_grasp_posture.position.empty()) 01223 { 01224 ROS_ERROR("Gripper DOF not specified in grasp or pre-grasp"); 01225 response.error_code.value = response.error_code.OTHER_ERROR; 01226 return true; 01227 } 01228 01229 graspit_ros_planning_msgs::TestGrasp test_srv; 01230 if (default_grasp_test_type_ == test_srv.request.DIRECT) 01231 { 01232 testGraspDirect(grasp, object, test_srv.response); 01233 } 01234 else if (default_grasp_test_type_ == test_srv.request.COMPLIANT_CLOSE) 01235 { 01236 testGraspCompliant(grasp, object, test_srv.response); 01237 } 01238 else if (default_grasp_test_type_ == test_srv.request.REACTIVE_GRASP) 01239 { 01240 testGraspReactive(grasp, object, test_srv.response); 01241 } 01242 else if (default_grasp_test_type_ == test_srv.request.ROBUST_REACTIVE_GRASP) 01243 { 01244 testGraspReactive(grasp, object, test_srv.response); 01245 } 01246 if (test_srv.response.test_performed != test_srv.response.TEST_WAS_PERFORMED) 01247 { 01248 ROS_ERROR("Failed to test grasp"); 01249 response.error_code.value = response.error_code.OTHER_ERROR; 01250 return true; 01251 } 01252 01253 //come up with some probability value based on the test result 01254 double probability; 01255 //0 probability for grasps that result in collision 01256 if (test_srv.response.test_result == test_srv.response.HAND_COLLISION) 01257 probability = 0.0; 01258 //otherwise, return non-zero linear probability if the energy is below the threshold 01259 if (default_grasp_test_type_ == test_srv.request.ROBUST_REACTIVE_GRASP) 01260 { 01261 // Compute the mean and stddev of the values 01262 } 01263 probability = std::max(0.0, 1 - (test_srv.response.energy_value / default_energy_threshold_)); 01264 grasp.success_probability = probability; 01265 01266 response.grasps.push_back(grasp); 01267 } 01268 01269 return true; 01270 } 01271 01272 }