grasp_tester_fast.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 *  Copyright (c) 2009, Willow Garage, Inc.
00004 *  All rights reserved.
00005 *
00006 *  Redistribution and use in source and binary forms, with or without
00007 *  modification, are permitted provided that the following conditions
00008 *  are met:
00009 *
00010 *   * Redistributions of source code must retain the above copyright
00011 *     notice, this list of conditions and the following disclaimer.
00012 *   * Redistributions in binary form must reproduce the above
00013 *     copyright notice, this list of conditions and the following
00014 *     disclaimer in the documentation and/or other materials provided
00015 *     with the distribution.
00016 *   * Neither the name of the Willow Garage nor the names of its
00017 *     contributors may be used to endorse or promote products derived
00018 *     from this software without specific prior written permission.
00019 *
00020 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 
00031 *  POSSIBILITY OF SUCH DAMAGE.
00032 *********************************************************************/
00033 
00034 // Author(s): E. Gil Jones
00035 
00036 #include <sstream>
00037 
00038 #include "object_manipulator/grasp_execution/grasp_tester_fast.h"
00039 
00040 #include "object_manipulator/tools/hand_description.h"
00041 #include "object_manipulator/tools/vector_tools.h"
00042 #include "object_manipulator/tools/mechanism_interface.h"
00043 
00044 //#include <demo_synchronizer/synchronizer_client.h>
00045 
00046 using object_manipulation_msgs::GraspResult;
00047 using arm_navigation_msgs::ArmNavigationErrorCodes;
00048 
00049 namespace object_manipulator {
00050 
00051   void  print_contacts(planning_environment::CollisionModels* cm, planning_models::KinematicState* state) {
00052     std::vector<arm_navigation_msgs::ContactInformation> contacts;
00053     cm->getAllCollisionsForState(*state, contacts,1);
00054 
00055     std::vector<std::string> names;
00056     for(unsigned int j = 0; j < contacts.size(); j++) {
00057       names.push_back(contacts[j].contact_body_1);
00058       
00059       ROS_DEBUG_STREAM_NAMED("manipulation", "Collision between " << contacts[j].contact_body_1
00060                              << " and " << contacts[j].contact_body_2);
00061     }
00062   }
00063 
00064   void visualize_end_effector_in_state(planning_environment::CollisionModels* cm,
00065                                        planning_models::KinematicState* state, 
00066                                        const std::vector<std::string> &end_effector_links,
00067                                        const char *marker_name,
00068                                        ros::Publisher &vis_marker_array_publisher) {
00069     
00070     std_msgs::ColorRGBA col;
00071     col.r = 0.0;
00072     col.g = 1.0;
00073     col.b = 1.0;
00074     col.a = 1.0;
00075     visualization_msgs::MarkerArray arr;
00076     cm->getRobotMarkersGivenState(*state, arr, col,
00077                                   marker_name,
00078                                   ros::Duration(0.0),
00079                                   &end_effector_links);
00080     vis_marker_array_publisher.publish(arr);
00081 
00082   }
00083 
00084     void visualize_grasps(const object_manipulation_msgs::PickupGoal &pickup_goal,
00085                           const std::vector<object_manipulation_msgs::Grasp> &grasps,
00086                           const std::vector<GraspExecutionInfo> &execution_info,
00087                           ros::Publisher &vis_marker_publisher) {
00088         /* display markers for all of the grasps */
00089         for(unsigned int i = 0; i < grasps.size(); i++)
00090         {
00091             float r, g, b;
00092             switch(execution_info[i].result_.result_code)
00093             {
00094             case GraspResult::GRASP_OUT_OF_REACH:
00095                 r = 1.0; g = 0.0; b = 0.0;
00096                 break;
00097             case GraspResult::GRASP_IN_COLLISION:
00098                 r = 1.0; g = 0.0; b = 0.0;
00099                 break;
00100             case GraspResult::GRASP_UNFEASIBLE:
00101                 r = 1.0; g = 0.0; b = 0.0;
00102                 break;
00103             case GraspResult::PREGRASP_OUT_OF_REACH:
00104                 r = 1.0; g = 0.0; b = 1.0;
00105                 break;
00106             case GraspResult::PREGRASP_IN_COLLISION:
00107                 r = 1.0; g = 0.0; b = 1.0;
00108                 break;
00109             case GraspResult::PREGRASP_UNFEASIBLE:
00110                 r = 1.0; g = 0.0; b = 1.0;
00111                 break;
00112             case GraspResult::LIFT_OUT_OF_REACH:
00113                 r = 0.0; g = 0.0; b = 1.0;
00114                 break;
00115             case GraspResult::LIFT_IN_COLLISION:
00116                 r = 0.0; g = 0.0; b = 1.0;
00117                 break;
00118             case GraspResult::LIFT_UNFEASIBLE:
00119                 r = 0.0; g = 0.0; b = 1.0;
00120                 break;
00121             case GraspResult::SUCCESS:
00122                 r = 0.0; g = 1.0; b = 0.0;
00123                 break;
00124             default:
00125                 r = 0.0; g = 0.0; b = 0.0;
00126             }
00127 
00128             visualization_msgs::Marker marker;
00129 
00130             marker.pose = grasps[i].grasp_pose;
00131             marker.header.frame_id = pickup_goal.target.reference_frame_id;
00132             marker.header.stamp = ros::Time::now();
00133             std::ostringstream marker_ns;
00134             marker_ns << "grasp " << i << " (" << execution_info[i].result_.result_code << ")";
00135             marker.ns = marker_ns.str();
00136 
00137             marker.action = visualization_msgs::Marker::ADD;
00138             marker.lifetime = ros::Duration();
00139 
00140             marker.type = visualization_msgs::Marker::ARROW;
00141             marker.scale.x = 0.1235;
00142             marker.scale.y = 0.06;
00143             marker.scale.z = 0.06;
00144             marker.color.r = r;
00145             marker.color.g = g;
00146             marker.color.b = b;
00147             marker.color.a = 1.0;
00148 
00149             marker.id = 0;
00150 
00151             ROS_DEBUG("Displaying marker %d with ns %s", i, marker.ns.c_str());
00152             vis_marker_publisher.publish(marker);
00153         }
00154     }
00155 
00156     GraspTesterFast::GraspTesterFast(planning_environment::CollisionModels* cm,
00157                                      const std::string& plugin_name)
00158                                          : GraspTester(),
00159                                          consistent_angle_(M_PI/12.0),
00160                                          num_points_(10),
00161                                          redundancy_(2),
00162                                          cm_(cm),
00163                                          state_(NULL),
00164                                          kinematics_loader_("kinematics_base","kinematics::KinematicsBase")
00165     {
00166         ros::NodeHandle nh;
00167 
00168         vis_marker_publisher_ = nh.advertise<visualization_msgs::Marker> ("grasp_executor_fast", 128);
00169         vis_marker_array_publisher_ = nh.advertise<visualization_msgs::MarkerArray> ("grasp_executor_fast_array", 128);
00170 
00171         const std::map<std::string, planning_models::KinematicModel::GroupConfig>& group_config_map =
00172                 getCollisionModels()->getKinematicModel()->getJointModelGroupConfigMap();
00173 
00174         for(std::map<std::string, planning_models::KinematicModel::GroupConfig>::const_iterator it = group_config_map.begin();
00175         it != group_config_map.end();
00176         it++) {
00177             kinematics::KinematicsBase* kinematics_solver = NULL;
00178             try
00179             {
00180                 kinematics_solver = kinematics_loader_.createClassInstance(plugin_name);
00181             }
00182             catch(pluginlib::PluginlibException& ex)
00183             {
00184                 ROS_ERROR("The plugin failed to load. Error1: %s", ex.what());    //handle the class failing to load
00185                 return;
00186             }
00187             if(!it->second.base_link_.empty() && !it->second.tip_link_.empty()) {
00188                 ik_solver_map_[it->first] = new arm_kinematics_constraint_aware::ArmKinematicsSolverConstraintAware(kinematics_solver,
00189                                                                                                                     getCollisionModels(),
00190                                                                                                                     it->first);
00191                 ik_solver_map_[it->first]->setSearchDiscretization(.025);
00192             }
00193         }
00194     }
00195 
00196     GraspTesterFast::~GraspTesterFast()
00197     {
00198         for(std::map<std::string, arm_kinematics_constraint_aware::ArmKinematicsSolverConstraintAware*>::iterator it = ik_solver_map_.begin();
00199         it != ik_solver_map_.end();
00200         it++) {
00201             delete it->second;
00202         }
00203     }
00204 
00205     planning_environment::CollisionModels* GraspTesterFast::getCollisionModels() {
00206         if(cm_ == NULL) {
00207             return &mechInterface().getCollisionModels();
00208         } else {
00209             return cm_;
00210         }
00211     }
00212 
00213     planning_models::KinematicState* GraspTesterFast::getPlanningSceneState() {
00214         if(state_ == NULL) {
00215             if(mechInterface().getPlanningSceneState() == NULL)
00216             {
00217                 ROS_ERROR("Planning scene was NULL!  Did you forget to set it somewhere?  Getting new planning scene");
00218                 const arm_navigation_msgs::OrderedCollisionOperations collision_operations;
00219                 const std::vector<arm_navigation_msgs::LinkPadding> link_padding;
00220                 mechInterface().getPlanningScene(collision_operations, link_padding);
00221             }
00222             return mechInterface().getPlanningSceneState();
00223         }
00224         else {
00225             return state_;
00226         }
00227     }
00228 
00230     std::vector<arm_navigation_msgs::LinkPadding>
00231             GraspTesterFast::linkPaddingForGrasp(const object_manipulation_msgs::PickupGoal &pickup_goal)
00232     {
00233         return concat(MechanismInterface::gripperPadding(pickup_goal.arm_name, 0.0),
00234                       pickup_goal.additional_link_padding);
00235     }
00236 
00237 
00238 
00239     void GraspTesterFast::getGroupLinks(const std::string& group_name,
00240                                         std::vector<std::string>& group_links)
00241     {
00242         group_links.clear();
00243         const planning_models::KinematicModel::JointModelGroup* jmg =
00244                 getCollisionModels()->getKinematicModel()->getModelGroup(group_name);
00245         if(jmg == NULL) return;
00246         group_links = jmg->getGroupLinkNames();
00247     }
00248 
00249     void GraspTesterFast::getGroupJoints(const std::string& group_name,
00250                                          std::vector<std::string>& group_joints)
00251     {
00252         if(ik_solver_map_.find(group_name) == ik_solver_map_.end()) {
00253             ROS_ERROR_STREAM("No group for solver " << group_name);
00254             return;
00255         }
00256         group_joints = ik_solver_map_[group_name]->getJointNames();
00257     }
00258 
00259     bool GraspTesterFast::getInterpolatedIK(const std::string& arm_name,
00260                                             const tf::Transform& first_pose,
00261                                             const tf::Vector3& direction,
00262                                             const double& distance,
00263                                             const std::vector<double>& ik_solution,
00264                                             const bool& reverse,
00265                                             const bool& premultiply,
00266                                             trajectory_msgs::JointTrajectory& traj) {
00267 
00268         std::map<std::string, double> ik_solution_map;
00269         for(unsigned int i = 0; i < traj.joint_names.size(); i++) {
00270             ik_solution_map[traj.joint_names[i]] = ik_solution[i];
00271         }
00272 
00273         getPlanningSceneState()->setKinematicState(ik_solution_map);
00274 
00275         geometry_msgs::Pose start_pose;
00276         tf::poseTFToMsg(first_pose, start_pose);
00277 
00278         arm_navigation_msgs::Constraints emp;
00279         arm_navigation_msgs::ArmNavigationErrorCodes error_code;
00280         return ik_solver_map_[arm_name]->interpolateIKDirectional(start_pose,
00281                                                                   direction,
00282                                                                   distance,
00283                                                                   emp,
00284                                                                   getPlanningSceneState(),
00285                                                                   error_code,
00286                                                                   traj,
00287                                                                   redundancy_,
00288                                                                   consistent_angle_,
00289                                                                   reverse,
00290                                                                   premultiply,
00291                                                                   num_points_,
00292                                                                   ros::Duration(2.5),
00293                                                                   false);
00294     }
00295 
00296     /* this doesn't get called since testGrasps() does everything, but we still need to have
00297    this function since it is pure virtual in the base class */
00298     void GraspTesterFast::testGrasp(const object_manipulation_msgs::PickupGoal &pickup_goal,
00299                                     const object_manipulation_msgs::Grasp &grasp,
00300                                     GraspExecutionInfo &execution_info)  {}
00301 
00302     void GraspTesterFast::testGrasps(const object_manipulation_msgs::PickupGoal &pickup_goal,
00303                                      const std::vector<object_manipulation_msgs::Grasp> &grasps,
00304                                      std::vector<GraspExecutionInfo> &execution_info,
00305                                      bool return_on_first_hit)
00306 
00307     {
00308         ros::WallTime start = ros::WallTime::now();
00309         std::map<unsigned int, unsigned int> outcome_count;
00310         planning_environment::CollisionModels* cm = getCollisionModels();
00311         planning_models::KinematicState* state = getPlanningSceneState();
00312         std::map<std::string, double> planning_scene_state_values;
00313         state->getKinematicStateValues(planning_scene_state_values);
00314 
00315         std::vector<std::string> end_effector_links, arm_links;
00316         end_effector_links = handDescription().gripperTouchLinkNames(pickup_goal.arm_name);
00317         //getGroupLinks(handDescription().gripperCollisionName(pickup_goal.arm_name), end_effector_links);
00318         getGroupLinks(handDescription().armGroup(pickup_goal.arm_name), arm_links);
00319 
00320         collision_space::EnvironmentModel::AllowedCollisionMatrix original_acm = cm->getCurrentAllowedCollisionMatrix();
00321         cm->disableCollisionsForNonUpdatedLinks(pickup_goal.arm_name); /* disable collisions for all links not in the arm we are using */
00322         collision_space::EnvironmentModel::AllowedCollisionMatrix group_disable_acm = cm->getCurrentAllowedCollisionMatrix();
00323         collision_space::EnvironmentModel::AllowedCollisionMatrix object_disable_acm = group_disable_acm;
00324         object_disable_acm.changeEntry(pickup_goal.collision_object_name, end_effector_links, true);
00325         collision_space::EnvironmentModel::AllowedCollisionMatrix object_support_disable_acm = object_disable_acm;
00326         if(pickup_goal.allow_gripper_support_collision)
00327         {
00328             ROS_DEBUG("Disabling collisions between gripper and support surface");
00329             if(pickup_goal.collision_support_surface_name == "\"all\"")
00330             {
00331                 for(unsigned int i = 0; i < end_effector_links.size(); i++){
00332                     object_support_disable_acm.changeEntry(end_effector_links[i], true);
00333                 }
00334             }
00335             else{
00336                 ROS_DEBUG("not all");
00337                 object_support_disable_acm.changeEntry(pickup_goal.collision_support_surface_name, end_effector_links, true);
00338             }
00339         }
00340 
00341         /* allows collisions between the object and the and effector */
00342         collision_space::EnvironmentModel::AllowedCollisionMatrix object_all_arm_disable_acm = object_disable_acm;
00343 
00344         /* allows collisions between the end effector and the object, as well as between the end effector and the support surface */
00345         collision_space::EnvironmentModel::AllowedCollisionMatrix object_support_all_arm_disable_acm = object_support_disable_acm;
00346 
00347         /* allows collisions between the arm and anything else */
00348         collision_space::EnvironmentModel::AllowedCollisionMatrix group_all_arm_disable_acm = group_disable_acm;
00349 
00350         //turning off collisions for the arm associated with this end effector
00351         for(unsigned int i = 0; i < arm_links.size(); i++) {
00352             object_all_arm_disable_acm.changeEntry(arm_links[i], true);
00353             object_support_all_arm_disable_acm.changeEntry(arm_links[i], true);
00354             group_all_arm_disable_acm.changeEntry(arm_links[i], true);
00355         }
00356         cm->setAlteredAllowedCollisionMatrix(object_support_all_arm_disable_acm);
00357 
00358         //first we apply link padding for grasp check
00359         cm->applyLinkPaddingToCollisionSpace(linkPaddingForGrasp(pickup_goal));
00360 
00361         //setup that's not grasp specific
00362         std_msgs::Header target_header;
00363         target_header.frame_id = pickup_goal.target.reference_frame_id;
00364 
00365         bool in_object_frame = false;
00366         tf::Transform obj_pose(tf::Quaternion(0,0,0,1.0), tf::Vector3(0.0,0.0,0.0));
00367         if(pickup_goal.target.reference_frame_id == pickup_goal.collision_object_name) {
00368             in_object_frame = true;
00369             geometry_msgs::PoseStamped obj_world_pose_stamped;
00370             cm->convertPoseGivenWorldTransform(*state,
00371                                                cm->getWorldFrameId(),
00372                                                pickup_goal.target.potential_models[0].pose.header,
00373                                                pickup_goal.target.potential_models[0].pose.pose,
00374                                                obj_world_pose_stamped);
00375             tf::poseMsgToTF(obj_world_pose_stamped.pose, obj_pose);
00376         }
00377 
00378         execution_info.clear();
00379         execution_info.resize(grasps.size());
00380 
00381         tf::Vector3 pregrasp_dir;
00382         tf::vector3MsgToTF(doNegate(handDescription().approachDirection(pickup_goal.arm_name)), pregrasp_dir);
00383         pregrasp_dir.normalize();
00384 
00385         tf::Vector3 lift_dir;
00386         tf::vector3MsgToTF(pickup_goal.lift.direction.vector, lift_dir);
00387         lift_dir.normalize();
00388         tf::Vector3 distance_lift_dir = lift_dir*fabs(pickup_goal.lift.desired_distance);
00389         tf::Transform lift_trans(tf::Quaternion(0,0,0,1.0), distance_lift_dir);
00390 
00391         std::vector<tf::Transform> grasp_poses(grasps.size());
00392 
00393         ros::Rate debug_rate(0.2);
00394 
00395         //now this is grasp specific
00396         for(unsigned int i = 0; i < grasps.size(); i++) {
00397 
00398             //check whether the grasp pose is ok (only checking hand, not arms)
00399             //using pre-grasp posture, cause grasp_posture only matters for closing the gripper
00400             std::map<std::string, double> pre_grasp_joint_vals;
00401             for(unsigned int j = 0; j < grasps[i].pre_grasp_posture.name.size(); j++) {
00402                 pre_grasp_joint_vals[grasps[i].pre_grasp_posture.name[j]] = grasps[i].pre_grasp_posture.position[j];
00403             }
00404             state->setKinematicState(pre_grasp_joint_vals);
00405 
00406             //always true
00407             execution_info[i].result_.continuation_possible = true;
00408 
00409             if(!in_object_frame) {
00410                 geometry_msgs::PoseStamped grasp_world_pose_stamped;
00411                 if(!cm->convertPoseGivenWorldTransform(*state,
00412                                                        cm->getWorldFrameId(),
00413                                                        target_header,
00414                                                        grasps[i].grasp_pose,
00415                                                        grasp_world_pose_stamped)) {
00416                     ROS_WARN_STREAM("Can't convert into non-object frame " << target_header.frame_id);
00417                     continue;
00418                 }
00419                 tf::poseMsgToTF(grasp_world_pose_stamped.pose, grasp_poses[i]);
00420             } else {
00421                 tf::Transform gp;
00422                 tf::poseMsgToTF(grasps[i].grasp_pose, gp);
00423                 grasp_poses[i] = obj_pose*gp;
00424             }
00425             state->updateKinematicStateWithLinkAt(handDescription().gripperFrame(pickup_goal.arm_name),grasp_poses[i]);
00426             visualize_end_effector_in_state(cm, state, end_effector_links, "grasp", vis_marker_array_publisher_);
00427 
00428 
00429             if(cm->isKinematicStateInCollision(*state)) {
00430                 ROS_DEBUG_STREAM("Grasp in collision");
00431                 print_contacts(cm, state);
00432                 execution_info[i].result_.result_code = GraspResult::GRASP_IN_COLLISION;
00433                 outcome_count[GraspResult::GRASP_IN_COLLISION]++;
00434             } else {
00435                 execution_info[i].result_.result_code = 0;
00436             }
00437         }
00438 
00439         //now we revert link paddings for pre-grasp and lift checks
00440         cm->revertCollisionSpacePaddingToDefault();
00441 
00442         //first we do lift, with the hand in the grasp posture (collisions allowed between gripper and object)
00443         cm->setAlteredAllowedCollisionMatrix(object_support_all_arm_disable_acm);
00444         for(unsigned int i = 0; i < grasps.size(); i++) {
00445 
00446             if(execution_info[i].result_.result_code != 0) continue;
00447 
00448             std::map<std::string, double> grasp_joint_vals;
00449             for(unsigned int j = 0; j < grasps[i].grasp_posture.name.size(); j++) {
00450                 grasp_joint_vals[grasps[i].grasp_posture.name[j]] = grasps[i].grasp_posture.position[j];
00451             }
00452             state->setKinematicState(grasp_joint_vals);
00453 
00454             tf::Transform lift_pose = lift_trans*grasp_poses[i];
00455             state->updateKinematicStateWithLinkAt(handDescription().gripperFrame(pickup_goal.arm_name),lift_pose);
00456 
00457             if(cm->isKinematicStateInCollision(*state)) {
00458                 ROS_DEBUG_STREAM_NAMED("manipulation", "Lift in collision");
00459                 print_contacts(cm, state);
00460                 execution_info[i].result_.result_code = GraspResult::LIFT_IN_COLLISION;
00461                 outcome_count[GraspResult::LIFT_IN_COLLISION]++;
00462             }
00463         }
00464 
00465         //now we do pre-grasp not allowing object touch, but with arms disabled
00466         cm->setAlteredAllowedCollisionMatrix(group_all_arm_disable_acm);
00467 
00468         for(unsigned int i = 0; i < grasps.size(); i++) {
00469 
00470             if(execution_info[i].result_.result_code != 0) continue;
00471 
00472             //opening the gripper back to pre_grasp
00473             std::map<std::string, double> pre_grasp_joint_vals;
00474             for(unsigned int j = 0; j < grasps[i].pre_grasp_posture.name.size(); j++) {
00475                 pre_grasp_joint_vals[grasps[i].pre_grasp_posture.name[j]] = grasps[i].pre_grasp_posture.position[j];
00476             }
00477             state->setKinematicState(pre_grasp_joint_vals);
00478 
00479             tf::Vector3 distance_pregrasp_dir = pregrasp_dir * fabs(grasps[0].desired_approach_distance);
00480             tf::Transform pre_grasp_trans(tf::Quaternion(0,0,0,1.0), distance_pregrasp_dir);
00481             tf::Transform pre_grasp_pose = grasp_poses[i]*pre_grasp_trans;
00482             state->updateKinematicStateWithLinkAt(handDescription().gripperFrame(pickup_goal.arm_name),pre_grasp_pose);
00483             visualize_end_effector_in_state(cm, state, end_effector_links, "pre_grasp", vis_marker_array_publisher_);
00484 
00485 
00486             if(cm->isKinematicStateInCollision(*state)) {
00487                 ROS_DEBUG_STREAM_NAMED("manipulation", "Pre-grasp in collision");
00488                 print_contacts(cm, state);
00489 
00490                 execution_info[i].result_.result_code = GraspResult::PREGRASP_IN_COLLISION;
00491                 outcome_count[GraspResult::PREGRASP_IN_COLLISION]++;
00492                 continue;
00493             }
00494         }
00495 
00496         visualize_grasps(pickup_goal, grasps, execution_info, vis_marker_publisher_);
00497 
00498         std_msgs::Header world_header;
00499         world_header.frame_id = cm->getWorldFrameId();
00500         const std::vector<std::string>& joint_names = ik_solver_map_[pickup_goal.arm_name]->getJointNames();
00501 
00502         if(return_on_first_hit) {
00503 
00504             bool last_ik_failed = false;
00505             for(unsigned int i = 0; i < grasps.size(); i++) {
00506 
00507                 if(execution_info[i].result_.result_code != 0) continue;
00508 
00509                 if(!last_ik_failed) {
00510                     //now we move to the ik portion, which requires re-enabling collisions for the arms
00511                     cm->setAlteredAllowedCollisionMatrix(object_support_disable_acm);
00512 
00513                     //and also reducing link paddings
00514                     cm->applyLinkPaddingToCollisionSpace(linkPaddingForGrasp(pickup_goal));
00515                 }
00516                 //getting back to original state for seed
00517                 state->setKinematicState(planning_scene_state_values);
00518 
00519                 //adjusting planning scene state for pre-grasp
00520                 std::map<std::string, double> pre_grasp_values;
00521                 for(unsigned int j = 0; j < grasps[i].pre_grasp_posture.name.size(); j++) {
00522                     pre_grasp_values[grasps[i].pre_grasp_posture.name[j]] = grasps[i].pre_grasp_posture.position[j];
00523                 }
00524                 state->setKinematicState(pre_grasp_values);
00525 
00526                 //now call ik for grasp
00527                 geometry_msgs::Pose grasp_geom_pose;
00528                 tf::poseTFToMsg(grasp_poses[i], grasp_geom_pose);
00529                 geometry_msgs::PoseStamped base_link_grasp_pose;
00530                 cm->convertPoseGivenWorldTransform(*state,
00531                                                    ik_solver_map_[pickup_goal.arm_name]->getBaseName(),
00532                                                    world_header,
00533                                                    grasp_geom_pose,
00534                                                    base_link_grasp_pose);
00535 
00536                 arm_navigation_msgs::Constraints emp;
00537                 sensor_msgs::JointState solution;
00538                 arm_navigation_msgs::ArmNavigationErrorCodes error_code;
00539                 ROS_DEBUG_STREAM("X y z " << base_link_grasp_pose.pose.position.x << " "
00540                                 << base_link_grasp_pose.pose.position.y << " "
00541                                 << base_link_grasp_pose.pose.position.z);
00542                 if(!ik_solver_map_[pickup_goal.arm_name]->findConstraintAwareSolution(base_link_grasp_pose.pose,
00543                                                                                       emp,
00544                                                                                       state,
00545                                                                                       solution,
00546                                                                                       error_code,
00547                                                                                       false)) {
00548                     ROS_DEBUG_STREAM_NAMED("manipulation", "IK for grasp failed");
00549                     print_contacts(cm, state);
00550 
00551                     execution_info[i].result_.result_code = GraspResult::GRASP_OUT_OF_REACH;
00552                     outcome_count[GraspResult::GRASP_OUT_OF_REACH]++;
00553                     last_ik_failed = true;
00554                     continue;
00555                 } else {
00556                     last_ik_failed = false;
00557                 }
00558 
00559                 std::map<std::string, double> ik_map_pre_grasp;
00560                 std::map<std::string, double> ik_map_grasp;
00561                 for(unsigned int j = 0; j < joint_names.size(); j++) {
00562                     ik_map_pre_grasp[joint_names[j]] = solution.position[j];
00563                 }
00564                 ik_map_grasp = ik_map_pre_grasp;
00565 
00566                 for(unsigned int j = 0; j < grasps[i].pre_grasp_posture.name.size(); j++) {
00567                     ik_map_pre_grasp[grasps[i].pre_grasp_posture.name[j]] = grasps[i].pre_grasp_posture.position[j];
00568                 }
00569                 for(unsigned int j = 0; j < grasps[i].grasp_posture.name.size(); j++) {
00570                     ik_map_grasp[grasps[i].grasp_posture.name[j]] = grasps[i].grasp_posture.position[j];
00571                 }
00572 
00573                 state->setKinematicState(ik_map_pre_grasp);
00574 
00575                 //now we solve interpolated ik
00576                 tf::Transform base_link_bullet_grasp_pose;
00577                 tf::poseMsgToTF(base_link_grasp_pose.pose, base_link_bullet_grasp_pose);
00578                 execution_info[i].approach_trajectory_.joint_names = joint_names;
00579                 //now we need to do interpolated ik
00580                 if(!getInterpolatedIK(pickup_goal.arm_name,
00581                                       base_link_bullet_grasp_pose,
00582                                       pregrasp_dir,
00583                                       grasps[i].desired_approach_distance,
00584                                       solution.position,
00585                                       true,
00586                                       false,
00587                                       execution_info[i].approach_trajectory_)) {
00588                     ROS_DEBUG_STREAM_NAMED("manipulation", "No interpolated IK for pre-grasp to grasp");
00589                     execution_info[i].result_.result_code = GraspResult::PREGRASP_UNFEASIBLE;
00590                     outcome_count[GraspResult::PREGRASP_UNFEASIBLE]++;
00591                     continue;
00592                 }
00593 
00594                 ROS_DEBUG_STREAM_NAMED("manipulation", "Last approach point is " <<
00595                                  execution_info[i].approach_trajectory_.points.back().positions[0] << " " <<
00596                                  execution_info[i].approach_trajectory_.points.back().positions[1] << " " <<
00597                                  execution_info[i].approach_trajectory_.points.back().positions[2] << " " <<
00598                                  execution_info[i].approach_trajectory_.points.back().positions[3] << " " <<
00599                                  execution_info[i].approach_trajectory_.points.back().positions[4] << " " <<
00600                                  execution_info[i].approach_trajectory_.points.back().positions[5] << " " <<
00601                                  execution_info[i].approach_trajectory_.points.back().positions[6]);
00602 
00603                 state->setKinematicState(ik_map_grasp);
00604                 execution_info[i].lift_trajectory_.joint_names = joint_names;
00605                 if(!getInterpolatedIK(pickup_goal.arm_name,
00606                                       base_link_bullet_grasp_pose,
00607                                       lift_dir,
00608                                       pickup_goal.lift.desired_distance,
00609                                       solution.position,
00610                                       false,
00611                                       true,
00612                                       execution_info[i].lift_trajectory_)) {
00613                     ROS_DEBUG_STREAM_NAMED("manipulation", "No interpolated IK for grasp to lift");
00614                     execution_info[i].result_.result_code = GraspResult::LIFT_UNFEASIBLE;
00615                     outcome_count[GraspResult::LIFT_UNFEASIBLE]++;
00616                     continue;
00617                 }
00618 
00619                 ROS_DEBUG_STREAM_NAMED("manipulation", "First lift point is " <<
00620                                  execution_info[i].lift_trajectory_.points.front().positions[0] << " " <<
00621                                  execution_info[i].lift_trajectory_.points.front().positions[1] << " " <<
00622                                  execution_info[i].lift_trajectory_.points.front().positions[2] << " " <<
00623                                  execution_info[i].lift_trajectory_.points.front().positions[3] << " " <<
00624                                  execution_info[i].lift_trajectory_.points.front().positions[4] << " " <<
00625                                  execution_info[i].lift_trajectory_.points.front().positions[5] << " " <<
00626                                  execution_info[i].lift_trajectory_.points.front().positions[6]);
00627 
00628                 //now we revert link paddings and object collisions and do a final check for the initial ik points
00629                 cm->revertCollisionSpacePaddingToDefault();
00630 
00631                 //the start of the approach needs to be collision-free according to the default collision matrix
00632                 cm->setAlteredAllowedCollisionMatrix(group_disable_acm);
00633 
00634                 if(execution_info[i].approach_trajectory_.points.empty()) {
00635                     ROS_WARN_STREAM("No result code and no points in approach trajectory");
00636                     continue;
00637                 }
00638 
00639                 std::map<std::string, double> pre_grasp_ik = ik_map_pre_grasp;
00640                 for(unsigned int j = 0; j < joint_names.size(); j++) {
00641                     pre_grasp_ik[joint_names[j]] = execution_info[i].approach_trajectory_.points[0].positions[j];
00642                 }
00643                 state->setKinematicState(pre_grasp_ik);
00644                 if(cm->isKinematicStateInCollision(*state)) {
00645                     ROS_DEBUG_STREAM_NAMED("manipulation", "Final pre-grasp check failed");
00646                     std::vector<arm_navigation_msgs::ContactInformation> contacts;
00647                     execution_info[i].result_.result_code = GraspResult::PREGRASP_OUT_OF_REACH;
00648                     outcome_count[GraspResult::PREGRASP_OUT_OF_REACH]++;
00649                     continue;
00650                 }
00651 
00652                 //the object will be attached to the gripper for the lift, so we don't care if the object collides with the hand
00653                 cm->setAlteredAllowedCollisionMatrix(object_support_disable_acm);
00654 
00655                 if(execution_info[i].lift_trajectory_.points.empty()) {
00656                     ROS_WARN_STREAM("No result code and no points in lift trajectory");
00657                     continue;
00658                 }
00659                 std::map<std::string, double> lift_ik = ik_map_pre_grasp;
00660                 for(unsigned int j = 0; j < joint_names.size(); j++) {
00661                     lift_ik[joint_names[j]] = execution_info[i].lift_trajectory_.points.back().positions[j];
00662                 }
00663                 state->setKinematicState(lift_ik);
00664                 if(cm->isKinematicStateInCollision(*state)) {
00665                     ROS_DEBUG_STREAM_NAMED("manipulation", "Final lift check failed");
00666                     execution_info[i].result_.result_code = GraspResult::LIFT_OUT_OF_REACH;
00667                     outcome_count[GraspResult::LIFT_OUT_OF_REACH]++;
00668                     continue;
00669                 } else {
00670                     ROS_DEBUG_STREAM("Everything successful");
00671                     execution_info[i].result_.result_code = GraspResult::SUCCESS;
00672                     execution_info.resize(i+1);
00673                     outcome_count[GraspResult::SUCCESS]++;
00674                     break;
00675                 }
00676             }
00677             for(std::map<unsigned int, unsigned int>::iterator it = outcome_count.begin();
00678             it != outcome_count.end();
00679             it++) {
00680                 ROS_INFO_STREAM("Outcome " << it->first << " count " << it->second);
00681             }
00682             cm->setAlteredAllowedCollisionMatrix(original_acm);
00683             ROS_INFO_STREAM("Took " << (ros::WallTime::now()-start).toSec());
00684             return;
00685         }
00686 
00687 
00688         //now we move to the ik portion, which requires re-enabling collisions for the arms
00689         cm->setAlteredAllowedCollisionMatrix(object_support_disable_acm);
00690 
00691         //and also reducing link paddings
00692         cm->applyLinkPaddingToCollisionSpace(linkPaddingForGrasp(pickup_goal));
00693 
00694         for(unsigned int i = 0; i < grasps.size(); i++) {
00695 
00696             if(execution_info[i].result_.result_code != 0) continue;
00697 
00698             //getting back to original state for seed
00699             state->setKinematicState(planning_scene_state_values);
00700 
00701             //adjusting planning scene state for pre-grasp
00702             std::map<std::string, double> pre_grasp_values;
00703             for(unsigned int j = 0; j < grasps[i].pre_grasp_posture.name.size(); j++) {
00704                 pre_grasp_values[grasps[i].pre_grasp_posture.name[j]] = grasps[i].pre_grasp_posture.position[j];
00705             }
00706             state->setKinematicState(pre_grasp_values);
00707 
00708             //now call ik for grasp
00709             geometry_msgs::Pose grasp_geom_pose;
00710             tf::poseTFToMsg(grasp_poses[i], grasp_geom_pose);
00711             geometry_msgs::PoseStamped base_link_grasp_pose;
00712             cm->convertPoseGivenWorldTransform(*state,
00713                                                ik_solver_map_[pickup_goal.arm_name]->getBaseName(),
00714                                                world_header,
00715                                                grasp_geom_pose,
00716                                                base_link_grasp_pose);
00717 
00718             arm_navigation_msgs::Constraints emp;
00719             sensor_msgs::JointState solution;
00720             arm_navigation_msgs::ArmNavigationErrorCodes error_code;
00721             if(!ik_solver_map_[pickup_goal.arm_name]->findConstraintAwareSolution(base_link_grasp_pose.pose,
00722                                                                                   emp,
00723                                                                                   state,
00724                                                                                   solution,
00725                                                                                   error_code,
00726                                                                                   false)) {
00727                 ROS_DEBUG_STREAM_NAMED("manipulation", "Grasp out of reach");
00728                 print_contacts(cm, state);
00729                 execution_info[i].result_.result_code = GraspResult::GRASP_OUT_OF_REACH;
00730                 outcome_count[GraspResult::GRASP_OUT_OF_REACH]++;
00731                 continue;
00732             }
00733 
00734             std::map<std::string, double> ik_map_pre_grasp;
00735             std::map<std::string, double> ik_map_grasp;
00736             for(unsigned int j = 0; j < joint_names.size(); j++) {
00737                 ik_map_pre_grasp[joint_names[j]] = solution.position[j];
00738             }
00739             ik_map_grasp = ik_map_pre_grasp;
00740 
00741             for(unsigned int j = 0; j < grasps[i].pre_grasp_posture.name.size(); j++) {
00742                 ik_map_pre_grasp[grasps[i].pre_grasp_posture.name[j]] = grasps[i].pre_grasp_posture.position[j];
00743             }
00744             for(unsigned int j = 0; j < grasps[i].grasp_posture.name.size(); j++) {
00745                 ik_map_grasp[grasps[i].grasp_posture.name[j]] = grasps[i].grasp_posture.position[j];
00746             }
00747 
00748             state->setKinematicState(ik_map_pre_grasp);
00749 
00750             //now we solve interpolated ik
00751             tf::Transform base_link_bullet_grasp_pose;
00752             tf::poseMsgToTF(base_link_grasp_pose.pose, base_link_bullet_grasp_pose);
00753 
00754             /* try to do interpolated IK from grasp back to pregrasp */
00755             execution_info[i].approach_trajectory_.joint_names = joint_names;
00756             if(!getInterpolatedIK(pickup_goal.arm_name,
00757                                   base_link_bullet_grasp_pose,
00758                                   pregrasp_dir,
00759                                   grasps[i].desired_approach_distance,
00760                                   solution.position,
00761                                   true,
00762                                   false,
00763                                   execution_info[i].approach_trajectory_)) {
00764                 ROS_DEBUG_STREAM_NAMED("manipulation", "No interpolated IK for pre-grasp to grasp");
00765                 execution_info[i].result_.result_code = GraspResult::PREGRASP_UNFEASIBLE;
00766                 outcome_count[GraspResult::PREGRASP_UNFEASIBLE]++;
00767                 continue;
00768             }
00769 
00770             /* try to do interpolated IK for the lift */
00771             state->setKinematicState(ik_map_grasp);
00772             execution_info[i].lift_trajectory_.joint_names = joint_names;
00773             if(!getInterpolatedIK(pickup_goal.arm_name,
00774                                   base_link_bullet_grasp_pose,
00775                                   lift_dir,
00776                                   pickup_goal.lift.desired_distance,
00777                                   solution.position,
00778                                   false,
00779                                   true,
00780                                   execution_info[i].lift_trajectory_)) {
00781                 ROS_DEBUG_STREAM_NAMED("manipulation","No interpolated IK for grasp to lift");
00782                 execution_info[i].result_.result_code = GraspResult::LIFT_UNFEASIBLE;
00783                 outcome_count[GraspResult::LIFT_UNFEASIBLE]++;
00784                 continue;
00785             }
00786         }
00787 
00788         //now we revert link paddings and object collisions and do a final check for the initial ik points
00789         cm->revertCollisionSpacePaddingToDefault();
00790 
00791         cm->setAlteredAllowedCollisionMatrix(group_disable_acm);
00792 
00793         for(unsigned int i = 0; i < grasps.size(); i++) {
00794 
00795             if(execution_info[i].result_.result_code != 0) continue;
00796 
00797             if(execution_info[i].approach_trajectory_.points.empty()) {
00798                 ROS_WARN_STREAM("No result code and no points in approach trajectory");
00799                 continue;
00800             }
00801 
00802             std::map<std::string, double> ik_map_pre_grasp;
00803             for(unsigned int j = 0; j < joint_names.size(); j++) {
00804                 ik_map_pre_grasp[joint_names[j]] = execution_info[i].approach_trajectory_.points[0].positions[j];
00805             }
00806             for(unsigned int j = 0; j < grasps[i].pre_grasp_posture.name.size(); j++) {
00807                 ik_map_pre_grasp[grasps[i].pre_grasp_posture.name[j]] = grasps[i].pre_grasp_posture.position[j];
00808             }
00809             state->setKinematicState(ik_map_pre_grasp);
00810             if(cm->isKinematicStateInCollision(*state)) {
00811                 ROS_DEBUG_STREAM_NAMED("manipulation","Final pre-grasp check failed");
00812                 print_contacts(cm, state);
00813 
00814                 std::vector<arm_navigation_msgs::ContactInformation> contacts;
00815                 cm->getAllCollisionsForState(*state, contacts,1);
00816                 std::vector<std::string> names;
00817                 for(unsigned int j = 0; j < contacts.size(); j++) {
00818                     names.push_back(contacts[j].contact_body_1);
00819                 }
00820 
00821                 std_msgs::ColorRGBA col_pregrasp;
00822                 col_pregrasp.r = 0.0;
00823                 col_pregrasp.g = 0.0;
00824                 col_pregrasp.b = 1.0;
00825                 col_pregrasp.a = 1.0;
00826                 visualization_msgs::MarkerArray arr;
00827                 cm->getRobotPaddedMarkersGivenState(*state, arr, col_pregrasp,
00828                                                     "padded",
00829                                                     ros::Duration(0.0),
00830                                                     &names);
00831                 vis_marker_array_publisher_.publish(arr);
00832                 execution_info[i].result_.result_code = GraspResult::PREGRASP_OUT_OF_REACH;
00833                 outcome_count[GraspResult::PREGRASP_OUT_OF_REACH]++;
00834                 continue;
00835             }
00836 
00837         }
00838 
00839         //now we need to disable collisions with the object for lift
00840         cm->setAlteredAllowedCollisionMatrix(object_support_disable_acm);
00841 
00842         for(unsigned int i = 0; i < grasps.size(); i++) {
00843 
00844             if(execution_info[i].result_.result_code != 0) continue;
00845 
00846             if(execution_info[i].lift_trajectory_.points.empty()) {
00847                 ROS_WARN_STREAM("No result code and no points in lift trajectory");
00848                 continue;
00849             }
00850             std::map<std::string, double> ik_map_grasp;
00851             for(unsigned int j = 0; j < joint_names.size(); j++) {
00852                 ik_map_grasp[joint_names[j]] = execution_info[i].lift_trajectory_.points.back().positions[j];
00853             }
00854             for(unsigned int j = 0; j < grasps[i].grasp_posture.name.size(); j++) {
00855                 ik_map_grasp[grasps[i].grasp_posture.name[j]] = grasps[i].grasp_posture.position[j];
00856             }
00857             state->setKinematicState(ik_map_grasp);
00858             if(cm->isKinematicStateInCollision(*state)) {
00859                 ROS_DEBUG_STREAM_NAMED("manipulation","Final lift check failed");
00860                 print_contacts(cm, state);
00861                 execution_info[i].result_.result_code = GraspResult::LIFT_OUT_OF_REACH;
00862                 outcome_count[GraspResult::LIFT_OUT_OF_REACH]++;
00863                 continue;
00864             } else {
00865                 ROS_DEBUG_STREAM_NAMED("manipulation", "Everything successful");
00866                 execution_info[i].result_.result_code = GraspResult::SUCCESS;
00867                 outcome_count[GraspResult::SUCCESS]++;
00868             }
00869         }
00870         cm->setAlteredAllowedCollisionMatrix(original_acm);
00871 
00872         visualize_grasps(pickup_goal, grasps, execution_info, vis_marker_publisher_);
00873 
00874         ROS_DEBUG_STREAM("Took " << (ros::WallTime::now()-start).toSec());
00875 
00876         for(std::map<unsigned int, unsigned int>::iterator it = outcome_count.begin();
00877         it != outcome_count.end();
00878         it++) {
00879             ROS_INFO_STREAM("Outcome " << it->first << " count " << it->second);
00880         }
00881     }
00882 
00883 
00884 } //namespace object_manipulator


object_manipulator
Author(s): Matei Ciocarlie and Kaijen Hsiao
autogenerated on Thu Jan 2 2014 11:39:04