heregit add .git add .

This commit is contained in:
Kseninia Mikhaylova 2024-10-08 11:46:16 +03:00
parent 461364821d
commit 73e784bdb6
2 changed files with 27 additions and 14 deletions

View File

@ -46,6 +46,9 @@ class SocketRobotArm:
self.tkinter_start_cycle = tkinter.Button( self.tkinter_start_cycle = tkinter.Button(
self.tkinter_root, text="Start cycle", command=self.cycle_start self.tkinter_root, text="Start cycle", command=self.cycle_start
) )
self.tkinter_imitate = tkinter.Button(
self.tkinter_root, text="Imitate", command=self.imitate
)
self.physics_client = None self.physics_client = None
self.body_id = None self.body_id = None
@ -84,7 +87,8 @@ class SocketRobotArm:
# sys.exit() # sys.exit()
def cycle_base(self): def cycle_base(self):
self.tkinter_root.geometry("500x300") self.tkinter_root.geometry("700x400")
self.tkinter_imitate.pack(pady=20)
self.tkinter_start_cycle.pack(pady=20) self.tkinter_start_cycle.pack(pady=20)
self.tkinter_exit.pack(pady=20) self.tkinter_exit.pack(pady=20)
@ -138,6 +142,15 @@ class SocketRobotArm:
) )
time.sleep(0.5) time.sleep(0.5)
def imitate(self):
points = self.steps_from_file()
for p in points:
if p["action"] == "10":
angles = self.convert_to_joint(
[float(p) for p in [p["m0"], p["m1"], p["m2"]]]
)
self.set_joint(angles)
def convert_to_joint(self, coordinates): def convert_to_joint(self, coordinates):
num_joints = p.getNumJoints(self.body_id) num_joints = p.getNumJoints(self.body_id)
joint_info = [p.getJointInfo(self.body_id, i) for i in range(num_joints)] joint_info = [p.getJointInfo(self.body_id, i) for i in range(num_joints)]
@ -164,7 +177,7 @@ class SocketRobotArm:
) )
self.tkinter_info_label.pack() self.tkinter_info_label.pack()
self.tkinter_root.update() self.tkinter_root.update()
time.sleep(0.5) time.sleep(0.01)
def set_text(self, text): def set_text(self, text):
label = tkinter.Label(self.tkinter_root, text=text) label = tkinter.Label(self.tkinter_root, text=text)

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.00443333156" ixy="0.0" ixz="0.0" iyy="0.00443333156" iyz="0.0" izz="0.0072"/> <inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005"/>
</inertial> </inertial>
<visual> <visual>
<geometry> <geometry>
<box size="0.5 0.5 0.1" /> <box size="0.5 0.5 0.4" />
</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.00443333156" ixy="0.0" ixz="0.0" iyy="0.00443333156" iyz="0.0" izz="0.0072"/> <inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005"/>
</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.00443333156" ixy="0.0" ixz="0.0" iyy="0.00443333156" iyz="0.0" izz="0.0072"/> <inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005"/>
</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.00443333156" ixy="0.0" ixz="0.0" iyy="0.00443333156" iyz="0.0" izz="0.0072"/> <inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005"/>
</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.00443333156" ixy="0.0" ixz="0.0" iyy="0.00443333156" iyz="0.0" izz="0.0072"/> <inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005"/>
</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.00443333156" ixy="0.0" ixz="0.0" iyy="0.00443333156" iyz="0.0" izz="0.0072"/> <inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005"/>
</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.15" rpy="0 0 0" /> <origin xyz="0 0 0.494600" 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.3" rpy="0 0 0" /> <origin xyz="0 0 0.729921" 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.3" rpy="0 0 0" /> <origin xyz="0 0 0.098277" 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 0.3" rpy="0 0 0" /> <origin xyz="0 0 1.109039" 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.3" rpy="0 0 0" /> <origin xyz="0 0 0.0170450" 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>