Using universal_robot pkg and moveIt to control real UR5 robot.UR5 can move but can't move to the desired pose.It saied "time exceeded and current robot state not at goal, last point required"

asked 2016-12-27 01:20:40 -0500

Lileping gravatar image

When I use Universal_robot pkg and moveIt to control real UR5. The UR5 can't move to the desired pose.It stopped at a pose which is belong to the trajectory.My steps of operation are as follows

1."roslaunch ur_bringup ur_bringup.launch robot_ip:=192.168.1.160"which appears the connection is correct."The action server for this driver has been started"

2.Launch my moveit config file"roslaunch ur5_moveit_config_myself move_group.launch".The config file is generated by moveit_setup_assistant.and I add controller.yaml and ur5_moveit_controller_manager.launch.xml

3."rosrun rviz rviz"

4."rosrun le_node moveit_ik_demo.py" The file moveit_ik_demo.py is shown below.

After I run the moceit_ik_demo.py. The UR5 begins to move toward the desired pose.But it came to a sudden stop in the journey .and can't attach to the desired pose. In the first terminal(launching the ur_bringup.launch),it appead that

"[WARN] [WallTime: 1482755354.085866] Trajectory time exceeded and current robot state not at goal, last point required [WARN] [WallTime: 1482755354.086135] Current trajectory time: 1.92857694626, last point time: 1.913815417 [WARN] [WallTime: 1482755354.086456] Desired: [1.5887987717921845, -0.0001816342668607831, 0.0009067557118833066, -0.0009527113572694361, -0.0007133560068905353, -4.268342442810536e-05] actual: [1.6035473346710205, -0.6335380713092249, 0.2663407325744629, -0.233499828969137, -0.04164582887758428, -0.24181014696230108] velocity: [-0.003962783608585596, 0.1539221853017807, -0.06261198222637177, 0.06792659312486649, 0.009731191210448742, 0.060160811990499496] [2016-12-26 20:29:15.983806] Out: Braking"

Maybe the reason is the time of the trajectory is limited. and I tried many times with the same peogram (the desired pose is different).The trajectory time is no more than 3 seconds. But I don't konw how to modify the limit of trajectory time.

The moveit_ik_demo.py is as follows

import rospy, sys import moveit_commander from moveit_msgs.msg import RobotTrajectory from trajectory_msgs.msg import JointTrajectoryPoint

from geometry_msgs.msg import PoseStamped, Pose from tf.transformations import euler_from_quaternion, quaternion_from_euler

class MoveItDemo:

   def __init__(self):
        # Initialize the move_group API
    moveit_commander.roscpp_initialize(sys.argv)

    rospy.init_node('moveit_demo')

    # Initialize the move group for the right arm
    right_arm = moveit_commander.MoveGroupCommander('right_arm')

    # Get the name of the end-effector link
    end_effector_link = right_arm.get_end_effector_link()

    # Set the reference frame for pose targets
    reference_frame = 'desk '

    # Set the right arm reference frame accordingly
    right_arm.set_pose_reference_frame(reference_frame)

    # Allow replanning to increase the odds of a solution
    right_arm.allow_replanning(True)

    # Allow some leeway in position (meters) and orientation (radians)
    right_arm.set_goal_position_tolerance(0.01)
    right_arm.set_goal_orientation_tolerance(0.05)

    # Start the arm in the "resting" pose stored in the SRDF file
    right_arm.set_named_target('pose_2')
    right_arm.go()
rospy.sleep(2)

target_pose = PoseStamped()
target_pose.header.frame_id = reference_frame
    target_pose.header.stamp = rospy.Time.now()     
    target_pose.pose.position.x = 0.5
    target_pose.pose.position.y = -0.5
    target_pose.pose.position.z = 0.500
    target_pose.pose.orientation.x = 0.0
    target_pose.pose.orientation.y = 0.0
    target_pose.pose.orientation.z = 0.0
    target_pose.pose.orientation.w = -1.0

    # Set the start state to the current state
    right_arm.set_start_state_to_current_state()

    # Set the goal pose of the end effector to the stored pose
    right_arm.set_pose_target(target_pose, end_effector_link)

    # Plan the trajectory to ...
(more)
edit retag flag offensive close merge delete

Comments

Do you have a maximal speed set in the teach pendant?

NEngelhard gravatar image NEngelhard  ( 2016-12-27 04:12:42 -0500 )edit

Yes, the teach pendant had a maximal speed limit.But when I use ur_bringup.launch,The teaching box does not work well.

Lileping gravatar image Lileping  ( 2017-01-05 20:43:01 -0500 )edit