Universal_Robots_ROS_Driver: Unable to control I/O states on UR10 (Python)
Hi. I’m working on a project where I need to pick up objects using Universal Robots UR10 and a vacuum gripper. So far I am seeing positive results in executing move commands using movegroup python interface. I am, however, experiencing problems in controlling digital output states using my script. I am using the driver in this repository along with the ROS-I Universal Robots package.
Here’s my import list:
import sys
import copy
import rospy
import tf2_ros
import tf
import moveit_commander
import moveit_msgs.msg
import geometry_msgs.msg
#from math import pi
import math
from std_msgs.msg import String
from moveit_commander.conversions import pose_to_list
from ur_msgs.msg import SetIO
My function which I’m calling in the main function:
def apply_vacuum(self):
rospy.wait_for_service('/ur_hardware_interface/set_io')
try:
set_io = rospy.ServiceProxy('/ur_hardware_interface/set_io',SetIO)
set_io(fun = 1,pin = 2,state = 1)
except rospy.ServiceException, e:
print "Something went wrong: %s"%e
When I run the script I get no rospy.ServiceException. On my ur10_bringup.launch terminal I’m getting this error whenever I run the script above:
[ERROR] [1579178138.697529807]: Could not get fresh data package from robot
Running $rosservice list
yields /ur_hardware_interface/set_io
. I can even do a rosservice call, which results in True, although nothing seems to happen:
rosservice call /ur_hardware_interface/set_io 1 2 1
success: True
I’d like to know if this is a known issue or whether there’s a workaround or I’m missing something. I’m running ROS Kinetic on Ubuntu 16.04 LTS with Lenovo Thinkpad X260. My gripper is properly wired and connected and I can directly control the said output from the I/O tab on the teach pendant.
This issue has also been posted at answers.ros.org: https://answers.ros.org/question/341865/unable-to-control-io-states-on-ur10-python/
EDIT: Polyscope version: 3.11 URCaps: external_control_1.0.1
About this issue
- Original URL
- State: closed
- Created 4 years ago
- Comments: 23 (2 by maintainers)
Okay I tested with the I/O pins with no devices connected. I just monitored on the I/O tab on the teach pendant.
I was able to toggle the states. I need to know if there is a way to do the same for the tool states.