Skip to content

Commit

Permalink
Plotter showcase completed
Browse files Browse the repository at this point in the history
  • Loading branch information
ZodiusInfuser committed Nov 20, 2023
1 parent 8c6bb09 commit da6e027
Show file tree
Hide file tree
Showing 3 changed files with 127 additions and 66 deletions.
11 changes: 11 additions & 0 deletions examples/showcase/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ This folder contains a collection of *Showcase* examples, that bring together co

- [RC Rover](#rc-rover)
- [Spider Tank](#spider-tank)
- [CNC Plotter](#cnc-plotter)


## RC Rover
Expand All @@ -24,3 +25,13 @@ A showcase of Yukon as a hexapod robot, with 3 degrees of freedom per leg. It us
There is also a proto module wired up to a buzzer to alert the user to the battery voltage getting too low.

The program performs inverse kinematics for each leg, with the target points following a tripod walking gait.


## CNC Plotter
[plotter/main.py](plotter/main.py)

A showcase of Yukon as a 3-axis CNC pen plotter. It uses four Dual Motor modules, to control for stepper motors (the Y-Axis has two steppers). It also uses two Quad Servo Direct modules to provide convenient wiring for the machine's limit switches.

The program first homes the 3 axes of the machine to give an origin from which to plot from. Then after pressing 'A' it executes commands from a .gcode file loaded onto Yukon.

Only a subset of G-Code is supported, sufficient for performing linear moves of the machine, and raising and lowering its pen.
11 changes: 10 additions & 1 deletion examples/showcase/plotter/lib/parser.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,16 @@
from collections import namedtuple

"""
GCodeParser is a class for processing G-Code files into movement
and pen height commands for use with a CNC plotter.
Only a subset of G-Code commands are supported:
- G0/G1 - Linear Move
- G90 - Absolute Positioning
- G91 - Relative Positioning
- M3 - Spindle CW / Laser On (used to lower the pen to the page)
- M4 - Spindle CCW / Laser On (used to raise the pen just above the page)
- M5 - Spindle / Laser Off (used to raise the pen to its home position)
"""

Rect = namedtuple("Rect", ("x", "y", "width", "height"))
Expand Down
171 changes: 106 additions & 65 deletions examples/showcase/plotter/main.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,45 +12,69 @@
from parser import GCodeParser

"""
A showcase of Yukon as a pen plotter.
A showcase of Yukon as a 3-axis CNC pen plotter.
It uses four Dual Motor modules, to control for stepper motors (the Y-Axis has two steppers).
It also uses two Quad Servo Direct modules to provide convenient wiring for the machine's limit switches.
The program first homes the 3 axes of the machine to give an origin from which to plot from.
Then after pressing 'A' it executes commands from a .gcode file loaded onto Yukon.
Only a subset of G-Code is supported, sufficient for performing linear moves of the machine, and raising and lowering its pen.
Press "Boot/User" to exit the program.
Press "A" to start plotting once homed.
Press "B" to re-home the machine after plotting.
"""

# Constants
GCODE_FILE = "yukon_logo.gcode" # The file containing gcode instructions for drawing with the plotter
HOME_ON_PROGRAM_RUN = True # Should homing happen automatically when the program is first run, or require a button to be pressed?

CURRENT_SCALE = 0.5
IDLE_CURRENT_SCALE = 0.1

BELT_PITCH = 3
PULLEY_TOOTH_COUNT = 20
STEPS_PER_REV = 200
STEPS_PER_MM = STEPS_PER_REV / (BELT_PITCH * PULLEY_TOOTH_COUNT)
STEPS_PER_REV = 200 # The number of steps each stepper motor takes to perform a full revolution
BELT_PITCH = 3 # The spacing between each notch of the belts used on the X and Y axes
PULLEY_TOOTH_COUNT = 20 # The number of teeth on the X and Y axes direct-driven pulleys
BELT_STEPS_PER_MM = STEPS_PER_REV / (BELT_PITCH * PULLEY_TOOTH_COUNT)

PLOT_ORIGIN_X_MM = 200
PLOT_ORIGIN_Y_MM = 100
PLOT_SIZE_MM = 300
SPEED_MM_PER_SEC = 50
SCREW_MM_PER_REV = 8 # How many millimeters of travel a single revolution of the Z axis lead screw produces
SCREW_STEPS_PER_MM = STEPS_PER_REV / SCREW_MM_PER_REV

# Variables
yukon = Yukon() # Create a new Yukon object
x_module = DualMotorModule() # Create a DualMotorModule object
y1_module = DualMotorModule() # Create a DualMotorModule object
y2_module = DualMotorModule() # Create a DualMotorModule object
z_module = DualMotorModule() # Create a DualMotorModule object
l1_module = QuadServoDirectModule(init_servos=False)
l2_module = QuadServoDirectModule(init_servos=False)
PLOT_ORIGIN_X_MM = 200 # The X position to start the plotting from
PLOT_ORIGIN_Y_MM = 100 # The X position to start the plotting from
PLOT_SIZE_MM = 300 # The size to scale the largest dimension (width or height) of the gcode data to

# Store OkayStepper objects created later
x_stepper = None
y_stepper = None
z_stepper = None
BELT_SPEED_MM_PER_SEC = 50 # The speed to move the X and Y axes at when plotting
SCREW_SPEED_MM_PER_SEC = 20 # The speed to move the Z axis at when plotting

has_homed = False
movement_index = -1
first_home = True
PEN_LOWER_HEIGHT_MM = 62 # The height to lower the Z axis by to make the pen touch the paper
PEN_LIFT_AMOUNT_MM = 10 # The height to raise the pen by when switching between shapes to draw
PEN_LIFT_HEIGHT_MM = PEN_LOWER_HEIGHT_MM - PEN_LIFT_AMOUNT_MM

X_RETREAT_STEPS = 20 # The number of steps the X axis will retreat from its limit switch by, when homing
Y_RETREAT_STEPS = 50 # The number of steps the Y axis will retreat from its limit switch by, when homing
Z_RETREAT_STEPS = 20 # The number of steps the Z axis will retreat from its limit switch by, when homing
HOMING_SPEED_STEPS_PER_SEC = 5 # The speed to move each axis towards their limit switches by, when homing
RETREAT_SPEED_STEPS_PER_SEC = 200 # The speed to move each axis away (retreat) from their limit switches by, when homing
MAX_HOMING_STEPS = 3000 # The number of steps allowed before homing is considered to have failed

# Function to activate the main power, all modules, and all steppers
# Variables
yukon = Yukon() # Create a new Yukon object
x_module = DualMotorModule() # Create a DualMotorModule object for the X axis
y1_module = DualMotorModule() # Create a DualMotorModule object for one side of the Y axis
y2_module = DualMotorModule() # Create a DualMotorModule object for the other side of the Y axis
z_module = DualMotorModule() # Create a DualMotorModule object for the Z axis
l1_module = QuadServoDirectModule(init_servos=False) # Create a QuadServoDirectModule object for reading two limit switches
l2_module = QuadServoDirectModule(init_servos=False) # Create a QuadServoDirectModule object for reading two more limit switches
x_stepper = None # Variable for storing the X axis OkayStepper object created later
y_stepper = None # Variable for storing the Y axis OkayStepper object created later
z_stepper = None # Variable for storing the Z axis OkayStepper object created later
has_homed = False # Record if the plotter has been homed, meaning it knows its position
first_home = HOME_ON_PROGRAM_RUN # Is this the first time homing?


# Activate the main power, all modules, and all steppers
def activate():
yukon.enable_main_output()
x_module.enable()
Expand All @@ -62,7 +86,7 @@ def activate():
z_stepper.hold()


# Function to deactivate all steppers, modules and the main output
# Deactivate all steppers, all modules and the main output
def deactivate():
x_stepper.release()
y_stepper.release()
Expand All @@ -74,30 +98,39 @@ def deactivate():
yukon.disable_main_output()


# Function that homes a single plotter axis, given a stepper, speed, and limit switch
def home_axis(name, stepper, speed, limit_switch):
# Home a single plotter axis, given a stepper, retreat steps, and limit switch
def home_axis(name, stepper, retreat_steps, limit_switch):
print(f"Homing {name} ... ", end="")

# Perform two passes of the homing, first at a high speed, then at a lower speed
iteration = 0
while iteration < 2:
iteration += 1
# Is the limit switch pressed?
if limit_switch.value() == 1:
stepper.move_by_steps(speed, 0.2 * (iteration * iteration), debug=False)
# Move away from the limit switch by an amount sufficient to release the limit switch
stepper.move_by_steps(retreat_steps, (1.0 / HOMING_SPEED_STEPS_PER_SEC) * (iteration * iteration))
stepper.wait_for_move()

# Move towards the limit switch one step at a time, until it is pressed or too many steps occur
steps = 0
while limit_switch.value() != 1:
stepper.move_by_steps(-1, 0.005 * (iteration * iteration), debug=False)
stepper.move_by_steps(-1, (1.0 / RETREAT_SPEED_STEPS_PER_SEC) * (iteration * iteration))
stepper.wait_for_move()
steps += 1
if steps > 3000:

# Have too many steps passed?
if steps > MAX_HOMING_STEPS:
yukon.disable_main_output()
raise RuntimeError("Could not home Z")
stepper.hold()
stepper.zero_position()
raise RuntimeError(f"Could not home {name}")

stepper.hold() # Keep the stepper energized but at a lower power than when moving
stepper.zero_position() # Use the stepper's current position as its zero value
print("done")


def move_to_xy(x, y, speed=SPEED_MM_PER_SEC):
# Move the plotter to a given x and y position (in mm) at a set speed
def move_to_xy(x, y, speed=BELT_SPEED_MM_PER_SEC):
dx = x_stepper.unit_diff(x)
dy = y_stepper.unit_diff(y)

Expand All @@ -111,7 +144,8 @@ def move_to_xy(x, y, speed=SPEED_MM_PER_SEC):
y_stepper.wait_for_move()


def move_by_xy(dx, dy, speed=SPEED_MM_PER_SEC):
# Move the plotter by a given x and y position (in mm) at a set speed
def move_by_xy(dx, dy, speed=BELT_SPEED_MM_PER_SEC):
travel_time = math.sqrt(dx * dx + dy * dy) / speed
if travel_time > 0:
print(f"Moving by X {dx}, Y {dy}, in T {travel_time}")
Expand All @@ -122,36 +156,37 @@ def move_by_xy(dx, dy, speed=SPEED_MM_PER_SEC):
y_stepper.wait_for_move()


# Move the plotter's pen to its drawing height
def lower_pen():
z = 1550
dz = z_stepper.step_diff(z)
travel_time = abs(dz) / 300
dz = z_stepper.unit_diff(PEN_LOWER_HEIGHT_MM)
travel_time = abs(dz) / SCREW_SPEED_MM_PER_SEC
if travel_time > 0:
print(f"Lowering Pen, in T {travel_time}")
z_stepper.move_to_step(z, travel_time)
print(f"Lowering Pen to {PEN_LOWER_HEIGHT_MM}, in T {travel_time}")
z_stepper.move_to(PEN_LOWER_HEIGHT_MM, travel_time)
z_stepper.wait_for_move()


# Move the plotter's pen to just above its drawing height
def lift_pen():
z = 1000
dz = z_stepper.step_diff(z)
travel_time = abs(dz) / 300
dz = z_stepper.unit_diff(PEN_LIFT_HEIGHT_MM)
travel_time = abs(dz) / SCREW_SPEED_MM_PER_SEC
if travel_time > 0:
print(f"Lifting Pen, in T {travel_time}")
z_stepper.move_to_step(z, travel_time)
print(f"Lifting Pen to {PEN_LIFT_HEIGHT_MM}, in T {travel_time}")
z_stepper.move_to(PEN_LIFT_HEIGHT_MM, travel_time)
z_stepper.wait_for_move()


# Move the plotter's pen to its home height
def raise_pen():
z = 0
dz = z_stepper.step_diff(z)
travel_time = abs(dz) / 300
dz = z_stepper.units()
travel_time = abs(dz) / SCREW_SPEED_MM_PER_SEC
if travel_time > 0:
print(f"Raising Pen, in T {travel_time}")
z_stepper.move_to_step(z, travel_time)
print(f"Raising Pen to 0, in T {travel_time}")
z_stepper.move_to(0, travel_time)
z_stepper.wait_for_move()


# Create an instance of the GCodeParser, giving it the functions to call for movement and pen control
parser = GCodeParser(absolute_callback=move_to_xy,
relative_callback=move_by_xy,
lower_pen_callback=lower_pen,
Expand All @@ -172,14 +207,14 @@ def raise_pen():
# Verify that the DualMotorModules are attached to Yukon, and initialise them
yukon.verify_and_initialise()

# Create OkayStepper classes to drive the plotter's stepper motors
# The Y axis has two sets of motors as it is driven from both sides
# Create OkayStepper classes to drive the plotter's stepper motors, with their units scaled to be in millimeters
x_stepper = OkayStepper(x_module.motor1, x_module.motor2,
steps_per_unit=STEPS_PER_MM)
steps_per_unit=BELT_STEPS_PER_MM)
y_stepper = OkayStepper(y1_module.motor1, y1_module.motor2,
y2_module.motor2, y2_module.motor1,
steps_per_unit=STEPS_PER_MM)
z_stepper = OkayStepper(z_module.motor1, z_module.motor2)
y2_module.motor2, y2_module.motor1, # The Y axis has two sets of motors as it is driven from both sides
steps_per_unit=BELT_STEPS_PER_MM)
z_stepper = OkayStepper(z_module.motor1, z_module.motor2,
steps_per_unit=SCREW_STEPS_PER_MM)

# Set the hardware current limit of each DualMotorModule to its maximum as OkayStepper controls current with PWM instead
x_module.set_current_limit(DualMotorModule.MAX_CURRENT_LIMIT)
Expand All @@ -197,7 +232,10 @@ def raise_pen():
x_right_limit.init(Pin.IN, Pin.PULL_UP)
y_back_limit.init(Pin.IN, Pin.PULL_UP)

# Have the parser load in the GCode file
print(f"Loading '{GCODE_FILE}' ... ", end="")
parser.load_file(GCODE_FILE)
print("done")

if has_homed:
yukon.set_led('A', True) # Show that button A can be pressed
Expand All @@ -220,6 +258,7 @@ def raise_pen():
deactivate() # De-energize the steppers and turn off power
has_homed = False # Plotter could be moved, so require re-homing
yukon.set_led('B', True) # Show that button B can be pressed
print("Plotting finished. Press 'B' to re-home")

# Should gcode parsing / plotting be started?
elif yukon.is_pressed('A'):
Expand All @@ -233,39 +272,41 @@ def raise_pen():
parser.start_parsing(PLOT_ORIGIN_X_MM,
PLOT_ORIGIN_Y_MM,
PLOT_SIZE_MM)
print("Plotting started")

# Should homing be started?
elif first_home or yukon.is_pressed('B'):
# Wait for the button to be released
if not first_home:
# Wait for the button to be released
while yukon.is_pressed('B'):
pass
yukon.set_led('B', False) # Stop showing that button B can be pressed
activate() # Turn on power and energize the steppers

# Home each axis in turn
home_axis("Z", z_stepper, 20, z_up_limit)
home_axis("X", x_stepper, 20, x_right_limit)
home_axis("Y", y_stepper, 50, y_back_limit)
home_axis("Z", z_stepper, Z_RETREAT_STEPS, z_up_limit)
home_axis("X", x_stepper, X_RETREAT_STEPS, x_right_limit)
home_axis("Y", y_stepper, Y_RETREAT_STEPS, y_back_limit)

# Move to the origin of the plot
move_to_xy(PLOT_ORIGIN_X_MM, PLOT_ORIGIN_Y_MM)

print("Homing Complete")
has_homed = True
first_home = False

yukon.set_led('A', True) # Show that button A can be pressed
print("Homing finished. Press 'A' to start plotting")

finally:
# Release each stepper motor (if not already done so)
if x_stepper is not None:
x_stepper.release() # Release the X axis stepper motor (if not already done so)
x_stepper.release()

if y_stepper is not None:
y_stepper.release() # Release the Y axis stepper motor (if not already done so)
y_stepper.release()

if z_stepper is not None:
z_stepper.release() # Release the Z axis stepper motor (if not already done so)
z_stepper.release()

# Put the board back into a safe state, regardless of how the program may have ended
yukon.reset()

0 comments on commit da6e027

Please sign in to comment.