Skip to content

Commit 83b69d3

Browse files
authored
Add files via upload
1 parent f7284b5 commit 83b69d3

File tree

1 file changed

+118
-0
lines changed

1 file changed

+118
-0
lines changed

ur10_control.py

Lines changed: 118 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,118 @@
1+
from urx import Robot
2+
import time
3+
4+
# Created by Coder Shiyar | https://codershiyar.com
5+
# Netherlands Kurdistan | 25,
6+
def connect_to_robot(robot_ip):
7+
"""
8+
Connects to the UR10 robot.
9+
10+
Parameters:
11+
robot_ip (str): The IP address of the robot.
12+
13+
Returns:
14+
Robot: The connected robot object.
15+
"""
16+
robot = Robot(robot_ip)
17+
return robot
18+
19+
def move_to_position(robot, target_pose, acceleration=0.5, velocity=0.5):
20+
"""
21+
Moves the robot to a specified position.
22+
23+
Parameters:
24+
robot (Robot): The connected robot object.
25+
target_pose (tuple): Target position and orientation (X, Y, Z, RX, RY, RZ).
26+
acceleration (float): Acceleration value for the movement (default: 0.5).
27+
velocity (float): Velocity value for the movement (default: 0.5).
28+
"""
29+
robot.movej(target_pose, acc=acceleration, vel=velocity)
30+
31+
def stop_robot(robot):
32+
"""
33+
Stops the movement of the robot.
34+
35+
Parameters:
36+
robot (Robot): The connected robot object.
37+
"""
38+
robot.stopl()
39+
40+
def disconnect_robot(robot):
41+
"""
42+
Disconnects from the robot.
43+
44+
Parameters:
45+
robot (Robot): The connected robot object.
46+
"""
47+
robot.close()
48+
49+
def rotate_robot(robot, rx_offset, ry_offset, acceleration=0.5, velocity=0.5):
50+
"""
51+
Rotates the robot around its fixed position by adjusting RX and RY angles.
52+
53+
Parameters:
54+
robot (Robot): The connected robot object.
55+
rx_offset (float): Offset value for RX angle (in radians).
56+
ry_offset (float): Offset value for RY angle (in radians).
57+
acceleration (float): Acceleration value for the movement (default: 0.5).
58+
velocity (float): Velocity value for the movement (default: 0.5).
59+
"""
60+
current_pose = robot.getl()
61+
new_orientation = (current_pose[3], current_pose[4] + rx_offset, current_pose[5] + ry_offset)
62+
robot.movel(current_pose[0:3] + new_orientation, acc=acceleration, vel=velocity)
63+
64+
if __name__ == "__main__":
65+
# Example usage:
66+
robot_ip_address = "192.168.1.100" # Replace with the actual IP address of your UR10 robot
67+
68+
# Connect to the robot
69+
ur10_robot = connect_to_robot(robot_ip_address)
70+
71+
# Example target position (X, Y, Z, RX, RY, RZ)
72+
target_position = (0.5, 0.5, 0.5, 0, 0, 0)
73+
74+
# Move to the target position
75+
move_to_position(ur10_robot, target_position)
76+
77+
# Pause for safety
78+
time.sleep(2)
79+
80+
# Stop the robot
81+
stop_robot(ur10_robot)
82+
83+
# Rotate the robot around its fixed position by adjusting RX and RY angles
84+
rotate_robot(ur10_robot, rx_offset=0.1, ry_offset=0.1)
85+
86+
# Pause for safety
87+
time.sleep(2)
88+
89+
# Stop the robot
90+
stop_robot(ur10_robot)
91+
92+
# Disconnect from the robot
93+
disconnect_robot(ur10_robot)
94+
95+
96+
97+
98+
# Simple example to move robot to the target position.
99+
100+
# from urx import Robot
101+
102+
# def main(robot_ip):
103+
# # Connect to the robot
104+
# robot = Robot(robot_ip)
105+
106+
# # Set a target pose (position and orientation)
107+
# target_pose = (0.5, 0.5, 0.5, 0, 0, 0) # Example target pose (X, Y, Z, RX, RY, RZ)
108+
109+
# # Move to the target pose
110+
# robot.movej(target_pose, acc=0.5, vel=0.5) # MoveJ command (joint movement)
111+
112+
# # Close the connection
113+
# robot.close()
114+
115+
# if __name__ == "__main__":
116+
# # Specify the IP address of your UR10 robot
117+
# robot_ip_address = "192.168.1.100" # Example IP address, replace with your robot's IP
118+
# main(robot_ip_address)

0 commit comments

Comments
 (0)
pFad - Phonifier reborn

Pfad - The Proxy pFad of © 2024 Garber Painting. All rights reserved.

Note: This service is not intended for secure transactions such as banking, social media, email, or purchasing. Use at your own risk. We assume no liability whatsoever for broken pages.


Alternative Proxies:

Alternative Proxy

pFad Proxy

pFad v3 Proxy

pFad v4 Proxy