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

Failed to validate trajectory: couldn't receive full current joint state within 1s error

asked 2017-01-16 09:58:30 -0600

FábioBarbosa gravatar image

updated 2017-01-16 11:00:51 -0600

gvdhoorn gravatar image

hi!

I am learning how to work with gazebo+moveit on ros indigo. I am following the book "Mastering ROS for Robotics Programming" and i am working with seven_dof_arm. I tried to execute only moveit, planned a motion and all did well and the same happen when i only work with gazebo only and control by terminal a joint to move. My problem happens when i have the two running and somehow i cant execute my planning from moveit to gazebo, it gives always this error: "Failed to validate trajectory: couldn't receive full current joint state within 1s".

I don't known how to resolve this problem...

i have gazebo 2, ros indigo, moveit last update (from january 2017), ubuntu 14.04 trusty.

My result in the terminal when i try to plan and execute a valid state:

[ INFO] [1484581574.863269930, 60.697000000]: Planning request received for MoveGroup action. Forwarding to planning pipeline.
[ INFO] [1484581574.864123376, 60.697000000]: No optimization objective specified, defaulting to PathLengthOptimizationObjective
[ INFO] [1484581574.864214951, 60.697000000]: No planner specified. Using default.
[ INFO] [1484581574.864274631, 60.697000000]: LBKPIECE1: Attempting to use default projection.
[ INFO] [1484581574.864428301, 60.697000000]: LBKPIECE1: Attempting to use default projection.
[ INFO] [1484581574.864680354, 60.697000000]: LBKPIECE1: Attempting to use default projection.
[ INFO] [1484581574.864967007, 60.697000000]: LBKPIECE1: Starting planning with 1 states already in datastructure
[ INFO] [1484581574.865112877, 60.697000000]: LBKPIECE1: Starting planning with 1 states already in datastructure
[ INFO] [1484581574.865192578, 60.697000000]: LBKPIECE1: Attempting to use default projection.
[ INFO] [1484581574.865431756, 60.697000000]: LBKPIECE1: Starting planning with 1 states already in datastructure
[ INFO] [1484581574.865522202, 60.697000000]: LBKPIECE1: Attempting to use default projection.
[ INFO] [1484581574.865631368, 60.697000000]: LBKPIECE1: Starting planning with 1 states already in datastructure
[ INFO] [1484581575.092653727, 60.870000000]: LBKPIECE1: Created 132 (30 start + 102 goal) states in 116 cells (28 start (28 on boundary) + 88 goal (88 on boundary))
[ INFO] [1484581575.096303094, 60.873000000]: LBKPIECE1: Created 90 (53 start + 37 goal) states in 77 cells (51 start (51 on boundary) + 26 goal (26 on boundary))
[ INFO] [1484581575.099875817, 60.876000000]: LBKPIECE1: Created 93 (39 start + 54 goal) states in 78 cells (38 start (38 on boundary) + 40 goal (40 on boundary))
[ INFO] [1484581575.148138305, 60.908000000]: LBKPIECE1: Created 152 (47 start + 105 goal) states in 137 cells (46 start (46 on boundary) + 91 goal (91 on boundary))
[ INFO] [1484581575.219947981, 60.970000000]: ParallelPlan::solve(): Solution found by one or more threads in 0.355519 seconds
[ INFO] [1484581575.220561589, 60.970000000]: LBKPIECE1: Attempting to use default projection.
[ INFO] [1484581575.220679319, 60.971000000]: LBKPIECE1: Attempting to use default projection.
[ INFO] [1484581575.220783265, 60.971000000]: LBKPIECE1: Starting planning with 1 states already in datastructure
[ INFO] [1484581575.220883439, 60.971000000]: LBKPIECE1: Starting planning with 1 states already in datastructure
[ INFO] [1484581575.222415665, 60.971000000]: LBKPIECE1: Attempting to use default projection.
[ INFO] [1484581575.222642371, 60.971000000]: LBKPIECE1: Starting planning with 1 states already in datastructure
[ INFO] [1484581575.225482043, 60.975000000]: LBKPIECE1: Attempting to use default projection.
[ INFO] [1484581575.225660210, 60.975000000 ...
(more)
edit retag flag offensive close merge delete

Comments

Facing exactly the same issue. Any quick help would be greatly appreciated.

bluebird gravatar image bluebird  ( 2017-01-22 01:45:39 -0600 )edit

Trajectory validation was recently added to the Trajectory Execution Manager in MoveIt. For it to work, it needs access to the JointStates of your (simulated) robot. Could you perhaps include a screenshot of rqt_graph in your OP? Perhaps some topics are not correctly connected.

gvdhoorn gravatar image gvdhoorn  ( 2017-01-22 04:07:43 -0600 )edit

Please find the rqt_graph in the attached link. Kindly download and view the file. https://drive.google.com/file/d/0B7LA... The JointStates are being published in the robot_name namespace which the move_group is not having access to.

bluebird gravatar image bluebird  ( 2017-01-22 04:34:40 -0600 )edit

I see no publishers or subscribers to a joint_states topic. That would cause exactly what you are experiencing, as MoveIt does not receive updates about the (joint)state of your robot. I have not read the book you refer to, but what @Johnson suggests could be a good first step.

gvdhoorn gravatar image gvdhoorn  ( 2017-01-22 04:53:27 -0600 )edit

It looks like move_group subscribes to joint_states topic and Gazebo publishes to /robot_namespace/joint_states topic. So, writing a node which subscribes to namespace/joint_states and publishes to /joint_states might do. https://drive.google.com/file/d/0B7LA...

bluebird gravatar image bluebird  ( 2017-01-22 05:03:02 -0600 )edit

@bluebird: that is exactly what joint_state_publisher (with the source_list parameter) does ..

gvdhoorn gravatar image gvdhoorn  ( 2017-01-22 05:08:02 -0600 )edit

3 Answers

Sort by » oldest newest most voted
7

answered 2017-01-22 04:39:54 -0600

Johnson gravatar image

updated 2017-01-22 04:44:35 -0600

Hello,friends! I am also following the book"Mastering ROS for Robotics Programming"and found this problem too.To resolving it You should copy codes about node "joint_state_publisher" from demo.launch to anyone of launch files of example codes with moveit+gazebo.(I pasted it to "seven_dof_bringup_moveit.launch". )

The codes:

<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
    <param name="/use_gui" value="false"/>
    <rosparam param="/source_list">[/move_group/fake_controller_joint_states]</rosparam>
  </node>
edit flag offensive delete link more

Comments

When there is no robot, a fake controller is used which is what demo.launch does. However, there is a simulated robot in the gazebo environment which has its own trajectory and joint states controller. I don't think using the fake controller manager to solve this issue is the right way.

bluebird gravatar image bluebird  ( 2017-01-22 04:51:52 -0600 )edit
1

@bluebird: the snippet posted by @Johnson does not make MoveIt/Gazebo use the fake controllers, it only makes sure that joint_state_publisher gathers the JointStates published on /move_group/fake_controller_joint_states and republishes them on /joint_states.

gvdhoorn gravatar image gvdhoorn  ( 2017-01-22 05:09:42 -0600 )edit

You could have a try. You will found that the simulated robot in gazebo is following the trajectory of moveit.

Johnson gravatar image Johnson  ( 2017-01-22 05:10:26 -0600 )edit

@Johnson and @gvdhoorn, thanks a lot for the quick help. It is working now.

bluebird gravatar image bluebird  ( 2017-01-22 05:32:10 -0600 )edit

A correction to the above code. The topic to be source listed is the one to which Gazebo publishes to. Although source listing /move_group/fake_controller_joint_states makes the robot move in gazebo, the desired tasks of subscribing to gazebo joint states and publishing to /joint_states is not done.

bluebird gravatar image bluebird  ( 2017-01-23 00:08:08 -0600 )edit
2

No, because you probably need to replace /move_group/fake_controller_joint_states with /robot_namespace/joint_states. I took @Johnson's answer as an example of how you solve these kind of problems, not as a copy/paste solution.

gvdhoorn gravatar image gvdhoorn  ( 2017-01-23 01:35:04 -0600 )edit

thank you all. finally i could correct this problem. Now its working correctly

FábioBarbosa gravatar image FábioBarbosa  ( 2017-01-26 09:55:35 -0600 )edit

@FábioBarbosa: if you feel that your question has been answered, please tick the checkmark to the left of the answer that you feel best answers your question (in this case there is only one answer).

gvdhoorn gravatar image gvdhoorn  ( 2017-01-26 13:37:55 -0600 )edit
2

answered 2017-10-23 10:13:24 -0600

noAimInLife gravatar image

In the official page MoveIt! concepts, under the Joint State Information section, it says that:

Note that move_group will not setup its own joint state publisher - this is something that has to be implemented on each robot.

Also when I tried following:

$ roslaunch seven_dof_arm_gazebo seven_dof_arm_bringup_moveit.launch

$ roslaunch seven_dof_arm_config moveit_planning_execution.launch
OR
$ roslaunch seven_dof_arm_config moveit_rviz.launch

Then when I try to execute the plan, It outputs: [ WARN] [1508769661.548873800, 62.280000000]: Failed to validate trajectory: couldn't receive full current joint state within 1s

but after running this:

$ rostopic list -v

It outputs: /seven_dof_arm/joint_states [sensor_msgs/JointState] 1 publisher

(I cannot understand why this is not working)

so I added following code in the seven_dof_arm_bringup_moveit.launch file:

<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />

and It worked fine.

edit flag offensive delete link more
0

answered 2017-11-17 00:43:55 -0600

ufr3c_tjc gravatar image

updated 2017-11-17 00:44:33 -0600

I'm going to add another answer here, to give another possible cause of this problem in case people come looking.

I had this error when adding vision to MoveIt. I was streaming in 20 point clouds per second, and publishing 20 joint state messages per second also. My hunch is that MoveIt is using the same pool of asynchronous threads to process both these messages. I suspect that because I was sending so many point clouds, there were occasions where all threads were being used to process point clouds, and none were processing the joint state callbacks within the required 1 second.

I throttled the point cloud back to once per second and everything is back to normal.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2017-01-16 09:54:15 -0600

Seen: 6,312 times

Last updated: Nov 17 '17