simple_grasps_server.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (Modified BSD License)
00003  *
00004  *  Copyright (c) 2013-2014, PAL Robotics, S.L.
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 PAL Robotics, S.L. 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 /* Author: Bence Magyar
00036  *         Enrique Fernandez
00037  * Desc:   Action server wrapper for object grasp generator.
00038  */
00039 
00040 // ROS
00041 #include <ros/ros.h>
00042 #include <geometry_msgs/PoseArray.h>
00043 #include <actionlib/server/simple_action_server.h>
00044 
00045 // Grasp generation
00046 #include <moveit_simple_grasps/simple_grasps.h>
00047 #include <moveit_simple_grasps/GenerateGraspsAction.h>
00048 #include <moveit_simple_grasps/GraspGeneratorOptions.h>
00049 
00050 
00051 // Baxter specific properties
00052 #include <moveit_simple_grasps/grasp_data.h>
00053 #include <moveit_simple_grasps/custom_environment2.h>
00054 
00055 namespace moveit_simple_grasps
00056 {
00057 
00058   bool graspGeneratorOptions2Inner(
00059           const moveit_simple_grasps::GraspGeneratorOptions &options,
00060           grasp_axis_t &axis,
00061           grasp_direction_t &direction,
00062           grasp_rotation_t &rotation)
00063   {
00064     switch(options.grasp_axis)
00065     {
00066      case GraspGeneratorOptions::GRASP_AXIS_X:
00067         axis = X_AXIS;
00068         break;
00069      case GraspGeneratorOptions::GRASP_AXIS_Y:
00070         axis = Y_AXIS;
00071         break;
00072      case GraspGeneratorOptions::GRASP_AXIS_Z:
00073         axis = Z_AXIS;
00074         break;
00075      default:
00076         assert(false);
00077         break;
00078     }
00079 
00080     switch(options.grasp_direction)
00081     {
00082      case GraspGeneratorOptions::GRASP_DIRECTION_UP:
00083         direction = UP;
00084         break;
00085      case GraspGeneratorOptions::GRASP_DIRECTION_DOWN:
00086         direction = DOWN;
00087         break;
00088      default:
00089         assert(false);
00090         break;
00091     }
00092 
00093     switch(options.grasp_rotation)
00094     {
00095      case GraspGeneratorOptions::GRASP_ROTATION_FULL:
00096         rotation = FULL;
00097         break;
00098      case GraspGeneratorOptions::GRASP_ROTATION_HALF:
00099         rotation = HALF;
00100         break;
00101      default:
00102         assert(false);
00103         break;
00104     }
00105     return true;
00106   }
00107 
00108   class GraspGeneratorServer
00109   {
00110   private:
00111     // A shared node handle
00112     ros::NodeHandle nh_;
00113 
00114     // Action server
00115     actionlib::SimpleActionServer<moveit_simple_grasps::GenerateGraspsAction> as_;
00116     moveit_simple_grasps::GenerateGraspsResult result_;
00117 
00118     // Grasp generator
00119     moveit_simple_grasps::SimpleGraspsPtr simple_grasps_;
00120 
00121     // class for publishing stuff to rviz
00122     moveit_visual_tools::VisualToolsPtr visual_tools_;
00123 
00124     // robot-specific data for generating grasps
00125     moveit_simple_grasps::GraspData grasp_data_;
00126 
00127     // which arm are we using
00128     std::string end_effector_name_;
00129     std::string planning_group_name_;
00130 
00131   public:
00132 
00133     // Constructor
00134     GraspGeneratorServer(const std::string &name)
00135       : nh_("~")
00136       , as_(nh_, name, boost::bind(&moveit_simple_grasps::GraspGeneratorServer::executeCB, this, _1), false)
00137       , end_effector_name_("end_effector")
00138       , planning_group_name_("arm")
00139     {
00140       // ---------------------------------------------------------------------------------------------
00141       nh_.param("group", planning_group_name_, planning_group_name_);
00142       nh_.param("end_effector", end_effector_name_, end_effector_name_);
00143 
00144       // Load grasp data specific to our robot
00145       if (!grasp_data_.loadRobotGraspData(nh_, end_effector_name_))
00146         ros::shutdown();
00147 
00148       // ---------------------------------------------------------------------------------------------
00149       // Load the Robot Viz Tools for publishing to Rviz
00150       visual_tools_.reset(new moveit_visual_tools::VisualTools(grasp_data_.base_link_));
00151       visual_tools_->setLifetime(120.0);
00152       visual_tools_->setMuted(false);
00153       visual_tools_->loadEEMarker(grasp_data_.ee_group_, planning_group_name_);
00154 
00155       // ---------------------------------------------------------------------------------------------
00156       // Load grasp generator
00157       simple_grasps_.reset( new moveit_simple_grasps::SimpleGrasps(visual_tools_) );
00158       as_.start();
00159     }
00160 
00161     void executeCB(const moveit_simple_grasps::GenerateGraspsGoalConstPtr &goal)
00162     {
00163       // ---------------------------------------------------------------------------------------------
00164       // Remove previous results
00165       result_.grasps.clear();
00166 
00167       // ---------------------------------------------------------------------------------------------
00168       // Set object width and generate grasps
00169       grasp_data_.object_size_ = goal->width;
00170 
00171       // Generate grasps for all options that were passed
00172       grasp_axis_t axis;
00173       grasp_direction_t direction;
00174       grasp_rotation_t rotation;
00175       for(size_t i=0; i<goal->options.size(); ++i)
00176       {
00177         graspGeneratorOptions2Inner(goal->options[i], axis, direction, rotation);
00178         simple_grasps_->generateAxisGrasps(goal->pose, axis, direction, rotation, 0, grasp_data_, result_.grasps);
00179       }
00180       // fallback behaviour, generate default grasps when no options were passed
00181       if(goal->options.empty())
00182       {
00183         simple_grasps_->generateBlockGrasps(goal->pose, grasp_data_, result_.grasps);
00184       }
00185 
00186       // ---------------------------------------------------------------------------------------------
00187       // Publish results
00188       as_.setSucceeded(result_);
00189     }
00190 
00191   };
00192 }
00193 
00194 
00195 int main(int argc, char *argv[])
00196 {
00197   ros::init(argc, argv, "grasp_generator_server");
00198 
00199   moveit_simple_grasps::GraspGeneratorServer grasp_generator_server("generate");
00200 
00201   ros::spin();
00202 
00203   return 0;
00204 }


moveit_simple_grasps
Author(s): Dave Coleman
autogenerated on Fri Aug 28 2015 11:36:01