Robotics StackExchange | Archived questions

Cobot executes planning once, then refuses any more planning executions

Hello. I'm working on a project that uses the Aubo i5. The code depends on MoveIt. I have a function that sets a Pose that's used as its goal, passes it to the MoveGroupCommander using the class's setposetarget function, and plans a route for the end effector to this goal, and then executes the planning. This works perfectly in a simulation, but when trying to control an actual robot, it doesn't. When I call my function for the first time, the robot works perfectly. But if I call the same function again, nothing happens. A plan is made, but I then get a timeout. If I then restart all of my software, I can make another movement, but then need to restart all the software again. I don't need to restart the Aubo i5 itself, just the software on my laptop.

To launch my program, I need to execute the following command: "roslaunch auboi5moveitconfig moveitplanningexecution.launch sim:=false robotip:=192.168.1.10". This launches the control software for the robot. I then run "rosrun robotao movegroupsubpub.py", which is my own code that does the planning and execution. This program listens to a topic on which and x, y, and z is published, which are the coordinates of the goal.

Here is the code for planning and execution: def gotoposegoalinput(self,x,y,z): # Copy class variables to local variables to make the web tutorials more clear. # In practice, you should use the class variables directly unless you have a good # reason not to. group = self.group

## BEGIN_SUB_TUTORIAL plan_to_pose
##
## Planning to a Pose Goal
## ^^^^^^^^^^^^^^^^^^^^^^^
## We can plan a motion for this group to a desired pose for the
## end-effector:
orientation = tf.transformations.quaternion_from_euler(pi, 0.0, -pi/2)
pose_goal = geometry_msgs.msg.Pose()
pose_goal.orientation.x = orientation[0]
pose_goal.orientation.y = orientation[1]
pose_goal.orientation.z = orientation[2]
pose_goal.orientation.w = orientation[3]
#pose_goal.orientation.w = 1.0
pose_goal.position.x = x
pose_goal.position.y = y
pose_goal.position.z = z
group.set_pose_target(pose_goal)

## Now, we call the planner to compute the plan and execute it.
plan = group.go(wait=True)
# Calling `stop()` ensures that there is no residual movement
group.stop()
# It is always good to clear your targets after planning with poses.
# Note: there is no equivalent function for clear_joint_value_targets()
group.clear_pose_targets()

## END_SUB_TUTORIAL

# For testing:
# Note that since this section of code will not be included in the tutorials
# we use the class variable rather than the copied state variable
current_pose = self.group.get_current_pose().pose
return all_close(pose_goal, current_pose, 0.01)

group refers to a moveit_commander.MoveGroupCommander object.

Below is part of the output from moveitplanningexecution.launch. Things prefaced by dashes are commands that I put in in-between. Multiple newlines represent that a small amount of time (some seconds) passed in between outputs. I will post an attachment once I've gotten more karma (currently at 1, new account, stupid spam protection)

 You can start planning now!

[ INFO] [1572254135.576545228]: Loading robot model 'aubo_i5'...
[ WARN] [1572254135.576735364]: Skipping virtual joint 'base_link' because its child frame 'base_link' does not match the URDF frame 'world'
[ INFO] [1572254135.576792087]: No root/virtual joint specified in SRDF. Assuming fixed joint
[ INFO] [1572254135.863134193]: Loading robot model 'aubo_i5'...
[ WARN] [1572254135.863393023]: Skipping virtual joint 'base_link' because its child frame 'base_link' does not match the URDF frame 'world'
[ INFO] [1572254135.863499809]: No root/virtual joint specified in SRDF. Assuming fixed joint
[ INFO] [1572254136.634436635]: Starting scene monitor
[ INFO] [1572254136.637862616]: Listening to '/move_group/monitored_planning_scene'
[ WARN] [1572254136.826878576]: The STL file 'package://aubo_description/meshes/aubo_i5/collision/pedestal.STL' is malformed. It starts with the word 'solid', indicating that it's an ASCII STL file, but it does not contain the word 'endsolid' so it is either a malformed ASCII STL file or it is actually a binary STL file. Trying to interpret it as a binary STL file instead.
[ INFO] [1572254137.583064467]: Constructing new MoveGroup connection for group 'manipulator_i5' in namespace ''
[ INFO] [1572254138.618141296]: Ready to take commands for planning group manipulator_i5.
[ INFO] [1572254138.618220385]: Looking around: no
[ INFO] [1572254138.618253950]: Replanning: no
[ WARN] [1572254138.626816772]: Interactive marker 'EE:goal_wrist3_Link' contains unnormalized quaternions. This warning will only be output once but may be true for others; enable DEBUG messages for ros.rviz.quaternions to see more details.




-----running command 1:
-----rostopic pub  -1 /cobot/gripper_coordinate robotao/GripperCoordinate "x_axis: 0.5
-----y_axis: 0.5
-----z_axis: 0.15"

[ INFO] [1572254205.942548362]: Combined planning and execution request received for MoveGroup action. Forwarding to planning and execution pipeline.
[ INFO] [1572254205.943270698]: Planning attempt 1 of at most 1
[ INFO] [1572254205.945152438]: Planner configuration 'manipulator_i5' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
[ INFO] [1572254205.945789626]: RRTConnect: Starting planning with 1 states already in datastructure
[ INFO] [1572254205.975153380]: RRTConnect: Created 5 states (3 start + 2 goal)
[ INFO] [1572254205.975310303]: Solution found in 0.029709 seconds
[ INFO] [1572254205.987476023]: SimpleSetup: Path simplification took 0.011721 seconds and changed from 4 to 2 states
[ INFO] [1572254207.660722688]: Completed trajectory execution with status SUCCEEDED ...
[ INFO] [1572254207.792242631]: Received event 'stop'
[ERROR] [1572254207.792277171]: To transition to an aborted state, the goal must be in a preempting or active state, it is currently in state: 3




-----running command 2:
-----rostopic pub  -1 /cobot/gripper_coordinate robotao/GripperCoordinate "x_axis: 0.5
-----y_axis: 0.5
-----z_axis: 0.15" 

[ INFO] [1572254268.117640714]: Combined planning and execution request received for MoveGroup action. Forwarding to planning and execution pipeline.
[ INFO] [1572254268.117803953]: Planning attempt 1 of at most 1
[ INFO] [1572254268.118522298]: Planner configuration 'manipulator_i5' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
[ INFO] [1572254268.118714775]: RRTConnect: Starting planning with 1 states already in datastructure
[ INFO] [1572254268.169308951]: RRTConnect: Created 16 states (14 start + 2 goal)
[ INFO] [1572254268.169494051]: Solution found in 0.050825 seconds
[ INFO] [1572254268.184387746]: SimpleSetup: Path simplification took 0.014642 seconds and changed from 3 to 2 states



[ERROR] [1572254273.416677157]: Controller is taking too long to execute trajectory (the expected upper bound for the trajectory execution was 5.217249 seconds). Stopping trajectory.
[ INFO] [1572254273.417050084]: Cancelling execution for aubo_i5_controller
[ INFO] [1572254273.417317368]: Completed trajectory execution with status TIMED_OUT ...
[ INFO] [1572254273.588281928]: Received event 'stop'
[ERROR] [1572254273.588294589]: To transition to an aborted state, the goal must be in a preempting or active state, it is currently in state: 2   

.

I'm using ROS Kinetic along with the Aubo drivers as found here: https://github.com/lg609/aubo_robot

Asked by Amanoo on 2019-10-31 04:35:37 UTC

Comments

The errors referring to action goals seem to indicate that the aubo driver is not handling the FollowJointTrajectory action goals properly.

I would ask the author of that driver to assist you.

Asked by gvdhoorn on 2019-10-31 08:59:29 UTC

Answers