Skip to content

Commit c5b06bb

Browse files
authored
Merge pull request #52 from elephantrobotics/280-gcode
add 280 M5 gcode scripts
2 parents 7c2971d + c41f8a8 commit c5b06bb

File tree

4 files changed

+138
-0
lines changed

4 files changed

+138
-0
lines changed
Lines changed: 94 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,94 @@
1+
#!/usr/bin/python
2+
# -*- coding:utf-8 -*-
3+
# This code is suitable for using the mycobot 280 M5 device to draw simple patterns
4+
# such as triangles, squares, and five-pointed stars.
5+
# It controls the movement of the robotic arm by parsing instructions in a gcode file to implement drawing operations.
6+
7+
# Running this code requires installing the 'pymycobot'
8+
# driver library and python driver environment.
9+
# If you don't installed, please refer to here :
10+
# https://docs.elephantrobotics.com/docs/gitbook-en/7-ApplicationBasePython/
11+
12+
# The gcode trajectory file used in this code is generated by Elephant luban, please check for details:
13+
# https://docs.elephantrobotics.com/docs/ultraArm-en/3-HowToUseultraArm/2-SoftwareControl/2-Luban/2-Luban.html
14+
15+
# import library
16+
import time
17+
from pymycobot.mycobot import MyCobot # import mycobot library,if don't have, first 'pip install pymycobot'
18+
19+
# use PC and M5 control
20+
mc = MyCobot('COM14', 115200) # WINDOWS use ,need check port number when you PC
21+
# mc = MyCobot('/dev/ttyUSB0',115200) # VM linux use
22+
time.sleep(0.5)
23+
24+
# Set interpolation mode
25+
mc.set_fresh_mode(0)
26+
time.sleep(0.5)
27+
# Send the initial point angle of the robot arm, the speed is 50,
28+
# it can be customized and modified, as long as the end is facing down
29+
mc.send_angles([0, -40, -130, 80, 0, 50], 50)
30+
# Wait 3 seconds for the robot arm to move to the specified angle
31+
time.sleep(3)
32+
# Get the current coordinates of the robot arm
33+
get_coords = mc.get_coords()
34+
time.sleep(1.5)
35+
# Save the parsed coordinates
36+
data_coords = []
37+
# Set the drawing speed to 100, and the speed range is 0~100
38+
draw_speed = 100
39+
40+
41+
def process_gcode(file_path):
42+
"""
43+
Parse the contents of the gcode file, extract the XYZ coordinate values, and save the coordinate data into a list
44+
:param file_path: Gcode file path
45+
:return: A coordinate list
46+
"""
47+
# The last valid coordinate, using the rx, ry, rz values
48+
# in the current coordinates of the robot arm as the starting attitude
49+
last_coords = [0.0, 0.0, 0.0, get_coords[3], get_coords[4], get_coords[5]]
50+
with open(file_path, 'r') as file:
51+
# Line-by-line processing instructions
52+
for line in file:
53+
command = line.strip() # Remove newline characters and other whitespace characters at the end of the line
54+
if command.startswith("G0") or command.startswith("G1"): # Move command
55+
coords = last_coords[:] # Copy the previous valid coordinates
56+
command_parts = command.split()
57+
for part in command_parts[1:]:
58+
if part.startswith("X") or part.startswith("x"):
59+
coords[0] = float(part[1:]) # Extract and transform X coordinate data
60+
elif part.startswith("Y") or part.startswith("y"):
61+
coords[1] = float(part[1:]) # Extract and transform Y coordinate data
62+
elif part.startswith("Z") or part.startswith("z"):
63+
coords[2] = float(part[1:]) # Extract and transform Z coordinate data
64+
if coords[0] == 0.0 and coords[1] == 0.0: # If XY data is missing, use the last valid XY coordinates
65+
coords[0] = last_coords[0]
66+
coords[1] = last_coords[1]
67+
if coords[2] == 0.0: # If Z data is missing, use the last valid Z coordinate
68+
coords[2] = last_coords[2]
69+
last_coords = coords
70+
data_coords.append(coords) # Add coordinates to list and save
71+
return data_coords
72+
73+
74+
type = int(input('Please input 1-4(1-square 2-triangle 3-five point star 4-quit):'))
75+
if type == 1:
76+
# Pass in the gcode file path and obtain the coordinate data
77+
# File path can be customized
78+
coords_data = process_gcode('square.nc')
79+
# Send coordinates to the robot arm one by one
80+
for i in coords_data:
81+
mc.send_coords(i, draw_speed, 1) # Send coordinates to the robot arm
82+
time.sleep(3.5) # Wait 3.5 seconds for the robot arm movement to complete
83+
elif type == 2:
84+
coords_data = process_gcode('triangle.nc')
85+
for i in coords_data:
86+
mc.send_coords(i, draw_speed, 1)
87+
time.sleep(3.5)
88+
elif type == 3:
89+
coords_data = process_gcode('five_point_star.nc')
90+
for i in coords_data:
91+
mc.send_coords(i, draw_speed, 1)
92+
time.sleep(3.5)
93+
elif type == 4:
94+
exit(0)
Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
G90
2+
G4 S1
3+
G01 x170 y0 z60 F15
4+
G4 S1
5+
G0 Y-32.03 X195.54
6+
G0 Z49.00
7+
G1 Y-9.66 X195.54
8+
G1 Y-2.75 X215.61
9+
G1 Y4.16 X195.54
10+
G1 Y26.52 X195.54
11+
G1 Y8.43 X183.14
12+
G1 Y15.34 X163.08
13+
G1 Y-2.75 X175.48
14+
G1 Y-20.84 X163.08
15+
G1 Y-13.93 X183.14
16+
G1 Y-32.03 X195.54
17+
G0 Z70.00
18+
G0 Y-2.75 X189.34
19+
M21 P0

demo/myCobot_280_demo/square.nc

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
G90
2+
G4 S1
3+
G01 X170 Y0 Z60 F15
4+
G4 S1
5+
G0 Y-18.33 X204.06
6+
G0 Z50.00
7+
G1 Y16.67 X204.06
8+
G1 Y16.67 X169.06
9+
G1 Y-18.33 X169.06
10+
G1 Y-18.33 X204.06
11+
G0 Z75.00
12+
G0 Y-0.83 X186.56
13+
M21 P0

demo/myCobot_280_demo/triangle.nc

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
G90
2+
G4 S1
3+
G01 X170 Y0 Z60 F15
4+
G4 S1
5+
G0 Y18.54 X168.58
6+
G0 Z49.00
7+
G1 Y-18.07 X168.58
8+
G1 Y18.54 X204.81
9+
G1 Y18.54 X168.58
10+
G0 Z70.00
11+
G0 Y0.24 X186.69
12+
M21 P0

0 commit comments

Comments
 (0)