Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
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);
00082
00083 target_pose3.position.y -= 1;
00084 waypoints.push_back(target_pose3);
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,
00093 0.0,
00094 trajectory);
00095
00096 ROS_INFO("Visualizing plan 4 (cartesian path) (%.2f%% acheived)",
00097 fraction * 100.0);
00098
00099 sleep(15.0);
00100 my_plan.trajectory_ = trajectory;
00101 group.execute(my_plan);
00102
00103
00104
00105 ros::shutdown();
00106 return 0;
00107 }