0

Rosanswers logo

Hello everyone! I'm using moveit! package to do motion planning on real dual_ur5 platform.I can ping both the IP adresses of the two arms.All config plugins may work well (like the .yaml files).But the warning occured when I run a Python file with moveit commander:[ WARN] [1508121443.319273668]: Failed to validate trajectory: couldn't receive full current joint state within 1s.

My bringup.launch:

 <launch>

<group ns="left"> <arg name="limited" default="false"/> <arg name="robot_ip" default="192.168.0.108"/> <arg name="reverse_port" default="50001"/> <arg name="min_payload" default="0.0"/> <arg name="max_payload" default="5.0"/> <arg name="prefix" default="left_" /> <include file="$(find ur_bringup)/launch/ur5_bringup.launch"> <arg name="limited" value="$(arg limited)"/> <arg name="robot_ip" value="$(arg robot_ip)"/> <arg name="reverse_port" value="$(arg reverse_port)"/> <arg name="min_payload" value="$(arg min_payload)"/> <arg name="max_payload" value="$(arg max_payload)"/> <arg name="prefix" value="$(arg prefix)"/> </include> </group>

<group ns="right"> <arg name="limited" default="false"/> <arg name="robot_ip" default="192.168.0.109"/>
<arg name="reverse_port" default="50002"/>
<arg name="min_payload" default="0.0"/> <arg name="max_payload" default="5.0"/> <arg name="prefix" default="right_" /> <include file="$(find ur_bringup)/launch/ur5_bringup.launch"> <arg name="limited" value="$(arg limited)"/> <arg name="robot_ip" value="$(arg robot_ip)"/> <arg name="reverse_port" value="$(arg reverse_port)"/> <arg name="min_payload" value="$(arg min_payload)"/> <arg name="max_payload" value="$(arg max_payload)"/> <arg name="prefix" value="$(arg prefix)"/> </include> </group>

</launch>


controllers.yaml in moveit_config package:

controller_list:
  • name: "left" action_ns: left_follow_joint_trajectory type: FollowJointTrajectory joints:

    • left_shoulder_pan_joint
    • left_shoulder_lift_joint
    • left_elbow_joint
    • left_wrist_1_joint
    • left_wrist_2_joint
    • left_wrist_3_joint
  • name: "right" action_ns: right_follow_joint_trajectory type: FollowJointTrajectory joints:

    • right_shoulder_pan_joint
    • right_shoulder_lift_joint
    • right_elbow_joint
    • right_wrist_1_joint
    • right_wrist_2_joint
    • right_wrist_3_joint


The warning in the terminal after runnning the python file:

[ INFO] [1508121442.292992289]: Planning request received for MoveGroup action. Forwarding to planning pipeline.
[ INFO] [1508121442.293298977]: No optimization objective specified, defaulting to PathLengthOptimizationObjective
[ INFO] [1508121442.293327316]: No planner specified. Using default.
[ INFO] [1508121442.293420818]: RRTConnect: Starting planning with 1 states already in datastructure
[ INFO] [1508121442.314419323]: RRTConnect: Created 4 states (2 start + 2 goal)
[ INFO] [1508121442.314442216]: Solution found in 0.021074 seconds
[ INFO] [1508121442.314505058]: SimpleSetup: Path simplification took 0.000045 seconds and changed from 3 to 2 states
[ INFO] [1508121442.317369505]: Received new trajectory execution service request...
***[ WARN] [1508121443.319273668]: Failed to validate trajectory: couldn't receive full current joint state within 1s
[ INFO] [1508121443.319330948]: Execution `enter code here`completed: ABORTED***

ur5_bringup.launch:

<launch>

<!-- robot_ip: IP-address of the robot's socket-messaging server --> <arg name="robot_ip"/> <arg name="port" default="50001"/> <arg name="limited" default="false"/> <arg name="min_payload" default="0.0"/> <arg name="max_payload" default="5.0"/> <arg name="prefix" default="" /> <!-- robot model <include file="$(find ur_description)/launch/ur5_upload.launch"> <arg name="limited" value="$(arg limited)"/> </include>-->

<!-- ur common --> <include file="$(find ur_modern_driver)/launch/ur_common.launch"> <arg name="prefix" value="$(arg prefix)" /> <arg name="robot_ip" value="$(arg robot_ip)"/> <arg name="port" value="$(arg port)"/> <arg name="min_payload" value="$(arg min_payload)"/> <arg name="max_payload" value="$(arg max_payload)"/> </include>

</launch>


ur_common.launch:

<launch>
  <!-- robot_ip: IP-address of the robot's socket-messaging server -->
  <arg name="robot_ip" />
  <arg name="port" />
  <arg name="min_payload" />
  <arg name="max_payload" />
  <arg name="prefix" default="" />
  <arg name="servoj_time" default="0.008" />
  <arg name="base_frame" default="$(arg prefix)base" />
  <arg name="tool_frame" default="$(arg prefix)tool0_controller" />

<!-- The max_velocity parameter is only used for debugging in the ur_driver. It's not related to actual velocity limits --> <arg name="max_velocity" default="10.0"/> <!-- [rad/s] -->

<node name="$(arg prefix)robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" > <remap from="joint_states" to="$(arg prefix)joint_states"/> </node>

<!-- driver --> <node name="$(arg prefix)ur_driver" pkg="ur_modern_driver" type="ur_driver" output="screen"> <!-- copy the specified IP address to be consistant with ROS-Industrial spec. --> <param name="prefix" type="str" value="$(arg prefix)" /> <param name="robot_ip_address" type="str" value="$(arg robot_ip)" /> <param name="min_payload" type="double" value="$(arg min_payload)" /> <param name="max_payload" type="double" value="$(arg max_payload)" /> <param name="max_velocity" type="double" value="$(arg max_velocity)" /> <param name="servoj_time" type="double" value="$(arg servoj_time)" /> <param name="base_frame" type="str" value="$(arg base_frame)"/> <param name="tool_frame" type="str" value="$(arg tool_frame)"/> <param name="reverse_port" type="int" value="$(arg port)" /> <remap from="follow_joint_trajectory" to="$(arg prefix)follow_joint_trajectory"/> </node> </launch>


Originally posted by yyf on ROS Answers with karma: 23 on 2017-10-18

Post score: 0

1 Answers1

0

Rosanswers logo

[ WARN] [1508121443.319273668]: Failed to validate trajectory: couldn't receive full current joint state within 1s.

You don't show any launch files - so it's hard to know for certain, but it sounds like the JointState msgs from your driver instances are not reaching MoveIt / the MoveIt commander.

MoveIt will try to make sure that the trajectory that you want to execte actually starts at the current state of the robot (to avoid large sudden movements). For that it needs JointState messages, or it can't determine current state. Your two ur_driver instances should be publishing in the left and right namespaces, so there is no global /joint_states topic for MoveIt to listen to.

Easiest is probably to use a joint_state_publisher instance with the source_list parameter to publish an aggregate message on /joint_states. See moveit_resources/fanuc_moveit_config/launch/demo.launch for an example, and wiki/joint_state_publisher - Node API - parameters for info on source_list.


Originally posted by gvdhoorn with karma: 86574 on 2017-10-19

This answer was ACCEPTED on the original site

Post score: 1


Original comments

Comment by yyf on 2017-10-19:
I have added two launch files.The /joint_states message is established in ur_common.launch:

<remap from="joint_states" to="$(arg prefix)joint_states"/>

Comment by gvdhoorn on 2017-10-19:
The value of prefix is set to "left_" and "right_". So I would expect two topics: left_joint_states and right_joint_states. That is not /joint_states that MoveIt will be looking for.

Comment by gvdhoorn on 2017-10-19:
Also: I don't think a remap is necessary. The topics should be published under /left/joint_states and /right/joint_states automatically. The remap confuses me.

Comment by yyf on 2017-10-30:
Thank you very much!The problem is /left/joint_states was not connected with moveit!

Comment by Soul Goumey on 2018-09-04:
hello! I actually have the same problem. I am trying to control an UR5 and UR10 with move_group_python_interface. Can you please add your ur_moveit_planning_trajectory_execution.launch? or did you use the one from the ur5_moveit_config package? did you also use move_group.launch in a group ns?

gvdhoorn-rse
  • 39,013
  • 1
  • 1
  • 4