MoveIt! error - Robot only moves when I "plan and execute" and not when I "plan" and then "execute"

asked 2018-04-24 13:00:23 -0500

znbrito gravatar image

updated 2018-05-02 08:15:31 -0500

Hello guys,

I am working on Ubuntu 16.04 LTS and ROS Kinetic. I managed to connect MoveIt! with my real Robotis Manipulator-H and now I can perform path planning using the MoveIt! GUI on RViz. However, after I perform path planning in the GUI (using the "plan and execute"), I always see this message on the terminal where I ran the MoveIt! RViz GUI:

[ INFO] [1524586969.369797363]: Fake execution of trajectory
[ INFO] [1524586969.826177422]: Get Joint Trajectory
[ INFO] [1524586969.826249800]: Send Motion Trajectory
[ INFO] [1524586970.325910473]: End Trajectory
[ INFO] [1524586972.670081887]: Didnt received robot state (joint angles) with recent timestamp within 7.8412e-05 seconds.
Check clock synchronization if your are running ROS across multiple machines!
[ WARN] [1524586972.670136939]: Failed to receive current joint state
[ INFO] [1524586972.670190086]: Completed trajectory execution with status SUCCEEDED ...

After that, I tried to execute some code that had previously worked when I was simulating the manipulator in Gazebo. When I ran the node that sends to code, it suddenly shuted down with no specific error, as you can see here:

[ INFO] [1524591470.337832395]: Using solve type Speed
[ INFO] [1524591470.711624508]: Publishing maintained planning scene on ''
[manipulator_h_move_group_interface_tutorial-1] process has died [pid 12991, exit code -11, cmd /home/josebrito/catkin_ws/devel/lib/manipulator_h_path_planning/manipulator_h_move_group_interface_tutorial __name:=manipulator_h_move_group_interface_tutorial __log:=/home/josebrito/.ros/log/2b327d8a-47e6-11e8-86f0-f894c21e0ad7/manipulator_h_move_group_interface_tutorial-1.log].
log file: /home/josebrito/.ros/log/2b327d8a-47e6-11e8-86f0-f894c21e0ad7/manipulator_h_move_group_interface_tutorial-1*.log

Basically, the most important part of the code is this:

  // Visualizing plans
  // ^^^^^^^^^^^^^^^^^
  //
  // We can also visualize the plan as a line with markers in Rviz.
  ROS_INFO_NAMED("tutorial", "Visualizing plan 1 as trajectory line");
  visual_tools.publishAxisLabeled(target_pose1, "pose1");
  visual_tools.publishText(text_pose, "Pose goal planning", rvt::WHITE, rvt::XLARGE);
  visual_tools.publishTrajectoryLine(my_plan.trajectory_, joint_model_group->getLinkModel("end_link"), joint_model_group, rvt::LIME_GREEN);
  visual_tools.trigger();



  // Moving to a pose goal
  // ^^^^^^^^^^^^^^^^^^^^^
  //
  // Moving to a pose goal is similar to the step above
  // except we now use the move() function. Note that
  // the pose goal we had set earlier is still active
  // and so the robot will try to move to that goal. We will
  // not use that function in this tutorial since it is
  // a blocking function and requires a controller to be active
  // and report success on execution of a trajectory.

  // Uncomment below line when working with a real robot (or Gazebo simulation)
  move_group.execute(my_plan);

  // Wait for the user click on the RVizVisualToolsGui or N if he has the 'Key Tool' selected. Also print a specific message in the terminal
  visual_tools.prompt("Click 'Next' in the RVizVisualToolsGui or N if you have the 'Key Tool' selected");

And after spending some time trying to figure out where the problem is coming from, I found out that if I commented this line of code:

visual_tools.publishTrajectoryLine(my_plan.trajectory_, joint_model_group->getLinkModel("end_link"), joint_model_group, rvt::LIME_GREEN);

The error disappears (????? strange error). However, now whenever I run the code I get messages saying that the trajectory was executed but in fact it is not being executed because my manipulator just doesn't move. This are the messages that I get: image description

The black manipulator ... (more)

edit retag flag offensive close merge delete