moveit_group_api.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, SRI International
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 SRI International 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: Sachin Chitta */
00036 
00037 #include <moveit/move_group_interface/move_group.h>
00038 #include <moveit/planning_scene_interface/planning_scene_interface.h>
00039 
00040 #include <moveit_msgs/DisplayRobotState.h>
00041 #include <moveit_msgs/DisplayTrajectory.h>
00042 
00043 #include <moveit_msgs/AttachedCollisionObject.h>
00044 #include <moveit_msgs/CollisionObject.h>
00045 
00046 int main(int argc, char **argv)
00047 {
00048   ros::init(argc, argv, "move_group_interface_tutorial");
00049   ros::NodeHandle node_handle;
00050   ros::AsyncSpinner spinner(1);
00051   spinner.start();
00052 
00053 
00054 
00055   sleep(20.0);
00056 
00057 
00058 
00059   moveit::planning_interface::MoveGroup group("arm");
00060 
00061 
00062   moveit::planning_interface::PlanningSceneInterface planning_scene_interface;
00063 
00064 
00065   ros::Publisher display_publisher = node_handle.advertise<moveit_msgs::DisplayTrajectory>("/move_group/display_planned_path", 1, true);
00066   moveit_msgs::DisplayTrajectory display_trajectory;
00067 
00068   robot_state::RobotState start_state(*group.getCurrentState());
00069   geometry_msgs::Pose start_pose2;
00070   start_pose2.orientation.w = -1.0;
00071   start_pose2.position.x = 0.55;
00072   start_pose2.position.y = -0.05;
00073   start_pose2.position.z = 0.8;
00074 
00075   moveit::planning_interface::MoveGroup::Plan my_plan;
00076   std::vector<geometry_msgs::Pose> waypoints;
00077 
00078   geometry_msgs::Pose target_pose3 = start_pose2;
00079   target_pose3.position.x += 1;
00080   target_pose3.position.z += 1;
00081   waypoints.push_back(target_pose3);  // up and out
00082 
00083   target_pose3.position.y -= 1;
00084   waypoints.push_back(target_pose3);  // left
00085 
00086   target_pose3.position.z -= 1;
00087   target_pose3.position.y += 0.2;
00088   target_pose3.position.x -= 0.2;
00089   waypoints.push_back(target_pose3);
00090   moveit_msgs::RobotTrajectory trajectory;
00091   double fraction = group.computeCartesianPath(waypoints,
00092                                                0.01,  // eef_step
00093                                                0.0,   // jump_threshold
00094                                                trajectory);
00095 
00096   ROS_INFO("Visualizing plan 4 (cartesian path) (%.2f%% acheived)",
00097            fraction * 100.0);
00098 /* Sleep to give Rviz time to visualize the plan. */
00099   sleep(15.0);
00100   my_plan.trajectory_ = trajectory;
00101   group.execute(my_plan);
00102 
00103 // END_TUTORIAL
00104 
00105   ros::shutdown();
00106   return 0;
00107 }


ric_robot
Author(s): RoboTiCan
autogenerated on Fri May 20 2016 03:50:58