RS485 tool communication with URCap

Hey,

I am using a UR3e robot, and I am trying to communicate through URCaps with my Custom end-effector tool, using RS485. I want to build my own URCaps where I can select different states, which are then sent to my Custom end-effector tool via RS485. Does anyone have a simple example how I could do that? I also tried to work my way through the forum, which gave me new ideas, but now I’m stuck. Excuse me, I’m new to this field, I’d appreciate any help or advice.

I do not use RS485 myself, but I found this URCap example that might be useful to you:

1 Like

If I understand correctly, this is a Python daemon, with which I can then communicate with my custom end-effector tool via URScript (script code?) is that correct? Is there also a way to send individual signals directly to my custom end-effector tool via URCaps?

Yes, this URCap implements a python daemon that has 2 main functions:

  • Implements and handles all of the RS485 communication.
  • Creates and runs a parallel process with a XML-RPC server, which is for communicating the daemon with Polyscope.

Then, on the URCap source java files:

  • The DaemonInstallation node contribution defines in URScript language the tool_modbus_write, tool_modbus_read and init_tool_modbus functions, which connect and get a response from the Python XML-RPC server in order to read/write on the bus.
  • From Polyscope you only need to call these functions in order to access the bus.

So, if you want to add more functions for your custom tool, you would need to add more services on the daemon server and call those functions from the Daemon node contribution.
For example:

#  ------------------------ modbus_xmlrpc.py ------------------------ 
# -- define new function in the daemon python:
def send_some_signal_to_custom_tool(value_from_polyscope):
  local output = 0
  # -- do some stuff in here
  return value
# -- add new function to server
server.register_function(send_some_signal_to_custom_tool,"send_some_signal_to_custom_tool")
//  ------------------------ DaemonInstallationNodeContribution.java ------------------------ 
public DaemonInstallationNodeContribution(InstallationAPIProvider apiProvider, DaemonInstallationNodeView view,
			DataModel model, CreationContext context, ModbusDaemonService modbusDaemonService) {
//...
// define new function in URScript to access the server:
@Override
	public void generateScript(ScriptWriter writer) {
		writer.assign(XMLRPC_VARIABLE, "rpc_factory(\"xmlrpc\", \"http://127.0.0.1:40408/RPC2\")");
		// call this from Polyscope: ex --> tool_send_signal(1)
		writer.appendLine("def tool_send_signal(value_to_python):");
		writer.appendLine("local response = modbus_xmlrpc.send_some_signal_to_custom_tool(value_to_python)");
		writer.appendLine("return response");
		writer.appendLine("end");

	}
// ...
}

First, thank you for your help and sorry if I don’t understand all of this right away. First, you define a new function, where I define the value I want to transfer. After that, the function will be added to the server. So that I can access it, I have to add a new function in the daemon node contribution so that I can access it via Polyscope (tool_send_signal(1)). Hope I got that right. Is there also a way to send this data to my custom tool without script code, like a customer who selects one of 5 states which are then sent to the custom tool without having to deal with URScript. If that’s not possible, that’s ok. I would appreciate any help.

Yes, you understood it right.
About what you want to do, you can make a URCap with a view node, which the user drops on the program and it executes URScript commands underneath everytime the program reaches there.
To learn the basics about how to create a view node, here is a URCap tutorial. This tutorial explains how to do it with turning on/off one single output. In your case it’d be more complicated, but you can get a lot from this tutorial, including how to compile and install a URCap.

Thank you for your help, I’ll try it in the next few days when I can work on the robot again

Hi!

I have a question about how to define new functions.
I would like to write a function that handles writing/reading to/from multiple register.
Something like this.

------------------------ modbus_xmlrpc.py ------------------------

def tool_modbus_write(register_address, data):
try:
global instrument
instrument.write_register(register_address-1,data,0)
except Exception:
Logger.error(“Error in modbus write method”, exc_info=True)
return “Modbus failed writing”
return “Succesfully executed!”

def tool_modbus_write_multiple(address0,value0,address1,value1):
global value
value[0] = tool_modbus_write(address0,value0)
value[1] = tool_modbus_write(address1,value1)
return value

server.register_function(tool_modbus_write,“tool_modbus_write”)
server.register_function(tool_modbus_write_multiple,“tool_modbus_write_multiple”)

------------------------

The problem is that this function is not valid. My guess is that I’m doing something wrong when calling the existing “tool_modbus_write(register_address,data)” function from within my custom function.
Is it possible to call a function from within a custom function?

// Oliver