Move (JOG) along Base or Tool axis

What is the best way to move/rotate the robot along one single axis in Base or Tool space with script commands? For example: The robot should move in X+ Tool Space as long as i push a button, just like when using the teach pendant.

I tried to use movej:
I read the actual position of the robot and just add for example 0.5mm to the X value and then call the movej command with the new calculated position. I do this in a loop as long as the button is pressed. It works but i think there must be another way…

Thx in advance

The speedl command is what you’re looking for - you can find it in the URScript manual.

speedl([0,0,0.2,0,0,0],0.5,1)

By default this will drive the robot in the base frame Z direction at the desired speed for 1 second. Beware that when it times out the robot will stop with a nasty jolt, so make sure you follow it with a stopl() command for a nicer deceleration.

For jogging in the tool frame, I calculated a Z offset in the tool frame, then the direction towards that point in the base frame and used that for the speedl command (possibly not the smartest approach, but it works). These 3 lines could be nested together but i’ve separated them for clarity.

For the button push part, put the speedl command inside a loop checking the digital input, with “Check expression continuously” option checked in Polyscope.

Thx for your reply,
works great in base frame but not in tool frame. Of course your code works if i use your code in the panel environment, but my problem is that i am using the realtime client interface and i think i cannot use variable assignment (i.e. pos=get_actual_tcp_pose()) and then use the variable “pos” later.
I can use speedl command over client interface but for calculating the correct values from tool frame into base frame the code seems not to work. Am i right that there is a problem when using variables over client interface?

I just tried to send your code line by line over the client interface an that seems not to work. Any other ideas? Or maybe any ideas how to calculate the correct base vectors(calculated from tool frame) to use them directly with the speedl command?

You can actually send a whole program/function to the realtime client interface, it will execute as soon as the end of the function is received.

So if you build up that program I sent in Polyscope and then save it, it will generate a .script file for execution by the controller. When you press play on the touch screen, polyscope essentially just sends this file to a client interface for execution.

You can do the same thing from any other device. You can test it with this command in the linux terminal in URSIM (where speed_tool.script is your program script file):

cat speed_tool.script | nc 127.0.0.1 30003

This program will stop whenever another command is received by the client interface.

1 Like

Ahh okay…
works perfect now after sending the whole program as a function!
Thx for your help!

Now got another problem :slight_smile: :
For x,y,z it works fine but how about turning around tool frame (Rx,Ry;Rz)… i tried to use the same calculation as for x,y,z but that results in the same rotation as in base system.

Hi, I wasn’t able to transform the rotation direction into the base coordinate frame to work correctly with speedl last week. Not sure what I was doing wrong, but hopefully someone else can jump in and advise?

1 Like

Hello all,

I tried to develop the function which expresses the tool_speed with respect to a frame in the robot base. The goal is to use the speedl function whatever the frame (working_frame, tool_frame…)

The job for the cartesian speed projection in the robot base was done by @ajp .

I got the same logic for the rotation. The rotation is expressed in “rotation vector” formalism for ur robots. A bit of vocabulary about wikipedia : Axis-Angle & rotation vector:

  • axis-angle = [(ex, ey, ez), angle] , e is the vector which defines the rotation (expressed in a frame)
  • axis_with_angle_magnitude = rotation_vector = [ex * θ, ey * θ, ez * θ]

Like the cartesian speed vector the rotation is a vector. I used the same method as the cartesian speed vector.
Diagram :

Below the script function :

  def get_speed_wrt_base(tool_speed, frame_wrt_base):
  	# convert tool_speed expressed in the frame_wrt_base in the robot base frame
  	# examples :
  	# speed_wrt_base([0.020, 0.020,0,0,0,0], plane_1)
  	# speedl(get_speed_wrt_base([0,0,0.02,0,0,1.57], get_actual_tcp_pose()),a=1,t=0.5,aRot=4))
  
  	#### input arguments
  	# tool_speed : [Tx, Ty, Tz, Rx, Ry, Rz] spatial vector list - Txyz [m/s]), Rxyz [rad/s]
  	# frame_wrt_base : pose
  
  	#### output arguments
  	# speed_wrt_base : [Tx, Ty, Tz, Rx, Ry, Rz] spatial vector list - Txyz [m/s]), Rxyz [rad/s]
  
  	# Translationnal speed vector calculus
  	T_wrt_frame=p[tool_speed[0],tool_speed[1],tool_speed[2],0,0,0]
  	T_wrt_base_raw= pose_trans (frame_wrt_base, T_wrt_frame)
  	T_wrt_base=pose_sub(T_wrt_base_raw,frame_wrt_base)
  
  	# Rotationnal speed vector calculus
  	R_wrt_frame=p[tool_speed[3],tool_speed[4],tool_speed[5],0,0,0]
  	R_wrt_frame_abs=norm([R_wrt_frame[0],R_wrt_frame[1],R_wrt_frame[2]])
  	if R_wrt_frame_abs != 0:  # test if zero vector
  		R_wrt_base_raw=pose_trans(frame_wrt_base, R_wrt_frame)
  		R_wrt_base=pose_sub(R_wrt_base_raw, frame_wrt_base)
  	else:
  		R_wrt_base=p[0,0,0,0,0,0]
  	end
  
  	# Concatenate T and R
  	speed_wrt_base_list=[T_wrt_base[0],T_wrt_base[1],T_wrt_base[2],R_wrt_base[0],R_wrt_base[1],R_wrt_base[2]]
  	
    return speed_wrt_base_list
      
  end

The speedl function can be used wit this new calculated spatial vector. Example for a screwing move along the Z TCP (whatever the TCP postion and orientation) :
speedl(get_speed_wrt_base([0,0,0.02,0,0,1.57], get_actual_tcp_pose()),a=1,t=0.5,aRot=4))
The function works with any working_frame.

Do not hesitate to give me feedback…

2 Likes

Great! Thanks for sharing this.

Really great. This was something I was looking for. This enables to implement jog functionality like in the UR teach panel. Thank you very much.