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

Moveit tutorial cartesian path error, missing valid timestamp data?

asked 2019-05-03 03:38:27 -0500

nd gravatar image

updated 2019-05-06 07:40:54 -0500

Hello,

I am following tutorial for Cartesian path using move_group c++ interface. But I am getting error when I send this trajectory to motoman robot.

[ERROR] [1556871367.163994139]: Validation failed: Missing valid timestamp data for trajectory pt 1
[ERROR] [1556871371.219235895]: Controller is taking too long to execute trajectory (the expected upper bound for the trajectory execution was 4.056057 seconds). Stopping trajectory

source code I am executing is,

      static const std::string PLANNING_GROUP = "arm";

   // The :move_group_interface:`MoveGroup` class can be easily
   // setup using just the name of the planning group you would like to control and plan for.
      moveit::planning_interface::MoveGroupInterface move_group(PLANNING_GROUP);

   // We will use the :planning_scene_interface:`PlanningSceneInterface`
   // class to add and remove collision objects in our "virtual world" scene
      moveit::planning_interface::PlanningSceneInterface planning_scene_interface;

   // Raw pointers are frequently used to refer to the planning group for improved performance.
      const robot_state::JointModelGroup* joint_model_group = move_group.getCurrentState()->getJointModelGroup(PLANNING_GROUP);
      geometry_msgs::Pose target_pose2 = move_group.getCurrentPose().pose;

      std::vector<geometry_msgs::Pose> waypoints;
      waypoints.push_back(target_pose2);
      //geometry_msgs::Pose target_pose3 = target_pose2;
      target_pose2.position.z -= 0.4;
      waypoints.push_back(target_pose2);

      target_pose2.position.x += 0.4;
      waypoints.push_back(target_pose2);

      move_group.setMaxVelocityScalingFactor(0.1);


      moveit_msgs::RobotTrajectory trajectory;
      const double jump_thresold = 0.0;
      const double eef_step = 0.01;
      move_group.computeCartesianPath(waypoints, eef_step, jump_thresold, trajectory);
      moveit::planning_interface::MoveGroupInterface::Plan my_plan1;
      my_plan1.trajectory_ = trajectory;
      move_group.execute(my_plan1);

How can I solve this?

thanks.

...................................................................................................

[ERROR] [1557146297.748611305] [/motion_streaming_interface] [ros.motoman_driver]: Validation failed: Missing valid timestamp data for trajectory pt 1
[ERROR] [1557146299.550803668] [/move_group] [ros.moveit_ros_planning.trajectory_execution_manager]: Controller is taking too long to execute trajectory (the expected upper bound for the trajectory execution was 1.804171 seconds). Stopping trajectory.
edit retag flag offensive close merge delete

Comments

Not an answer but an observation: you may want to change your ROS logging configuration to include the name of the node and/or the logger so that you can more easily determine where certain log lines are coming from.

Example:

ROSCONSOLE_FORMAT='[${severity}] [${time}] [${node}] [${logger}]: ${message}'

The "validation failed" line is most likely coming from motoman_driver.

gvdhoorn gravatar image gvdhoorn  ( 2019-05-03 04:16:44 -0500 )edit

what can be possible answer? is there any mistake in code? robot is moving in rviz but not in real.

nd gravatar image nd  ( 2019-05-03 04:59:16 -0500 )edit

Please update the error lines with the updated rosconsole format config first.

gvdhoorn gravatar image gvdhoorn  ( 2019-05-03 07:54:51 -0500 )edit

sorry but I could not figured out how to update that list.

but when I set first target pose1 and then using cartesian path from that pose(target pose1) to new target pose2 then It is working. but directly getting pose from move_group.getCurrentPose().pose is not working on real robot.

nd gravatar image nd  ( 2019-05-06 05:02:10 -0500 )edit

sorry but I could not figured out how to update that list.

add the line I showed you to your $HOME/.bashrc (prefix it with export), start a new terminal and rerun your code.

gvdhoorn gravatar image gvdhoorn  ( 2019-05-06 06:58:20 -0500 )edit

updated...

nd gravatar image nd  ( 2019-05-06 07:41:13 -0500 )edit

Can you read out the trajectory.joint_trajectory.points[point number].time_from_start.toSec(). For every point of the trajectory will be check for a time_from_start that is not 0.ONLY THE FIRST POINT OF THE TRAJECTORY HAS A TIME_FROM_START OF 0. If the second point has a time value of 0, that means the robot does not need to move from points.

Kluun gravatar image Kluun  ( 2019-05-15 08:12:02 -0500 )edit

I am facing same issue when using KDL with cartesian paths, I dont know how this can be tackled down, computeCartesianPath() takes vector<geometryPose> which indeed lacks the header and leading this error

Fetullah Atas gravatar image Fetullah Atas  ( 2020-08-14 02:50:56 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2021-04-29 11:07:13 -0500

luowei gravatar image

hello, i am face the same problem in the use real robot of staubli tx90 ,after reference the comment above i solve my issue.(i am a chinese,and my english is not well) my issue as follow: this ERROR is from link text it has follow code in line 359-360 :

  1. if ((i > 0) && (pt.time_from_start.toSec() == 0))
  2. ROS_ERROR_RETURN(false, "Validation failed: Missing valid timestamp data for trajectory pt %d", i);

the i is the number of point of this trajectory which was generate by compute_cartesian_path(),so i remove the current position point from waypoints,then add the other points to waypoints,and adjust eef_step to make secs and nsecs starting with the second point in the trajectory points is not 0 ,the output of trajectory will like follow:


points:

- 
  positions: [2.108776330947876, -1.9812618494033813, 1.9390465021133423, -0.5018525719642639, 0.5606833696365356, -3.183285713195801]
  velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
  accelerations: [0.8235095563086486, 0.0, 0.0, 0.0, 0.0, 0.0]
  effort: []
  time_from_start: 
    secs: 0
    nsecs:         0
- 
  positions: [2.1089364101262262, -1.9812590654326576, 1.9389832311590194, -0.5019567354049222, 0.5607331482680914, -3.183351569435987]
  velocities: [0.014828695025699192, 0.00025848478191981743, -0.005865001402171719, -0.009645346020956728, 0.004613587043633859, -0.0061049437144617275]
  accelerations: [0.9886697575487532, 0.01728195425169232, -0.3913577021689268, -0.6427849328498018, 0.307795562008559, -0.40739227930748345]
  effort: []
  time_from_start: 
    secs: 0
    nsecs:  19717330
- 
  positions: [2.109096447290984, -1.9812562733384256, 1.9389199174983955, -0.5020608168453513, 0.5607829497680554, -3.1834174745134054]
  velocities: [0.014547021024027582, 0.00025392540918097015, -0.00575598233144198, -0.00945979402778211, 0.004527334312262674, -0.0059918148431933145]
  accelerations: [-0.9775614481946764, -0.017036846470972623, 0.38661387642784256, 0.6359013889656868, -0.30413611428222415, 0.40240419108740666]
  effort: []
  time_from_start: 
    secs: 0
    nsecs:  27147549
- 
  positions: [2.109256457452625, -1.981253476197224, 1.9388565758948926, -0.5021648393599629, 0.5608327635832869, -3.183483418893228]
  velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
  accelerations: [-0.7134973773185114, -0.012472663553533377, 0.2824449866871931, 0.4638442371177143, -0.22212355863775582, 0.2940509625747436]
  effort: []
  time_from_start: 
    secs: 0
    nsecs:  48325922
edit flag offensive delete link more

Comments

This solution worked for ABB IRB120 robot. Thank you.

RROS_Rohit gravatar image RROS_Rohit  ( 2022-06-09 01:03:58 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2019-05-03 03:38:27 -0500

Seen: 677 times

Last updated: May 06 '19