Rotate TCP in Rx direction only

I have a camera attached to the flange and I want to rotate it in place on the Rz direction only.
The TCP setting is as follows.

The program below rotates it up to 179deg at 1deg per movej to one direction.
Go back to original position and rotate to 179deg at 1deg per movej to the opposite direction.

    $ 2 "ロボットプログラム"
    $ 3 "MoveJ"
    $ 4 "home" "breakAfter"
    movej(home, a=1.3962634015954636, v=1.0471975511965976)
    $ 5 "loop_counter:=1"
    global loop_counter=1
    $ 6 "ループ loop_counter≤179"
    while (loop_counter <= 179):
      $ 7 "pose:=pose_trans(get_actual_tcp_pose(), p[0,0,0,0,0,d2r(1)])"
      global pose= pose_trans ( get_actual_tcp_pose (), p[0,0,0,0,0, d2r (1)])
      $ 8 "movej(pose, a=1.2, v=0.5)"
      movej(pose, a=1.2, v=0.5)
      $ 9 "loop_counter:=loop_counter+1"
      global loop_counter=loop_counter+1
    end
    $ 10 "MoveJ"
    $ 11 "home" "breakAfter"
    movej(home, a=1.3962634015954636, v=1.0471975511965976)
    $ 12 "loop_counter:=-1"
    global loop_counter=-1
    $ 13 "ループ loop_counter≥-179"
    while (loop_counter >= -179):
      $ 14 "pose:=pose_trans(get_actual_tcp_pose(), p[0,0,0,0,0,d2r(-1)])"
      global pose= pose_trans ( get_actual_tcp_pose (), p[0,0,0,0,0, d2r (-1)])
      $ 15 "movej(pose, a=1.2, v=0.5)"
      movej(pose, a=1.2, v=0.5)
      $ 16 "loop_counter:=loop_counter-1"
      global loop_counter=loop_counter-1
    end

It rotates as expected until it comes to a certain point where it switches the position of the robot arm.
In the gif below, the robot arm starts above the flange and pivots to below the flange.
If I restart the program with the robot arm starting below the flange, it pivots to above the flange instead.
rotate_in_place

・I have tried teaching fixed waypoints with 45degree intervals and movej between them and this pivot movement does not occur.
・I have tried changing it to movel and it still occurs.

Does someone know how to rotate in the TCP Rz direction only while preventing the pivot movement in the gif above?

similar topic

Have you tried setting joint limits in Installation → Safety?

@sean7
thanks for your suggestion.
i haven’t tried setting that yet. it’s in its default setting.
what setting do you suggest i try? sorry i’m not that familir with the safety settings
should i set the joint limits to be more restricted?

@sean7
i tried reducing the joint limits as i thought this would prevent the joint from pivoting.
it resulted in a protective stop.

Hi @francis

If you want to program just a rotation, you have to keep in mind that the last 3 elements in the pose array are of a rotation vector type. We cannot, or at least very difficultly, interpret this. When we want a rotation, we think in the “RPY” type.

This means that, if you want a rotation of 179deg around your y-axis of your chosen TCP (your Y-axis points outward of the tool flange), then you can accomplish this by doing these steps:

  1. A rotation of 179deg, transform it to radians:
    rot_rad_rpy = [0, d2r(179), 0]

  2. This “rot_rad_rpy” as we interpret is, is of the type “RPY”. So we need to transform it “Rotation vector”:
    rot_rad_rotvec = rpy2rotvec(rot_rad_rpy)

  3. At this point, we have a rotation, of the type “rotation vector”. Now all that is left, is to tell the robot to use this rotation around your TCP, which you already did correctly in your code:
    new_pose = pose_trans ( get_actual_tcp_pose(), p[0, 0, 0, rot_rad_rotvec[0], rot_rad_rotvec [1], rot_rad_rotvec[2] ] )

When you try this, you will see that the robot will turn correctly.
Keep in mind that this is a rotation around your TCP Y-axis. If you kept the TCP as default (so Z pointing outward), then in the first step you would need to do: rot_rad_rpy = [0, 0, d2r(179)]

If you have any questions, feel free to contact me.

Kind regards
Dieter

1 Like

@d.verhofstadt
thank you for your suggestion.

  1. i wanted to rotate it around the z-axis. the blue arrow pointing downwards.
  2. i changed the rotation in your step 1 to [0, 0, d2r(179)] and changed it to 1 degree intervals [0, 0, d2r(1)] then looped it 179 times in one direction
    $ 2 "ロボットプログラム"
    $ 3 "MoveJ"
    $ 4 "home" "breakAfter"
    movej(home, a=1.3962634015954636, v=1.0471975511965976)
    $ 5 "loop_counter:=1"
    global loop_counter=1
    $ 6 "ループ loop_counter≤179"
    while (loop_counter <= 179):
      $ 7 "rot_rad_rpy:=[0,0,d2r(1)]"
      global rot_rad_rpy=[0,0,d2r(1)]
      $ 8 "rot_rad_rotvec:=rpy2rotvec(rot_rad_rpy)"
      global rot_rad_rotvec=rpy2rotvec(rot_rad_rpy)
      $ 9 "pose:=pose_trans(get_actual_tcp_pose(), p[0,0,0,rot_rad_rotvec[0],rot_rad_rotvec[1],rot_rad_rotvec[2]])"
      global pose= pose_trans ( get_actual_tcp_pose (), p[0,0,0,rot_rad_rotvec[0],rot_rad_rotvec[1],rot_rad_rotvec[2]])
      $ 10 "movej(pose, a=1.2, v=0.5)"
      movej(pose, a=1.2, v=0.5)
      $ 11 "loop_counter:=loop_counter+1"
      global loop_counter=loop_counter+1
    end
    $ 12 "MoveJ"
    $ 13 "home" "breakAfter"
    movej(home, a=1.3962634015954636, v=1.0471975511965976)
    $ 14 "loop_counter:=1"
    global loop_counter=1
    $ 15 "ループ loop_counter≤179"
    while (loop_counter <= 179):
      $ 16 "rot_rad_rpy:=[0,0,d2r(-1)]"
      global rot_rad_rpy=[0,0,d2r(-1)]
      $ 17 "rot_rad_rotvec:=rpy2rotvec(rot_rad_rpy)"
      global rot_rad_rotvec=rpy2rotvec(rot_rad_rpy)
      $ 18 "pose:=pose_trans(get_actual_tcp_pose(), p[0,0,0,rot_rad_rotvec[0],rot_rad_rotvec[1],rot_rad_rotvec[2]])"
      global pose= pose_trans ( get_actual_tcp_pose (), p[0,0,0,rot_rad_rotvec[0],rot_rad_rotvec[1],rot_rad_rotvec[2]])
      $ 19 "movej(pose, a=1.2, v=0.5)"
      movej(pose, a=1.2, v=0.5)
      $ 20 "loop_counter:=loop_counter+1"
      global loop_counter=loop_counter+1
    end
    $ 21 "MoveJ"
    $ 22 "home" "breakAfter"
    movej(home, a=1.3962634015954636, v=1.0471975511965976)
  end

the joint still pivots positions as shown in the gif i shared above.
but if i drop the loop and set 179 degrees, it correctly rotates without the joint pivot.

Hi @francis

I will have to check with our robots if we also have this behaviour.
And is there a reason for the loop?
Why not immediately asking to move to a position with a 179deg rotation?
This would also result in a more efficient and fluent motion of the robot arm.

Kind regards
Dieter

@d.verhofstadt
no rush. thanks for the help.
we want to pause the movement and take pictures on every waypoint that’s why we don’t directly go to 179degrees

Hi @francis,

One thing to notice is that using get_actual_tcp_pose the error(difference between actual pose and target) will sum up for each iteration. I you are using get_target_tcp_pose() you will the error will not accumulate for each iteration.

Best regards
Ebbe