Skip to content

Commit

Permalink
Update ur10_control.py
Browse files Browse the repository at this point in the history
  • Loading branch information
codershiyar committed Mar 25, 2024
1 parent 9018557 commit 8e53ad0
Showing 1 changed file with 16 additions and 14 deletions.
30 changes: 16 additions & 14 deletions ur10_control.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
from urx import Robot
import time
import sys

# Created by Coder Shiyar | https://codershiyar.com
# Netherlands Kurdistan | 25,
Expand Down Expand Up @@ -130,20 +131,21 @@ def rotate_robot(robot, rx_offset, ry_offset, acceleration=0.5, velocity=0.5):



# extra:
# # Get the current pose of the robot
# current_pose = robot.get_pose()
# Extra: Making Adjustments to Rotation from Current Orientation/Position
# If you find it necessary to alter rotation while maintaining your current orientation or position, you can utilize specific adjustments for each axis.
# For instance, if you need to make changes to the rotation about the Z-axis (rz) or the Y-axis (ry), follow similar principles for adjustments on other axes as needed. This method ensures precise modifications while preserving the desired orientation or position.

# # Get the current pose of the robot
# current_positions = robot.getj()
# print("Current joint positions:", current_positions)

# # Extract rotation vector and position from the pose
# pattern = r"[-+]?\d*\.\d+|\d+"
# numbers = [float(num) for num in re.findall(pattern, str(current_pose))]
# rotation_vector = tuple(numbers[:3])
# position = tuple(numbers[3:6])
# print("Rotation vector:", rotation_vector)
# print("Position:", position)

# # Convert mm to meters for position
# px, py, pz = [num * 1000 for num in position]
# px, py, pz = current_positions[:3]
# # Assign rotational components
# rx, ry, rz =rotation_vector
# print((px, py, pz, rx, ry, rz))
# rx, ry, rz = current_positions[3:6]

# # Create a new pose by adding the offset to the current pose
# new_position = (px, py, pz, rx, ry - 0.2, rz - 0.3)

# # Move the robot to the new orientation while keeping the position fixed
# robot.movej(new_position, acc=0.2, vel=0.1)

0 comments on commit 8e53ad0

Please sign in to comment.