[moveit] problem about Cartesian Paths of move_group_interface
I follow tutorials in http://docs.ros.org/kinetic/api/movei...,and when i plan a Cartesian Paths for UR3, i write the following codes for UR3:
std::vector<geometry_msgs::Pose> waypoints;
waypoints.push_back(target_pose1);
geometry_msgs::Pose target_pose2 = target_pose1;
target_pose2.position.z += 0.1;
waypoints.push_back(target_pose2); // up
target_pose2.position.y -= 0.1;
waypoints.push_back(target_pose2); // left
target_pose2.position.z -= 0.1;
target_pose2.position.y += 0.1;
target_pose2.position.x -= 0.1;
waypoints.push_back(target_pose2);
move_group.setMaxVelocityScalingFactor(0.1);
moveit_msgs::RobotTrajectory trajectory;
const double jump_threshold = 0.0;
const double eef_step = 0.005;
double fraction = move_group.computeCartesianPath(waypoints, eef_step, jump_threshold, trajectory);
ROS_INFO_NAMED("tutorial", "Visualizing plan 4 (cartesian path) (%.2f%% acheived)", fraction * 100.0);
sleep(15.0);
ROS_INFO_STREAM("cartesian path .....");
my_plan.trajectory_= trajectory;
move_group.execute(my_plan);
The problem is that the fuction double fraction = move_group.computeCartesianPath(waypoints, eef_step, jump_threshold, trajectory);
seems work not well .In the terminal i got the following information:
INFO] [1489330212.136327474]: Visualizing plan 4 (cartesian path) (0.00% acheived)
[ INFO] [1489330227.136626416]: cartesian path .....
[ WARN] [1489330227.461583608]: Skipping path because 1 points passed in.
Some problem occur when running the function for 0.00% has achieved as terminal implied. So it didn't plan out the cartesian path. soi can't see the path in rviz.
I see that you are making tool motion increments of 0.1 m for each point which may cause some of the points to have unreachable orientation, especially in the case of an arm with a small work envelope like the UR3.
See the method description here
hello,I also have the same question.so you mean that the first point of the cartesian path should be the gurrent pose of the robot right? By the way how can I know whether the point I want to put in the waypoints is reachable before I fail to compute the path?