ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

moveit incomplete cartesian path execution

asked 2017-06-19 06:37:39 -0500

Felix_N gravatar image

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

edit retag flag offensive close merge delete

Comments

I'm stumbling on the exact same problem as well... Have you managed to solve it?

marcmitxy gravatar image marcmitxy  ( 2017-07-11 17:11:22 -0500 )edit

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.

daniel_maier gravatar image daniel_maier  ( 2018-04-12 04:11:53 -0500 )edit

Planning time limits are for planners. computeCartesianPath(..) is not a planner and does not take those limits into account.

gvdhoorn gravatar image gvdhoorn  ( 2018-04-12 04:14:41 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2017-07-11 21:59:20 -0500

According to the description here several tool poses get generated based on the eef step parameter. I could be that some of those poses aren't reachable (no ik solution).

edit flag offensive delete link more

Comments

IK failing for certain poses is definitely a problem with computeCartesianPath(..). There are only two ways it can fail: IK or because of the jump_threshold. In the code above that is disabled, so I would guess it's the IK here.

gvdhoorn gravatar image gvdhoorn  ( 2017-07-12 05:04:31 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2017-06-19 06:37:39 -0500

Seen: 1,740 times

Last updated: Jul 11 '17