This commit is contained in:
aarizona 2024-10-08 15:37:44 +03:00
parent 73e784bdb6
commit 00f29fac2b
5 changed files with 65 additions and 37 deletions

View File

@ -8,23 +8,25 @@ import tkinter as tk
from func import * from func import *
window = tk.Tk() window = tk.Tk()
window.geometry('520x300') window.geometry("520x300")
label = tk.Label(window, text="Hello, world!") label = tk.Label(window, text="Hello, world!")
label.pack() label.pack()
all_files = glob.glob("data/data.txt") all_files = glob.glob("data/*.nc")
file = all_files[0] file = all_files[0]
data = [] data = [
with open(file, "r") as fp: ("line", 0, 0, 277.8, 0, 5, 0),
lines = fp.readlines() ]
for l in lines: # with open(file, "r") as fp:
r = l.strip().split(",") # lines = fp.readlines()
r[1] = float(r[1]) # for l in lines:
r[2] = float(r[2]) # r = l.strip().split(",")
r[3] = float(r[3]) # r[1] = float(r[1])
# r[2] = float(r[2])
# r[3] = float(r[3])
data.append(r) # data.append(r)
client = ModbusTcpClient( client = ModbusTcpClient(
host=MODBUS_SERVER_HOST, host=MODBUS_SERVER_HOST,

View File

@ -19,12 +19,12 @@ class SocketRobotArm:
line_smooth = 9 line_smooth = 9
line_tool = 1 line_tool = 1
global_speed = 100 global_speed = 10
physical_speed = 50 physical_speed = 10
# laser_id = 15 # laser_id = 15
laser_id = 14 laser_id = 14
# filename = 'half-sphere-no-angle' # filename = 'half-sphere-no-angle'
filename = "half-sphere" filename = "test"
urdf_filename = "sample" urdf_filename = "sample"
pass_size = 4 pass_size = 4
@ -54,6 +54,7 @@ class SocketRobotArm:
threading.Thread(target=self.run_pybullet, daemon=True).start() threading.Thread(target=self.run_pybullet, daemon=True).start()
print((self.port, self.host))
self.socket.connect((self.host, self.port)) self.socket.connect((self.host, self.port))
self.cycle_base() self.cycle_base()
@ -125,7 +126,8 @@ class SocketRobotArm:
self.tkinter_info_label.pack() self.tkinter_info_label.pack()
self.tkinter_root.update() self.tkinter_root.update()
step = 2 step = 4
empty = 1
for i in range(0, len(self.add_rcc_list), step): for i in range(0, len(self.add_rcc_list), step):
if not self.tkinter_info_label: if not self.tkinter_info_label:
return return
@ -136,11 +138,14 @@ class SocketRobotArm:
# self.update_text(m, text=f"Отправка данных {i}...{i+step-1}") # self.update_text(m, text=f"Отправка данных {i}...{i+step-1}")
self.tkinter_info_label.config(text=f"Отправка данных {i}...{i+step-1}") self.tkinter_info_label.config(text=f"Отправка данных {i}...{i+step-1}")
self.tkinter_root.update() self.tkinter_root.update()
# print(empty)
self.send_data( self.send_data(
make_addrcc_data(self.add_rcc_list[i : i + step], int(not i)) make_addrcc_data(
self.add_rcc_list[i : i + step], empty
) )
time.sleep(0.5) )
empty = 0
time.sleep(0.05)
def imitate(self): def imitate(self):
points = self.steps_from_file() points = self.steps_from_file()
@ -236,7 +241,7 @@ class SocketRobotArm:
def make_world_step(self, type, point): def make_world_step(self, type, point):
step = { step = {
"oneshot": "0", "oneshot": "1",
"delay": "0.0", "delay": "0.0",
"speed": str(self.line_speed), "speed": str(self.line_speed),
"smooth": str(self.line_smooth), "smooth": str(self.line_smooth),

19
data/test.nc.result Normal file
View File

@ -0,0 +1,19 @@
X165 Y0
X330 Y0
X500 Y165
X500 Y330
X330 Y500
X165 Y500
X0 Y330
X0 Y165
Z-50 V40 X0 Y0
Z-50 V40 X165 Y0
Z-50 V40 X330 Y0
Z-50 V-40 X500 Y165
Z-50 V-40 X500 Y330
Z-50 V-40 X330 Y500
Z-50 V-40 X165 Y500
Z-50 V40 X0 Y330
Z-50 V40 X0 Y165
Z-50 V40 X0 Y0
X0 Y0

View File

@ -1,7 +1,9 @@
# Настройки клиента Modbus # Настройки клиента Modbus
MODBUS_SERVER_HOST = "192.168.70.55" # IP-адрес Modbus-сервера # MODBUS_SERVER_HOST = "192.168.70.55" # IP-адрес Modbus-сервера
MODBUS_SERVER_HOST = "192.168.70.65" # IP-адрес Modbus-сервера
MODBUS_SERVER_PORT = 502 MODBUS_SERVER_PORT = 502
MODBUS_SLAVE_ID = 11 # MODBUS_SLAVE_ID = 11
MODBUS_SLAVE_ID = 22
indent = 21100 indent = 21100
s = 800 s = 800

View File

@ -5,11 +5,11 @@
<link name="base_link"> <link name="base_link">
<inertial> <inertial>
<mass value="1.0" /> <mass value="1.0" />
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005"/> <inertia ixx="0.00443333156" ixy="0.0" ixz="0.0" iyy="0.00443333156" iyz="0.0" izz="0.0072"/>
</inertial> </inertial>
<visual> <visual>
<geometry> <geometry>
<box size="0.5 0.5 0.4" /> <box size="0.5 0.5 0.1" />
</geometry> </geometry>
<material name="grey"> <material name="grey">
<color rgba="0.5 0.5 0.5 1.0" /> <color rgba="0.5 0.5 0.5 1.0" />
@ -20,7 +20,7 @@
<link name="link1"> <link name="link1">
<inertial> <inertial>
<mass value="1.0" /> <mass value="1.0" />
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005"/> <inertia ixx="0.00443333156" ixy="0.0" ixz="0.0" iyy="0.00443333156" iyz="0.0" izz="0.0072"/>
</inertial> </inertial>
<visual> <visual>
<geometry> <geometry>
@ -35,7 +35,7 @@
<link name="link2"> <link name="link2">
<inertial> <inertial>
<mass value="1.0" /> <mass value="1.0" />
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005"/> <inertia ixx="0.00443333156" ixy="0.0" ixz="0.0" iyy="0.00443333156" iyz="0.0" izz="0.0072"/>
</inertial> </inertial>
<visual> <visual>
<geometry> <geometry>
@ -50,7 +50,7 @@
<link name="link3"> <link name="link3">
<inertial> <inertial>
<mass value="1.0" /> <mass value="1.0" />
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005"/> <inertia ixx="0.00443333156" ixy="0.0" ixz="0.0" iyy="0.00443333156" iyz="0.0" izz="0.0072"/>
</inertial> </inertial>
<visual> <visual>
<geometry> <geometry>
@ -65,7 +65,7 @@
<link name="link4"> <link name="link4">
<inertial> <inertial>
<mass value="1.0" /> <mass value="1.0" />
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005"/> <inertia ixx="0.00443333156" ixy="0.0" ixz="0.0" iyy="0.00443333156" iyz="0.0" izz="0.0072"/>
</inertial> </inertial>
<visual> <visual>
<geometry> <geometry>
@ -80,7 +80,7 @@
<link name="end_effector"> <link name="end_effector">
<inertial> <inertial>
<mass value="1.0" /> <mass value="1.0" />
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005"/> <inertia ixx="0.00443333156" ixy="0.0" ixz="0.0" iyy="0.00443333156" iyz="0.0" izz="0.0072"/>
</inertial> </inertial>
<visual> <visual>
<geometry> <geometry>
@ -96,7 +96,7 @@
<joint name="joint1" type="revolute"> <joint name="joint1" type="revolute">
<parent link="base_link" /> <parent link="base_link" />
<child link="link1" /> <child link="link1" />
<origin xyz="0 0 0.494600" rpy="0 0 0" /> <origin xyz="0 0 0.15" rpy="0 0 0" />
<axis xyz="0 0 1" /> <axis xyz="0 0 1" />
<limit lower="-3.14" upper="3.14" effort="10" velocity="1" /> <limit lower="-3.14" upper="3.14" effort="10" velocity="1" />
</joint> </joint>
@ -104,7 +104,7 @@
<joint name="joint2" type="revolute"> <joint name="joint2" type="revolute">
<parent link="link1" /> <parent link="link1" />
<child link="link2" /> <child link="link2" />
<origin xyz="0 0 0.729921" rpy="0 0 0" /> <origin xyz="0 0 0.3" rpy="0 0 0" />
<axis xyz="0 1 0" /> <axis xyz="0 1 0" />
<limit lower="-3.14" upper="3.14" effort="10" velocity="1" /> <limit lower="-3.14" upper="3.14" effort="10" velocity="1" />
</joint> </joint>
@ -112,7 +112,7 @@
<joint name="joint3" type="revolute"> <joint name="joint3" type="revolute">
<parent link="link2" /> <parent link="link2" />
<child link="link3" /> <child link="link3" />
<origin xyz="0 0 0.098277" rpy="0 0 0" /> <origin xyz="0 0 0.3" rpy="0 0 0" />
<axis xyz="0 1 0" /> <axis xyz="0 1 0" />
<limit lower="-3.14" upper="3.14" effort="10" velocity="1" /> <limit lower="-3.14" upper="3.14" effort="10" velocity="1" />
</joint> </joint>
@ -120,7 +120,7 @@
<joint name="joint4" type="revolute"> <joint name="joint4" type="revolute">
<parent link="link3" /> <parent link="link3" />
<child link="link4" /> <child link="link4" />
<origin xyz="0 0 1.109039" rpy="0 0 0" /> <origin xyz="0 0 0.3" rpy="0 0 0" />
<axis xyz="0 1 0" /> <axis xyz="0 1 0" />
<limit lower="-3.14" upper="3.14" effort="10" velocity="1" /> <limit lower="-3.14" upper="3.14" effort="10" velocity="1" />
</joint> </joint>
@ -128,7 +128,7 @@
<joint name="end_effector_joint" type="revolute"> <joint name="end_effector_joint" type="revolute">
<parent link="link4" /> <parent link="link4" />
<child link="end_effector" /> <child link="end_effector" />
<origin xyz="0 0 0.0170450" rpy="0 0 0" /> <origin xyz="0 0 0.3" rpy="0 0 0" />
<axis xyz="0 1 0" /> <axis xyz="0 1 0" />
<limit lower="-3.14" upper="3.14" effort="10" velocity="1" /> <limit lower="-3.14" upper="3.14" effort="10" velocity="1" />
</joint> </joint>