moveit incomplete cartesian path execution
Hi everyone,
Im currently programming a 6DOF robotic arm using moveit. I already managed to send goals via setPoseTarget(target_pose). However, I know want to use the cartesian path feature but I keep having trouble with it.
Here is the code which compiles just fine (i use a pointer to the move_group. This works in all other cases):
ros::AsyncSpinner spinner(1);
spinner.start();
std::vector<geometry_msgs::Pose> waypoints;
geometry_msgs::Pose cart_start_pose = move_point->getCurrentPose().pose;
waypoints.push_back(cart_start_pose);
geometry_msgs::Pose cart_target_pose = cart_start_pose;
cart_target_pose.position.z -= 0.01;
waypoints.push_back(cart_target_pose); // down
cart_target_pose.position.z -= 0.01;
waypoints.push_back(cart_target_pose); // down again
move_point->setPlanningTime(10.0);
moveit_msgs::RobotTrajectory trajectory;
const double jump_threshold = 0.0;
const double eef_step = 0.01;
double fraction = move_point->computeCartesianPath(waypoints, eef_step, jump_threshold, trajectory);
ROS_INFO_NAMED("tutorial", "Visualizing plan 4 (cartesian path) (%.2f%% acheived)", fraction * 100.0);
spinner.stop();
Using the "normal" goal planning the arm can easily move down about 10 cm so the goal is definitely valid.
The callback message i get is:
Computed Cartesian path with 2 points (followed 33.333333% of requested trajectory)
Setting only one goal besides the start position the percentage is 50%, setting 3 it is 25%. Obviously only the (already reached) start position is followed, which of course results in the robot not moving at all.
Any ideas how i get the model moving further than just the start position?
Thanks in advance,
Felix
I'm stumbling on the exact same problem as well... Have you managed to solve it?
I also observed the same behavior. It seems to work a bit better if I use TracIK instead of KDL but I hard get close to 100% reproducibly. Also, the maximum planning time is never reached, it seems to give up much earlier.
Planning time limits are for planners.
computeCartesianPath(..)
is not a planner and does not take those limits into account.