mirror of https://github.com/Desuuuu/klipper.git
Merge remote-tracking branch 'upstream/master' into dev
This commit is contained in:
commit
cfb51d72a3
|
@ -0,0 +1,31 @@
|
|||
# Enable the github stale issue bot tracker
|
||||
name: "Close stale issues"
|
||||
on:
|
||||
schedule:
|
||||
- cron: "0 0 * * *"
|
||||
jobs:
|
||||
stale:
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/stale@v3
|
||||
with:
|
||||
repo-token: ${{ secrets.GITHUB_TOKEN }}
|
||||
stale-issue-message: |
|
||||
Hello,
|
||||
|
||||
It looks like there hasn't been any recent updates on this
|
||||
Klipper github issue. If you created this issue and no
|
||||
longer consider it open, then please login to github and
|
||||
close the issue. Otherwise, if there is no further activity
|
||||
on this thread then it will be automatically closed in a few
|
||||
days.
|
||||
|
||||
Best regards,
|
||||
|
||||
~ Your friendly GitIssueBot
|
||||
|
||||
PS: I'm just an automated script, not a human being.
|
||||
|
||||
exempt-issue-labels: 'enhancement,bug'
|
||||
days-before-stale: 21
|
||||
days-before-close: 7
|
|
@ -0,0 +1,97 @@
|
|||
# Support for the green Tevo Tarantula Pro. To use this config, the firmware
|
||||
# should be compiled for the AVR atmega2560.
|
||||
# Note that this config file is for the "old green" Tarantula pro, with a
|
||||
# MKS Gen_l 8-bit board.
|
||||
# It _will not_ work out of the box for the "new orange" Tarantula pro with a
|
||||
# MKS Sgen_l 32-bit board.
|
||||
|
||||
# See the example.cfg file for a description of available parameters.
|
||||
|
||||
[stepper_x]
|
||||
step_pin: ar54
|
||||
dir_pin: !ar55
|
||||
enable_pin: !ar38
|
||||
step_distance: 0.012583
|
||||
endstop_pin: ^!ar3
|
||||
position_endstop: -2
|
||||
position_max: 220
|
||||
position_min: -2
|
||||
homing_speed: 25.0
|
||||
|
||||
[stepper_y]
|
||||
step_pin: ar60
|
||||
dir_pin: ar61
|
||||
enable_pin: !ar56
|
||||
step_distance: 0.01256
|
||||
endstop_pin: ^!ar14
|
||||
position_endstop: 0
|
||||
position_max: 220
|
||||
homing_speed: 25.0
|
||||
|
||||
[stepper_z]
|
||||
step_pin: ar46
|
||||
dir_pin: ar48
|
||||
enable_pin: !ar62
|
||||
step_distance: 0.002492
|
||||
endstop_pin: ^!ar18
|
||||
position_endstop: 0
|
||||
position_max: 200
|
||||
|
||||
# Enable for dual-z addon
|
||||
#[stepper_z1]
|
||||
#step_pin: ar36
|
||||
#dir_pin: ar34
|
||||
#enable_pin: !ar30
|
||||
#step_distance: 0.002492
|
||||
|
||||
[extruder]
|
||||
step_pin: ar26
|
||||
dir_pin: ar28
|
||||
enable_pin: !ar24
|
||||
step_distance: 0.002470
|
||||
nozzle_diameter: 0.400
|
||||
filament_diameter: 1.75
|
||||
|
||||
heater_pin: ar10
|
||||
sensor_type: EPCOS 100K B57560G104F
|
||||
sensor_pin: analog13
|
||||
control: pid
|
||||
pid_Kp: 22.5
|
||||
pid_Ki: 1.78
|
||||
pid_Kd: 74.16
|
||||
min_temp: 0
|
||||
max_temp: 220
|
||||
|
||||
[heater_bed]
|
||||
heater_pin: ar8
|
||||
sensor_type: EPCOS 100K B57560G104F
|
||||
sensor_pin: analog14
|
||||
control: watermark
|
||||
min_temp: 0
|
||||
max_temp: 110
|
||||
|
||||
[fan]
|
||||
pin: ar9
|
||||
|
||||
[mcu]
|
||||
serial: /dev/serial/by-id/usb-1a86_USB2.0-Serial-if00-port0
|
||||
pin_map: arduino
|
||||
|
||||
[printer]
|
||||
kinematics: cartesian
|
||||
max_velocity: 400
|
||||
max_accel: 3000
|
||||
max_z_velocity: 50
|
||||
max_z_accel: 100
|
||||
|
||||
[heater_fan nozzle_fan]
|
||||
pin: ar7
|
||||
|
||||
[display]
|
||||
lcd_type: uc1701
|
||||
cs_pin: ar25
|
||||
a0_pin: ar27
|
||||
encoder_pins: ^!ar31, ^!ar33
|
||||
click_pin: ^!ar35
|
||||
kill_pin: !ar41
|
||||
menu_reverse_navigation: true
|
|
@ -125,12 +125,13 @@ of a typical move command. The [kinematics](Kinematics.md) document
|
|||
provides further information on the mechanics of moves.
|
||||
|
||||
* Processing for a move command starts in gcode.py. The goal of
|
||||
gcode.py is to translate G-code into internal calls. Changes in
|
||||
origin (eg, G92), changes in relative vs absolute positions (eg,
|
||||
G90), and unit changes (eg, F6000=100mm/s) are handled here. The
|
||||
code path for a move is: `_process_data() -> _process_commands() ->
|
||||
cmd_G1()`. Ultimately the ToolHead class is invoked to execute the
|
||||
actual request: `cmd_G1() -> ToolHead.move()`
|
||||
gcode.py is to translate G-code into internal calls. A G1 command
|
||||
will invoke cmd_G1() in klippy/extras/gcode_move.py. The
|
||||
gcode_move.py code handles changes in origin (eg, G92), changes in
|
||||
relative vs absolute positions (eg, G90), and unit changes (eg,
|
||||
F6000=100mm/s). The code path for a move is: `_process_data() ->
|
||||
_process_commands() -> cmd_G1()`. Ultimately the ToolHead class is
|
||||
invoked to execute the actual request: `cmd_G1() -> ToolHead.move()`
|
||||
|
||||
* The ToolHead class (in toolhead.py) handles "look-ahead" and tracks
|
||||
the timing of printing actions. The main codepath for a move is:
|
||||
|
@ -473,9 +474,9 @@ system specified in the config file. This may differ from the
|
|||
bed_tilt, skew_correction) is in effect. This may differ from the
|
||||
actual coordinates specified in the last `G1` command if the g-code
|
||||
origin has been changed (eg, `G92`, `SET_GCODE_OFFSET`, `M221`). The
|
||||
`M114` command (`gcode.get_status()['gcode_position']`) will report
|
||||
the last g-code position relative to the current g-code coordinate
|
||||
system.
|
||||
`M114` command (`gcode_move.get_status()['gcode_position']`) will
|
||||
report the last g-code position relative to the current g-code
|
||||
coordinate system.
|
||||
|
||||
The "gcode base" is the location of the g-code origin in cartesian
|
||||
coordinates relative to the coordinate system specified in the config
|
||||
|
|
|
@ -119,34 +119,42 @@ other macros, as the called macro is evaluated when it is invoked
|
|||
By convention, the name immediately following `printer` is the name of
|
||||
a config section. So, for example, `printer.fan` refers to the fan
|
||||
object created by the `[fan]` config section. There are some
|
||||
exceptions to this rule - notably the `gcode` and `toolhead` objects.
|
||||
If the config section contains spaces in it, then one can access it
|
||||
via the `[ ]` accessor - for example:
|
||||
exceptions to this rule - notably the `gcode_move` and `toolhead`
|
||||
objects. If the config section contains spaces in it, then one can
|
||||
access it via the `[ ]` accessor - for example:
|
||||
`printer["generic_heater my_chamber_heater"].temperature`.
|
||||
|
||||
Some printer objects allow one to alter the state of the printer. By
|
||||
convention, these objects use an `action_` prefix. For example,
|
||||
`printer.gcode.action_emergency_stop()` would cause the printer to go
|
||||
into a shutdown state. These actions are taken at the time that the
|
||||
macro is evaluated, which may be a significant amount of time before
|
||||
the generated commands are executed.
|
||||
|
||||
The following are common printer attributes:
|
||||
- `printer.fan.speed`: The fan speed as a float between 0.0 and 1.0.
|
||||
- `printer.gcode.action_respond_info(msg)`: Write the given `msg` to
|
||||
the /tmp/printer pseudo-terminal. Each line of `msg` will be sent
|
||||
with a "// " prefix.
|
||||
- `printer.gcode.action_respond_error(msg)`: Write the given `msg` to
|
||||
the /tmp/printer pseudo-terminal. The first line of `msg` will be
|
||||
sent with a "!! " prefix and subsequent lines will have a "// "
|
||||
prefix.
|
||||
- `printer.gcode.action_emergency_stop(msg)`: Transition the printer
|
||||
to a shutdown state. The `msg` parameter is optional, it may be
|
||||
useful to describe the reason for the shutdown.
|
||||
- `printer.gcode.gcode_position`: The current position of the toolhead
|
||||
relative to the current G-Code origin. It is possible to access the
|
||||
x, y, z, and e components of this position (eg,
|
||||
`printer.gcode.gcode_position.x`).
|
||||
- `printer.gcode_move.gcode_position`: The current position of the
|
||||
toolhead relative to the current G-Code origin. That is, positions
|
||||
that one might directly send to a `G1` command. It is possible to
|
||||
access the x, y, z, and e components of this position (eg,
|
||||
`printer.gcode_move.gcode_position.x`).
|
||||
- `printer.gcode_move.position`: The last commanded position of the
|
||||
toolhead using the coordinate system specified in the config
|
||||
file. It is possible to access the x, y, z, and e components of this
|
||||
position (eg, `printer.gcode_move.position.x`).
|
||||
- `printer.gcode_move.homing_origin`: The origin of the gcode
|
||||
coordinate system (relative to the coordinate system specified in
|
||||
the config file) to use after a `G28` command. The
|
||||
`SET_GCODE_OFFSET` command can alter this position. It is possible
|
||||
to access the x, y, and z components of this position (eg,
|
||||
`printer.gcode_move.homing_origin.x`).
|
||||
- `printer.gcode_move.speed`: The last speed set in a `G1` command (in
|
||||
mm/s).
|
||||
- `printer.gcode_move.speed_factor`: The "speed factor override" as
|
||||
set by an `M220` command. This is a floating point value such
|
||||
that 1.0 means no override and, for example, 2.0 would double
|
||||
requested speed.
|
||||
- `printer.gcode_move.extrude_factor`: The "extrude factor override"
|
||||
as set by an `M221` command. This is a floating point value such
|
||||
that 1.0 means no override and, for example, 2.0 would double
|
||||
requested extrusions.
|
||||
- `printer.gcode_move.absolute_coordinates`: This returns True if in
|
||||
`G90` absolute coordinate mode or False if in `G91` relative mode.
|
||||
- `printer.gcode_move.absolute_extrude`: This returns True if in `M82`
|
||||
absolute extrude mode or False if in `M83` relative mode.
|
||||
- `printer["gcode_macro <macro_name>"].<variable>`: The current value
|
||||
of a gcode_macro variable.
|
||||
- `printer.<heater>.temperature`: The last reported temperature (in
|
||||
|
@ -155,6 +163,12 @@ The following are common printer attributes:
|
|||
<config_name>`.
|
||||
- `printer.<heater>.target`: The current target temperature (in
|
||||
Celsius as a float) for the given heater.
|
||||
- `printer.idle_timeout.state`: The current state of the printer as
|
||||
tracked by the idle_timeout module. It is one of the following
|
||||
strings: "Idle", "Printing", "Ready".
|
||||
- `printer.idle_timeout.printing_time`: The amount of time (in
|
||||
seconds) the printer has been in the "Printing" state (as tracked by
|
||||
the idle_timeout module).
|
||||
- `printer.pause_resume.is_paused`: Returns true if a PAUSE command
|
||||
has been executed without a corresponding RESUME.
|
||||
- `printer.toolhead.position`: The last commanded position of the
|
||||
|
@ -194,6 +208,26 @@ attributes may be available (via `get_status()` methods defined in the
|
|||
software). However, undocumented attributes may change without notice
|
||||
in future Klipper releases.
|
||||
|
||||
### Actions
|
||||
|
||||
There are some commands available that can alter the state of the
|
||||
printer. For example, `{ action_emergency_stop() }` would cause the
|
||||
printer to go into a shutdown state. Note that these actions are taken
|
||||
at the time that the macro is evaluated, which may be a significant
|
||||
amount of time before the generated g-code commands are executed.
|
||||
|
||||
Available "action" commands:
|
||||
- `action_respond_info(msg)`: Write the given `msg` to the
|
||||
/tmp/printer pseudo-terminal. Each line of `msg` will be sent with a
|
||||
"// " prefix.
|
||||
- `action_raise_error(msg)`: Abort the current macro (and any calling
|
||||
macros) and write the given `msg` to the /tmp/printer
|
||||
pseudo-terminal. The first line of `msg` will be sent with a "!! "
|
||||
prefix and subsequent lines will have a "// " prefix.
|
||||
- `action_emergency_stop(msg)`: Transition the printer to a shutdown
|
||||
state. The `msg` parameter is optional, it may be useful to describe
|
||||
the reason for the shutdown.
|
||||
|
||||
### Variables
|
||||
|
||||
The SET_GCODE_VARIABLE command may be useful for saving state between
|
||||
|
@ -267,11 +301,8 @@ the gcode option:
|
|||
[delayed_gcode report_temp]
|
||||
initial_duration: 2.
|
||||
gcode:
|
||||
{printer.gcode.action_respond_info(
|
||||
"Extruder Temp: %.1f" %
|
||||
(printer.extruder0.temperature))}
|
||||
{action_respond_info("Extruder Temp: %.1f" % (printer.extruder0.temperature))}
|
||||
UPDATE_DELAYED_GCODE ID=report_temp DURATION=2
|
||||
|
||||
```
|
||||
|
||||
The above delayed_gcode will send "// Extruder Temp: [ex0_temp]" to
|
||||
|
|
|
@ -6,6 +6,17 @@ All dates in this document are approximate.
|
|||
|
||||
# Changes
|
||||
|
||||
20200816: The gcode macro `printer.gcode` object has been renamed to
|
||||
`printer.gcode_move`. Several undocumented variables in
|
||||
`printer.toolhead` and `printer.gcode` have been removed. See
|
||||
docs/Command_Templates.md for a list of available template variables.
|
||||
|
||||
20200816: The gcode macro "action_" system has changed. Replace any
|
||||
calls to `printer.gcode.action_emergency_stop()` with
|
||||
`action_emergency_stop()`, `printer.gcode.action_respond_info()` with
|
||||
`action_respond_info()`, and `printer.gcode.action_respond_error()`
|
||||
with `action_raise_error()`.
|
||||
|
||||
20200809: The menu system has been rewritten. If the menu has been
|
||||
customized then it will be necessary to update to the new
|
||||
configuration. See config/example-menu.cfg for configuration details
|
||||
|
|
|
@ -92,26 +92,17 @@ Sensor generates two analog output based on calculated filament width. Sum of ou
|
|||
**hall_filament_width_sensor.is_active** Sensor on or off
|
||||
|
||||
## Template for menu variables
|
||||
[menu __filament_width_current]
|
||||
type: item
|
||||
name: "Dia:{0:4.2f} mm"
|
||||
parameter: hall_filament_width_sensor.Diameter
|
||||
[menu __main __filament __width_current]
|
||||
type: command
|
||||
enable: {'hall_filament_width_sensor' in printer}
|
||||
name: Dia: {'%.2F' % printer.hall_filament_width_sensor.Diameter}
|
||||
index: 0
|
||||
|
||||
[menu __filament_raw_width_current]
|
||||
type: item
|
||||
name: "RAW:{0:4.0f}"
|
||||
parameter: hall_filament_width_sensor.Raw
|
||||
|
||||
[menu __filament]
|
||||
type: list
|
||||
name: Filament
|
||||
items:
|
||||
__temp __hotend0_current, __temp __hotend0_target
|
||||
.__unload
|
||||
.__load
|
||||
.__feed
|
||||
__filament_width_current
|
||||
__filament_raw_width_current
|
||||
[menu __main __filament __raw_width_current]
|
||||
type: command
|
||||
enable: {'hall_filament_width_sensor' in printer}
|
||||
name: Raw: {'%4.0F' % printer.hall_filament_width_sensor.Raw}
|
||||
index: 1
|
||||
|
||||
## Calibration procedure
|
||||
Insert first calibration rod (1.5 mm size) get first raw sensor value
|
||||
|
|
|
@ -261,38 +261,33 @@ AD8497 = [
|
|||
(1360, 6.671), (1380, 6.754)
|
||||
]
|
||||
|
||||
PT100 = [
|
||||
(0, 0.00), (1, 1.11), (10, 1.15), (20, 1.20), (30, 1.24), (40, 1.28),
|
||||
(50, 1.32), (60, 1.36), (70, 1.40), (80, 1.44), (90, 1.48), (100, 1.52),
|
||||
(110, 1.56), (120, 1.61), (130, 1.65), (140, 1.68), (150, 1.72),
|
||||
(160, 1.76), (170, 1.80), (180, 1.84), (190, 1.88), (200, 1.92),
|
||||
(210, 1.96), (220, 2.00), (230, 2.04), (240, 2.07), (250, 2.11),
|
||||
(260, 2.15), (270, 2.18), (280, 2.22), (290, 2.26), (300, 2.29),
|
||||
(310, 2.33), (320, 2.37), (330, 2.41), (340, 2.44), (350, 2.48),
|
||||
(360, 2.51), (370, 2.55), (380, 2.58), (390, 2.62), (400, 2.66),
|
||||
(500, 3.00), (600, 3.33), (700, 3.63), (800, 3.93), (900, 4.21),
|
||||
(1000, 4.48), (1100, 4.73)
|
||||
def calc_pt100(base=100.):
|
||||
# Calc PT100/PT1000 temperature/resistance pairs using formula
|
||||
A, B = (3.9083e-3, -5.775e-7)
|
||||
return [(float(t), base * (1. + A*t + B*t*t)) for t in range(0, 500, 10)]
|
||||
|
||||
def calc_ina826_pt100():
|
||||
# Standard circuit is 4400ohm pullup with 10x gain to 5V
|
||||
return [(t, 10. * 5. * r / (4400. + r)) for t, r in calc_pt100()]
|
||||
|
||||
DefaultVoltageSensors = [
|
||||
("AD595", AD595), ("AD597", AD597), ("AD8494", AD8494), ("AD8495", AD8495),
|
||||
("AD8496", AD8496), ("AD8497", AD8497),
|
||||
("PT100 INA826", calc_ina826_pt100())
|
||||
]
|
||||
|
||||
PT1000 = [
|
||||
(0., 1000.), (100., 1385.1), (200., 1758.6), (300., 2120.5),
|
||||
(400., 2470.9), (500., 2809.8),
|
||||
DefaultResistanceSensors = [
|
||||
("PT1000", calc_pt100(1000.))
|
||||
]
|
||||
|
||||
def load_config(config):
|
||||
# Register default sensors
|
||||
pheaters = config.get_printer().load_object(config, "heaters")
|
||||
for sensor_type, params in [("AD595", AD595),
|
||||
("AD597", AD597),
|
||||
("AD8494", AD8494),
|
||||
("AD8495", AD8495),
|
||||
("AD8496", AD8496),
|
||||
("AD8497", AD8497),
|
||||
("PT100 INA826", PT100)]:
|
||||
for sensor_type, params in DefaultVoltageSensors:
|
||||
func = (lambda config, params=params:
|
||||
PrinterADCtoTemperature(config, LinearVoltage(config, params)))
|
||||
pheaters.add_sensor_factory(sensor_type, func)
|
||||
for sensor_type, params in [("PT1000", PT1000)]:
|
||||
for sensor_type, params in DefaultResistanceSensors:
|
||||
func = (lambda config, params=params:
|
||||
PrinterADCtoTemperature(config,
|
||||
LinearResistance(config, params)))
|
||||
|
|
|
@ -87,7 +87,9 @@ class BedMesh:
|
|||
self.gcode.register_command(
|
||||
'BED_MESH_CLEAR', self.cmd_BED_MESH_CLEAR,
|
||||
desc=self.cmd_BED_MESH_CLEAR_help)
|
||||
self.gcode.set_move_transform(self)
|
||||
# Register transform
|
||||
gcode_move = self.printer.load_object(config, 'gcode_move')
|
||||
gcode_move.set_move_transform(self)
|
||||
def handle_ready(self):
|
||||
self.toolhead = self.printer.lookup_object('toolhead')
|
||||
self.bmc.print_generated_points(logging.info)
|
||||
|
@ -126,7 +128,8 @@ class BedMesh:
|
|||
self.z_mesh = mesh
|
||||
self.splitter.initialize(mesh)
|
||||
# cache the current position before a transform takes place
|
||||
self.gcode.reset_last_position()
|
||||
gcode_move = self.printer.lookup_object('gcode_move')
|
||||
gcode_move.reset_last_position()
|
||||
def get_z_factor(self, z_pos):
|
||||
if z_pos >= self.fade_end:
|
||||
return 0.
|
||||
|
|
|
@ -46,13 +46,7 @@ class BedScrews:
|
|||
self.cmd_BED_SCREWS_ADJUST,
|
||||
desc=self.cmd_BED_SCREWS_ADJUST_help)
|
||||
def move(self, coord, speed):
|
||||
toolhead = self.printer.lookup_object('toolhead')
|
||||
curpos = toolhead.get_position()
|
||||
for i in range(len(coord)):
|
||||
if coord[i] is not None:
|
||||
curpos[i] = coord[i]
|
||||
toolhead.move(curpos, speed)
|
||||
self.gcode.reset_last_position()
|
||||
self.printer.lookup_object('toolhead').manual_move(coord, speed)
|
||||
def move_to_screw(self, state, screw):
|
||||
# Move up, over, and then down
|
||||
self.move((None, None, self.horizontal_move_z), self.lift_speed)
|
||||
|
|
|
@ -19,8 +19,8 @@ class BedTilt:
|
|||
BedTiltCalibrate(config, self)
|
||||
self.toolhead = None
|
||||
# Register move transform with g-code class
|
||||
gcode = self.printer.lookup_object('gcode')
|
||||
gcode.set_move_transform(self)
|
||||
gcode_move = self.printer.load_object(config, 'gcode_move')
|
||||
gcode_move.set_move_transform(self)
|
||||
def handle_connect(self):
|
||||
self.toolhead = self.printer.lookup_object('toolhead')
|
||||
def get_position(self):
|
||||
|
@ -34,6 +34,8 @@ class BedTilt:
|
|||
self.x_adjust = x_adjust
|
||||
self.y_adjust = y_adjust
|
||||
self.z_adjust = z_adjust
|
||||
gcode_move = self.printer.lookup_object('gcode_move')
|
||||
gcode_move.reset_last_position()
|
||||
configfile = self.printer.lookup_object('configfile')
|
||||
configfile.set('bed_tilt', 'x_adjust', "%.6f" % (x_adjust,))
|
||||
configfile.set('bed_tilt', 'y_adjust', "%.6f" % (y_adjust,))
|
||||
|
@ -80,7 +82,6 @@ class BedTiltCalibrate:
|
|||
z_adjust = (new_params['z_adjust'] - z_offset
|
||||
- x_adjust * offsets[0] - y_adjust * offsets[1])
|
||||
self.bedtilt.update_adjust(x_adjust, y_adjust, z_adjust)
|
||||
self.gcode.reset_last_position()
|
||||
# Log and report results
|
||||
logging.info("Calculated bed_tilt parameters: %s", new_params)
|
||||
for pos in positions:
|
||||
|
|
|
@ -83,7 +83,7 @@ text: { render("_heater_temperature", param_heater_name="heater_bed") }
|
|||
position: 1, 10
|
||||
text:
|
||||
~feedrate~
|
||||
{ "{:>4.0%}".format(printer.gcode.speed_factor) }
|
||||
{ "{:>4.0%}".format(printer.gcode_move.speed_factor) }
|
||||
|
||||
[display_data _default_16x4 print_progress]
|
||||
position: 2, 0
|
||||
|
@ -164,7 +164,7 @@ text:
|
|||
position: 2, 0
|
||||
text:
|
||||
~feedrate~
|
||||
{ "{:^4.0%}".format(printer.gcode.speed_factor) }
|
||||
{ "{:^4.0%}".format(printer.gcode_move.speed_factor) }
|
||||
|
||||
[display_data _default_20x4 print_progress]
|
||||
position: 2, 8
|
||||
|
|
|
@ -8,6 +8,11 @@
|
|||
import logging, os, ast
|
||||
from . import hd44780, st7920, uc1701, menu
|
||||
|
||||
# Normal time between each screen redraw
|
||||
REDRAW_TIME = 0.500
|
||||
# Minimum time between screen redraws
|
||||
REDRAW_MIN_TIME = 0.100
|
||||
|
||||
LCD_chips = {
|
||||
'st7920': st7920.ST7920, 'hd44780': hd44780.HD44780,
|
||||
'uc1701': uc1701.UC1701, 'ssd1306': uc1701.SSD1306, 'sh1106': uc1701.SH1106,
|
||||
|
@ -66,9 +71,8 @@ class DisplayGroup:
|
|||
template = gcode_macro.load_template(c, 'text')
|
||||
self.data_items.append((row, col, template))
|
||||
def show(self, display, templates, eventtime):
|
||||
swrap = self.data_items[0][2].create_status_wrapper(eventtime)
|
||||
context = { 'printer': swrap,
|
||||
'draw_progress_bar': display.draw_progress_bar }
|
||||
context = self.data_items[0][2].create_template_context(eventtime)
|
||||
context['draw_progress_bar'] = display.draw_progress_bar
|
||||
def render(name, **kwargs):
|
||||
return templates[name].render(context, **kwargs)
|
||||
context['render'] = render
|
||||
|
@ -100,9 +104,12 @@ class PrinterLCD:
|
|||
self.show_data_group = self.display_data_groups.get(dgroup)
|
||||
if self.show_data_group is None:
|
||||
raise config.error("Unknown display_data group '%s'" % (dgroup,))
|
||||
# Screen updating
|
||||
self.printer.register_event_handler("klippy:ready", self.handle_ready)
|
||||
self.screen_update_timer = self.reactor.register_timer(
|
||||
self.screen_update_event)
|
||||
self.redraw_request_pending = False
|
||||
self.redraw_time = 0.
|
||||
# Register g-code commands
|
||||
gcode = self.printer.lookup_object("gcode")
|
||||
gcode.register_mux_command('SET_DISPLAY_GROUP', 'DISPLAY', name,
|
||||
|
@ -111,6 +118,8 @@ class PrinterLCD:
|
|||
if name == 'display':
|
||||
gcode.register_mux_command('SET_DISPLAY_GROUP', 'DISPLAY', None,
|
||||
self.cmd_SET_DISPLAY_GROUP)
|
||||
def get_dimensions(self):
|
||||
return self.lcd_chip.get_dimensions()
|
||||
# Configurable display
|
||||
def _parse_glyph(self, config, glyph_name, data, width, height):
|
||||
glyph_data = []
|
||||
|
@ -184,19 +193,28 @@ class PrinterLCD:
|
|||
self.reactor.update_timer(self.screen_update_timer, self.reactor.NOW)
|
||||
# Screen updating
|
||||
def screen_update_event(self, eventtime):
|
||||
if self.redraw_request_pending:
|
||||
self.redraw_request_pending = False
|
||||
self.redraw_time = eventtime + REDRAW_MIN_TIME
|
||||
self.lcd_chip.clear()
|
||||
# update menu component
|
||||
if self.menu is not None:
|
||||
ret = self.menu.screen_update_event(eventtime)
|
||||
if ret:
|
||||
return ret
|
||||
self.lcd_chip.flush()
|
||||
return eventtime + REDRAW_TIME
|
||||
# Update normal display
|
||||
self.lcd_chip.clear()
|
||||
try:
|
||||
self.show_data_group.show(self, self.display_templates, eventtime)
|
||||
except:
|
||||
logging.exception("Error during display screen update")
|
||||
self.lcd_chip.flush()
|
||||
return eventtime + .500
|
||||
return eventtime + REDRAW_TIME
|
||||
def request_redraw(self):
|
||||
if self.redraw_request_pending:
|
||||
return
|
||||
self.redraw_request_pending = True
|
||||
self.reactor.update_timer(self.screen_update_timer, self.redraw_time)
|
||||
def draw_text(self, row, col, mixed_text, eventtime):
|
||||
pos = col
|
||||
for i, text in enumerate(mixed_text.split('~')):
|
||||
|
|
|
@ -96,7 +96,7 @@ name: Tune
|
|||
[menu __main __tune __speed]
|
||||
type: input
|
||||
name: Speed: {'%3d' % (menu.input*100)}%
|
||||
input: {printer.gcode.speed_factor}
|
||||
input: {printer.gcode_move.speed_factor}
|
||||
input_min: 0
|
||||
input_max: 2
|
||||
input_step: 0.01
|
||||
|
@ -107,7 +107,7 @@ gcode:
|
|||
[menu __main __tune __flow]
|
||||
type: input
|
||||
name: Flow: {'%3d' % (menu.input*100)}%
|
||||
input: {printer.gcode.extrude_factor}
|
||||
input: {printer.gcode_move.extrude_factor}
|
||||
input_min: 0
|
||||
input_max: 2
|
||||
input_step: 0.01
|
||||
|
@ -118,7 +118,7 @@ gcode:
|
|||
[menu __main __tune __offsetz]
|
||||
type: input
|
||||
name: Offset Z:{'%05.3f' % menu.input}
|
||||
input: {printer.gcode.homing_zpos}
|
||||
input: {printer.gcode_move.homing_origin.z}
|
||||
input_min: -5
|
||||
input_max: 5
|
||||
input_step: 0.005
|
||||
|
@ -137,21 +137,21 @@ type: command
|
|||
enable: {printer.idle_timeout.state == "Printing"}
|
||||
name: Pause printing
|
||||
gcode:
|
||||
{printer.gcode.action_respond_info('action:pause')}
|
||||
{action_respond_info('action:pause')}
|
||||
|
||||
[menu __main __octoprint __resume]
|
||||
type: command
|
||||
enable: {not printer.idle_timeout.state == "Printing"}
|
||||
name: Resume printing
|
||||
gcode:
|
||||
{printer.gcode.action_respond_info('action:resume')}
|
||||
{action_respond_info('action:resume')}
|
||||
|
||||
[menu __main __octoprint __abort]
|
||||
type: command
|
||||
enable: {printer.idle_timeout.state == "Printing"}
|
||||
name: Abort printing
|
||||
gcode:
|
||||
{printer.gcode.action_respond_info('action:cancel')}
|
||||
{action_respond_info('action:cancel')}
|
||||
|
||||
### menu virtual sdcard ###
|
||||
[menu __main __sdcard]
|
||||
|
@ -260,7 +260,7 @@ name: Move 10mm
|
|||
[menu __main __control __move_10mm __axis_x]
|
||||
type: input
|
||||
name: Move X:{'%05.1f' % menu.input}
|
||||
input: {printer.gcode.gcode_position.x}
|
||||
input: {printer.gcode_move.gcode_position.x}
|
||||
input_min: 0
|
||||
input_max: 200
|
||||
input_step: 10.0
|
||||
|
@ -273,7 +273,7 @@ gcode:
|
|||
[menu __main __control __move_10mm __axis_y]
|
||||
type: input
|
||||
name: Move Y:{'%05.1f' % menu.input}
|
||||
input: {printer.gcode.gcode_position.y}
|
||||
input: {printer.gcode_move.gcode_position.y}
|
||||
input_min: 0
|
||||
input_max: 200
|
||||
input_step: 10.0
|
||||
|
@ -287,7 +287,7 @@ gcode:
|
|||
type: input
|
||||
enable: {not printer.idle_timeout.state == "Printing"}
|
||||
name: Move Z:{'%05.1f' % menu.input}
|
||||
input: {printer.gcode.gcode_position.z}
|
||||
input: {printer.gcode_move.gcode_position.z}
|
||||
input_min: 0
|
||||
input_max: 200
|
||||
input_step: 10.0
|
||||
|
@ -320,7 +320,7 @@ name: Move 1mm
|
|||
[menu __main __control __move_1mm __axis_x]
|
||||
type: input
|
||||
name: Move X:{'%05.1f' % menu.input}
|
||||
input: {printer.gcode.gcode_position.x}
|
||||
input: {printer.gcode_move.gcode_position.x}
|
||||
input_min: 0
|
||||
input_max: 200
|
||||
input_step: 1.0
|
||||
|
@ -333,7 +333,7 @@ gcode:
|
|||
[menu __main __control __move_1mm __axis_y]
|
||||
type: input
|
||||
name: Move Y:{'%05.1f' % menu.input}
|
||||
input: {printer.gcode.gcode_position.y}
|
||||
input: {printer.gcode_move.gcode_position.y}
|
||||
input_min: 0
|
||||
input_max: 200
|
||||
input_step: 1.0
|
||||
|
@ -347,7 +347,7 @@ gcode:
|
|||
type: input
|
||||
enable: {not printer.idle_timeout.state == "Printing"}
|
||||
name: Move Z:{'%05.1f' % menu.input}
|
||||
input: {printer.gcode.gcode_position.z}
|
||||
input: {printer.gcode_move.gcode_position.z}
|
||||
input_min: 0
|
||||
input_max: 200
|
||||
input_step: 1.0
|
||||
|
@ -380,7 +380,7 @@ name: Move 0.1mm
|
|||
[menu __main __control __move_01mm __axis_x]
|
||||
type: input
|
||||
name: Move X:{'%05.1f' % menu.input}
|
||||
input: {printer.gcode.gcode_position.x}
|
||||
input: {printer.gcode_move.gcode_position.x}
|
||||
input_min: 0
|
||||
input_max: 200
|
||||
input_step: 0.1
|
||||
|
@ -393,7 +393,7 @@ gcode:
|
|||
[menu __main __control __move_01mm __axis_y]
|
||||
type: input
|
||||
name: Move Y:{'%05.1f' % menu.input}
|
||||
input: {printer.gcode.gcode_position.y}
|
||||
input: {printer.gcode_move.gcode_position.y}
|
||||
input_min: 0
|
||||
input_max: 200
|
||||
input_step: 0.1
|
||||
|
@ -407,7 +407,7 @@ gcode:
|
|||
type: input
|
||||
enable: {not printer.idle_timeout.state == "Printing"}
|
||||
name: Move Z:{'%05.1f' % menu.input}
|
||||
input: {printer.gcode.gcode_position.z}
|
||||
input: {printer.gcode_move.gcode_position.z}
|
||||
input_min: 0
|
||||
input_max: 200
|
||||
input_step: 0.1
|
||||
|
@ -677,7 +677,7 @@ gcode:
|
|||
[menu __main __setup __calib __delta_calib_man __move_z]
|
||||
type: input
|
||||
name: Move Z: {'%03.2f' % menu.input}
|
||||
input: {printer.gcode.gcode_position.z}
|
||||
input: {printer.gcode_move.gcode_position.z}
|
||||
input_step: 1
|
||||
realtime: True
|
||||
gcode:
|
||||
|
@ -720,8 +720,9 @@ name: Dump parameters
|
|||
gcode:
|
||||
{% for name1 in printer %}
|
||||
{% for name2 in printer[name1] %}
|
||||
{ printer.gcode.action_respond_info("printer['%s'].%s = %s" % (name1, name2, printer[name1][name2])) }
|
||||
{ action_respond_info("printer['%s'].%s = %s"
|
||||
% (name1, name2, printer[name1][name2])) }
|
||||
{% else %}
|
||||
{ printer.gcode.action_respond_info("printer['%s'] = %s" % (name1, printer[name1])) }
|
||||
{ action_respond_info("printer['%s'] = %s" % (name1, printer[name1])) }
|
||||
{% endfor %}
|
||||
{% endfor %}
|
||||
|
|
|
@ -7,7 +7,6 @@
|
|||
import os, logging
|
||||
from string import Template
|
||||
from . import menu_keys
|
||||
from .. import gcode_macro
|
||||
|
||||
|
||||
class sentinel:
|
||||
|
@ -328,7 +327,6 @@ class MenuContainer(MenuElement):
|
|||
item.add_parents(self._parents)
|
||||
item.add_parents(self)
|
||||
item.assert_recursive_relation()
|
||||
item.populate()
|
||||
if index is None:
|
||||
self._allitems.append((item, name))
|
||||
else:
|
||||
|
@ -346,7 +344,6 @@ class MenuContainer(MenuElement):
|
|||
self._populate()
|
||||
# send populate event
|
||||
self.send_event('populate', self)
|
||||
self.update_items()
|
||||
|
||||
def update_items(self):
|
||||
_a = [(item, name) for item, name in self._allitems
|
||||
|
@ -553,7 +550,12 @@ class MenuInput(MenuCommand):
|
|||
class MenuList(MenuContainer):
|
||||
def __init__(self, manager, config):
|
||||
super(MenuList, self).__init__(manager, config)
|
||||
self._show_title = True
|
||||
# create back item
|
||||
self._itemBack = self.manager.menuitem_from({
|
||||
'type': 'command',
|
||||
'name': '..',
|
||||
'gcode': '{menu.back()}'
|
||||
})
|
||||
|
||||
def _names_aslist(self):
|
||||
return self.manager.lookup_children(self.get_ns())
|
||||
|
@ -561,15 +563,7 @@ class MenuList(MenuContainer):
|
|||
def _populate(self):
|
||||
super(MenuList, self)._populate()
|
||||
# add back as first item
|
||||
name = '..'
|
||||
if self._show_title:
|
||||
name += ' %s' % str(self._name())
|
||||
item = self.manager.menuitem_from({
|
||||
'type': 'command',
|
||||
'name': self.manager.asliteral(name),
|
||||
'gcode': '{menu.back()}'
|
||||
})
|
||||
self.insert_item(item, 0)
|
||||
self.insert_item(self._itemBack, 0)
|
||||
|
||||
def render_container(self, eventtime):
|
||||
rows = []
|
||||
|
@ -621,8 +615,7 @@ menu_items = {
|
|||
}
|
||||
|
||||
|
||||
MENU_UPDATE_DELAY = .100
|
||||
TIMER_DELAY = .100
|
||||
TIMER_DELAY = 1.0
|
||||
|
||||
|
||||
class MenuManager:
|
||||
|
@ -632,7 +625,6 @@ class MenuManager:
|
|||
self.menustack = []
|
||||
self.children = {}
|
||||
self.top_row = 0
|
||||
self.timeout_idx = 0
|
||||
self.display = display
|
||||
self.printer = config.get_printer()
|
||||
self.pconfig = self.printer.lookup_object('configfile')
|
||||
|
@ -641,10 +633,9 @@ class MenuManager:
|
|||
self.context = {}
|
||||
self.root = None
|
||||
self._root = config.get('menu_root', '__main')
|
||||
self.cols, self.rows = self.display.lcd_chip.get_dimensions()
|
||||
self.cols, self.rows = self.display.get_dimensions()
|
||||
self.timeout = config.getint('menu_timeout', 0)
|
||||
self.timer = 0
|
||||
self.eventtime = 0
|
||||
# reverse container navigation
|
||||
self._reverse_navigation = config.getboolean(
|
||||
'menu_reverse_navigation', False)
|
||||
|
@ -670,10 +661,7 @@ class MenuManager:
|
|||
reactor.register_timer(self.timer_event, reactor.NOW)
|
||||
|
||||
def timer_event(self, eventtime):
|
||||
self.eventtime = eventtime
|
||||
self.timeout_idx = (self.timeout_idx + 1) % 10 # 0.1*10 = 1s
|
||||
if self.timeout_idx == 0:
|
||||
self.timeout_check(eventtime)
|
||||
self.timeout_check(eventtime)
|
||||
return eventtime + TIMER_DELAY
|
||||
|
||||
def timeout_check(self, eventtime):
|
||||
|
@ -702,7 +690,6 @@ class MenuManager:
|
|||
self.update_context(eventtime)
|
||||
if isinstance(self.root, MenuContainer):
|
||||
self.root.init_selection()
|
||||
self.root.populate()
|
||||
self.stack_push(self.root)
|
||||
self.running = True
|
||||
return
|
||||
|
@ -710,8 +697,6 @@ class MenuManager:
|
|||
logging.error("Invalid root, menu stopped!")
|
||||
self.running = False
|
||||
|
||||
self.running = False
|
||||
|
||||
def get_status(self, eventtime):
|
||||
return {
|
||||
'timeout': self.timeout,
|
||||
|
@ -736,18 +721,17 @@ class MenuManager:
|
|||
|
||||
def update_context(self, eventtime):
|
||||
# menu default jinja2 context
|
||||
self.context = {
|
||||
'printer': gcode_macro.GetStatusWrapper(self.printer, eventtime),
|
||||
'menu': {
|
||||
'eventtime': eventtime,
|
||||
'back': self._action_back,
|
||||
'exit': self._action_exit
|
||||
}
|
||||
self.context = self.gcode_macro.create_template_context(eventtime)
|
||||
self.context['menu'] = {
|
||||
'eventtime': eventtime,
|
||||
'back': self._action_back,
|
||||
'exit': self._action_exit
|
||||
}
|
||||
|
||||
def stack_push(self, container):
|
||||
if not isinstance(container, MenuContainer):
|
||||
raise error("Wrong type, expected MenuContainer")
|
||||
container.populate()
|
||||
top = self.stack_peek()
|
||||
if top is not None:
|
||||
if isinstance(top, MenuList):
|
||||
|
@ -815,14 +799,11 @@ class MenuManager:
|
|||
|
||||
def screen_update_event(self, eventtime):
|
||||
# screen update
|
||||
if self.is_running():
|
||||
self.display.lcd_chip.clear()
|
||||
for y, line in enumerate(self.render(eventtime)):
|
||||
self.display.draw_text(y, 0, line, eventtime)
|
||||
self.display.lcd_chip.flush()
|
||||
return eventtime + MENU_UPDATE_DELAY
|
||||
else:
|
||||
return 0
|
||||
if not self.is_running():
|
||||
return False
|
||||
for y, line in enumerate(self.render(eventtime)):
|
||||
self.display.draw_text(y, 0, line, eventtime)
|
||||
return True
|
||||
|
||||
def up(self, fast_rate=False):
|
||||
container = self.stack_peek()
|
||||
|
@ -1005,6 +986,7 @@ class MenuManager:
|
|||
self.down(True)
|
||||
elif key == 'back':
|
||||
self.back()
|
||||
self.display.request_redraw()
|
||||
|
||||
# Collection of manager class helper methods
|
||||
|
||||
|
|
|
@ -132,8 +132,6 @@ class ForceMove:
|
|||
z = gcmd.get_float('Z', curpos[2])
|
||||
logging.info("SET_KINEMATIC_POSITION pos=%.3f,%.3f,%.3f", x, y, z)
|
||||
toolhead.set_position([x, y, z, curpos[3]], homing_axes=(0, 1, 2))
|
||||
gcode = self.printer.lookup_object('gcode')
|
||||
gcode.reset_last_position()
|
||||
|
||||
def load_config(config):
|
||||
return ForceMove(config)
|
||||
|
|
|
@ -17,14 +17,15 @@ class ArcSupport:
|
|||
self.printer = config.get_printer()
|
||||
self.mm_per_arc_segment = config.getfloat('resolution', 1., above=0.0)
|
||||
|
||||
self.gcode_move = self.printer.load_object(config, 'gcode_move')
|
||||
self.gcode = self.printer.lookup_object('gcode')
|
||||
self.gcode.register_command("G2", self.cmd_G2)
|
||||
self.gcode.register_command("G3", self.cmd_G2)
|
||||
|
||||
def cmd_G2(self, gcmd):
|
||||
gcodestatus = self.gcode.get_status()
|
||||
gcodestatus = self.gcode_move.get_status()
|
||||
if not gcodestatus['absolute_coordinates']:
|
||||
raise self.gcode.error("G2/G3 does not support relative move mode")
|
||||
raise gcmd.error("G2/G3 does not support relative move mode")
|
||||
currentPos = gcodestatus['gcode_position']
|
||||
|
||||
# Parse parameters
|
||||
|
@ -60,7 +61,7 @@ class ArcSupport:
|
|||
if asF is not None:
|
||||
g1_params['F'] = asF
|
||||
g1_gcmd = self.gcode.create_gcode_command("G1", "G1", g1_params)
|
||||
self.gcode.cmd_G1(g1_gcmd)
|
||||
self.gcode_move.cmd_G1(g1_gcmd)
|
||||
|
||||
# function planArc() originates from marlin plan_arc()
|
||||
# https://github.com/MarlinFirmware/Marlin
|
||||
|
|
|
@ -45,6 +45,8 @@ class TemplateWrapper:
|
|||
self.printer = printer
|
||||
self.name = name
|
||||
self.gcode = self.printer.lookup_object('gcode')
|
||||
gcode_macro = self.printer.lookup_object('gcode_macro')
|
||||
self.create_template_context = gcode_macro.create_template_context
|
||||
try:
|
||||
self.template = env.from_string(script)
|
||||
except Exception as e:
|
||||
|
@ -52,11 +54,9 @@ class TemplateWrapper:
|
|||
name, traceback.format_exception_only(type(e), e)[-1])
|
||||
logging.exception(msg)
|
||||
raise printer.config_error(msg)
|
||||
def create_status_wrapper(self, eventtime=None):
|
||||
return GetStatusWrapper(self.printer, eventtime)
|
||||
def render(self, context=None):
|
||||
if context is None:
|
||||
context = {'printer': self.create_status_wrapper()}
|
||||
context = self.create_template_context()
|
||||
try:
|
||||
return str(self.template.render(context))
|
||||
except Exception as e:
|
||||
|
@ -79,6 +79,21 @@ class PrinterGCodeMacro:
|
|||
else:
|
||||
script = config.get(option, default)
|
||||
return TemplateWrapper(self.printer, self.env, name, script)
|
||||
def _action_emergency_stop(self, msg="action_emergency_stop"):
|
||||
self.printer.invoke_shutdown("Shutdown due to %s" % (msg,))
|
||||
return ""
|
||||
def _action_respond_info(self, msg):
|
||||
self.printer.lookup_object('gcode').respond_info(msg)
|
||||
return ""
|
||||
def _action_raise_error(self, msg):
|
||||
raise self.printer.command_error(msg)
|
||||
def create_template_context(self, eventtime=None):
|
||||
return {
|
||||
'printer': GetStatusWrapper(self.printer, eventtime),
|
||||
'action_emergency_stop': self._action_emergency_stop,
|
||||
'action_respond_info': self._action_respond_info,
|
||||
'action_raise_error': self._action_raise_error,
|
||||
}
|
||||
|
||||
def load_config(config):
|
||||
return PrinterGCodeMacro(config)
|
||||
|
@ -159,7 +174,7 @@ class GCodeMacro:
|
|||
kwparams = dict(self.kwparams)
|
||||
kwparams.update(params)
|
||||
kwparams.update(self.variables)
|
||||
kwparams['printer'] = self.template.create_status_wrapper()
|
||||
kwparams.update(self.template.create_template_context())
|
||||
kwparams['params'] = params
|
||||
self.in_script = True
|
||||
try:
|
||||
|
|
|
@ -0,0 +1,280 @@
|
|||
# G-Code G1 movement commands (and associated coordinate manipulation)
|
||||
#
|
||||
# Copyright (C) 2016-2020 Kevin O'Connor <kevin@koconnor.net>
|
||||
#
|
||||
# This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
import logging
|
||||
import homing
|
||||
|
||||
class GCodeMove:
|
||||
def __init__(self, config):
|
||||
self.printer = printer = config.get_printer()
|
||||
printer.register_event_handler("klippy:ready", self._handle_ready)
|
||||
printer.register_event_handler("klippy:shutdown", self._handle_shutdown)
|
||||
printer.register_event_handler("toolhead:set_position",
|
||||
self.reset_last_position)
|
||||
printer.register_event_handler("toolhead:manual_move",
|
||||
self.reset_last_position)
|
||||
printer.register_event_handler("gcode:command_error",
|
||||
self.reset_last_position)
|
||||
printer.register_event_handler("extruder:activate_extruder",
|
||||
self._handle_activate_extruder)
|
||||
self.is_printer_ready = False
|
||||
# Register g-code commands
|
||||
gcode = printer.lookup_object('gcode')
|
||||
handlers = [
|
||||
'G1', 'G28', 'G20', 'G21',
|
||||
'M82', 'M83', 'G90', 'G91', 'G92', 'M220', 'M221',
|
||||
'SET_GCODE_OFFSET', 'SAVE_GCODE_STATE', 'RESTORE_GCODE_STATE',
|
||||
]
|
||||
for cmd in handlers:
|
||||
func = getattr(self, 'cmd_' + cmd)
|
||||
desc = getattr(self, 'cmd_' + cmd + '_help', None)
|
||||
gcode.register_command(cmd, func, False, desc)
|
||||
gcode.register_command('G0', self.cmd_G1)
|
||||
gcode.register_command('M114', self.cmd_M114, True)
|
||||
gcode.register_command('GET_POSITION', self.cmd_GET_POSITION, True)
|
||||
# G-Code coordinate manipulation
|
||||
self.absolute_coord = self.absolute_extrude = True
|
||||
self.base_position = [0.0, 0.0, 0.0, 0.0]
|
||||
self.last_position = [0.0, 0.0, 0.0, 0.0]
|
||||
self.homing_position = [0.0, 0.0, 0.0, 0.0]
|
||||
self.speed = 25.
|
||||
self.speed_factor = 1. / 60.
|
||||
self.extrude_factor = 1.
|
||||
# G-Code state
|
||||
self.saved_states = {}
|
||||
self.move_transform = self.move_with_transform = None
|
||||
self.position_with_transform = (lambda: [0., 0., 0., 0.])
|
||||
def _handle_ready(self):
|
||||
self.is_printer_ready = True
|
||||
if self.move_transform is None:
|
||||
toolhead = self.printer.lookup_object('toolhead')
|
||||
self.move_with_transform = toolhead.move
|
||||
self.position_with_transform = toolhead.get_position
|
||||
def _handle_shutdown(self):
|
||||
if not self.is_printer_ready:
|
||||
return
|
||||
self.is_printer_ready = False
|
||||
logging.info("gcode state: absolute_coord=%s absolute_extrude=%s"
|
||||
" base_position=%s last_position=%s homing_position=%s"
|
||||
" speed_factor=%s extrude_factor=%s speed=%s",
|
||||
self.absolute_coord, self.absolute_extrude,
|
||||
self.base_position, self.last_position,
|
||||
self.homing_position, self.speed_factor,
|
||||
self.extrude_factor, self.speed)
|
||||
def _handle_activate_extruder(self):
|
||||
self.reset_last_position()
|
||||
self.extrude_factor = 1.
|
||||
self.base_position[3] = self.last_position[3]
|
||||
def set_move_transform(self, transform, force=False):
|
||||
if self.move_transform is not None and not force:
|
||||
raise self.printer.config_error(
|
||||
"G-Code move transform already specified")
|
||||
old_transform = self.move_transform
|
||||
if old_transform is None:
|
||||
old_transform = self.printer.lookup_object('toolhead', None)
|
||||
self.move_transform = transform
|
||||
self.move_with_transform = transform.move
|
||||
self.position_with_transform = transform.get_position
|
||||
return old_transform
|
||||
def _get_gcode_position(self):
|
||||
p = [lp - bp for lp, bp in zip(self.last_position, self.base_position)]
|
||||
p[3] /= self.extrude_factor
|
||||
return p
|
||||
def _get_gcode_speed(self):
|
||||
return self.speed / self.speed_factor
|
||||
def _get_gcode_speed_override(self):
|
||||
return self.speed_factor * 60.
|
||||
def get_status(self, eventtime=None):
|
||||
move_position = self._get_gcode_position()
|
||||
return {
|
||||
'speed_factor': self._get_gcode_speed_override(),
|
||||
'speed': self._get_gcode_speed(),
|
||||
'extrude_factor': self.extrude_factor,
|
||||
'absolute_coordinates': self.absolute_coord,
|
||||
'absolute_extrude': self.absolute_extrude,
|
||||
'homing_origin': homing.Coord(*self.homing_position),
|
||||
'position': homing.Coord(*self.last_position),
|
||||
'gcode_position': homing.Coord(*move_position),
|
||||
}
|
||||
def reset_last_position(self):
|
||||
if self.is_printer_ready:
|
||||
self.last_position = self.position_with_transform()
|
||||
# G-Code movement commands
|
||||
def cmd_G1(self, gcmd):
|
||||
# Move
|
||||
params = gcmd.get_command_parameters()
|
||||
try:
|
||||
for pos, axis in enumerate('XYZ'):
|
||||
if axis in params:
|
||||
v = float(params[axis])
|
||||
if not self.absolute_coord:
|
||||
# value relative to position of last move
|
||||
self.last_position[pos] += v
|
||||
else:
|
||||
# value relative to base coordinate position
|
||||
self.last_position[pos] = v + self.base_position[pos]
|
||||
if 'E' in params:
|
||||
v = float(params['E']) * self.extrude_factor
|
||||
if not self.absolute_coord or not self.absolute_extrude:
|
||||
# value relative to position of last move
|
||||
self.last_position[3] += v
|
||||
else:
|
||||
# value relative to base coordinate position
|
||||
self.last_position[3] = v + self.base_position[3]
|
||||
if 'F' in params:
|
||||
gcode_speed = float(params['F'])
|
||||
if gcode_speed <= 0.:
|
||||
raise gcmd.error("Invalid speed in '%s'"
|
||||
% (gcmd.get_commandline(),))
|
||||
self.speed = gcode_speed * self.speed_factor
|
||||
except ValueError as e:
|
||||
raise gcmd.error("Unable to parse move '%s'"
|
||||
% (gcmd.get_commandline(),))
|
||||
self.move_with_transform(self.last_position, self.speed)
|
||||
def cmd_G28(self, gcmd):
|
||||
# Move to origin
|
||||
axes = []
|
||||
for pos, axis in enumerate('XYZ'):
|
||||
if gcmd.get(axis, None) is not None:
|
||||
axes.append(pos)
|
||||
if not axes:
|
||||
axes = [0, 1, 2]
|
||||
homing_state = homing.Homing(self.printer)
|
||||
homing_state.home_axes(axes)
|
||||
for axis in homing_state.get_axes():
|
||||
self.base_position[axis] = self.homing_position[axis]
|
||||
# G-Code coordinate manipulation
|
||||
def cmd_G20(self, gcmd):
|
||||
# Set units to inches
|
||||
raise gcmd.error('Machine does not support G20 (inches) command')
|
||||
def cmd_G21(self, gcmd):
|
||||
# Set units to millimeters
|
||||
pass
|
||||
def cmd_M82(self, gcmd):
|
||||
# Use absolute distances for extrusion
|
||||
self.absolute_extrude = True
|
||||
def cmd_M83(self, gcmd):
|
||||
# Use relative distances for extrusion
|
||||
self.absolute_extrude = False
|
||||
def cmd_G90(self, gcmd):
|
||||
# Use absolute coordinates
|
||||
self.absolute_coord = True
|
||||
def cmd_G91(self, gcmd):
|
||||
# Use relative coordinates
|
||||
self.absolute_coord = False
|
||||
def cmd_G92(self, gcmd):
|
||||
# Set position
|
||||
offsets = [ gcmd.get_float(a, None) for a in 'XYZE' ]
|
||||
for i, offset in enumerate(offsets):
|
||||
if offset is not None:
|
||||
if i == 3:
|
||||
offset *= self.extrude_factor
|
||||
self.base_position[i] = self.last_position[i] - offset
|
||||
if offsets == [None, None, None, None]:
|
||||
self.base_position = list(self.last_position)
|
||||
def cmd_M114(self, gcmd):
|
||||
# Get Current Position
|
||||
p = self._get_gcode_position()
|
||||
gcmd.respond_raw("X:%.3f Y:%.3f Z:%.3f E:%.3f" % tuple(p))
|
||||
def cmd_M220(self, gcmd):
|
||||
# Set speed factor override percentage
|
||||
value = gcmd.get_float('S', 100., above=0.) / (60. * 100.)
|
||||
self.speed = self._get_gcode_speed() * value
|
||||
self.speed_factor = value
|
||||
def cmd_M221(self, gcmd):
|
||||
# Set extrude factor override percentage
|
||||
new_extrude_factor = gcmd.get_float('S', 100., above=0.) / 100.
|
||||
last_e_pos = self.last_position[3]
|
||||
e_value = (last_e_pos - self.base_position[3]) / self.extrude_factor
|
||||
self.base_position[3] = last_e_pos - e_value * new_extrude_factor
|
||||
self.extrude_factor = new_extrude_factor
|
||||
cmd_SET_GCODE_OFFSET_help = "Set a virtual offset to g-code positions"
|
||||
def cmd_SET_GCODE_OFFSET(self, gcmd):
|
||||
move_delta = [0., 0., 0., 0.]
|
||||
for pos, axis in enumerate('XYZE'):
|
||||
offset = gcmd.get_float(axis, None)
|
||||
if offset is None:
|
||||
offset = gcmd.get_float(axis + '_ADJUST', None)
|
||||
if offset is None:
|
||||
continue
|
||||
offset += self.homing_position[pos]
|
||||
delta = offset - self.homing_position[pos]
|
||||
move_delta[pos] = delta
|
||||
self.base_position[pos] += delta
|
||||
self.homing_position[pos] = offset
|
||||
# Move the toolhead the given offset if requested
|
||||
if gcmd.get_int('MOVE', 0):
|
||||
speed = gcmd.get_float('MOVE_SPEED', self.speed, above=0.)
|
||||
for pos, delta in enumerate(move_delta):
|
||||
self.last_position[pos] += delta
|
||||
self.move_with_transform(self.last_position, speed)
|
||||
cmd_SAVE_GCODE_STATE_help = "Save G-Code coordinate state"
|
||||
def cmd_SAVE_GCODE_STATE(self, gcmd):
|
||||
state_name = gcmd.get('NAME', 'default')
|
||||
self.saved_states[state_name] = {
|
||||
'absolute_coord': self.absolute_coord,
|
||||
'absolute_extrude': self.absolute_extrude,
|
||||
'base_position': list(self.base_position),
|
||||
'last_position': list(self.last_position),
|
||||
'homing_position': list(self.homing_position),
|
||||
'speed': self.speed, 'speed_factor': self.speed_factor,
|
||||
'extrude_factor': self.extrude_factor,
|
||||
}
|
||||
cmd_RESTORE_GCODE_STATE_help = "Restore a previously saved G-Code state"
|
||||
def cmd_RESTORE_GCODE_STATE(self, gcmd):
|
||||
state_name = gcmd.get('NAME', 'default')
|
||||
state = self.saved_states.get(state_name)
|
||||
if state is None:
|
||||
raise gcmd.error("Unknown g-code state: %s" % (state_name,))
|
||||
# Restore state
|
||||
self.absolute_coord = state['absolute_coord']
|
||||
self.absolute_extrude = state['absolute_extrude']
|
||||
self.base_position = list(state['base_position'])
|
||||
self.homing_position = list(state['homing_position'])
|
||||
self.speed = state['speed']
|
||||
self.speed_factor = state['speed_factor']
|
||||
self.extrude_factor = state['extrude_factor']
|
||||
# Restore the relative E position
|
||||
e_diff = self.last_position[3] - state['last_position'][3]
|
||||
self.base_position[3] += e_diff
|
||||
# Move the toolhead back if requested
|
||||
if gcmd.get_int('MOVE', 0):
|
||||
speed = gcmd.get_float('MOVE_SPEED', self.speed, above=0.)
|
||||
self.last_position[:3] = state['last_position'][:3]
|
||||
self.move_with_transform(self.last_position, speed)
|
||||
def cmd_GET_POSITION(self, gcmd):
|
||||
toolhead = self.printer.lookup_object('toolhead', None)
|
||||
if toolhead is None:
|
||||
raise gcmd.error("Printer not ready")
|
||||
kin = toolhead.get_kinematics()
|
||||
steppers = kin.get_steppers()
|
||||
mcu_pos = " ".join(["%s:%d" % (s.get_name(), s.get_mcu_position())
|
||||
for s in steppers])
|
||||
for s in steppers:
|
||||
s.set_tag_position(s.get_commanded_position())
|
||||
stepper_pos = " ".join(["%s:%.6f" % (s.get_name(), s.get_tag_position())
|
||||
for s in steppers])
|
||||
kin_pos = " ".join(["%s:%.6f" % (a, v)
|
||||
for a, v in zip("XYZ", kin.calc_tag_position())])
|
||||
toolhead_pos = " ".join(["%s:%.6f" % (a, v) for a, v in zip(
|
||||
"XYZE", toolhead.get_position())])
|
||||
gcode_pos = " ".join(["%s:%.6f" % (a, v)
|
||||
for a, v in zip("XYZE", self.last_position)])
|
||||
base_pos = " ".join(["%s:%.6f" % (a, v)
|
||||
for a, v in zip("XYZE", self.base_position)])
|
||||
homing_pos = " ".join(["%s:%.6f" % (a, v)
|
||||
for a, v in zip("XYZ", self.homing_position)])
|
||||
gcmd.respond_info("mcu: %s\n"
|
||||
"stepper: %s\n"
|
||||
"kinematic: %s\n"
|
||||
"toolhead: %s\n"
|
||||
"gcode: %s\n"
|
||||
"gcode base: %s\n"
|
||||
"gcode homing: %s"
|
||||
% (mcu_pos, stepper_pos, kin_pos, toolhead_pos,
|
||||
gcode_pos, base_pos, homing_pos))
|
||||
|
||||
def load_config(config):
|
||||
return GCodeMove(config)
|
|
@ -40,6 +40,8 @@ class HallFilamentWidthSensor:
|
|||
self.filament_array = []
|
||||
self.lastFilamentWidthReading = 0
|
||||
self.lastFilamentWidthReading2 = 0
|
||||
self.firstExtruderUpdatePosition = 0
|
||||
self.filament_width = self.nominal_filament_dia
|
||||
# printer objects
|
||||
self.toolhead = self.ppins = self.mcu_adc = None
|
||||
self.printer.register_event_handler("klippy:ready", self.handle_ready)
|
||||
|
@ -112,6 +114,8 @@ class HallFilamentWidthSensor:
|
|||
# add first item to array
|
||||
self.filament_array.append([self.measurement_delay + last_epos,
|
||||
self.diameter])
|
||||
self.firstExtruderUpdatePosition = (self.measurement_delay
|
||||
+ last_epos)
|
||||
|
||||
def extrude_factor_update_event(self, eventtime):
|
||||
# Update extrude factor
|
||||
|
@ -130,15 +134,18 @@ class HallFilamentWidthSensor:
|
|||
if pending_position <= last_epos:
|
||||
# Get first item in filament_array queue
|
||||
item = self.filament_array.pop(0)
|
||||
filament_width = item[1]
|
||||
elif self.use_current_dia_while_delay:
|
||||
filament_width = self.diameter
|
||||
self.filament_width = item[1]
|
||||
else:
|
||||
filament_width = self.nominal_filament_dia
|
||||
if ((filament_width <= self.max_diameter)
|
||||
and (filament_width >= self.min_diameter)):
|
||||
if ((self.use_current_dia_while_delay)
|
||||
and (self.firstExtruderUpdatePosition
|
||||
== pending_position)):
|
||||
self.filament_width = self.diameter
|
||||
elif self.firstExtruderUpdatePosition == pending_position:
|
||||
self.filament_width = self.nominal_filament_dia
|
||||
if ((self.filament_width <= self.max_diameter)
|
||||
and (self.filament_width >= self.min_diameter)):
|
||||
percentage = round(self.nominal_filament_dia**2
|
||||
/ filament_width**2 * 100)
|
||||
/ self.filament_width**2 * 100)
|
||||
self.gcode.run_script("M221 S" + str(percentage))
|
||||
else:
|
||||
self.gcode.run_script("M221 S100")
|
||||
|
|
|
@ -13,6 +13,7 @@ class HomingOverride:
|
|||
gcode_macro = self.printer.load_object(config, 'gcode_macro')
|
||||
self.template = gcode_macro.load_template(config, 'gcode')
|
||||
self.in_script = False
|
||||
self.printer.load_object(config, 'gcode_move')
|
||||
self.gcode = self.printer.lookup_object('gcode')
|
||||
self.prev_G28 = self.gcode.register_command("G28", None)
|
||||
self.gcode.register_command("G28", self.cmd_G28)
|
||||
|
@ -32,14 +33,14 @@ class HomingOverride:
|
|||
if no_axis:
|
||||
override = True
|
||||
else:
|
||||
# check if we home an axsis which needs the override
|
||||
# check if we home an axis which needs the override
|
||||
override = False
|
||||
for axis in self.axes:
|
||||
if gcmd.get(axis, None) is not None:
|
||||
override = True
|
||||
|
||||
if not override:
|
||||
self.gcode.cmd_G28(gcmd)
|
||||
self.prev_G28(gcmd)
|
||||
return
|
||||
|
||||
# Calculate forced position (if configured)
|
||||
|
@ -51,13 +52,12 @@ class HomingOverride:
|
|||
pos[axis] = loc
|
||||
homing_axes.append(axis)
|
||||
toolhead.set_position(pos, homing_axes=homing_axes)
|
||||
self.gcode.reset_last_position()
|
||||
# Perform homing
|
||||
kwparams = { 'printer': self.template.create_status_wrapper() }
|
||||
kwparams['params'] = gcmd.get_command_parameters()
|
||||
context = self.template.create_template_context()
|
||||
context['params'] = gcmd.get_command_parameters()
|
||||
try:
|
||||
self.in_script = True
|
||||
self.template.run_gcode_from_command(kwparams)
|
||||
self.template.run_gcode_from_command(context)
|
||||
finally:
|
||||
self.in_script = False
|
||||
|
||||
|
|
|
@ -93,11 +93,10 @@ class ManualProbeHelper:
|
|||
def move_z(self, z_pos):
|
||||
curpos = self.toolhead.get_position()
|
||||
try:
|
||||
if curpos[2] - z_pos < Z_BOB_MINIMUM:
|
||||
curpos[2] = z_pos + Z_BOB_MINIMUM
|
||||
self.toolhead.move(curpos, self.speed)
|
||||
curpos[2] = z_pos
|
||||
self.toolhead.move(curpos, self.speed)
|
||||
z_bob_pos = z_pos + Z_BOB_MINIMUM
|
||||
if curpos[2] < z_bob_pos:
|
||||
self.toolhead.manual_move([None, None, z_bob_pos], self.speed)
|
||||
self.toolhead.manual_move([None, None, z_pos], self.speed)
|
||||
except homing.CommandError as e:
|
||||
self.finalize(False)
|
||||
raise
|
||||
|
|
|
@ -19,27 +19,20 @@ class PauseResume:
|
|||
self.gcode.register_command("CLEAR_PAUSE", self.cmd_CLEAR_PAUSE)
|
||||
self.gcode.register_command("CANCEL_PRINT", self.cmd_CANCEL_PRINT)
|
||||
webhooks = self.printer.lookup_object('webhooks')
|
||||
webhooks.register_endpoint(
|
||||
"pause_resume/cancel", self._handle_web_request)
|
||||
webhooks.register_endpoint(
|
||||
"pause_resume/pause", self._handle_web_request)
|
||||
webhooks.register_endpoint(
|
||||
"pause_resume/resume", self._handle_web_request)
|
||||
webhooks.register_endpoint("pause_resume/cancel",
|
||||
self._handle_cancel_request)
|
||||
webhooks.register_endpoint("pause_resume/pause",
|
||||
self._handle_pause_request)
|
||||
webhooks.register_endpoint("pause_resume/resume",
|
||||
self._handle_resume_request)
|
||||
def handle_ready(self):
|
||||
self.v_sd = self.printer.lookup_object('virtual_sdcard', None)
|
||||
def _handle_web_request(self, web_request):
|
||||
if web_request.get_method() != 'POST':
|
||||
raise web_request.error("Invalid Request Method")
|
||||
path = web_request.get_path()
|
||||
if path == "pause_resume/cancel":
|
||||
script = "CANCEL_PRINT"
|
||||
elif path == "pause_resume/pause":
|
||||
script = "PAUSE"
|
||||
elif path == "pause_resume/resume":
|
||||
script = "RESUME"
|
||||
else:
|
||||
raise web_request.error("Invalid Path")
|
||||
self.gcode.run_script(script)
|
||||
def _handle_cancel_request(self, web_request):
|
||||
self.gcode.run_script("CANCEL_PRINT")
|
||||
def _handle_pause_request(self, web_request):
|
||||
self.gcode.run_script("PAUSE")
|
||||
def _handle_resume_request(self, web_request):
|
||||
self.gcode.run_script("RESUME")
|
||||
def get_status(self, eventtime):
|
||||
return {
|
||||
'is_paused': self.is_paused
|
||||
|
|
|
@ -7,12 +7,12 @@
|
|||
class PrintStats:
|
||||
def __init__(self, config):
|
||||
printer = config.get_printer()
|
||||
self.gcode = printer.lookup_object('gcode')
|
||||
self.gcode_move = printer.load_object(config, 'gcode_move')
|
||||
self.reactor = printer.get_reactor()
|
||||
self.reset()
|
||||
def _update_filament_usage(self, eventtime):
|
||||
gc_status = self.gcode.get_status(eventtime)
|
||||
cur_epos = gc_status['last_epos']
|
||||
gc_status = self.gcode_move.get_status(eventtime)
|
||||
cur_epos = gc_status['position'].e
|
||||
self.filament_used += (cur_epos - self.last_epos) \
|
||||
/ gc_status['extrude_factor']
|
||||
self.last_epos = cur_epos
|
||||
|
@ -29,8 +29,8 @@ class PrintStats:
|
|||
self.prev_pause_duration += pause_duration
|
||||
self.last_pause_time = None
|
||||
# Reset last e-position
|
||||
gc_status = self.gcode.get_status(curtime)
|
||||
self.last_epos = gc_status['last_epos']
|
||||
gc_status = self.gcode_move.get_status(curtime)
|
||||
self.last_epos = gc_status['position'].e
|
||||
self.state = "printing"
|
||||
self.error_message = ""
|
||||
def note_pause(self):
|
||||
|
|
|
@ -123,16 +123,9 @@ class PrinterProbe:
|
|||
pos = toolhead.get_position()
|
||||
self.gcode.respond_info("probe at %.3f,%.3f is z=%.6f"
|
||||
% (pos[0], pos[1], pos[2]))
|
||||
self.gcode.reset_last_position()
|
||||
return pos[:3]
|
||||
def _move(self, coord, speed):
|
||||
toolhead = self.printer.lookup_object('toolhead')
|
||||
curpos = toolhead.get_position()
|
||||
for i in range(len(coord)):
|
||||
if coord[i] is not None:
|
||||
curpos[i] = coord[i]
|
||||
toolhead.move(curpos, speed)
|
||||
self.gcode.reset_last_position()
|
||||
self.printer.lookup_object('toolhead').manual_move(coord, speed)
|
||||
def _calc_mean(self, positions):
|
||||
count = float(len(positions))
|
||||
return [sum([pos[i] for pos in positions]) / count
|
||||
|
@ -355,24 +348,20 @@ class ProbePointsHelper:
|
|||
if not self.results:
|
||||
# Use full speed to first probe position
|
||||
speed = self.speed
|
||||
curpos = toolhead.get_position()
|
||||
curpos[2] = self.horizontal_move_z
|
||||
toolhead.move(curpos, speed)
|
||||
toolhead.manual_move([None, None, self.horizontal_move_z], speed)
|
||||
# Check if done probing
|
||||
if len(self.results) >= len(self.probe_points):
|
||||
self.gcode.reset_last_position()
|
||||
toolhead.get_last_move_time()
|
||||
res = self.finalize_callback(self.probe_offsets, self.results)
|
||||
if res != "retry":
|
||||
return True
|
||||
self.results = []
|
||||
# Move to next XY probe point
|
||||
curpos[:2] = self.probe_points[len(self.results)]
|
||||
nextpos = list(self.probe_points[len(self.results)])
|
||||
if self.use_offsets:
|
||||
curpos[0] -= self.probe_offsets[0]
|
||||
curpos[1] -= self.probe_offsets[1]
|
||||
toolhead.move(curpos, self.speed)
|
||||
self.gcode.reset_last_position()
|
||||
nextpos[0] -= self.probe_offsets[0]
|
||||
nextpos[1] -= self.probe_offsets[1]
|
||||
toolhead.manual_move(nextpos, self.speed)
|
||||
return False
|
||||
def start_probe(self, gcmd):
|
||||
manual_probe.verify_no_manual_probe(self.printer)
|
||||
|
|
|
@ -22,8 +22,6 @@ class QueryEndstops:
|
|||
def get_status(self, eventtime):
|
||||
return {'last_query': {name: value for name, value in self.last_state}}
|
||||
def _handle_web_request(self, web_request):
|
||||
if web_request.get_method() != 'GET':
|
||||
raise web_request.error("Invalid Request Method")
|
||||
gc_mutex = self.printer.lookup_object('gcode').get_mutex()
|
||||
toolhead = self.printer.lookup_object('toolhead')
|
||||
with gc_mutex:
|
||||
|
|
|
@ -20,6 +20,7 @@ class SafeZHoming:
|
|||
self.max_z = config.getsection('stepper_z').getfloat('position_max')
|
||||
self.speed = config.getfloat('speed', 50.0, above=0.)
|
||||
self.move_to_previous = config.getboolean('move_to_previous', False)
|
||||
self.printer.load_object(config, 'gcode_move')
|
||||
self.gcode = self.printer.lookup_object('gcode')
|
||||
self.prev_G28 = self.gcode.register_command("G28", None)
|
||||
self.gcode.register_command("G28", self.cmd_G28)
|
||||
|
@ -30,23 +31,23 @@ class SafeZHoming:
|
|||
|
||||
def cmd_G28(self, gcmd):
|
||||
toolhead = self.printer.lookup_object('toolhead')
|
||||
curtime = self.printer.get_reactor().monotonic()
|
||||
kin_status = toolhead.get_kinematics().get_status(curtime)
|
||||
|
||||
# Perform Z Hop if necessary
|
||||
if self.z_hop != 0.0:
|
||||
pos = toolhead.get_position()
|
||||
# Check if Z axis is homed or has a known position
|
||||
curtime = self.printer.get_reactor().monotonic()
|
||||
kin_status = toolhead.get_kinematics().get_status(curtime)
|
||||
if 'z' in kin_status['homed_axes']:
|
||||
# Check if the zhop would exceed the printer limits
|
||||
pos = toolhead.get_position()
|
||||
if pos[2] + self.z_hop > self.max_z:
|
||||
gcmd.respond_info(
|
||||
"No zhop performed, target Z out of bounds: " +
|
||||
str(pos[2] + self.z_hop))
|
||||
elif pos[2] < self.z_hop:
|
||||
self._perform_z_hop(pos)
|
||||
self._perform_z_hop()
|
||||
else:
|
||||
self._perform_z_hop(pos)
|
||||
self._perform_z_hop()
|
||||
if hasattr(toolhead.get_kinematics(), "note_z_not_homed"):
|
||||
toolhead.get_kinematics().note_z_not_homed()
|
||||
|
||||
|
@ -66,46 +67,33 @@ class SafeZHoming:
|
|||
g28_gcmd = self.gcode.create_gcode_command("G28", "G28", new_params)
|
||||
self.prev_G28(g28_gcmd)
|
||||
|
||||
# Update the currently homed axes
|
||||
curtime = self.printer.get_reactor().monotonic()
|
||||
kin_status = toolhead.get_kinematics().get_status(curtime)
|
||||
|
||||
# Home Z axis if necessary
|
||||
if need_z:
|
||||
pos = toolhead.get_position()
|
||||
prev_x = pos[0]
|
||||
prev_y = pos[1]
|
||||
pos[0] = self.home_x_pos
|
||||
pos[1] = self.home_y_pos
|
||||
# Throw an error if X or Y are not homed
|
||||
curtime = self.printer.get_reactor().monotonic()
|
||||
kin_status = toolhead.get_kinematics().get_status(curtime)
|
||||
if ('x' not in kin_status['homed_axes'] or
|
||||
'y' not in kin_status['homed_axes']):
|
||||
raise gcmd.error("Must home X and Y axes first")
|
||||
# Move to safe XY homing position
|
||||
toolhead.move(pos, self.speed)
|
||||
self.gcode.reset_last_position()
|
||||
prevpos = toolhead.get_position()
|
||||
toolhead.manual_move([self.home_x_pos, self.home_y_pos], self.speed)
|
||||
# Home Z
|
||||
g28_gcmd = self.gcode.create_gcode_command("G28", "G28", {'Z': '0'})
|
||||
self.prev_G28(g28_gcmd)
|
||||
# Perform Z Hop again for pressure-based probes
|
||||
pos = toolhead.get_position()
|
||||
if self.z_hop:
|
||||
pos[2] = self.z_hop
|
||||
toolhead.move(pos, self.z_hop_speed)
|
||||
toolhead.manual_move([None, None, self.z_hop], self.z_hop_speed)
|
||||
# Move XY back to previous positions
|
||||
if self.move_to_previous:
|
||||
pos[0] = prev_x
|
||||
pos[1] = prev_y
|
||||
toolhead.move(pos, self.speed)
|
||||
self.gcode.reset_last_position()
|
||||
toolhead.manual_move(prevpos[:2], self.speed)
|
||||
|
||||
def _perform_z_hop(self, pos):
|
||||
def _perform_z_hop(self):
|
||||
toolhead = self.printer.lookup_object('toolhead')
|
||||
# Perform the Z-Hop
|
||||
pos = toolhead.get_position()
|
||||
toolhead.set_position(pos, homing_axes=[2])
|
||||
pos[2] = pos[2] + self.z_hop
|
||||
toolhead.move(pos, self.z_hop_speed)
|
||||
self.gcode.reset_last_position()
|
||||
toolhead.manual_move([None, None, pos[2]+self.z_hop], self.z_hop_speed)
|
||||
|
||||
def load_config(config):
|
||||
return SafeZHoming(config)
|
||||
|
|
|
@ -40,8 +40,8 @@ class PrinterSkew:
|
|||
gcode.register_command('SKEW_PROFILE', self.cmd_SKEW_PROFILE,
|
||||
desc=self.cmd_SKEW_PROFILE_help)
|
||||
def _handle_ready(self):
|
||||
gcode = self.printer.lookup_object('gcode')
|
||||
self.next_transform = gcode.set_move_transform(self, force=True)
|
||||
gcode_move = self.printer.lookup_object('gcode_move')
|
||||
self.next_transform = gcode_move.set_move_transform(self, force=True)
|
||||
def _load_storage(self, config):
|
||||
stored_profs = config.get_prefix_sections(self.name)
|
||||
# Remove primary skew_correction section, as it is not a stored profile
|
||||
|
@ -69,6 +69,12 @@ class PrinterSkew:
|
|||
def move(self, newpos, speed):
|
||||
corrected_pos = self.calc_skew(newpos)
|
||||
self.next_transform.move(corrected_pos, speed)
|
||||
def _update_skew(self, xy_factor, xz_factor, yz_factor):
|
||||
self.xy_factor = xy_factor
|
||||
self.xz_factor = xz_factor
|
||||
self.yz_factor = yz_factor
|
||||
gcode_move = self.printer.lookup_object('gcode_move')
|
||||
gcode_move.reset_last_position()
|
||||
cmd_GET_CURRENT_SKEW_help = "Report current printer skew"
|
||||
def cmd_GET_CURRENT_SKEW(self, gcmd):
|
||||
out = "Current Printer Skew:"
|
||||
|
@ -90,9 +96,7 @@ class PrinterSkew:
|
|||
cmd_SET_SKEW_help = "Set skew based on lengths of measured object"
|
||||
def cmd_SET_SKEW(self, gcmd):
|
||||
if gcmd.get_int("CLEAR", 0):
|
||||
self.xy_factor = 0.
|
||||
self.xz_factor = 0.
|
||||
self.yz_factor = 0.
|
||||
self._update_skew(0., 0., 0.)
|
||||
return
|
||||
planes = ["XY", "XZ", "YZ"]
|
||||
for plane in planes:
|
||||
|
@ -113,14 +117,13 @@ class PrinterSkew:
|
|||
def cmd_SKEW_PROFILE(self, gcmd):
|
||||
if gcmd.get('LOAD', None) is not None:
|
||||
name = gcmd.get('LOAD')
|
||||
if name not in self.skew_profiles:
|
||||
prof = self.skew_profiles.get(name)
|
||||
if prof is None:
|
||||
gcmd.respond_info(
|
||||
"skew_correction: Load failed, unknown profile [%s]"
|
||||
% (name))
|
||||
return
|
||||
self.xy_factor = self.skew_profiles[name]['xy_skew']
|
||||
self.xz_factor = self.skew_profiles[name]['xz_skew']
|
||||
self.yz_factor = self.skew_profiles[name]['yz_skew']
|
||||
self._update_skew(prof['xy_skew'], prof['xz_skew'], prof['yz_skew'])
|
||||
elif gcmd.get('SAVE', None) is not None:
|
||||
name = gcmd.get('SAVE')
|
||||
configfile = self.printer.lookup_object('configfile')
|
||||
|
|
|
@ -13,7 +13,9 @@ class TuningTower:
|
|||
self.normal_transform = None
|
||||
self.last_position = [0., 0., 0., 0.]
|
||||
self.last_z = self.start = self.factor = self.band = 0.
|
||||
self.last_command_value = None
|
||||
self.command_fmt = ""
|
||||
self.gcode_move = self.printer.load_object(config, "gcode_move")
|
||||
# Register command
|
||||
self.gcode = self.printer.lookup_object("gcode")
|
||||
self.gcode.register_command("TUNING_TOWER", self.cmd_TUNING_TOWER,
|
||||
|
@ -33,9 +35,10 @@ class TuningTower:
|
|||
self.command_fmt = "%s %s%%.9f" % (command, parameter)
|
||||
else:
|
||||
self.command_fmt = "%s %s=%%.9f" % (command, parameter)
|
||||
self.normal_transform = self.gcode.set_move_transform(self, force=True)
|
||||
nt = self.gcode_move.set_move_transform(self, force=True)
|
||||
self.normal_transform = nt
|
||||
self.last_z = -99999999.9
|
||||
self.gcode.reset_last_position()
|
||||
self.last_command_value = None
|
||||
self.get_position()
|
||||
gcmd.respond_info("Starting tuning test (start=%.6f factor=%.6f)"
|
||||
% (self.start, self.factor))
|
||||
|
@ -58,11 +61,11 @@ class TuningTower:
|
|||
self.end_test()
|
||||
else:
|
||||
# Process update
|
||||
z_offset = self.gcode.get_status()['base_zpos']
|
||||
oldval = self.calc_value(self.last_z - z_offset)
|
||||
newval = self.calc_value(z - z_offset)
|
||||
gcode_z = self.gcode_move.get_status()['gcode_position'].z
|
||||
newval = self.calc_value(gcode_z)
|
||||
self.last_z = z
|
||||
if newval != oldval:
|
||||
if newval != self.last_command_value:
|
||||
self.last_command_value = newval
|
||||
self.gcode.run_script_from_command(self.command_fmt
|
||||
% (newval,))
|
||||
# Forward move to actual handler
|
||||
|
@ -70,7 +73,7 @@ class TuningTower:
|
|||
normal_transform.move(newpos, speed)
|
||||
def end_test(self):
|
||||
self.gcode.respond_info("Ending tuning test mode")
|
||||
self.gcode.set_move_transform(self.normal_transform, force=True)
|
||||
self.gcode_move.set_move_transform(self.normal_transform, force=True)
|
||||
self.normal_transform = None
|
||||
|
||||
def load_config(config):
|
||||
|
|
|
@ -24,7 +24,6 @@ class VirtualSD:
|
|||
self.work_timer = None
|
||||
# Register commands
|
||||
self.gcode = printer.lookup_object('gcode')
|
||||
self.gcode.register_command('M21', None)
|
||||
for cmd in ['M20', 'M21', 'M23', 'M24', 'M25', 'M26', 'M27']:
|
||||
self.gcode.register_command(cmd, getattr(self, 'cmd_' + cmd))
|
||||
for cmd in ['M28', 'M29', 'M30']:
|
||||
|
@ -35,9 +34,6 @@ class VirtualSD:
|
|||
self.gcode.register_command(
|
||||
"SDCARD_PRINT_FILE", self.cmd_SDCARD_PRINT_FILE,
|
||||
desc=self.cmd_SDCARD_PRINT_FILE_help)
|
||||
# Register sd path
|
||||
webhooks = printer.lookup_object('webhooks')
|
||||
webhooks.register_static_path("sd_path", self.sdcard_dirname)
|
||||
def handle_shutdown(self):
|
||||
if self.work_timer is not None:
|
||||
self.must_pause_work = True
|
||||
|
|
|
@ -65,7 +65,6 @@ class ZAdjustHelper:
|
|||
last_stepper.set_trapq(toolhead.get_trapq())
|
||||
curpos[2] += first_stepper_offset
|
||||
toolhead.set_position(curpos)
|
||||
gcode.reset_last_position()
|
||||
|
||||
class RetryHelper:
|
||||
def __init__(self, config, error_msg_extra = ""):
|
||||
|
|
359
klippy/gcode.py
359
klippy/gcode.py
|
@ -66,8 +66,8 @@ class GCodeCommand:
|
|||
return self.get(name, default, parser=float, minval=minval,
|
||||
maxval=maxval, above=above, below=below)
|
||||
|
||||
# Parse and handle G-Code commands
|
||||
class GCodeParser:
|
||||
# Parse and dispatch G-Code commands
|
||||
class GCodeDispatch:
|
||||
error = homing.CommandError
|
||||
def __init__(self, printer):
|
||||
self.printer = printer
|
||||
|
@ -76,18 +76,6 @@ class GCodeParser:
|
|||
printer.register_event_handler("klippy:shutdown", self._handle_shutdown)
|
||||
printer.register_event_handler("klippy:disconnect",
|
||||
self._handle_disconnect)
|
||||
printer.register_event_handler("extruder:activate_extruder",
|
||||
self._handle_activate_extruder)
|
||||
# Register webhooks
|
||||
webhooks = self.printer.lookup_object('webhooks')
|
||||
webhooks.register_endpoint(
|
||||
"gcode/help", self._handle_remote_help)
|
||||
webhooks.register_endpoint(
|
||||
"gcode/script", self._handle_remote_script)
|
||||
webhooks.register_endpoint(
|
||||
"gcode/restart", self._handle_remote_restart)
|
||||
webhooks.register_endpoint(
|
||||
"gcode/firmware_restart", self._handle_remote_restart)
|
||||
# Command handling
|
||||
self.is_printer_ready = False
|
||||
self.mutex = printer.get_reactor().mutex()
|
||||
|
@ -96,26 +84,13 @@ class GCodeParser:
|
|||
self.ready_gcode_handlers = {}
|
||||
self.mux_commands = {}
|
||||
self.gcode_help = {}
|
||||
for cmd in self.all_handlers:
|
||||
# Register commands needed before config file is loaded
|
||||
handlers = ['M110', 'M112', 'M115',
|
||||
'RESTART', 'FIRMWARE_RESTART', 'ECHO', 'STATUS', 'HELP']
|
||||
for cmd in handlers:
|
||||
func = getattr(self, 'cmd_' + cmd)
|
||||
wnr = getattr(self, 'cmd_' + cmd + '_when_not_ready', False)
|
||||
desc = getattr(self, 'cmd_' + cmd + '_help', None)
|
||||
self.register_command(cmd, func, wnr, desc)
|
||||
for a in getattr(self, 'cmd_' + cmd + '_aliases', []):
|
||||
self.register_command(a, func, wnr)
|
||||
# G-Code coordinate manipulation
|
||||
self.absolute_coord = self.absolute_extrude = True
|
||||
self.base_position = [0.0, 0.0, 0.0, 0.0]
|
||||
self.last_position = [0.0, 0.0, 0.0, 0.0]
|
||||
self.homing_position = [0.0, 0.0, 0.0, 0.0]
|
||||
self.speed = 25.
|
||||
self.speed_factor = 1. / 60.
|
||||
self.extrude_factor = 1.
|
||||
# G-Code state
|
||||
self.saved_states = {}
|
||||
self.move_transform = self.move_with_transform = None
|
||||
self.position_with_transform = (lambda: [0., 0., 0., 0.])
|
||||
self.toolhead = None
|
||||
self.register_command(cmd, func, True, desc)
|
||||
def is_traditional_gcode(self, cmd):
|
||||
# A "traditional" g-code command is a letter and followed by a number
|
||||
try:
|
||||
|
@ -158,71 +133,10 @@ class GCodeParser:
|
|||
"mux command %s %s %s already registered (%s)" % (
|
||||
cmd, key, value, prev_values))
|
||||
prev_values[value] = func
|
||||
def get_command_help(self):
|
||||
return dict(self.gcode_help)
|
||||
def register_output_handler(self, cb):
|
||||
self.output_callbacks.append(cb)
|
||||
def set_move_transform(self, transform, force=False):
|
||||
if self.move_transform is not None and not force:
|
||||
raise self.printer.config_error(
|
||||
"G-Code move transform already specified")
|
||||
old_transform = self.move_transform
|
||||
if old_transform is None:
|
||||
old_transform = self.toolhead
|
||||
self.move_transform = transform
|
||||
self.move_with_transform = transform.move
|
||||
self.position_with_transform = transform.get_position
|
||||
return old_transform
|
||||
def _action_emergency_stop(self, msg="action_emergency_stop"):
|
||||
self.printer.invoke_shutdown("Shutdown due to %s" % (msg,))
|
||||
return ""
|
||||
def _action_respond_info(self, msg):
|
||||
self.respond_info(msg)
|
||||
return ""
|
||||
def _action_respond_error(self, msg):
|
||||
self._respond_error(msg)
|
||||
return ""
|
||||
def _get_gcode_position(self):
|
||||
p = [lp - bp for lp, bp in zip(self.last_position, self.base_position)]
|
||||
p[3] /= self.extrude_factor
|
||||
return p
|
||||
def _get_gcode_speed(self):
|
||||
return self.speed / self.speed_factor
|
||||
def _get_gcode_speed_override(self):
|
||||
return self.speed_factor * 60.
|
||||
def get_status(self, eventtime=None):
|
||||
move_position = self._get_gcode_position()
|
||||
return {
|
||||
'speed_factor': self._get_gcode_speed_override(),
|
||||
'speed': self._get_gcode_speed(),
|
||||
'extrude_factor': self.extrude_factor,
|
||||
'absolute_coordinates': self.absolute_coord,
|
||||
'absolute_extrude': self.absolute_extrude,
|
||||
'move_xpos': move_position[0],
|
||||
'move_ypos': move_position[1],
|
||||
'move_zpos': move_position[2],
|
||||
'move_epos': move_position[3],
|
||||
'last_xpos': self.last_position[0],
|
||||
'last_ypos': self.last_position[1],
|
||||
'last_zpos': self.last_position[2],
|
||||
'last_epos': self.last_position[3],
|
||||
'base_xpos': self.base_position[0],
|
||||
'base_ypos': self.base_position[1],
|
||||
'base_zpos': self.base_position[2],
|
||||
'base_epos': self.base_position[3],
|
||||
'homing_xpos': self.homing_position[0],
|
||||
'homing_ypos': self.homing_position[1],
|
||||
'homing_zpos': self.homing_position[2],
|
||||
'gcode_position': homing.Coord(*move_position),
|
||||
'action_respond_info': self._action_respond_info,
|
||||
'action_respond_error': self._action_respond_error,
|
||||
'action_emergency_stop': self._action_emergency_stop,
|
||||
}
|
||||
def dump_state(self):
|
||||
return ("gcode state: absolute_coord=%s absolute_extrude=%s"
|
||||
" base_position=%s last_position=%s homing_position=%s"
|
||||
" speed_factor=%s extrude_factor=%s speed=%s"
|
||||
% (self.absolute_coord, self.absolute_extrude,
|
||||
self.base_position, self.last_position, self.homing_position,
|
||||
self.speed_factor, self.extrude_factor, self.speed))
|
||||
def _handle_shutdown(self):
|
||||
if not self.is_printer_ready:
|
||||
return
|
||||
|
@ -234,18 +148,7 @@ class GCodeParser:
|
|||
def _handle_ready(self):
|
||||
self.is_printer_ready = True
|
||||
self.gcode_handlers = self.ready_gcode_handlers
|
||||
self.toolhead = self.printer.lookup_object('toolhead')
|
||||
if self.move_transform is None:
|
||||
self.move_with_transform = self.toolhead.move
|
||||
self.position_with_transform = self.toolhead.get_position
|
||||
self._respond_state("Ready")
|
||||
def _handle_activate_extruder(self):
|
||||
self.reset_last_position()
|
||||
self.extrude_factor = 1.
|
||||
self.base_position[3] = self.last_position[3]
|
||||
def reset_last_position(self):
|
||||
if self.is_printer_ready:
|
||||
self.last_position = self.position_with_transform()
|
||||
# Parse input into commands
|
||||
args_r = re.compile('([A-Z_]+|[A-Z*/])')
|
||||
def _process_commands(self, commands, need_ack=True):
|
||||
|
@ -274,7 +177,6 @@ class GCodeParser:
|
|||
handler(gcmd)
|
||||
except self.error as e:
|
||||
self._respond_error(str(e))
|
||||
self.reset_last_position()
|
||||
self.printer.send_event("gcode:command_error")
|
||||
if not need_ack:
|
||||
raise
|
||||
|
@ -342,6 +244,9 @@ class GCodeParser:
|
|||
# Don't warn about temperature requests when not ready
|
||||
gcmd.ack("T:0")
|
||||
return
|
||||
if cmd == 'M21':
|
||||
# Don't warn about sd card init when not ready
|
||||
return
|
||||
if not self.is_printer_ready:
|
||||
raise gcmd.error(self.printer.get_state_message()[0])
|
||||
return
|
||||
|
@ -372,233 +277,36 @@ class GCodeParser:
|
|||
raise gcmd.error("The value '%s' is not valid for %s"
|
||||
% (key_param, key))
|
||||
values[key_param](gcmd)
|
||||
all_handlers = [
|
||||
'G1', 'G4', 'G28', 'M400',
|
||||
'G20', 'M82', 'M83', 'G90', 'G91', 'G92', 'M114', 'M220', 'M221',
|
||||
'SET_GCODE_OFFSET', 'SAVE_GCODE_STATE', 'RESTORE_GCODE_STATE',
|
||||
'M112', 'M115', 'IGNORE', 'GET_POSITION',
|
||||
'RESTART', 'FIRMWARE_RESTART', 'ECHO', 'STATUS', 'HELP']
|
||||
# G-Code movement commands
|
||||
cmd_G1_aliases = ['G0']
|
||||
def cmd_G1(self, gcmd):
|
||||
# Move
|
||||
params = gcmd._params
|
||||
try:
|
||||
for pos, axis in enumerate('XYZ'):
|
||||
if axis in params:
|
||||
v = float(params[axis])
|
||||
if not self.absolute_coord:
|
||||
# value relative to position of last move
|
||||
self.last_position[pos] += v
|
||||
else:
|
||||
# value relative to base coordinate position
|
||||
self.last_position[pos] = v + self.base_position[pos]
|
||||
if 'E' in params:
|
||||
v = float(params['E']) * self.extrude_factor
|
||||
if not self.absolute_coord or not self.absolute_extrude:
|
||||
# value relative to position of last move
|
||||
self.last_position[3] += v
|
||||
else:
|
||||
# value relative to base coordinate position
|
||||
self.last_position[3] = v + self.base_position[3]
|
||||
if 'F' in params:
|
||||
gcode_speed = float(params['F'])
|
||||
if gcode_speed <= 0.:
|
||||
raise gcmd.error("Invalid speed in '%s'"
|
||||
% (gcmd.get_commandline(),))
|
||||
self.speed = gcode_speed * self.speed_factor
|
||||
except ValueError as e:
|
||||
raise gcmd.error("Unable to parse move '%s'"
|
||||
% (gcmd.get_commandline(),))
|
||||
self.move_with_transform(self.last_position, self.speed)
|
||||
def cmd_G4(self, gcmd):
|
||||
# Dwell
|
||||
delay = gcmd.get_float('P', 0., minval=0.) / 1000.
|
||||
self.toolhead.dwell(delay)
|
||||
def cmd_G28(self, gcmd):
|
||||
# Move to origin
|
||||
axes = []
|
||||
for pos, axis in enumerate('XYZ'):
|
||||
if gcmd.get(axis, None) is not None:
|
||||
axes.append(pos)
|
||||
if not axes:
|
||||
axes = [0, 1, 2]
|
||||
homing_state = homing.Homing(self.printer)
|
||||
if self.is_fileinput:
|
||||
homing_state.set_no_verify_retract()
|
||||
homing_state.home_axes(axes)
|
||||
for axis in homing_state.get_axes():
|
||||
self.base_position[axis] = self.homing_position[axis]
|
||||
self.reset_last_position()
|
||||
def cmd_M400(self, gcmd):
|
||||
# Wait for current moves to finish
|
||||
self.toolhead.wait_moves()
|
||||
# G-Code coordinate manipulation
|
||||
def cmd_G20(self, gcmd):
|
||||
# Set units to inches
|
||||
raise gcmd.error('Machine does not support G20 (inches) command')
|
||||
def cmd_M82(self, gcmd):
|
||||
# Use absolute distances for extrusion
|
||||
self.absolute_extrude = True
|
||||
def cmd_M83(self, gcmd):
|
||||
# Use relative distances for extrusion
|
||||
self.absolute_extrude = False
|
||||
def cmd_G90(self, gcmd):
|
||||
# Use absolute coordinates
|
||||
self.absolute_coord = True
|
||||
def cmd_G91(self, gcmd):
|
||||
# Use relative coordinates
|
||||
self.absolute_coord = False
|
||||
def cmd_G92(self, gcmd):
|
||||
# Set position
|
||||
offsets = [ gcmd.get_float(a, None) for a in 'XYZE' ]
|
||||
for i, offset in enumerate(offsets):
|
||||
if offset is not None:
|
||||
if i == 3:
|
||||
offset *= self.extrude_factor
|
||||
self.base_position[i] = self.last_position[i] - offset
|
||||
if offsets == [None, None, None, None]:
|
||||
self.base_position = list(self.last_position)
|
||||
cmd_M114_when_not_ready = True
|
||||
def cmd_M114(self, gcmd):
|
||||
# Get Current Position
|
||||
p = self._get_gcode_position()
|
||||
gcmd.respond_raw("X:%.3f Y:%.3f Z:%.3f E:%.3f" % tuple(p))
|
||||
def cmd_M220(self, gcmd):
|
||||
# Set speed factor override percentage
|
||||
value = gcmd.get_float('S', 100., above=0.) / (60. * 100.)
|
||||
self.speed = self._get_gcode_speed() * value
|
||||
self.speed_factor = value
|
||||
def cmd_M221(self, gcmd):
|
||||
# Set extrude factor override percentage
|
||||
new_extrude_factor = gcmd.get_float('S', 100., above=0.) / 100.
|
||||
last_e_pos = self.last_position[3]
|
||||
e_value = (last_e_pos - self.base_position[3]) / self.extrude_factor
|
||||
self.base_position[3] = last_e_pos - e_value * new_extrude_factor
|
||||
self.extrude_factor = new_extrude_factor
|
||||
cmd_SET_GCODE_OFFSET_help = "Set a virtual offset to g-code positions"
|
||||
def cmd_SET_GCODE_OFFSET(self, gcmd):
|
||||
move_delta = [0., 0., 0., 0.]
|
||||
for pos, axis in enumerate('XYZE'):
|
||||
offset = gcmd.get_float(axis, None)
|
||||
if offset is None:
|
||||
offset = gcmd.get_float(axis + '_ADJUST', None)
|
||||
if offset is None:
|
||||
continue
|
||||
offset += self.homing_position[pos]
|
||||
delta = offset - self.homing_position[pos]
|
||||
move_delta[pos] = delta
|
||||
self.base_position[pos] += delta
|
||||
self.homing_position[pos] = offset
|
||||
# Move the toolhead the given offset if requested
|
||||
if gcmd.get_int('MOVE', 0):
|
||||
speed = gcmd.get_float('MOVE_SPEED', self.speed, above=0.)
|
||||
for pos, delta in enumerate(move_delta):
|
||||
self.last_position[pos] += delta
|
||||
self.move_with_transform(self.last_position, speed)
|
||||
cmd_SAVE_GCODE_STATE_help = "Save G-Code coordinate state"
|
||||
def cmd_SAVE_GCODE_STATE(self, gcmd):
|
||||
state_name = gcmd.get('NAME', 'default')
|
||||
self.saved_states[state_name] = {
|
||||
'absolute_coord': self.absolute_coord,
|
||||
'absolute_extrude': self.absolute_extrude,
|
||||
'base_position': list(self.base_position),
|
||||
'last_position': list(self.last_position),
|
||||
'homing_position': list(self.homing_position),
|
||||
'speed': self.speed, 'speed_factor': self.speed_factor,
|
||||
'extrude_factor': self.extrude_factor,
|
||||
}
|
||||
cmd_RESTORE_GCODE_STATE_help = "Restore a previously saved G-Code state"
|
||||
def cmd_RESTORE_GCODE_STATE(self, gcmd):
|
||||
state_name = gcmd.get('NAME', 'default')
|
||||
state = self.saved_states.get(state_name)
|
||||
if state is None:
|
||||
raise gcmd.error("Unknown g-code state: %s" % (state_name,))
|
||||
# Restore state
|
||||
self.absolute_coord = state['absolute_coord']
|
||||
self.absolute_extrude = state['absolute_extrude']
|
||||
self.base_position = list(state['base_position'])
|
||||
self.homing_position = list(state['homing_position'])
|
||||
self.speed = state['speed']
|
||||
self.speed_factor = state['speed_factor']
|
||||
self.extrude_factor = state['extrude_factor']
|
||||
# Restore the relative E position
|
||||
e_diff = self.last_position[3] - state['last_position'][3]
|
||||
self.base_position[3] += e_diff
|
||||
# Move the toolhead back if requested
|
||||
if gcmd.get_int('MOVE', 0):
|
||||
speed = gcmd.get_float('MOVE_SPEED', self.speed, above=0.)
|
||||
self.last_position[:3] = state['last_position'][:3]
|
||||
self.move_with_transform(self.last_position, speed)
|
||||
# G-Code miscellaneous commands
|
||||
cmd_M112_when_not_ready = True
|
||||
# Low-level G-Code commands that are needed before the config file is loaded
|
||||
def cmd_M110(self, gcmd):
|
||||
# Set Current Line Number
|
||||
pass
|
||||
def cmd_M112(self, gcmd):
|
||||
# Emergency Stop
|
||||
self.printer.invoke_shutdown("Shutdown due to M112 command")
|
||||
cmd_M115_when_not_ready = True
|
||||
def cmd_M115(self, gcmd):
|
||||
# Get Firmware Version and Capabilities
|
||||
software_version = self.printer.get_start_args().get('software_version')
|
||||
kw = {"FIRMWARE_NAME": "Klipper", "FIRMWARE_VERSION": software_version}
|
||||
gcmd.ack(" ".join(["%s:%s" % (k, v) for k, v in kw.items()]))
|
||||
cmd_IGNORE_when_not_ready = True
|
||||
cmd_IGNORE_aliases = ["G21", "M110", "M21"]
|
||||
def cmd_IGNORE(self, gcmd):
|
||||
# Commands that are just silently accepted
|
||||
pass
|
||||
cmd_GET_POSITION_when_not_ready = True
|
||||
def cmd_GET_POSITION(self, gcmd):
|
||||
if self.toolhead is None:
|
||||
self.cmd_default(gcmd)
|
||||
return
|
||||
kin = self.toolhead.get_kinematics()
|
||||
steppers = kin.get_steppers()
|
||||
mcu_pos = " ".join(["%s:%d" % (s.get_name(), s.get_mcu_position())
|
||||
for s in steppers])
|
||||
for s in steppers:
|
||||
s.set_tag_position(s.get_commanded_position())
|
||||
stepper_pos = " ".join(["%s:%.6f" % (s.get_name(), s.get_tag_position())
|
||||
for s in steppers])
|
||||
kin_pos = " ".join(["%s:%.6f" % (a, v)
|
||||
for a, v in zip("XYZ", kin.calc_tag_position())])
|
||||
toolhead_pos = " ".join(["%s:%.6f" % (a, v) for a, v in zip(
|
||||
"XYZE", self.toolhead.get_position())])
|
||||
gcode_pos = " ".join(["%s:%.6f" % (a, v)
|
||||
for a, v in zip("XYZE", self.last_position)])
|
||||
base_pos = " ".join(["%s:%.6f" % (a, v)
|
||||
for a, v in zip("XYZE", self.base_position)])
|
||||
homing_pos = " ".join(["%s:%.6f" % (a, v)
|
||||
for a, v in zip("XYZ", self.homing_position)])
|
||||
gcmd.respond_info("mcu: %s\n"
|
||||
"stepper: %s\n"
|
||||
"kinematic: %s\n"
|
||||
"toolhead: %s\n"
|
||||
"gcode: %s\n"
|
||||
"gcode base: %s\n"
|
||||
"gcode homing: %s"
|
||||
% (mcu_pos, stepper_pos, kin_pos, toolhead_pos,
|
||||
gcode_pos, base_pos, homing_pos))
|
||||
def request_restart(self, result):
|
||||
if self.is_printer_ready:
|
||||
print_time = self.toolhead.get_last_move_time()
|
||||
toolhead = self.printer.lookup_object('toolhead')
|
||||
print_time = toolhead.get_last_move_time()
|
||||
if result == 'exit':
|
||||
logging.info("Exiting (print time %.3fs)" % (print_time,))
|
||||
self.printer.send_event("gcode:request_restart", print_time)
|
||||
self.toolhead.dwell(0.500)
|
||||
self.toolhead.wait_moves()
|
||||
toolhead.dwell(0.500)
|
||||
toolhead.wait_moves()
|
||||
self.printer.request_exit(result)
|
||||
cmd_RESTART_when_not_ready = True
|
||||
cmd_RESTART_help = "Reload config file and restart host software"
|
||||
def cmd_RESTART(self, gcmd):
|
||||
self.request_restart('restart')
|
||||
cmd_FIRMWARE_RESTART_when_not_ready = True
|
||||
cmd_FIRMWARE_RESTART_help = "Restart firmware, host, and reload config"
|
||||
def cmd_FIRMWARE_RESTART(self, gcmd):
|
||||
self.request_restart('firmware_restart')
|
||||
cmd_ECHO_when_not_ready = True
|
||||
def cmd_ECHO(self, gcmd):
|
||||
gcmd.respond_info(gcmd.get_commandline(), log=False)
|
||||
cmd_STATUS_when_not_ready = True
|
||||
cmd_STATUS_help = "Report the printer status"
|
||||
def cmd_STATUS(self, gcmd):
|
||||
if self.is_printer_ready:
|
||||
|
@ -607,7 +315,6 @@ class GCodeParser:
|
|||
msg = self.printer.get_state_message()[0]
|
||||
msg = msg.rstrip() + "\nKlipper state: Not ready"
|
||||
raise gcmd.error(msg)
|
||||
cmd_HELP_when_not_ready = True
|
||||
def cmd_HELP(self, gcmd):
|
||||
cmdhelp = []
|
||||
if not self.is_printer_ready:
|
||||
|
@ -617,24 +324,6 @@ class GCodeParser:
|
|||
if cmd in self.gcode_help:
|
||||
cmdhelp.append("%-10s: %s" % (cmd, self.gcode_help[cmd]))
|
||||
gcmd.respond_info("\n".join(cmdhelp), log=False)
|
||||
# Webhooks
|
||||
def _handle_remote_help(self, web_request):
|
||||
if web_request.get_method() != 'GET':
|
||||
raise web_request.error("Invalid Request Method")
|
||||
web_request.send(dict(self.gcode_help))
|
||||
def _handle_remote_restart(self, web_request):
|
||||
if web_request.get_method() != 'POST':
|
||||
raise web_request.error("Invalid Request Method")
|
||||
path = web_request.get_path()
|
||||
if path == "gcode/restart":
|
||||
self.run_script('restart')
|
||||
elif path == "gcode/firmware_restart":
|
||||
self.run_script('firmware_restart')
|
||||
def _handle_remote_script(self, web_request):
|
||||
if web_request.get_method() != 'POST':
|
||||
raise web_request.error("Invalid Request Method")
|
||||
script = web_request.get('script')
|
||||
self.run_script(script)
|
||||
|
||||
# Support reading gcode from a pseudo-tty interface
|
||||
class GCodeIO:
|
||||
|
@ -666,11 +355,9 @@ class GCodeIO:
|
|||
self._process_data)
|
||||
def _dump_debug(self):
|
||||
out = []
|
||||
out.append("Dumping gcode input %d blocks" % (
|
||||
len(self.input_log),))
|
||||
out.append("Dumping gcode input %d blocks" % (len(self.input_log),))
|
||||
for eventtime, data in self.input_log:
|
||||
out.append("Read %f: %s" % (eventtime, repr(data)))
|
||||
out.append(self.gcode.dump_state())
|
||||
logging.info("\n".join(out))
|
||||
def _handle_shutdown(self):
|
||||
if not self.is_printer_ready:
|
||||
|
@ -708,7 +395,7 @@ class GCodeIO:
|
|||
# Check for M112 out-of-order
|
||||
for line in lines:
|
||||
if self.m112_r.match(line) is not None:
|
||||
self.cmd_M112(None)
|
||||
self.gcode.cmd_M112(None)
|
||||
if self.is_processing_data:
|
||||
if len(pending_commands) >= 20:
|
||||
# Stop reading input
|
||||
|
@ -737,5 +424,5 @@ class GCodeIO:
|
|||
return False, "gcodein=%d" % (self.bytes_read,)
|
||||
|
||||
def add_early_printer_objects(printer):
|
||||
printer.add_object('gcode', GCodeParser(printer))
|
||||
printer.add_object('gcode', GCodeDispatch(printer))
|
||||
printer.add_object('gcode_io', GCodeIO(printer))
|
||||
|
|
|
@ -15,8 +15,8 @@ class Homing:
|
|||
self.toolhead = printer.lookup_object('toolhead')
|
||||
self.changed_axes = []
|
||||
self.verify_retract = True
|
||||
def set_no_verify_retract(self):
|
||||
self.verify_retract = False
|
||||
if self.printer.get_start_args().get("debuginput"):
|
||||
self.verify_retract = False
|
||||
def set_axes(self, axes):
|
||||
self.changed_axes = axes
|
||||
def get_axes(self):
|
||||
|
|
|
@ -136,10 +136,8 @@ class CartKinematics:
|
|||
self.limits[dc_axis] = dc_rail.get_range()
|
||||
cmd_SET_DUAL_CARRIAGE_help = "Set which carriage is active"
|
||||
def cmd_SET_DUAL_CARRIAGE(self, gcmd):
|
||||
gcode = self.printer.lookup_object('gcode')
|
||||
carriage = gcmd.get_int('CARRIAGE', minval=0, maxval=1)
|
||||
self._activate_carriage(carriage)
|
||||
gcode.reset_last_position()
|
||||
|
||||
def load_kinematics(toolhead, config):
|
||||
return CartKinematics(toolhead, config)
|
||||
|
|
|
@ -59,7 +59,7 @@ class Printer:
|
|||
self.event_handlers = {}
|
||||
self.objects = collections.OrderedDict()
|
||||
# Init printer components that must be setup prior to config
|
||||
for m in [webhooks, gcode]:
|
||||
for m in [gcode, webhooks]:
|
||||
m.add_early_printer_objects(self)
|
||||
def get_start_args(self):
|
||||
return self.start_args
|
||||
|
@ -70,6 +70,8 @@ class Printer:
|
|||
category = "ready"
|
||||
elif self.state_message == message_startup:
|
||||
category = "startup"
|
||||
elif self.in_shutdown_state:
|
||||
category = "shutdown"
|
||||
else:
|
||||
category = "error"
|
||||
return self.state_message, category
|
||||
|
@ -247,6 +249,8 @@ def main():
|
|||
opts.add_option("-I", "--input-tty", dest="inputtty",
|
||||
default='/tmp/printer',
|
||||
help="input tty name (default is /tmp/printer)")
|
||||
opts.add_option("-a", "--api-server", dest="apiserver",
|
||||
help="api server unix domain socket filename")
|
||||
opts.add_option("-l", "--logfile", dest="logfile",
|
||||
help="write log to file instead of stderr")
|
||||
opts.add_option("-v", action="store_true", dest="verbose",
|
||||
|
@ -259,7 +263,8 @@ def main():
|
|||
options, args = opts.parse_args()
|
||||
if len(args) != 1:
|
||||
opts.error("Incorrect number of arguments")
|
||||
start_args = {'config_file': args[0], 'start_reason': 'startup'}
|
||||
start_args = {'config_file': args[0], 'apiserver': options.apiserver,
|
||||
'start_reason': 'startup'}
|
||||
|
||||
debuglevel = logging.INFO
|
||||
if options.verbose:
|
||||
|
|
|
@ -232,7 +232,6 @@ class ToolHead:
|
|||
self.need_check_stall = -1.
|
||||
self.flush_timer = self.reactor.register_timer(self._flush_handler)
|
||||
self.move_queue.set_flush_time(self.buffer_time_high)
|
||||
self.last_print_start_time = 0.
|
||||
self.idle_flush_print_time = 0.
|
||||
self.print_stall = 0
|
||||
self.drip_completion = None
|
||||
|
@ -260,14 +259,17 @@ class ToolHead:
|
|||
msg = "Error loading kinematics '%s'" % (kin_name,)
|
||||
logging.exception(msg)
|
||||
raise config.error(msg)
|
||||
# SET_VELOCITY_LIMIT command
|
||||
# Register commands
|
||||
gcode = self.printer.lookup_object('gcode')
|
||||
gcode.register_command('G4', self.cmd_G4)
|
||||
gcode.register_command('M400', self.cmd_M400)
|
||||
gcode.register_command('SET_VELOCITY_LIMIT',
|
||||
self.cmd_SET_VELOCITY_LIMIT,
|
||||
desc=self.cmd_SET_VELOCITY_LIMIT_help)
|
||||
gcode.register_command('M204', self.cmd_M204)
|
||||
# Load some default modules
|
||||
modules = ["idle_timeout", "statistics", "manual_probe", "tuning_tower"]
|
||||
modules = ["gcode_move", "idle_timeout", "statistics", "manual_probe",
|
||||
"tuning_tower"]
|
||||
for module_name in modules:
|
||||
self.printer.load_object(config, module_name)
|
||||
# Print time tracking
|
||||
|
@ -295,7 +297,7 @@ class ToolHead:
|
|||
kin_time += self.kin_flush_delay
|
||||
min_print_time = max(est_print_time + self.buffer_time_start, kin_time)
|
||||
if min_print_time > self.print_time:
|
||||
self.print_time = self.last_print_start_time = min_print_time
|
||||
self.print_time = min_print_time
|
||||
self.printer.send_event("toolhead:sync_print_time",
|
||||
curtime, est_print_time, self.print_time)
|
||||
def _process_moves(self, moves):
|
||||
|
@ -400,6 +402,7 @@ class ToolHead:
|
|||
self.trapq_free_moves(self.trapq, self.reactor.NEVER)
|
||||
self.commanded_pos[:] = newpos
|
||||
self.kin.set_position(newpos, homing_axes)
|
||||
self.printer.send_event("toolhead:set_position")
|
||||
def move(self, newpos, speed):
|
||||
move = Move(self, self.commanded_pos, newpos, speed)
|
||||
if not move.move_d:
|
||||
|
@ -412,6 +415,13 @@ class ToolHead:
|
|||
self.move_queue.add_move(move)
|
||||
if self.print_time > self.need_check_stall:
|
||||
self._check_stall()
|
||||
def manual_move(self, coord, speed):
|
||||
curpos = list(self.commanded_pos)
|
||||
for i in range(len(coord)):
|
||||
if coord[i] is not None:
|
||||
curpos[i] = coord[i]
|
||||
self.move(curpos, speed)
|
||||
self.printer.send_event("toolhead:manual_move")
|
||||
def dwell(self, delay):
|
||||
next_print_time = self.get_last_move_time() + max(0., delay)
|
||||
self._update_move_time(next_print_time)
|
||||
|
@ -484,18 +494,11 @@ class ToolHead:
|
|||
def get_status(self, eventtime):
|
||||
print_time = self.print_time
|
||||
estimated_print_time = self.mcu.estimated_print_time(eventtime)
|
||||
last_print_start_time = self.last_print_start_time
|
||||
buffer_time = print_time - estimated_print_time
|
||||
if buffer_time > -1. or not self.special_queuing_state:
|
||||
status = "Printing"
|
||||
else:
|
||||
status = "Ready"
|
||||
res = dict(self.kin.get_status(eventtime))
|
||||
res.update({ 'status': status, 'print_time': print_time,
|
||||
res.update({ 'print_time': print_time,
|
||||
'estimated_print_time': estimated_print_time,
|
||||
'extruder': self.extruder.get_name(),
|
||||
'position': homing.Coord(*self.commanded_pos),
|
||||
'printing_time': print_time - last_print_start_time,
|
||||
'max_velocity': self.max_velocity,
|
||||
'max_accel': self.max_accel,
|
||||
'max_accel_to_decel': self.requested_accel_to_decel,
|
||||
|
@ -540,6 +543,13 @@ class ToolHead:
|
|||
self.junction_deviation = scv2 * (math.sqrt(2.) - 1.) / self.max_accel
|
||||
self.max_accel_to_decel = min(self.requested_accel_to_decel,
|
||||
self.max_accel)
|
||||
def cmd_G4(self, gcmd):
|
||||
# Dwell
|
||||
delay = gcmd.get_float('P', 0., minval=0.) / 1000.
|
||||
self.dwell(delay)
|
||||
def cmd_M400(self, gcmd):
|
||||
# Wait for current moves to finish
|
||||
self.wait_moves()
|
||||
cmd_SET_VELOCITY_LIMIT_help = "Set printer velocity limits"
|
||||
def cmd_SET_VELOCITY_LIMIT(self, gcmd):
|
||||
print_time = self.get_last_move_time()
|
||||
|
|
|
@ -11,8 +11,6 @@ import errno
|
|||
import json
|
||||
import homing
|
||||
|
||||
SERVER_ADDRESS = "/tmp/klippy_uds"
|
||||
|
||||
# Json decodes strings as unicode types in Python 2.x. This doesn't
|
||||
# play well with some parts of Klipper (particuarly displays), so we
|
||||
# need to create an object hook. This solution borrowed from:
|
||||
|
@ -29,10 +27,6 @@ def byteify(data, ignore_dicts=False):
|
|||
for k, v in data.items()}
|
||||
return data
|
||||
|
||||
def json_loads_byteified(data):
|
||||
return byteify(
|
||||
json.loads(data, object_hook=byteify), True)
|
||||
|
||||
class WebRequestError(homing.CommandError):
|
||||
def __init__(self, message,):
|
||||
Exception.__init__(self, message)
|
||||
|
@ -47,36 +41,47 @@ class Sentinel:
|
|||
|
||||
class WebRequest:
|
||||
error = WebRequestError
|
||||
def __init__(self, base_request):
|
||||
self.id = base_request['id']
|
||||
self.path = base_request['path']
|
||||
self.method = base_request['method']
|
||||
self.args = base_request['args']
|
||||
def __init__(self, client_conn, request):
|
||||
self.client_conn = client_conn
|
||||
base_request = json.loads(request, object_hook=byteify)
|
||||
if type(base_request) != dict:
|
||||
raise ValueError("Not a top-level dictionary")
|
||||
self.id = base_request.get('id', None)
|
||||
self.method = base_request.get('method')
|
||||
self.params = base_request.get('params', {})
|
||||
if type(self.method) != str or type(self.params) != dict:
|
||||
raise ValueError("Invalid request type")
|
||||
self.response = None
|
||||
self.is_error = False
|
||||
|
||||
def get(self, item, default=Sentinel):
|
||||
if item not in self.args:
|
||||
if default == Sentinel:
|
||||
raise WebRequestError("Invalid Argument [%s]" % item)
|
||||
return default
|
||||
return self.args[item]
|
||||
def get_client_connection(self):
|
||||
return self.client_conn
|
||||
|
||||
def get_int(self, item):
|
||||
return int(self.get(item))
|
||||
def get(self, item, default=Sentinel, types=None):
|
||||
value = self.params.get(item, default)
|
||||
if value is Sentinel:
|
||||
raise WebRequestError("Missing Argument [%s]" % (item,))
|
||||
if types is not None and type(value) not in types:
|
||||
raise WebRequestError("Invalid Argument Type [%s]" % (item,))
|
||||
return value
|
||||
|
||||
def get_float(self, item):
|
||||
return float(self.get(item))
|
||||
def get_str(self, item, default=Sentinel):
|
||||
return self.get(item, default, types=(str,))
|
||||
|
||||
def get_args(self):
|
||||
return self.args
|
||||
def get_int(self, item, default=Sentinel):
|
||||
return self.get(item, default, types=(int,))
|
||||
|
||||
def get_path(self):
|
||||
return self.path
|
||||
def get_float(self, item, default=Sentinel):
|
||||
return float(self.get(item, default, types=(int, float)))
|
||||
|
||||
def get_dict(self, item, default=Sentinel):
|
||||
return self.get(item, default, types=(dict,))
|
||||
|
||||
def get_method(self):
|
||||
return self.method
|
||||
|
||||
def set_error(self, error):
|
||||
self.is_error = True
|
||||
self.response = error.to_dict()
|
||||
|
||||
def send(self, data):
|
||||
|
@ -85,11 +90,16 @@ class WebRequest:
|
|||
self.response = data
|
||||
|
||||
def finish(self):
|
||||
if self.id is None:
|
||||
return None
|
||||
rtype = "result"
|
||||
if self.is_error:
|
||||
rtype = "error"
|
||||
if self.response is None:
|
||||
# No error was set and the user never executed
|
||||
# send, default response is "ok"
|
||||
self.response = "ok"
|
||||
return {"request_id": self.id, "response": self.response}
|
||||
# send, default response is {}
|
||||
self.response = {}
|
||||
return {"id": self.id, rtype: self.response}
|
||||
|
||||
class ServerSocket:
|
||||
def __init__(self, webhooks, printer):
|
||||
|
@ -98,15 +108,16 @@ class ServerSocket:
|
|||
self.reactor = printer.get_reactor()
|
||||
self.sock = self.fd_handle = None
|
||||
self.clients = {}
|
||||
is_fileinput = (printer.get_start_args().get('debuginput')
|
||||
is not None)
|
||||
if is_fileinput:
|
||||
# Do not enable server in batch mode
|
||||
start_args = printer.get_start_args()
|
||||
server_address = start_args.get('apiserver')
|
||||
is_fileinput = (start_args.get('debuginput') is not None)
|
||||
if not server_address or is_fileinput:
|
||||
# Do not enable server
|
||||
return
|
||||
self._remove_socket_file(SERVER_ADDRESS)
|
||||
self._remove_socket_file(server_address)
|
||||
self.sock = socket.socket(socket.AF_UNIX, socket.SOCK_STREAM)
|
||||
self.sock.setblocking(0)
|
||||
self.sock.bind(SERVER_ADDRESS)
|
||||
self.sock.bind(server_address)
|
||||
self.sock.listen(1)
|
||||
self.fd_handle = self.reactor.register_fd(
|
||||
self.sock.fileno(), self._handle_accept)
|
||||
|
@ -145,10 +156,6 @@ class ServerSocket:
|
|||
def pop_client(self, client_id):
|
||||
self.clients.pop(client_id, None)
|
||||
|
||||
def send_all_clients(self, data):
|
||||
for client in self.clients.values():
|
||||
client.send(data)
|
||||
|
||||
class ClientConnection:
|
||||
def __init__(self, server, sock):
|
||||
self.printer = server.printer
|
||||
|
@ -175,6 +182,9 @@ class ClientConnection:
|
|||
pass
|
||||
self.server.pop_client(self.uid)
|
||||
|
||||
def is_closed(self):
|
||||
return self.fd_handle is None
|
||||
|
||||
def process_received(self, eventtime):
|
||||
try:
|
||||
data = self.sock.recv(4096)
|
||||
|
@ -193,34 +203,31 @@ class ClientConnection:
|
|||
requests[0] = self.partial_data + requests[0]
|
||||
self.partial_data = requests.pop()
|
||||
for req in requests:
|
||||
logging.debug(
|
||||
"webhooks: Request received: %s" % (req))
|
||||
try:
|
||||
web_request = WebRequest(json_loads_byteified(req))
|
||||
web_request = WebRequest(self, req)
|
||||
except Exception:
|
||||
logging.exception(
|
||||
"webhooks: Error decoding Server Request %s"
|
||||
% (req))
|
||||
logging.exception("webhooks: Error decoding Server Request %s"
|
||||
% (req))
|
||||
continue
|
||||
self.reactor.register_callback(
|
||||
lambda e, s=self, wr=web_request: s._process_request(wr))
|
||||
|
||||
def _process_request(self, web_request):
|
||||
try:
|
||||
func = self.webhooks.get_callback(
|
||||
web_request.get_path())
|
||||
func = self.webhooks.get_callback(web_request.get_method())
|
||||
func(web_request)
|
||||
except homing.CommandError as e:
|
||||
web_request.set_error(WebRequestError(e.message))
|
||||
except Exception as e:
|
||||
msg = "Internal Error on WebRequest: %s" % (web_request.get_path())
|
||||
msg = ("Internal Error on WebRequest: %s"
|
||||
% (web_request.get_method()))
|
||||
logging.exception(msg)
|
||||
web_request.set_error(WebRequestError(e.message))
|
||||
self.printer.invoke_shutdown(msg)
|
||||
result = web_request.finish()
|
||||
logging.debug(
|
||||
"webhooks: Sending response - %s" % (str(result)))
|
||||
self.send({'method': "response", 'params': result})
|
||||
if result is None:
|
||||
return
|
||||
self.send(result)
|
||||
|
||||
def send(self, data):
|
||||
self.send_buffer += json.dumps(data) + "\x03"
|
||||
|
@ -256,72 +263,31 @@ class WebHooks:
|
|||
def __init__(self, printer):
|
||||
self.printer = printer
|
||||
self._endpoints = {"list_endpoints": self._handle_list_endpoints}
|
||||
self._static_paths = []
|
||||
self.register_endpoint("info", self._handle_info_request)
|
||||
self.register_endpoint("emergency_stop", self._handle_estop_request)
|
||||
start_args = printer.get_start_args()
|
||||
log_file = start_args.get('log_file')
|
||||
cfg_file = start_args.get('config_file')
|
||||
klipper_path = os.path.normpath(os.path.join(
|
||||
os.path.dirname(__file__), ".."))
|
||||
if log_file is not None:
|
||||
self.register_static_path("klippy.log", log_file)
|
||||
self.register_static_path("printer.cfg", cfg_file)
|
||||
self.register_static_path("klippy_env", sys.executable)
|
||||
self.register_static_path("klipper_path", klipper_path)
|
||||
self.sconn = ServerSocket(self, printer)
|
||||
StatusHandler(self)
|
||||
|
||||
# Register Events
|
||||
printer.register_event_handler(
|
||||
"klippy:connect", self._handle_connect)
|
||||
printer.register_event_handler(
|
||||
"klippy:shutdown", self._notify_shutdown)
|
||||
|
||||
def _handle_connect(self):
|
||||
gcode = self.printer.lookup_object('gcode')
|
||||
gcode.register_output_handler(self._process_gcode_response)
|
||||
|
||||
def _notify_shutdown(self):
|
||||
self.call_remote_method("set_klippy_shutdown")
|
||||
|
||||
def _process_gcode_response(self, gc_response):
|
||||
self.call_remote_method(
|
||||
"process_gcode_response", response=gc_response)
|
||||
|
||||
def register_endpoint(self, path, callback):
|
||||
if path in self._endpoints:
|
||||
raise WebRequestError("Path already registered to an endpoint")
|
||||
self._endpoints[path] = callback
|
||||
|
||||
def register_static_path(self, resource_id, file_path):
|
||||
static_path_info = {
|
||||
'resource_id': resource_id, 'file_path': file_path}
|
||||
self._static_paths.append(static_path_info)
|
||||
|
||||
def _handle_list_endpoints(self, web_request):
|
||||
web_request.send({
|
||||
'hooks': self._endpoints.keys(),
|
||||
'static_paths': self._static_paths})
|
||||
web_request.send({'endpoints': self._endpoints.keys()})
|
||||
|
||||
def _handle_info_request(self, web_request):
|
||||
if web_request.get_method() != 'GET':
|
||||
raise web_request.error("Invalid Request Method")
|
||||
state_message, state = self.printer.get_state_message()
|
||||
klipper_path = os.path.normpath(os.path.join(
|
||||
os.path.dirname(__file__), ".."))
|
||||
response = {'state': state, 'state_message': state_message,
|
||||
'hostname': socket.gethostname(),
|
||||
'klipper_path': klipper_path, 'python_path': sys.executable}
|
||||
start_args = self.printer.get_start_args()
|
||||
state_message, msg_type = self.printer.get_state_message()
|
||||
version = start_args['software_version']
|
||||
cpu_info = start_args['cpu_info']
|
||||
error = msg_type == "error"
|
||||
web_request.send(
|
||||
{'cpu': cpu_info, 'version': version,
|
||||
'hostname': socket.gethostname(),
|
||||
'is_ready': msg_type == "ready",
|
||||
'error_detected': error,
|
||||
'message': state_message})
|
||||
for sa in ['log_file', 'config_file', 'software_version', 'cpu_info']:
|
||||
response[sa] = start_args.get(sa)
|
||||
web_request.send(response)
|
||||
|
||||
def _handle_estop_request(self, web_request):
|
||||
if web_request.get_method() != 'POST':
|
||||
raise web_request.error("Invalid Request Method")
|
||||
self.printer.invoke_shutdown("Shutdown due to webhooks request")
|
||||
|
||||
def get_connection(self):
|
||||
|
@ -335,150 +301,145 @@ class WebHooks:
|
|||
raise WebRequestError(msg)
|
||||
return cb
|
||||
|
||||
def call_remote_method(self, method, **kwargs):
|
||||
self.sconn.send_all_clients({'method': method, 'params': kwargs})
|
||||
def get_status(self, eventtime):
|
||||
state_message, state = self.printer.get_state_message()
|
||||
return {'state': state, 'state_message': state_message}
|
||||
|
||||
def _action_call_remote_method(self, method, **kwargs):
|
||||
self.call_remote_method(method, **kwargs)
|
||||
return ""
|
||||
|
||||
def get_status(self, eventtime=0.):
|
||||
return {
|
||||
"action_call_remote_method": self._action_call_remote_method
|
||||
}
|
||||
class GCodeHelper:
|
||||
def __init__(self, printer):
|
||||
self.printer = printer
|
||||
self.gcode = printer.lookup_object("gcode")
|
||||
# Output subscription tracking
|
||||
self.is_output_registered = False
|
||||
self.clients = {}
|
||||
# Register webhooks
|
||||
wh = printer.lookup_object('webhooks')
|
||||
wh.register_endpoint("gcode/help", self._handle_help)
|
||||
wh.register_endpoint("gcode/script", self._handle_script)
|
||||
wh.register_endpoint("gcode/restart", self._handle_restart)
|
||||
wh.register_endpoint("gcode/firmware_restart",
|
||||
self._handle_firmware_restart)
|
||||
wh.register_endpoint("gcode/subscribe_output",
|
||||
self._handle_subscribe_output)
|
||||
def _handle_help(self, web_request):
|
||||
web_request.send(self.gcode.get_command_help())
|
||||
def _handle_script(self, web_request):
|
||||
self.gcode.run_script(web_request.get_str('script'))
|
||||
def _handle_restart(self, web_request):
|
||||
self.gcode.run_script('restart')
|
||||
def _handle_firmware_restart(self, web_request):
|
||||
self.gcode.run_script('firmware_restart')
|
||||
def _output_callback(self, msg):
|
||||
for cconn, template in list(self.clients.items()):
|
||||
if cconn.is_closed():
|
||||
del self.clients[cconn]
|
||||
continue
|
||||
tmp = dict(template)
|
||||
tmp['params'] = {'response': msg}
|
||||
cconn.send(tmp)
|
||||
def _handle_subscribe_output(self, web_request):
|
||||
cconn = web_request.get_client_connection()
|
||||
template = web_request.get_dict('response_template', {})
|
||||
self.clients[cconn] = template
|
||||
if not self.is_output_registered:
|
||||
self.gcode.register_output_handler(self._output_callback)
|
||||
self.is_output_registered = True
|
||||
|
||||
SUBSCRIPTION_REFRESH_TIME = .25
|
||||
|
||||
class StatusHandler:
|
||||
def __init__(self, webhooks):
|
||||
self.printer = webhooks.printer
|
||||
self.webhooks = webhooks
|
||||
self.ready = self.timer_started = False
|
||||
self.reactor = self.printer.get_reactor()
|
||||
self.available_objects = {}
|
||||
self.subscriptions = {}
|
||||
self.subscription_timer = self.reactor.register_timer(
|
||||
self._batch_subscription_handler, self.reactor.NEVER)
|
||||
|
||||
# Register events
|
||||
self.printer.register_event_handler(
|
||||
"klippy:ready", self._handle_ready)
|
||||
self.printer.register_event_handler(
|
||||
"gcode:request_restart", self._handle_restart)
|
||||
|
||||
class QueryStatusHelper:
|
||||
def __init__(self, printer):
|
||||
self.printer = printer
|
||||
self.clients = {}
|
||||
self.pending_queries = []
|
||||
self.query_timer = None
|
||||
self.last_query = {}
|
||||
# Register webhooks
|
||||
webhooks.register_endpoint(
|
||||
"objects/list",
|
||||
self._handle_object_request)
|
||||
webhooks.register_endpoint(
|
||||
"objects/status",
|
||||
self._handle_status_request)
|
||||
webhooks.register_endpoint(
|
||||
"objects/subscription",
|
||||
self._handle_subscription_request)
|
||||
|
||||
def _handle_ready(self):
|
||||
eventtime = self.reactor.monotonic()
|
||||
self.available_objects = {}
|
||||
objs = self.printer.lookup_objects()
|
||||
status_objs = {n: o for n, o in objs if hasattr(o, "get_status")}
|
||||
for name, obj in status_objs.items():
|
||||
attrs = obj.get_status(eventtime)
|
||||
self.available_objects[name] = attrs.keys()
|
||||
self.ready = True
|
||||
|
||||
def _handle_restart(self, eventtime):
|
||||
self.ready = False
|
||||
self.reactor.update_timer(self.subscription_timer, self.reactor.NEVER)
|
||||
|
||||
def _batch_subscription_handler(self, eventtime):
|
||||
status = self._process_status_request(self.subscriptions, eventtime)
|
||||
self.webhooks.call_remote_method(
|
||||
"process_status_update", status=status)
|
||||
return eventtime + SUBSCRIPTION_REFRESH_TIME
|
||||
|
||||
def _process_status_request(self, requested_objects, eventtime):
|
||||
result = {}
|
||||
if self.ready:
|
||||
for name, req_items in requested_objects.items():
|
||||
obj = self.printer.lookup_object(name, None)
|
||||
if obj is not None and name in self.available_objects:
|
||||
status = obj.get_status(eventtime)
|
||||
if not req_items:
|
||||
# return all items excluding callables
|
||||
result[name] = {k: v for k, v in status.items()
|
||||
if not callable(v)}
|
||||
else:
|
||||
# return requested items excluding callables
|
||||
result[name] = {k: v for k, v in status.items()
|
||||
if k in req_items and not callable(v)}
|
||||
else:
|
||||
result = {"status": "Klippy Not Ready"}
|
||||
return result
|
||||
|
||||
def _handle_object_request(self, web_request):
|
||||
if web_request.get_method() != 'GET':
|
||||
raise web_request.error("Invalid Request Method")
|
||||
web_request.send(dict(self.available_objects))
|
||||
|
||||
def _handle_status_request(self, web_request):
|
||||
if web_request.get_method() != 'GET':
|
||||
raise web_request.error("Invalid Request Method")
|
||||
args = web_request.get_args()
|
||||
eventtime = self.reactor.monotonic()
|
||||
result = self._process_status_request(args, eventtime)
|
||||
web_request.send(result)
|
||||
|
||||
def _handle_subscription_request(self, web_request):
|
||||
method = web_request.get_method()
|
||||
if method == 'POST':
|
||||
# add a subscription
|
||||
args = web_request.get_args()
|
||||
if args:
|
||||
self.add_subscripton(args)
|
||||
else:
|
||||
raise web_request.error("Invalid argument")
|
||||
else:
|
||||
# get subscription info
|
||||
result = dict(self.subscriptions)
|
||||
web_request.send(result)
|
||||
|
||||
def add_subscripton(self, new_sub):
|
||||
if not new_sub:
|
||||
return
|
||||
for obj_name, req_items in new_sub.items():
|
||||
if obj_name not in self.available_objects:
|
||||
logging.info(
|
||||
"webhooks: Object {%s} not available for subscription"
|
||||
% (obj_name))
|
||||
webhooks = printer.lookup_object('webhooks')
|
||||
webhooks.register_endpoint("objects/list", self._handle_list)
|
||||
webhooks.register_endpoint("objects/query", self._handle_query)
|
||||
webhooks.register_endpoint("objects/subscribe", self._handle_subscribe)
|
||||
def _handle_list(self, web_request):
|
||||
objects = [n for n, o in self.printer.lookup_objects()
|
||||
if hasattr(o, 'get_status')]
|
||||
web_request.send({'objects': objects})
|
||||
def _do_query(self, eventtime):
|
||||
last_query = self.last_query
|
||||
query = self.last_query = {}
|
||||
msglist = self.pending_queries
|
||||
self.pending_queries = []
|
||||
msglist.extend(self.clients.values())
|
||||
# Generate get_status() info for each client
|
||||
for cconn, subscription, send_func, template in msglist:
|
||||
is_query = cconn is None
|
||||
if not is_query and cconn.is_closed():
|
||||
del self.clients[cconn]
|
||||
continue
|
||||
# validate requested items
|
||||
if req_items:
|
||||
avail_items = set(self.available_objects[obj_name])
|
||||
invalid_items = set(req_items) - avail_items
|
||||
if invalid_items:
|
||||
logging.info(
|
||||
"webhooks: Removed invalid items [%s] from "
|
||||
"subscription request %s" %
|
||||
(", ".join(invalid_items), obj_name))
|
||||
req_items = list(set(req_items) - invalid_items)
|
||||
if not req_items:
|
||||
# No valid items remaining
|
||||
continue
|
||||
# Add or update subscription
|
||||
existing_items = self.subscriptions.get(obj_name, None)
|
||||
if existing_items is not None:
|
||||
if req_items == [] or existing_items == []:
|
||||
# Subscribe to all items
|
||||
self.subscriptions[obj_name] = []
|
||||
else:
|
||||
req_items = list(set(req_items) | set(existing_items))
|
||||
self.subscriptions[obj_name] = req_items
|
||||
else:
|
||||
self.subscriptions[obj_name] = req_items
|
||||
if not self.timer_started:
|
||||
self.reactor.update_timer(self.subscription_timer, self.reactor.NOW)
|
||||
self.timer_started = True
|
||||
# Query each requested printer object
|
||||
cquery = {}
|
||||
for obj_name, req_items in subscription.items():
|
||||
res = query.get(obj_name, None)
|
||||
if res is None:
|
||||
po = self.printer.lookup_object(obj_name, None)
|
||||
if po is None or not hasattr(po, 'get_status'):
|
||||
res = query[obj_name] = {}
|
||||
else:
|
||||
res = query[obj_name] = po.get_status(eventtime)
|
||||
if req_items is None:
|
||||
req_items = list(res.keys())
|
||||
if req_items:
|
||||
subscription[obj_name] = req_items
|
||||
lres = last_query.get(obj_name, {})
|
||||
cres = {}
|
||||
for ri in req_items:
|
||||
rd = res.get(ri, None)
|
||||
if is_query or rd != lres.get(ri):
|
||||
cres[ri] = rd
|
||||
if cres or is_query:
|
||||
cquery[obj_name] = cres
|
||||
# Send data
|
||||
if cquery or is_query:
|
||||
tmp = dict(template)
|
||||
tmp['params'] = {'eventtime': eventtime, 'status': cquery}
|
||||
send_func(tmp)
|
||||
if not query:
|
||||
# Unregister timer if there are no longer any subscriptions
|
||||
reactor = self.printer.get_reactor()
|
||||
reactor.unregister_timer(self.query_timer)
|
||||
self.query_timer = None
|
||||
return reactor.NEVER
|
||||
return eventtime + SUBSCRIPTION_REFRESH_TIME
|
||||
def _handle_query(self, web_request, is_subscribe=False):
|
||||
objects = web_request.get_dict('objects')
|
||||
# Validate subscription format
|
||||
for k, v in objects.items():
|
||||
if type(k) != str or (v is not None and type(v) != list):
|
||||
raise web_request.error("Invalid argument")
|
||||
if v is not None:
|
||||
for ri in v:
|
||||
if type(ri) != str:
|
||||
raise web_request.error("Invalid argument")
|
||||
# Add to pending queries
|
||||
cconn = web_request.get_client_connection()
|
||||
template = web_request.get_dict('response_template', {})
|
||||
if is_subscribe and cconn in self.clients:
|
||||
del self.clients[cconn]
|
||||
reactor = self.printer.get_reactor()
|
||||
complete = reactor.completion()
|
||||
self.pending_queries.append((None, objects, complete.complete, {}))
|
||||
# Start timer if needed
|
||||
if self.query_timer is None:
|
||||
qt = reactor.register_timer(self._do_query, reactor.NOW)
|
||||
self.query_timer = qt
|
||||
# Wait for data to be queried
|
||||
msg = complete.wait()
|
||||
web_request.send(msg['params'])
|
||||
if is_subscribe:
|
||||
self.clients[cconn] = (cconn, objects, cconn.send, template)
|
||||
def _handle_subscribe(self, web_request):
|
||||
self._handle_query(web_request, is_subscribe=True)
|
||||
|
||||
def add_early_printer_objects(printer):
|
||||
printer.add_object('webhooks', WebHooks(printer))
|
||||
GCodeHelper(printer)
|
||||
QueryStatusHelper(printer)
|
||||
|
|
|
@ -0,0 +1,5 @@
|
|||
*.o
|
||||
bossac/bin/
|
||||
bossac/obj/
|
||||
hidflash/hid-flash
|
||||
hub-ctrl/hub-ctrl
|
|
@ -0,0 +1,142 @@
|
|||
#!/usr/bin/env python2
|
||||
# Tool to graph temperature sensor ADC resolution
|
||||
#
|
||||
# Copyright (C) 2020 Kevin O'Connor <kevin@koconnor.net>
|
||||
#
|
||||
# This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
import sys, os, optparse
|
||||
import matplotlib
|
||||
|
||||
|
||||
######################################################################
|
||||
# Dummy config / printer / etc. class emulation
|
||||
######################################################################
|
||||
|
||||
class DummyConfig:
|
||||
def __init__(self, config_settings):
|
||||
self.config_settings = config_settings
|
||||
self.sensor_factories = {}
|
||||
# Emulate config class
|
||||
def getfloat(self, option, default, **kw):
|
||||
return self.config_settings.get(option, default)
|
||||
def get(self, option, default=None):
|
||||
return default
|
||||
def get_printer(self):
|
||||
return self
|
||||
def get_name(self):
|
||||
return "dummy"
|
||||
# Emulate printer class
|
||||
def load_object(self, config, name):
|
||||
return self
|
||||
def lookup_object(self, name):
|
||||
return self
|
||||
# Emulate heaters class
|
||||
def add_sensor_factory(self, name, factory):
|
||||
self.sensor_factories[name] = factory
|
||||
def do_create_sensor(self, sensor_type):
|
||||
return self.sensor_factories[sensor_type](self).adc_convert
|
||||
# Emulate query_adc class
|
||||
def register_adc(self, name, klass):
|
||||
pass
|
||||
# Emulate pins class
|
||||
def setup_pin(self, pin_type, pin_name):
|
||||
return self
|
||||
# Emulate mcu_adc class
|
||||
def setup_adc_callback(self, time, callback):
|
||||
pass
|
||||
|
||||
|
||||
######################################################################
|
||||
# Plotting
|
||||
######################################################################
|
||||
|
||||
def plot_adc_resolution(config, sensors):
|
||||
# Temperature list
|
||||
all_temps = [float(i) for i in range(1, 351)]
|
||||
temps = all_temps[:-1]
|
||||
# Build plot
|
||||
fig, (ax1, ax2) = matplotlib.pyplot.subplots(nrows=2, sharex=True)
|
||||
pullup = config.getfloat('pullup_resistor', 0.)
|
||||
adc_voltage = config.getfloat('adc_voltage', 0.)
|
||||
ax1.set_title("Temperature Sensor (pullup=%.0f, adc_voltage=%.3f)"
|
||||
% (pullup, adc_voltage))
|
||||
ax1.set_ylabel('ADC')
|
||||
ax2.set_ylabel('ADC change per 1C')
|
||||
for sensor in sensors:
|
||||
sc = config.do_create_sensor(sensor)
|
||||
adcs = [sc.calc_adc(t) for t in all_temps]
|
||||
ax1.plot(temps, adcs[:-1], label=sensor, alpha=0.6)
|
||||
adc_deltas = [abs(adcs[i+1] - adcs[i]) for i in range(len(temps))]
|
||||
ax2.plot(temps, adc_deltas, alpha=0.6)
|
||||
fontP = matplotlib.font_manager.FontProperties()
|
||||
fontP.set_size('x-small')
|
||||
ax1.legend(loc='best', prop=fontP)
|
||||
ax2.set_xlabel('Temperature (C)')
|
||||
ax1.grid(True)
|
||||
ax2.grid(True)
|
||||
fig.tight_layout()
|
||||
return fig
|
||||
|
||||
|
||||
######################################################################
|
||||
# Startup
|
||||
######################################################################
|
||||
|
||||
def setup_matplotlib(output_to_file):
|
||||
global matplotlib
|
||||
if output_to_file:
|
||||
matplotlib.rcParams.update({'figure.autolayout': True})
|
||||
matplotlib.use('Agg')
|
||||
import matplotlib.pyplot, matplotlib.dates, matplotlib.font_manager
|
||||
import matplotlib.ticker
|
||||
|
||||
def import_sensors(config):
|
||||
global extras
|
||||
# Load adc_temperature.py and thermistor.py modules
|
||||
kdir = os.path.join(os.path.dirname(__file__), '..', 'klippy')
|
||||
sys.path.append(kdir)
|
||||
import extras.adc_temperature, extras.thermistor
|
||||
extras.thermistor.load_config(config)
|
||||
extras.adc_temperature.load_config(config)
|
||||
|
||||
def main():
|
||||
# Parse command-line arguments
|
||||
usage = "%prog [options]"
|
||||
opts = optparse.OptionParser(usage)
|
||||
opts.add_option("-o", "--output", type="string", dest="output",
|
||||
default=None, help="filename of output graph")
|
||||
opts.add_option("-p", "--pullup", type="float", dest="pullup",
|
||||
default=4700., help="pullup resistor")
|
||||
opts.add_option("-v", "--voltage", type="float", dest="voltage",
|
||||
default=5., help="pullup resistor")
|
||||
opts.add_option("-s", "--sensors", type="string", dest="sensors",
|
||||
default="", help="list of sensors (comma separated)")
|
||||
options, args = opts.parse_args()
|
||||
if len(args) != 0:
|
||||
opts.error("Incorrect number of arguments")
|
||||
|
||||
# Import sensors
|
||||
config_settings = {'pullup_resistor': options.pullup,
|
||||
'adc_voltage': options.voltage}
|
||||
config = DummyConfig(config_settings)
|
||||
import_sensors(config)
|
||||
|
||||
# Determine sensors to graph
|
||||
if options.sensors:
|
||||
sensors = [s.strip() for s in options.sensors.split(',')]
|
||||
else:
|
||||
sensors = sorted(config.sensor_factories.keys())
|
||||
|
||||
# Draw graph
|
||||
setup_matplotlib(options.output is not None)
|
||||
fig = plot_adc_resolution(config, sensors)
|
||||
|
||||
# Show graph
|
||||
if options.output is None:
|
||||
matplotlib.pyplot.show()
|
||||
else:
|
||||
fig.set_size_inches(8, 6)
|
||||
fig.savefig(options.output)
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
|
@ -0,0 +1,89 @@
|
|||
#!/usr/bin/env python2
|
||||
# Test console for webhooks interface
|
||||
#
|
||||
# Copyright (C) 2020 Kevin O'Connor <kevin@koconnor.net>
|
||||
#
|
||||
# This file may be distributed under the terms of the GNU GPLv3 license.
|
||||
import sys, os, optparse, socket, fcntl, select, json, errno, time
|
||||
|
||||
# Set a file-descriptor as non-blocking
|
||||
def set_nonblock(fd):
|
||||
fcntl.fcntl(fd, fcntl.F_SETFL
|
||||
, fcntl.fcntl(fd, fcntl.F_GETFL) | os.O_NONBLOCK)
|
||||
|
||||
def webhook_socket_create(uds_filename):
|
||||
sock = socket.socket(socket.AF_UNIX, socket.SOCK_STREAM)
|
||||
sock.setblocking(0)
|
||||
sys.stderr.write("Waiting for connect to %s\n" % (uds_filename,))
|
||||
while 1:
|
||||
try:
|
||||
sock.connect(uds_filename)
|
||||
except socket.error as e:
|
||||
if e.errno == errno.ECONNREFUSED:
|
||||
time.sleep(0.1)
|
||||
continue
|
||||
sys.stderr.write("Unable to connect socket %s [%d,%s]\n"
|
||||
% (uds_filename, e.errno,
|
||||
errno.errorcode[e.errno]))
|
||||
sys.exit(-1)
|
||||
break
|
||||
sys.stderr.write("Connection.\n")
|
||||
return sock
|
||||
|
||||
class KeyboardReader:
|
||||
def __init__(self, uds_filename):
|
||||
self.kbd_fd = sys.stdin.fileno()
|
||||
set_nonblock(self.kbd_fd)
|
||||
self.webhook_socket = webhook_socket_create(uds_filename)
|
||||
self.poll = select.poll()
|
||||
self.poll.register(sys.stdin, select.POLLIN | select.POLLHUP)
|
||||
self.poll.register(self.webhook_socket, select.POLLIN | select.POLLHUP)
|
||||
self.kbd_data = self.socket_data = ""
|
||||
def process_socket(self):
|
||||
data = self.webhook_socket.recv(4096)
|
||||
if not data:
|
||||
sys.stderr.write("Socket closed\n")
|
||||
sys.exit(0)
|
||||
parts = data.split('\x03')
|
||||
parts[0] = self.socket_data + parts[0]
|
||||
self.socket_data = parts.pop()
|
||||
for line in parts:
|
||||
sys.stdout.write("GOT: %s\n" % (line,))
|
||||
def process_kbd(self):
|
||||
data = os.read(self.kbd_fd, 4096)
|
||||
parts = data.split('\n')
|
||||
parts[0] = self.kbd_data + parts[0]
|
||||
self.kbd_data = parts.pop()
|
||||
for line in parts:
|
||||
line = line.strip()
|
||||
if not line or line.startswith('#'):
|
||||
continue
|
||||
try:
|
||||
m = json.loads(line)
|
||||
except:
|
||||
sys.stderr.write("ERROR: Unable to parse line\n")
|
||||
continue
|
||||
cm = json.dumps(m, separators=(',', ':'))
|
||||
sys.stdout.write("SEND: %s\n" % (cm,))
|
||||
self.webhook_socket.send("%s\x03" % (cm,))
|
||||
def run(self):
|
||||
while 1:
|
||||
res = self.poll.poll(1000.)
|
||||
for fd, event in res:
|
||||
if fd == self.kbd_fd:
|
||||
self.process_kbd()
|
||||
else:
|
||||
self.process_socket()
|
||||
|
||||
def main():
|
||||
usage = "%prog [options] <socket filename>"
|
||||
opts = optparse.OptionParser(usage)
|
||||
options, args = opts.parse_args()
|
||||
if len(args) != 1:
|
||||
opts.error("Incorrect number of arguments")
|
||||
|
||||
ml = KeyboardReader(args[0])
|
||||
ml.run()
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
|
@ -73,16 +73,16 @@ gcode:
|
|||
|
||||
[gcode_macro TEST_expression]
|
||||
gcode:
|
||||
{% if printer.gcode.gcode_position.x != 0.0 %}
|
||||
{% if printer.gcode_move.gcode_position.x != 0.0 %}
|
||||
M112
|
||||
{% else %}
|
||||
{ printer.gcode.action_respond_info("TEST_expression") }
|
||||
{ action_respond_info("TEST_expression") }
|
||||
{% endif %}
|
||||
|
||||
[gcode_macro TEST_variable]
|
||||
variable_t: 12.0
|
||||
gcode:
|
||||
{ printer.gcode.action_respond_info("TEST_variable") }
|
||||
{ action_respond_info("TEST_variable") }
|
||||
{% if t - 12.0 != printer.toolhead.position.y %}
|
||||
M112
|
||||
{% endif %}
|
||||
|
@ -94,21 +94,21 @@ gcode:
|
|||
|
||||
[gcode_macro TEST_variable_part2]
|
||||
gcode:
|
||||
{ printer.gcode.action_respond_info("TEST_variable_part2") }
|
||||
{ action_respond_info("TEST_variable_part2") }
|
||||
{% if printer["gcode_macro TEST_variable"].t != 17.0 %}
|
||||
M112
|
||||
{% endif %}
|
||||
|
||||
[gcode_macro TEST_param]
|
||||
gcode:
|
||||
{ printer.gcode.action_respond_info("TEST_param") }
|
||||
{ action_respond_info("TEST_param") }
|
||||
{% if params.T != "123" %}
|
||||
M112
|
||||
{% endif %}
|
||||
|
||||
[gcode_macro TEST_in]
|
||||
gcode:
|
||||
{% if "abc" in printer or "gcode" not in printer %}
|
||||
{% if "abc" in printer or "toolhead" not in printer %}
|
||||
M112
|
||||
{% endif %}
|
||||
|
||||
|
|
|
@ -40,6 +40,7 @@ CONFIG ../../config/printer-mtw-create-2015.cfg
|
|||
CONFIG ../../config/printer-seemecnc-rostock-max-v2-2015.cfg
|
||||
CONFIG ../../config/printer-sovol-sv01-2020.cfg
|
||||
CONFIG ../../config/printer-tevo-flash-2018.cfg
|
||||
CONFIG ../../config/printer-tevo-tarantula-pro-2020.cfg
|
||||
CONFIG ../../config/printer-velleman-k8200-2013.cfg
|
||||
CONFIG ../../config/printer-wanhao-duplicator-i3-mini-2017.cfg
|
||||
CONFIG ../../config/printer-wanhao-duplicator-i3-plus-2017.cfg
|
||||
|
|
Loading…
Reference in New Issue