External force-torque sensor implementation

This is a guide on how to integrate an external Force/Torque sensor with the robot controller, e.g. by developing a URCap.

From SW 3.3 and newer it is possible to feed external force/torque measurements into the robot controller, and use this input as an alternative to the internal measurements in e.g. force mode.
The feature is enabled and disabled with a special script command and the force/torque measurements can be streamed into the robot controller using the RTDE interface as described below.

The functionality can be integrated in a URCap for easy installation of external F/T sensors on Universal Robots.

Feeding F/T measurements into the robot controller
The RTDE interface, described in this article, can be used for feeding F/T measurements into the real-time control loop of the robot.

A special input variable should be used for this purpose:
Name: external_force_torque
Type: VECTOR6D

Script functions for using an external F/T sensor in the robot controller.

enable_external_ft_sensor(enable, sensor_mass = 0.0, sensor_measuring_offset = [0.0, 0.0, 0.0], sensor_cog = [0.0, 0.0, 0.0])

This function is used for enabling and disabling the use of external F/T measurements in the controller.

If no other RTDE watchdog has been configured (using script function rtde_set_watchdog, see URScript manual), a default watchdog will be set to a 10Hz minimum update frequency when the external F/T sensor functionality is enabled. If the update frequency is not met the robot program will pause.

Parameters

  • enable: enable or disable feature (bool)
  • sensor_mass: mass of the sensor in kilograms (float)
  • sensor_measuring_offset: [x, y, z] measuring offset of the sensor in meters relative to the tool flange frame
  • sensor_cog: [x, y, z] center of gravity of the sensor in meters relative to the tool flange frame

Remark: the TCP Configuration in the installation must also include the weight and offset contribution of the sensor.

6 Likes

Hello,

I like to use the Robotiq FT 300 in a force control application.
Can you please provide a simple program to enable the external force sensor.
Where should I define the variable “external_force_torque”, in the Polyscope the name is too long, only “external_force_” but not more can be assigned.

Do I have to setup the RTDE interface with a PC first? Or is the default frequency always “created”

Here is my test program but it drops an error, the error is “C207A0 Fieldbus Input not connected” - Safety Stop
The program is moving to a start position, then the robot moves downwards to the waypopint_down with force control. After a few seconds the Waypoint_up is targeted again. It works with the “internal” force sensors but I like to compare the FT 300 and the internal sensors.

def Force_Mode():
  set_standard_analog_input_domain(0, 1)
  set_standard_analog_input_domain(1, 1)
  set_tool_analog_input_domain(0, 1)
  set_tool_analog_input_domain(1, 1)
  set_analog_outputdomain(0, 0)
  set_analog_outputdomain(1, 0)
  set_tool_voltage(0)
  set_standard_digital_input_action(0, "default")
  set_standard_digital_input_action(1, "default")
  set_standard_digital_input_action(2, "default")
  set_standard_digital_input_action(3, "default")
  set_standard_digital_input_action(4, "default")
  set_standard_digital_input_action(5, "default")
  set_standard_digital_input_action(6, "default")
  set_standard_digital_input_action(7, "default")
  set_tool_digital_input_action(0, "default")
  set_tool_digital_input_action(1, "default")
  set_tcp(p[0.0,0.0,0.0,0.0,0.0,0.0])
  set_payload(0.0)
  set_gravity([0.0, 0.0, 9.82])
  ###############################################################
  # Script file used to communicate with Robotiq's ft sensor
  # Version: 0.0.1
  ###############################################################
  
  def rq_move_relative(P_from, P_to, Pi):
  return pose_trans(P_to, pose_trans(pose_inv(P_from), Pi))
  end
  
  def rq_elementWiseSub(list1, list2):
  global rq_return_list=list1
  i=0
  while i<length(list1):
  rq_return_list[i]=list1[i] - list2[i]
  i=i+1
  end
  return rq_return_list
  end
  
  if (not socket_open("127.0.0.1",63351,"stream")):
  popup("Can't connect to the sensor driver", "Robotiq's FT Sensor", error=True)
  end
  $ 1 "BeforeStart"
  $ 2 "enable≔ True "
  global enable=  True  
  $ 3 "external_force≔[0,0,0,0,0,0]"
  global external_force=[0,0,0,0,0,0]
  $ 4 "rtde_set_watchdog('external_force_torque', 100, 'ignore')"
  rtde_set_watchdog("external_force_torque", 100, "ignore")
  $ 5 "enable_external_ft_sensor(enable, sensor_mass = 0.0, sensor_measuring_offset = [0.0, 0.0, 0.0], sensor_cog = [0.0, 0.0, 0.0])"
  enable_external_ft_sensor(enable, sensor_mass = 0.0, sensor_measuring_offset = [0.0, 0.0, 0.0], sensor_cog = [0.0, 0.0, 0.0])
  $ 12 "Thread_1"
  thread Thread_1():
    while (True):
      global forceValue=force()
      sleep(0.1)
    end
  end
  threadId_Thread_1 = run Thread_1()
  while (True):
    $ 6 "Robot Program"
    $ 7 "MoveJ"
    $ 8 "Waypoint_Start"
    movej([0.6462507248063873, -1.4844754633383452, -1.5128539488861268, -1.7149360353413172, 1.5719077446302612, 2.1474470147886393E-5], a=1.3962634015954636, v=1.0471975511965976)
    sync()
    force_mode(tool_pose(), [0, 0, 1, 0, 0, 0], [0.0, 0.0, 10.0, 0.0, 0.0, 0.0], 2, [0.1, 0.1, 0.1, 0.3490658503988659, 0.3490658503988659, 0.3490658503988659])
    $ 9 "Force"
    $ 10 "Waypoint_Up"
    movej([0.6464576065826698, -1.5403758500235991, -1.2224835464270631, -1.9494061552478996, 1.5719451782179874, -6.373389472713598E-5], a=1.3962634015954636, v=1.0471975511965976)
    $ 11 "Waypoint_Down"
    movej([0.646095034637308, -1.4801480793962298, -1.768406307748009, -1.4637108915522674, 1.5717788898311778, 1.228272960736904E-4], t=5.0)
    end_force_mode()
    stopl(5.0)
  end
end

@generalmidi,

The external_force_torque of type VECTOR6D have to be fed using the RTDE interface, not using URScript.
You will need URScript to enable the external force data, but you need RTDE to make sure you have real-time streaming capability.

The RTDE interface is described in a separate article, and you should have some form of external executable to read the data from the F/T sensor and stream it over RTDE.
The executable could either be a URCap daemon process, or an external device running a daemon.

However, in the case of the Robotiq FT 300, why not ask @a.mottard or check out Robotiq’s FT300 URCap.

@jbm @generalmidi

Using the FT300 or FT150 forces and torques signals to feed UR’s force mode is something we get asked about a lot. It is a feature we have not started working on, but it is definitely one we will want to look into. Especially with our new Path recording feature - included in our FT300 URCaps package - it would be a very useful feature to have. As of now, we do not have an idea or a time frame for when and how we could come up with a feature like that, but we will keep you updated.

@jbm, are you aware of anyone who was able to feed the values of an external force sensor in UR’s force mode?

1 Like

@a.mottard, I believe that @jda have done this succesfully.

Hi,

we have the Robotiq FT 300 and want to use the build in Active Drive Toolbar. We want to enable/disable via code e.g. a digital input.

We tried to build our own solution based on the 3 provided examples that come in the urcap but the movement falters so we want to use the Active Drive Toolbar which works fluently but we don’t know how to access it.

Do you have any suggestions? Which possibilities do we have?

Thanks for your effort

I have bought an ATI force torque sensor. I now want to embed it’s values to the Controller. I already used RTDE. But I cannot find the necessary information on howto configure the RTDE. I would like to see an xml file like the one for the control_loop sample:

<?xml version="1.0"?>

<rtde_config>




<recipe key="setp">
	<field name="input_double_register_0" type="DOUBLE"/>
	<field name="input_double_register_1" type="DOUBLE"/>
	<field name="input_double_register_2" type="DOUBLE"/>
	<field name="input_double_register_3" type="DOUBLE"/>
	<field name="input_double_register_4" type="DOUBLE"/>
	<field name="input_double_register_5" type="DOUBLE"/>
</recipe>

<recipe key="watchdog">
	<field name="input_int_register_0" type="INT32"/>
</recipe>

</rtde_config>

Can you provide me that?

Hello fratz

It is not possible to activate the Active Drive from a UR program because the Active Drive send its own program to the controller. The Active Driver can only be activated if no UR program is running.

1 Like

Is there a standard or recommended way to signal a failure in the health of an external sensor other than triggering a “C207A0 Fieldbus Input not connected” Protective Stop by halting RTDE streaming?

@jbm Has anyone you know of successfully used force mode or an external force/torque sensor inside of conveyor tracking? Right now I am trying to use force mode inside conveyor tracking, and as soon as force mode is applied it stops tracking and protective stops. Would an external sensor with a URCap solve this or will I run into the same issue?

I’m doubting you can use both force mode and conveyor tracking at the same time since you can see they both use “internal variable” u26426u24231, which might cause access conflicts.

Ok, thank you. Here also is the answer I got from UR:
“I would not use force mode with conveyor tracking. When the robot is in force mode the controller is controlling the TCP based on force feedback (‘loop 1’). When it is in conveyor tracking mode it is continuously using the conveyor signal to adjust the TCP (‘loop 2’). In ANY closed loop control system it is generally a bad idea to have two control loops acting on the same output at the same time. You get unpredictable results.”

Hi,

Anyone knows if it is possible to know the current status (enabled or disabled) of the force injection in the controller.

The problem I face is that enable_external_ft_sensor might have been enabled in the script but another external application has to know if it is on or off. Where can I get this feedback?

So, is it possible to know:

  1. if the RTDE interface is getting force values from an external sensor
  2. if the enable_external_ft_sensor has been set.

Thanks

Hi,

I use a Force/Torque sensor in a UR10 CB3.0 SW3.4.5 robot. When the enable_external_ft_sensor is enabled, I can read the sensor data with the get_tcp_force() Urscript function, when the enable_external_ft_sensor is disabled I can read the internal robot force data with the same get_tcp_force() . So all the RTDE stuff is working.

But when I use a force_mode() function I can’t see any difference between enabled/disabled external ft sensor. The robot always acts as if it was using the internal force measure, not the external sensor.

Has anyone test the use of a enabled external ft sensor in a force_mode() function? or is not possible?

Thanks

Hi,

I have implemented a daemon that uses RTDE to feed the “external_force_torque” parameters in the UR. In order to get it work, I just had to add this function “enable_external_ft_sensor(…)” to my URcap’s daemon installation node contribution and everything worked as expected.

As I was unable to find a “external F/T sensor implementation guidelines” in your download center. The majority of the info came from this thread so for completion of this thread I would like to discuss two more topics regarding “external F/T sensor implementation”. These topics are:

  • Update rate of F/T measurement through the RTDE protocol. I noticed that for low update rates the force controller of the e-series robot is becoming unstable and the TCP oscillates if the contact material is hard. So I would like to know what is the preferred update rate and cut-off frequency for the CB3 and E-series robot controller. Maybe the default watchdog that is being created by the function “enable_external_ft_sensor()” should not be 10Hz but the minimum to have a stable force mode.

  • Taring (zero-ing) of the sensor, I noticed that the default F/T sensor of the e-series is being tared automatically in some occasions. For example every time the I am testing the the force mode (test + freedrive button) is being tared. My question is if there is a way for a urcap to contribute URscript code in the event of pressing the freedrive button or if its possible to allow the URcontroller to tare the external F/T sensor for example the URcap to provides its own implementation of “zero_ftsensor()” function. What is in your opinion the good practise regarding the strategy of taring the sensor.

1 Like

Hi,
I send you dm if you would be able to reply that would be awesome :slight_smile:

I have finished a admittance force control program in PC, acquire F/T sensor data in 500HZ though 30003 port, and send servoj script though 30003 port.
Considering the real-time, I want to write this algorithm in teachpendant, but I don’t know how to acquire F/T sensor data in teachpendant. Please give me some simple examples , Thanks!

Hi, when I did enable_external_ft_sensor, it showed “C207A0 Fieldbus Input not connected”.
How to resolve this issue?
I already disabled all the Fieldbus in installation

Before that external FT sensor needs to start writing to RTDE input variable external_force_torque