Skip to content
Snippets Groups Projects
Commit 32607e00 authored by ipa-fxm's avatar ipa-fxm
Browse files

moved service definition to ur_msgs, fix typos, add payload bound parameters

parent bf32d835
Branches
Tags
No related merge requests found
......@@ -4,32 +4,10 @@ project(ur_driver)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED message_generation)
find_package(catkin REQUIRED)
catkin_python_setup()
#######################################
## Declare ROS messages and services ##
#######################################
## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )
## Generate services in the 'srv' folder
add_service_files(
FILES
URSetPayload.srv
)
## Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES
#control_msgs# sensor_msgs
)
###################################
## catkin specific configuration ##
......
......@@ -220,7 +220,7 @@ def driverProg():
#send_waypoint_finished(waypoint_id)
set_servo_setpoint(waypoint_id, q, t)
elif mtype == MSG_SET_PAYLOAD:
params = socket_read_binary_integer(1)
params = socket_read_binary_integer(1)
if params[0] == 0:
send_out("Received no parameters for setPayload message")
end
......@@ -240,7 +240,7 @@ def driverProg():
send_out("Received no parameters for set_out message")
end
if params_mult[2] > 0:
set_digital_out(params_mult[1], True)
set_digital_out(params_mult[1], True)
elif params_mult[2] == 0:
set_digital_out(params_mult[1], False)
end
......@@ -252,7 +252,7 @@ def driverProg():
send_out("Received no parameters for set_out message")
end
if params_mult[2] != 0:
set_flag(params_mult[1], True)
set_flag(params_mult[1], True)
elif params_mult[2] == 0:
set_flag(params_mult[1], False)
end
......
......@@ -19,9 +19,8 @@ from geometry_msgs.msg import WrenchStamped
from ur_driver.deserialize import RobotState, RobotMode
from ur_msgs.srv import SetIO
from ur_msgs.srv import SetPayload, SetIO
from ur_msgs.msg import *
from ur_driver.srv import *
# renaming classes
DigitalIn = Digital
......@@ -60,6 +59,12 @@ MULT_jointstate = 10000.0
MULT_time = 1000000.0
MULT_blend = 1000.0
#Bounds for SetPayload service
MIN_PAYLOAD = 0.0
MAX_PAYLOAD = 5.0 #UR5
#MAX_PAYLOAD = 10.0 #UR10
FUN_SET_DIGITAL_OUT = 1
FUN_SET_FLAG = 2
FUN_SET_ANALOG_OUT = 3
......@@ -448,7 +453,7 @@ class CommanderTCPHandler(SocketServer.BaseRequestHandler):
with self.socket_lock:
self.request.send(buf)
#Experimental set_payload implementation
#Experimental set_payload implementation
def send_payload(self,payload):
buf = struct.pack('!ii', MSG_SET_PAYLOAD, payload * MULT_payload)
with self.socket_lock:
......@@ -606,14 +611,14 @@ def within_tolerance(a_vec, b_vec, tol_vec):
class URServiceProvider(object):
def __init__(self, robot):
self.robot = robot
rospy.Service('ur_driver/setPayload', URSetPayload, self.setPayload)
rospy.Service('ur_driver/setPayload', SetPayload, self.setPayload)
def set_robot(self, robot):
self.robot = robot
def setPayload(self, req):
if req.payload < 0 or req.payload > 20.00:
print 'ERROR: Payload out of bounce'
if req.payload < MIN_PAYLOAD or req.payload > MAX_PAYLOAD:
print 'ERROR: Payload out of bounds'
return False
if self.robot:
......
......@@ -18,6 +18,7 @@ find_package(catkin REQUIRED COMPONENTS message_generation std_msgs)
## Generate services in the 'srv' folder
add_service_files(
FILES
SetPayload.srv
SetIO.srv
)
......
File moved
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment