demo.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2012, 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 /* Author: Ioan Sucan */
00036 
00037 #include <moveit/move_group_interface/move_group.h>
00038 #include <ros/ros.h>
00039 
00040 void demoPick(moveit::planning_interface::MoveGroup &group)
00041 {
00042   std::vector<manipulation_msgs::Grasp> grasps;
00043   for (std::size_t i = 0 ; i < 20 ; ++i)
00044   {
00045     geometry_msgs::PoseStamped p = group.getRandomPose();
00046     p.pose.orientation.x = 0;
00047     p.pose.orientation.y = 0;
00048     p.pose.orientation.z = 0;
00049     p.pose.orientation.w = 1;
00050     manipulation_msgs::Grasp g;
00051     g.grasp_pose = p;
00052     g.approach.direction.vector.x = 1.0;
00053     g.retreat.direction.vector.z = 1.0;
00054     g.retreat.direction.header = p.header;
00055     g.approach.min_distance = 0.2;
00056     g.approach.desired_distance = 0.4;
00057     g.retreat.min_distance = 0.1;
00058     g.retreat.desired_distance = 0.27;
00059     g.pre_grasp_posture.name.resize(1, "r_gripper_joint");
00060     g.pre_grasp_posture.position.resize(1);
00061     g.pre_grasp_posture.position[0] = 1;
00062 
00063     g.grasp_posture.name.resize(1, "r_gripper_joint");
00064     g.grasp_posture.position.resize(1);
00065     g.grasp_posture.position[0] = 0;
00066 
00067     grasps.push_back(g);
00068   }
00069   group.pick("bubu", grasps);
00070 }
00071 
00072 void demoPlace(moveit::planning_interface::MoveGroup &group)
00073 {
00074   std::vector<manipulation_msgs::PlaceLocation> loc;
00075   for (std::size_t i = 0 ; i < 20 ; ++i)
00076   {
00077     geometry_msgs::PoseStamped p = group.getRandomPose();
00078     p.pose.orientation.x = 0;
00079     p.pose.orientation.y = 0;
00080     p.pose.orientation.z = 0;
00081     p.pose.orientation.w = 1;
00082     manipulation_msgs::PlaceLocation g;
00083     g.place_pose = p;
00084     g.approach.direction.vector.x = 1.0;
00085     g.retreat.direction.vector.z = 1.0;
00086     g.retreat.direction.header = p.header;
00087     g.approach.min_distance = 0.2;
00088     g.approach.desired_distance = 0.4;
00089     g.retreat.min_distance = 0.1;
00090     g.retreat.desired_distance = 0.27;
00091 
00092     g.post_place_posture.name.resize(1, "r_gripper_joint");
00093     g.post_place_posture.position.resize(1);
00094     g.post_place_posture.position[0] = 0;
00095 
00096     loc.push_back(g);
00097   }
00098   group.place("bubu", loc);
00099 }
00100 
00101 void attachObject(void)
00102 {
00103 
00104 }
00105 
00106 int main(int argc, char **argv)
00107 {
00108   ros::init(argc, argv, "move_group_interface_demo", ros::init_options::AnonymousName);
00109 
00110   ros::AsyncSpinner spinner(1);
00111   spinner.start();
00112 
00113   moveit::planning_interface::MoveGroup group(argc > 1 ? argv[1] : "right_arm");
00114   demoPlace(group);
00115 
00116   sleep(2);
00117 
00118   return 0;
00119 }


planning_interface
Author(s): Ioan Sucan
autogenerated on Mon Oct 6 2014 02:33:28