How do I execute the trajectory created by "computeCartesianPath" ?

5,083 views
Skip to first unread message

Pætur Dal Christiansen

unread,
May 6, 2014, 12:56:32 PM5/6/14
to moveit...@googlegroups.com
I still don't really understand what is going on when I use MoveIt, so bear with me please:

I am running MoveIt with the Universal Robot UR5, and I'm starting to figure it out. I can execute pose targets, joint targets, do kinematics calculations etc. I can also show the calculated cartesian path obtained by "computeCartesianPath" in Rviz, but when I try to execute it on the actual Robot, my controller refuses to play:

[ INFO] [1399394593.787557846]: Received new trajectory execution service request...
[New Thread 0xac534b40 (LWP 26093)]
[ INFO] [1399394593.789904393]: Trajectory was successfully forwarded to the controller
[New Thread 0xabd33b40 (LWP 26094)]
[ WARN] [1399394594.000383522]: Controller handle  reports status FAILED
[Thread 0xac534b40 (LWP 26093) exited]
[New Thread 0xab532b40 (LWP 26116)]

Question is: have I missed something, when setting up the controller? Or in my exection call? For the record, I'm using this code to execute the path:

ros::ServiceClient client = node_handle.serviceClient<moveit_msgs::ExecuteKnownTrajectory>("/execute_kinematic_path");

  moveit_msgs::ExecuteKnownTrajectory::Request request;
  moveit_msgs::ExecuteKnownTrajectory::Response response;

  request.trajectory = trajectory; 
  request.wait_for_execution = false;

BTW, I couldn't find any mention of how to execute a cartesian path in the documentation, so I might be some way off in the way I do things. This code is from a google search.

Pætur Dal Christiansen

unread,
May 8, 2014, 5:40:17 AM5/8/14
to moveit...@googlegroups.com
For anyone interested, it turns out that computeCartesianPath returns empty velocity vectors, and the driver for UR5 doesn't allow that. I solved it by manually setting all the velocities to 0 in the RobotTrajectory returned by computeCartesianPath. It doesn't generate very smooth motion though.

Moises Estrada

unread,
May 8, 2014, 4:38:13 PM5/8/14
to moveit...@googlegroups.com
Hey, I have worked a bit with computeCartesianPath and ran into the problem of having empty velocity vectors. Here is what I did to solve it:

  moveit_msgs::RobotTrajectory trajectory_msg;
  group.setPlanningTime(10.0);
 
  double fraction = group.computeCartesianPath(waypoints,
                                               0.01,  // eef_step
                                               0.0,   // jump_threshold
                                               trajectory_msg, false);
  // The trajectory needs to be modified so it will include velocities as well.
  // First to create a RobotTrajectory object
  robot_trajectory::RobotTrajectory rt(group.getCurrentState()->getRobotModel(), "arm_group");

  // Second get a RobotTrajectory from trajectory
  rt.setRobotTrajectoryMsg(*group.getCurrentState(), trajectory_msg);
 
  // Thrid create a IterativeParabolicTimeParameterization object
  trajectory_processing::IterativeParabolicTimeParameterization iptp;

  // Fourth compute computeTimeStamps
  success = iptp.computeTimeStamps(rt);
  ROS_INFO("Computed time stamp %s",success?"SUCCEDED":"FAILED");

  // Get RobotTrajectory_msg from RobotTrajectory
  rt.getRobotTrajectoryMsg(trajectory_msg);

  // Finally plan and execute the trajectory
  plan.trajectory_ = trajectory_msg;
  ROS_INFO("Visualizing plan 4 (cartesian path) (%.2f%% acheived)",fraction * 100.0);   
  sleep(5.0);
  group.execute(plan);

Hope this works for you.

Pætur Dal Christiansen

unread,
May 9, 2014, 5:22:20 AM5/9/14
to moveit...@googlegroups.com
That worked astonishingly well, thank you very much.

Patrick Goebel

unread,
May 23, 2014, 11:27:19 AM5/23/14
to moveit...@googlegroups.com
Hello,

Does anyone know if there is an equivalent to IterativeParabolicTimeParameterization in the Python API?  I can't find one but perhaps I'm just not looking in the right place.

Thanks!
patrick

Sachin Chitta

unread,
May 23, 2014, 2:12:32 PM5/23/14
to Patrick Goebel, moveit-users
Hey Patrick,

Its not in the Python API.

Sachin

Patrick Goebel

unread,
May 23, 2014, 2:25:31 PM5/23/14
to Sachin Chitta, moveit-users
OK, thanks Sachin.

--patrick

haixuanwo_clark

unread,
Dec 6, 2016, 12:47:54 AM12/6/16
to MoveIt! Users
hello
I'm in trouble using computeCartesianPath , It always return 33%.   when I change the waypoints, I can get success.but I change waypoints again ,It return 65%.

what happened ?
how to correctly use computeCartesianPath ?

advance thank



在 2014年5月7日星期三 UTC+8上午12:56:32,Pætur Dal Christiansen写道:

Mutu

unread,
Dec 7, 2016, 4:42:37 AM12/7/16
to MoveIt! Users
Hello haixuanwo_clark,

for exact information about the computecartesianpath function, look here:  http://docs.ros.org/jade/api/moveit_ros_planning_interface/html/classmoveit_1_1planning__interface_1_1MoveGroup.html

When you use the function, it depends whether your kinematics of the robot can reach any position of the interpolated path between your waypoints.
I.e.: When u have 2 waypoints and your function interpolates 100points to plan for your trajectory, then perhabs only 33 or 65 can be reached by your robot.

mutu

haixuanwo_clark

unread,
Dec 13, 2016, 3:51:23 AM12/13/16
to MoveIt! Users

I have looked you post web site.  but I still haven't know how to use computeCartesianPath.

Did you use it?  I alway fail.

I think I miss some config or computeCartesianPath's param.

How about you in using computeCartesianPath?



在 2016年12月7日星期三 UTC+8下午5:42:37,Mutu写道:

Mutu

unread,
Dec 15, 2016, 5:27:34 AM12/15/16
to MoveIt! Users
Hey,

take a look at this Code: https://github.com/ros-planning/moveit_tutorials/blob/indigo-devel/doc/pr2_tutorials/planning/src/move_group_interface_tutorial.cpp
from Line 210-240. Its the tutorial for programming in Indigo, but should work for the other versions too.

haixuan...@yahoo.com

unread,
Dec 15, 2016, 8:11:12 PM12/15/16
to Mutu, MoveIt! Users
thanks you for your reply.

I have finished learning this tutorials.

but I use this in my robot , I get fail. 

I have done that I get some position then push them into waypoints. this time, I use computerCartesianPath, It return 0.73.

I want know how correctly use it and what should give attention?

thanks again.
 


Sent from Yahoo Mail. Get the app


--
You received this message because you are subscribed to the Google Groups "MoveIt! Users" group.
To unsubscribe from this group and stop receiving emails from it, send an email to moveit-users...@googlegroups.com.
To view this discussion on the web visit
https://groups.google.com/d/msgid/moveit-users/ef662341-934f-4c73-92ea-ddb85604be6d%40googlegroups.com
.


Daniel Solomon

unread,
Jan 29, 2017, 7:56:19 AM1/29/17
to MoveIt! Users
Are you certain that 100% of the path is possible, and that the planner is incorrect? Could the planner be failing because the trajectory is not possible?

The planner could be failing correctly if there is a collision state, the robot passes through a singularity, or reaches the end of its workspace. It could also be failing incorrectly if IK is not able to solve.

If you can simulate or execute the partial trajectory that is returned, you will have a better sense of why planning is failing. You can also post a log here so people can help solve the problem, but the information you have given is too sparse to be able to answer your question.

Reply all
Reply to author
Forward
0 new messages