Full Code of nikivanov/mural for AI

main c817cd03863f cached
94 files
27.5 MB
64.7k tokens
121 symbols
1 requests
Download .txt
Showing preview only (259K chars total). Download the full file or copy to clipboard to get everything.
Repository: nikivanov/mural
Branch: main
Commit: c817cd03863f
Files: 94
Total size: 27.5 MB

Directory structure:
gitextract_5fn61nmk/

├── .devcontainer/
│   ├── Containerfile
│   └── devcontainer.json
├── .gitignore
├── .vscode/
│   ├── extensions.json
│   ├── launch.json
│   ├── settings.json
│   └── tasks.json
├── BOM.md
├── KinematicModel.md
├── LICENSE.md
├── README.md
├── STLs/
│   ├── PD clamp.stl
│   ├── black parts.3mf
│   ├── bottom.stl
│   ├── cover.stl
│   ├── idler.stl
│   ├── left belt loop.stl
│   ├── left motor carrier.stl
│   ├── mural v1.1.step
│   ├── pen.stl
│   ├── right belt loop.stl
│   ├── right motor carrier.stl
│   ├── servo clamp.stl
│   ├── servo pen driver.stl
│   └── white parts.3mf
├── build.py
├── data/
│   └── www/
│       ├── client.js
│       ├── dpad.less
│       ├── index.html
│       ├── main.css
│       ├── main.js
│       └── svgControl.js
├── images/
│   └── doc/
│       ├── kinematic_model1.drawio
│       └── tangent_point.drawio
├── include/
│   └── README
├── lib/
│   └── README
├── partitions.csv
├── platformio.ini
├── src/
│   ├── display.cpp
│   ├── display.h
│   ├── main.cpp
│   ├── movement.cpp
│   ├── movement.h
│   ├── pen.cpp
│   ├── pen.h
│   ├── phases/
│   │   ├── begindrawingphase.cpp
│   │   ├── begindrawingphase.h
│   │   ├── commandhandlingphase.cpp
│   │   ├── commandhandlingphase.h
│   │   ├── extendtohomephase.cpp
│   │   ├── extendtohomephase.h
│   │   ├── notsupportedphase.cpp
│   │   ├── notsupportedphase.h
│   │   ├── pencalibrationphase.cpp
│   │   ├── pencalibrationphase.h
│   │   ├── phase.h
│   │   ├── phasemanager.cpp
│   │   ├── phasemanager.h
│   │   ├── retractbeltsphase.cpp
│   │   ├── retractbeltsphase.h
│   │   ├── settopdistancephase.cpp
│   │   ├── settopdistancephase.h
│   │   ├── svgselectphase.cpp
│   │   └── svgselectphase.h
│   ├── runner.cpp
│   ├── runner.h
│   └── tasks/
│       ├── interpolatingmovementtask.cpp
│       ├── interpolatingmovementtask.h
│       ├── movementtask.cpp
│       ├── movementtask.h
│       ├── pentask.cpp
│       ├── pentask.h
│       └── task.h
├── test/
│   └── README
└── tsc/
    ├── package.json
    ├── src/
    │   ├── deduplicator.ts
    │   ├── flattener.ts
    │   ├── generator.ts
    │   ├── infill.ts
    │   ├── main.ts
    │   ├── measurer.ts
    │   ├── optimizer.ts
    │   ├── paperLoader.ts
    │   ├── renderer.ts
    │   ├── tester.ts
    │   ├── toCommands.ts
    │   ├── toSvgJson.ts
    │   ├── tracer.js
    │   ├── trimmer.ts
    │   ├── types.ts
    │   ├── utils.ts
    │   └── vectorizer.ts
    ├── tsconfig.json
    └── webpack.config.js

================================================
FILE CONTENTS
================================================

================================================
FILE: .devcontainer/Containerfile
================================================
ARG VARIANT=bookworm
FROM mcr.microsoft.com/vscode/devcontainers/base:${VARIANT}

ENV DEBIAN_FRONTEND=noninteractive
RUN sudo apt-get update \
 && sudo apt-get -y install --no-install-recommends \
      clang \
      python3-venv \
      udev

## Set up udev rules for PlatformIO
RUN curl -fsSL https://raw.githubusercontent.com/platformio/platformio-core/develop/platformio/assets/system/99-platformio-udev.rules | sudo tee /etc/udev/rules.d/99-platformio-udev.rules
RUN service udev restart 
RUN usermod -a -G dialout vscode
RUN usermod -a -G plugdev vscode

ARG FEDORA_COMPAT=0
### Set up compatibility with Fedora host (if needed)
### Since Fedora uses `18` as the group for dialout, we need to add it to the container
RUN if [ "$FEDORA_COMPAT" = "1" ]; then \
  sudo groupadd -g 18 compat_dialout; \
  sudo usermod -a -G compat_dialout vscode; \
fi


# Install PlatformIO CLI
USER vscode
RUN curl -fsSL -o /tmp/get-platformio.py https://raw.githubusercontent.com/platformio/platformio-core-installer/master/get-platformio.py
RUN python3 /tmp/get-platformio.py
RUN echo 'export PATH="$PATH:$HOME/.platformio/penv/bin"' | tee -a /home/vscode/.bashrc /home/vscode/.zshrc 
RUN echo 'export PATH="$PATH:$HOME/.platformio/penv/bin"' | sudo tee -a /root/.bashrc /root/.zshrc


================================================
FILE: .devcontainer/devcontainer.json
================================================
{
	"name": "PlatformIO (Community)",
	"build": {
		"dockerfile": "Containerfile",
		"context": ".",
		"args": {
			"FEDORA_COMPAT" : "1", // enables fedora compatibility mode (extra dialout group with gid 18)
			"VARIANT": "bookworm"
		}
	},
	"customizations": {
		"vscode": {
			"settings": {
				"terminal.integrated.defaultProfile.linux": "zsh"
			},
			"extensions": [
				"ms-vscode.cpptools",
				"platformio.platformio-ide"
			]
		}
	},
	"forwardPorts": [
		8008
	],
	"mounts": [
		"source=/dev/,target=/dev/,type=bind,consistency=consistent"
	],
	"runArgs": [
		"--privileged"
	],
	"features": {
		"ghcr.io/devcontainers/features/node:1": {
    		"version": "lts"
    	},
		"ghcr.io/devcontainers/features/git-lfs:1": "latest"
	},
	"postAttachCommand": "sudo service udev restart"
}

================================================
FILE: .gitignore
================================================
.pio
data/www/worker/*
tsc/node_modules
tsc/package-lock.json
tsc/dist
tsc/dist_packed
tsc/svgs/*
.DS_Store
.vscode/c_cpp_properties.json

================================================
FILE: .vscode/extensions.json
================================================
{
    // See http://go.microsoft.com/fwlink/?LinkId=827846
    // for the documentation about the extensions.json format
    "recommendations": [
        "platformio.platformio-ide"
    ],
    "unwantedRecommendations": [
        "ms-vscode.cpptools-extension-pack"
    ]
}


================================================
FILE: .vscode/launch.json
================================================
// AUTOMATICALLY GENERATED FILE. PLEASE DO NOT MODIFY IT MANUALLY
//
// PlatformIO Debugging Solution
//
// Documentation: https://docs.platformio.org/en/latest/plus/debugging.html
// Configuration: https://docs.platformio.org/en/latest/projectconf/sections/env/options/debug/index.html

{
    "version": "0.2.0",
    "configurations": [
        {
            "name": "Launch SVG Tester",
            "program": "${workspaceFolder}/tsc/dist/tester.js",
            "request": "launch",
            "skipFiles": [
                "<node_internals>/**"
            ],
            "type": "node",
            "preLaunchTask": "tsc: build - tsc/tsconfig.json",
            "env": {
                "server": "true"
            }
        },
        {
            "type": "platformio-debug",
            "request": "launch",
            "name": "PIO Debug",
            "executable": "/workspaces/mural/.pio/build/esp32dev/firmware.elf",
            "projectEnvName": "esp32dev",
            "toolchainBinDir": "/home/vscode/.platformio/packages/toolchain-xtensa-esp32/bin",
            "internalConsoleOptions": "openOnSessionStart",
            "preLaunchTask": {
                "type": "PlatformIO",
                "task": "Pre-Debug"
            }
        },
        {
            "type": "platformio-debug",
            "request": "launch",
            "name": "PIO Debug (skip Pre-Debug)",
            "executable": "/workspaces/mural/.pio/build/esp32dev/firmware.elf",
            "projectEnvName": "esp32dev",
            "toolchainBinDir": "/home/vscode/.platformio/packages/toolchain-xtensa-esp32/bin",
            "internalConsoleOptions": "openOnSessionStart"
        },
        {
            "type": "platformio-debug",
            "request": "launch",
            "name": "PIO Debug (without uploading)",
            "executable": "/workspaces/mural/.pio/build/esp32dev/firmware.elf",
            "projectEnvName": "esp32dev",
            "toolchainBinDir": "/home/vscode/.platformio/packages/toolchain-xtensa-esp32/bin",
            "internalConsoleOptions": "openOnSessionStart",
            "loadMode": "manual"
        }
    ]
}


================================================
FILE: .vscode/settings.json
================================================
{
    "files.associations": {
        "*.tcc": "cpp",
        "array": "cpp",
        "atomic": "cpp",
        "bitset": "cpp",
        "cctype": "cpp",
        "clocale": "cpp",
        "cmath": "cpp",
        "cstdarg": "cpp",
        "cstddef": "cpp",
        "cstdint": "cpp",
        "cstdio": "cpp",
        "cstdlib": "cpp",
        "cstring": "cpp",
        "ctime": "cpp",
        "cwchar": "cpp",
        "cwctype": "cpp",
        "deque": "cpp",
        "unordered_map": "cpp",
        "unordered_set": "cpp",
        "vector": "cpp",
        "exception": "cpp",
        "algorithm": "cpp",
        "functional": "cpp",
        "iterator": "cpp",
        "map": "cpp",
        "memory": "cpp",
        "memory_resource": "cpp",
        "numeric": "cpp",
        "optional": "cpp",
        "random": "cpp",
        "regex": "cpp",
        "string": "cpp",
        "string_view": "cpp",
        "system_error": "cpp",
        "tuple": "cpp",
        "type_traits": "cpp",
        "utility": "cpp",
        "fstream": "cpp",
        "initializer_list": "cpp",
        "iomanip": "cpp",
        "iosfwd": "cpp",
        "istream": "cpp",
        "limits": "cpp",
        "new": "cpp",
        "ostream": "cpp",
        "sstream": "cpp",
        "stdexcept": "cpp",
        "streambuf": "cpp",
        "cinttypes": "cpp",
        "typeinfo": "cpp"
    }
}

================================================
FILE: .vscode/tasks.json
================================================
{
	"version": "2.0.0",
	"tasks": [
		{
			"type": "typescript",
			"tsconfig": "tsc/tsconfig.json",
			"problemMatcher": [
				"$tsc"
			],
			"group": "build",
			"label": "tsc: build - tsc/tsconfig.json"
		}
	]
}

================================================
FILE: BOM.md
================================================
# Bill of Materials
All parts can be found on Amazon, AliExpress, Ebay etc. Make sure the items you're ordering match the pictures. Listed prices are the lowest I could find on AliExpress.

| Part| Reference Photo | Price | Notes
|---|---|---|---|
|NodeMCU ESP32 ESP-WROOM-32|![esp32](/images/bom/esp32.jpg)| $4 | 30 pin version
| 2x STEPPERONLINE Pancake Nema 17 motors |![nema17](/images/bom/nema17.jpg) ![nema17-dims](/images/bom/nema17-dims.jpg) | $18 | 
| 2x Stepper Motor Driver control extension boards |![driverboard](/images/bom/driverboard.jpg) | $2 |
| 2x BigTreeTech TMC2209 Stepper motor drivers |![drivers](/images/bom/tmc2209.jpg) | $14 |
| 2x GT2 Pulley 20 teeth 5mm bore 6mm shaft | ![pulley](/images/bom/pulley.jpg) ![pulley-dims](/images/bom/pulley_dims.jpg) | $2 | Make sure to get the pulley with those exact dimensions
| GT2 Timing belt 2mm pitch 6mm width | ![belt](/images/bom/belt.jpg) | $6 |
| MG90s metal gear servo | ![servo](/images/bom/mg90s.jpg) | $2 |
| USB-C PD trigger module | ![display](/images/bom/pd.jpg) | $1 |
| LM2596 step down voltage regulator | ![buck](/images/bom/buck.jpg) | $1 |
| 30W USB-C power delivery adapter | ![power](/images/bom/power.jpg) | $3 | You can use any PD adapter with at least 30W and can supply 12V 
| USB-C male-to-male 10ft cable | ![cable](/images/bom/cable.jpg) | $1 |
| M-F and F-F breadboard jumper wire 10cm and 20cm | ![wire](/images/bom/wire.jpg) | $2 |
| M3 hex bolt set | ![m3](/images/bom/m3.jpg) | $2 | You'll need 6/8/12/25 mm bolt lengths 
| 2.54m pitch male headers | ![headers](/images/bom/header.jpg) | $1 |
| M3 heat inserts | ![inserts](/images/bom/inserts.jpg) | $1 | Optional - only one is used for the pen, and you can use an M3 bolt without it
| 12mm M3 thumbscrew | ![thumbscrews](/images/bom/thumbscrews.jpg) | $1 |Optional, but sure is nicer. You only need 1 
| 10cm stepper motor cable | ![steppercable](/images/bom/steppercable.webp) | $2 | These are surprisingly hard to find, I bought mine on AliExpress. You can also simply cut and solder together the long cables that came with your steppers

================================================
FILE: KinematicModel.md
================================================
# Mural Kinematic Model

The Mural bot is suspended on two belts. As it moves across the wall it rotates slightly,
in particular it tilts towards the center as it moves to the edges of the drawing region.

In order to achieve precise drawing abilities it is essential that Mural keeps track of its
position in space. In particular, it needs to be aware of its inclination angle as it
moves around.

## Basic Model

Here, we describe the kinematic model of Mural, which is used to derive its exact location 
and orientation in space. The model is implemented in ``movement.cpp``, in particular the function ``getBeltLengths``.

The bot is modeled as a rigid body in 2D and all features are assumed to be projected onto the wall plane.
In this representation it can be modeled as two lines: One connecting the pulley tangent points
and orthogonal to it the line which goes through the pen center and the bot's center of mass $m$. The 
two lines coincide in a reference point called $Q$. 
The distance of the two tangent points is calles $s$.
The bot's mass is assumed to be concentrated into a single point (its center of gravity) which is
located in distance $d_m$ from $Q$. The pen center is located in distance $d_p$ from $Q$ .

The relevant forces in this model are: $F_L$ applied by the left pulley, $F_R$ applied by the right pulley, 
and the gravitational force $F_G$ affecting the center of mass.

![kinematic_model1](/images/doc/kinematic_model1.drawio.svg)

Assumptions:

- all mass is concentrated in a single point
- the belts masses are negligible
- the pin distance is much larger than the bot width $d_{pins} >> width_{bot}$ 

### Tangent points

In our model the belt connects to the bot in the tangent point of its pulley. Technically, this point 
is not fully stable: It rotates slightly around the pulley center as the bot tilts sideways.

In the following it is assumed that this rotation can be ignored, and the tangent point are fixed at
a $45^\circ$ belt angle.

![tangent_point](/images/doc/tangent_point.drawio.svg)

The tangent point of the left pulley is located $q$ shifted to the right and $q$ shifted up relative to the pulley center. Likewise, the right tangent point is located $q$ left of the right pulley center and $q$ above the line connecting both pulley centers.

$q$ can be calculated from the pulley diameter $d_{pulley}$ as

$q=\frac{d_{pulley}}{2\cdot \sqrt2}$

So, for a typical pulley diameter of $d_{pulley}=12.69$ mm we get $q=4.4866$ mm .

The lenght of the line connecting the tangent point is given as the distance of the pulley axes minus $2*q$ .

## Solving for the Equilibrium State

With forces $F$ affecting the Mural bot they are moving it (translation) and rotating it by generating torques. 
We are looking for the static state of the bot, in which the forces as well as the torques cancel out.
We'll find this state by updating the values describing the bot's location, the forces and the torques 
in a consecutive and decoupled manner. I.e. while computing the forces we assume there's no torque, and while 
computing the torque there's no translating force. Updating these values repeatedly and in a loop
will lead to convergence of all quantities towards their true equilibrium states.

On a top level, we run the following steps in a loop until the quantities converge:
- compute belt angles $\varphi_L$ and $\varphi_R$
- compute forces on both belts
- compute torque on mural, solve for mural inclination $\gamma$

With the result: mural inclination $\gamma$, length of both belts in wall plane, and belt forces $F_L$ and $F_R$ .

In a subsequent step, these quantities are used to compute the belt lengths in 3D. Finally, a dilation correction is applied to account for non-rigidity of the belts under force.

## Forces

In the equilibrium state the overall torque on the bot is zero and can be ignored. In this case
all forces can be assumed to be applied to a single point:

![kinematic_model_forces](/images/doc/kinematic_model_forces.jpg)

Introducing the angles $\rho = 90^\circ-\varphi_R$ and $\delta = 90^\circ-\varphi_L$ we can apply the [Law of Sines](https://en.wikipedia.org/wiki/Law_of_sines) and get:

$\frac{F_R}{F_G}=\frac{\sin(\delta)}{\sin\left( \varphi_R + \varphi_L \right)}$

$\Leftrightarrow F_R=\frac{F_G\cdot\sin(\delta)}{\sin\left( \varphi_L + \varphi_R \right)} =
\frac{F_G\cdot\cos(\varphi_L)}{\sin\left( \varphi_L + \varphi_R \right)}$

and likewise

$\frac{F_L}{F_G}=\frac{\sin(\rho)}{\sin\left( \varphi_L + \varphi_R \right)}$

$\Leftrightarrow F_L=\frac{F_G\cdot\sin(\rho)}{\sin\left( \varphi_L + \varphi_R \right)} =
\frac{F_G\cdot\cos(\varphi_R)}{\sin\left( \varphi_L + \varphi_R \right)}$


## Torques

![kinematic_model_torques](/images/doc/kinematic_model_torques.jpg)

Given the forces we can compute the torque values $T_L$ ,  $T_R$ and  $T_m$ they induce around the reference point $Q$.
What we are interested in is the bot inclination angle $\gamma$. A positive $\gamma$ means the bot tilts to the right,
while a negative $\gamma$ represents a tilt to the left.

Let's introduce the auxilliary angles $\alpha$ and $\beta$ representing the direction of the belts relative to the
line connecting the tangent points:
$\varphi_L = \alpha + \gamma$
and 
$\varphi_R = \beta - \gamma$ .

As $Q$ is located in the center between the tangent points we get $s_L = 0.5\cdot s$ and $s_R = 0.5\cdot s$.

The torque induced on the left tangent point is 

$T_L = s_L \cdot \sin(\alpha)\cdot F_L$ 

, and it is pushing the bot clockwise.

Analogously, $T_R$ is affecting the right tangent point and rotating the bot counter-clockwise around $Q$:

$T_R = s_R \cdot \sin(\beta)\cdot F_R$ 

The gravity force $F_G$ of the bot results in torque $T_m$ which is rotating it counter-clockwise (for $\gamma>0$):

$T_m = s_m \cdot F_m$ , with

$s_m = d_m \cdot \tan(\gamma)$ and

$F_m = F_g \cdot \cos(\gamma)$ .

So we get

$T_m = d_m \cdot \tan(\gamma) \cdot F_G \cdot \cos(\gamma)$

In the static state the resulting torque is zero, so

$T_R - T_L + T_m \stackrel{!}{=} 0$

, and the implementation searches numerically for a $\gamma$ which fulfills this condition.

## Tangent Points given Pen Location

As our goal is to compute the precise belt lenths, we have to compute the exact tangent point location given the outcome
of the optimization operation (see ``Movement::getLeftTangentPoint``). For the left tangent point we calculate the distance from the 
pen center in $x$ and $y$ as

$P_{LX} = s_L \cdot \cos(\gamma) - d_p \cdot \sin(\gamma)$

$P_{LY} = s_L \cdot \sin(\gamma) + d_p \cdot \cos(\gamma)$

and with these the left tangent point coordinates as

$x_{PL} = x_{pen} - P_{LX}$

$y_{PL} = y_{pen} - P_{LY}$

In the same way we get for the right pulley:


$P_{RX} = s_R \cdot \cos(\gamma) + d_p \cdot \sin(\gamma)$

$P_{RY} = s_R \cdot \sin(\gamma) - d_p \cdot \cos(\gamma)$

and

$x_{PR} = x_{pen} + P_{RX}$

$y_{PR} = y_{pen} + P_{RY}$



================================================
FILE: LICENSE.md
================================================
## Creative Commons Attribution-NonCommercial 4.0 International Public License

By exercising the Licensed Rights (defined below), You accept and agree to be bound by the terms and conditions of this Creative Commons Attribution-NonCommercial 4.0 International Public License ("Public License"). To the extent this Public License may be interpreted as a contract, You are granted the Licensed Rights in consideration of Your acceptance of these terms and conditions, and the Licensor grants You such rights in consideration of benefits the Licensor receives from making the Licensed Material available under these terms and conditions.

### Section 1 – Definitions.

a. __Adapted Material__ means material subject to Copyright and Similar Rights that is derived from or based upon the Licensed Material and in which the Licensed Material is translated, altered, arranged, transformed, or otherwise modified in a manner requiring permission under the Copyright and Similar Rights held by the Licensor. For purposes of this Public License, where the Licensed Material is a musical work, performance, or sound recording, Adapted Material is always produced where the Licensed Material is synched in timed relation with a moving image.

b. __Adapter's License__ means the license You apply to Your Copyright and Similar Rights in Your contributions to Adapted Material in accordance with the terms and conditions of this Public License.

c. __Copyright and Similar Rights__ means copyright and/or similar rights closely related to copyright including, without limitation, performance, broadcast, sound recording, and Sui Generis Database Rights, without regard to how the rights are labeled or categorized. For purposes of this Public License, the rights specified in Section 2(b)(1)-(2) are not Copyright and Similar Rights.

d. __Effective Technological Measures__ means those measures that, in the absence of proper authority, may not be circumvented under laws fulfilling obligations under Article 11 of the WIPO Copyright Treaty adopted on December 20, 1996, and/or similar international agreements.

e. __Exceptions and Limitations__ means fair use, fair dealing, and/or any other exception or limitation to Copyright and Similar Rights that applies to Your use of the Licensed Material.

f. __Licensed Material__ means the artistic or literary work, database, or other material to which the Licensor applied this Public License.

g. __Licensed Rights__ means the rights granted to You subject to the terms and conditions of this Public License, which are limited to all Copyright and Similar Rights that apply to Your use of the Licensed Material and that the Licensor has authority to license.

h. __Licensor__ means the individual(s) or entity(ies) granting rights under this Public License.

i. __NonCommercial__ means not primarily intended for or directed towards commercial advantage or monetary compensation. For purposes of this Public License, the exchange of the Licensed Material for other material subject to Copyright and Similar Rights by digital file-sharing or similar means is NonCommercial provided there is no payment of monetary compensation in connection with the exchange.

j. __Share__ means to provide material to the public by any means or process that requires permission under the Licensed Rights, such as reproduction, public display, public performance, distribution, dissemination, communication, or importation, and to make material available to the public including in ways that members of the public may access the material from a place and at a time individually chosen by them.

k. __Sui Generis Database Rights__ means rights other than copyright resulting from Directive 96/9/EC of the European Parliament and of the Council of 11 March 1996 on the legal protection of databases, as amended and/or succeeded, as well as other essentially equivalent rights anywhere in the world.

l. __You__ means the individual or entity exercising the Licensed Rights under this Public License. Your has a corresponding meaning.

### Section 2 – Scope.

a. ___License grant.___

   1. Subject to the terms and conditions of this Public License, the Licensor hereby grants You a worldwide, royalty-free, non-sublicensable, non-exclusive, irrevocable license to exercise the Licensed Rights in the Licensed Material to:

       A. reproduce and Share the Licensed Material, in whole or in part, for NonCommercial purposes only; and

       B. produce, reproduce, and Share Adapted Material for NonCommercial purposes only.

   2. __Exceptions and Limitations.__ For the avoidance of doubt, where Exceptions and Limitations apply to Your use, this Public License does not apply, and You do not need to comply with its terms and conditions.

   3. __Term.__ The term of this Public License is specified in Section 6(a).

   4. __Media and formats; technical modifications allowed.__ The Licensor authorizes You to exercise the Licensed Rights in all media and formats whether now known or hereafter created, and to make technical modifications necessary to do so. The Licensor waives and/or agrees not to assert any right or authority to forbid You from making technical modifications necessary to exercise the Licensed Rights, including technical modifications necessary to circumvent Effective Technological Measures. For purposes of this Public License, simply making modifications authorized by this Section 2(a)(4) never produces Adapted Material.

   5. __Downstream recipients.__

        A. __Offer from the Licensor – Licensed Material.__ Every recipient of the Licensed Material automatically receives an offer from the Licensor to exercise the Licensed Rights under the terms and conditions of this Public License.

        B. __No downstream restrictions.__ You may not offer or impose any additional or different terms or conditions on, or apply any Effective Technological Measures to, the Licensed Material if doing so restricts exercise of the Licensed Rights by any recipient of the Licensed Material.

   6. __No endorsement.__ Nothing in this Public License constitutes or may be construed as permission to assert or imply that You are, or that Your use of the Licensed Material is, connected with, or sponsored, endorsed, or granted official status by, the Licensor or others designated to receive attribution as provided in Section 3(a)(1)(A)(i).

b. ___Other rights.___

   1. Moral rights, such as the right of integrity, are not licensed under this Public License, nor are publicity, privacy, and/or other similar personality rights; however, to the extent possible, the Licensor waives and/or agrees not to assert any such rights held by the Licensor to the limited extent necessary to allow You to exercise the Licensed Rights, but not otherwise.

   2. Patent and trademark rights are not licensed under this Public License.

   3. To the extent possible, the Licensor waives any right to collect royalties from You for the exercise of the Licensed Rights, whether directly or through a collecting society under any voluntary or waivable statutory or compulsory licensing scheme. In all other cases the Licensor expressly reserves any right to collect such royalties, including when the Licensed Material is used other than for NonCommercial purposes.

### Section 3 – License Conditions.

Your exercise of the Licensed Rights is expressly made subject to the following conditions.

a. ___Attribution.___

   1. If You Share the Licensed Material (including in modified form), You must:

       A. retain the following if it is supplied by the Licensor with the Licensed Material:

         i. identification of the creator(s) of the Licensed Material and any others designated to receive attribution, in any reasonable manner requested by the Licensor (including by pseudonym if designated);

         ii. a copyright notice;

         iii. a notice that refers to this Public License;

         iv. a notice that refers to the disclaimer of warranties;

         v. a URI or hyperlink to the Licensed Material to the extent reasonably practicable;

       B. indicate if You modified the Licensed Material and retain an indication of any previous modifications; and

       C. indicate the Licensed Material is licensed under this Public License, and include the text of, or the URI or hyperlink to, this Public License.

   2. You may satisfy the conditions in Section 3(a)(1) in any reasonable manner based on the medium, means, and context in which You Share the Licensed Material. For example, it may be reasonable to satisfy the conditions by providing a URI or hyperlink to a resource that includes the required information.

   3. If requested by the Licensor, You must remove any of the information required by Section 3(a)(1)(A) to the extent reasonably practicable.

   4. If You Share Adapted Material You produce, the Adapter's License You apply must not prevent recipients of the Adapted Material from complying with this Public License.

### Section 4 – Sui Generis Database Rights.

Where the Licensed Rights include Sui Generis Database Rights that apply to Your use of the Licensed Material:

a. for the avoidance of doubt, Section 2(a)(1) grants You the right to extract, reuse, reproduce, and Share all or a substantial portion of the contents of the database for NonCommercial purposes only;

b. if You include all or a substantial portion of the database contents in a database in which You have Sui Generis Database Rights, then the database in which You have Sui Generis Database Rights (but not its individual contents) is Adapted Material; and

c. You must comply with the conditions in Section 3(a) if You Share all or a substantial portion of the contents of the database.

For the avoidance of doubt, this Section 4 supplements and does not replace Your obligations under this Public License where the Licensed Rights include other Copyright and Similar Rights.

### Section 5 – Disclaimer of Warranties and Limitation of Liability.

a. __Unless otherwise separately undertaken by the Licensor, to the extent possible, the Licensor offers the Licensed Material as-is and as-available, and makes no representations or warranties of any kind concerning the Licensed Material, whether express, implied, statutory, or other. This includes, without limitation, warranties of title, merchantability, fitness for a particular purpose, non-infringement, absence of latent or other defects, accuracy, or the presence or absence of errors, whether or not known or discoverable. Where disclaimers of warranties are not allowed in full or in part, this disclaimer may not apply to You.__

b. __To the extent possible, in no event will the Licensor be liable to You on any legal theory (including, without limitation, negligence) or otherwise for any direct, special, indirect, incidental, consequential, punitive, exemplary, or other losses, costs, expenses, or damages arising out of this Public License or use of the Licensed Material, even if the Licensor has been advised of the possibility of such losses, costs, expenses, or damages. Where a limitation of liability is not allowed in full or in part, this limitation may not apply to You.__

c. The disclaimer of warranties and limitation of liability provided above shall be interpreted in a manner that, to the extent possible, most closely approximates an absolute disclaimer and waiver of all liability.

### Section 6 – Term and Termination.

a. This Public License applies for the term of the Copyright and Similar Rights licensed here. However, if You fail to comply with this Public License, then Your rights under this Public License terminate automatically.

b. Where Your right to use the Licensed Material has terminated under Section 6(a), it reinstates:

   1. automatically as of the date the violation is cured, provided it is cured within 30 days of Your discovery of the violation; or

   2. upon express reinstatement by the Licensor.

   For the avoidance of doubt, this Section 6(b) does not affect any right the Licensor may have to seek remedies for Your violations of this Public License.

c. For the avoidance of doubt, the Licensor may also offer the Licensed Material under separate terms or conditions or stop distributing the Licensed Material at any time; however, doing so will not terminate this Public License.

d. Sections 1, 5, 6, 7, and 8 survive termination of this Public License.

### Section 7 – Other Terms and Conditions.

a. The Licensor shall not be bound by any additional or different terms or conditions communicated by You unless expressly agreed.

b. Any arrangements, understandings, or agreements regarding the Licensed Material not stated herein are separate from and independent of the terms and conditions of this Public License.

### Section 8 – Interpretation.

a. For the avoidance of doubt, this Public License does not, and shall not be interpreted to, reduce, limit, restrict, or impose conditions on any use of the Licensed Material that could lawfully be made without permission under this Public License.

b. To the extent possible, if any provision of this Public License is deemed unenforceable, it shall be automatically reformed to the minimum extent necessary to make it enforceable. If the provision cannot be reformed, it shall be severed from this Public License without affecting the enforceability of the remaining terms and conditions.

c. No term or condition of this Public License will be waived and no failure to comply consented to unless expressly agreed to by the Licensor.

d. Nothing in this Public License constitutes or may be interpreted as a limitation upon, or waiver of, any privileges and immunities that apply to the Licensor or You, including from the legal processes of any jurisdiction or authority.


================================================
FILE: README.md
================================================
# [getmural.me](https://getmural.me)

Please find the main documentation on https://getmural.me. 

# Additional Information

## Positioning of the Drawing on the Wall

Here's how the image is prepared and drawn:

- The user defines the pin distance as part of the setup in the UI. For example 1 meter (or 1000mm). (This is d_pins in the image below.)
- The top margin is 20% of that distance, so the top of the image will be 200mm below the line between the two pins.
- Each side also has a 20% margin, so you'll get total of 60% of the horizontal distance, or 600mm.
- Now that we have the max width (600mm). The SVG is resized so its width is 600 and the height gets resized proportionally.
- Then a processing step is performed on the SVG to figure out what to actually draw, with each SVG unit being treated as millimeter.
- Finally it's converted into a simple format for Mural to draw, containing mostly its coordinate movement commands and pen up/down. This file is then uploaded to the microcontroller and executed line by line.

![image_positioning](/images/doc/muralbot_image_positioning.svg)

## Mural's Kinematic Model

Please find the kinematic model [here](KinematicModel.md).


================================================
FILE: STLs/mural v1.1.step
================================================
[File too large to display: 27.3 MB]

================================================
FILE: build.py
================================================
import os
Import("env")

print("Transpiling TS code")
env.Execute("rm data/www/worker/* || true")
currentPath = os.getcwd()

os.chdir('./tsc')
env.Execute("npm run build")
if not os.path.exists("../data/www/worker/"):
    os.makedirs("../data/www/worker/")
env.Execute("cp dist_packed/main.js ../data/www/worker/worker.js")
os.chdir(currentPath)

================================================
FILE: data/www/client.js
================================================
export async function leftRetractDown() {
    await postCommand("l-ret");
}

export async function leftExtendDown() {
    await postCommand("l-ext");
}

export async function rightRetractDown() {
    await postCommand("r-ret");
}

export async function rightExtendDown() {
    await postCommand("r-ext");
}

export async function leftRetractUp() {
    await postCommand("l-0");
}

export async function leftExtendUp() {
    await postCommand("l-0");
}

export async function rightRetractUp() {
    await postCommand("r-0");
}

export async function rightExtendUp() {
    await postCommand("r-0");
}

async function postCommand(command) {
    $.post("/command", {command}).fail(function() {
        alert("Command failed");
        location.reload();
    });
}

================================================
FILE: data/www/dpad.less
================================================
.set {
    overflow: hidden;
    text-align: center;
   .d-pad { margin-right: 40px; }
   .d-pad, .o-pad {
      display: inline-block;
      // transform: scale(.7);
    }
  }
  .set.setbg { background: #222; }
  .set.setbg2 { background: #5f9837; }
  
  
  @dpad-radius: 17%;
  @dpad-radius-in: 20%;
  @dpad-fg: #ddd;
  @dpad-fg-hover: #eee;
  @dpad-bg: #fff;
  @arrowcolor: #aaa;
  @tri-sml-a: 13px;
  @tri-sml-b: 19px;
  @tri-lrg-a: 13px;
  @tri-lrg-b: 19px;
  @dpad-arrow-shift: 5px;
  @dpad-arrow-move: 35%;
  .d-pad {
    position: relative;
    width: 200px;
    height: 200px;
    border-radius: 48%;
    overflow: hidden;
    &:before {
      content: '';
      position: absolute;
      top: 50%;
      left: 50%;
      border-radius: 5%;       
      transform: translate(-50%, -50%);
      width: 66.6%;
      height: 66.6%;
      background: @dpad-fg;
    }
    &:after {
      content: '';
      position: absolute;
      display: none;
      z-index:2;
      width: 20%;
      height: 20%;
      top: 50%;
      left: 50%;
      background: @dpad-fg;
      border-radius: 50%;   
      transform: translate(-50%, -50%);
      transition: all .25s;
      cursor: pointer;
    }
    &:hover:after {
      width: 30%;
      height: 30%;
    }  
    a {
      display:block;
      position: absolute;
      -webkit-tap-highlight-color:  rgba(255, 255, 255, 0);
      width: 33.3%;
      height: 43%;
      line-height: 40%;
      color: #fff;
      background: @dpad-fg;
      text-align: center;  
      &:hover {
        background: @dpad-fg-hover;
      }
      &:before {
        content: '';
        position: absolute;
        width: 0;
        height: 0;
        border-radius: 5px;
        border-style: solid;     
        transition: all .25s;
      }
      &:after {
        content: '';
        position: absolute;
        width: 102%;
        height: 78%;
        background: @dpad-bg;
        border-radius: @dpad-radius-in;
      }    
    }
    a.left, a.right {
      width: 43%;
      height: 33%;
      &:after {
        width: 78%;
        height: 102%;
      }    
    }
    
    a.up {
      top: 0;
      left: 50%;
      transform: translate(-50%, 0);
      border-radius: @dpad-radius @dpad-radius 50% 50%;
      &:hover {
        background: linear-gradient(0deg, @dpad-fg 0%, @dpad-fg-hover 50%);
      }
      &:after {
        left: 0;
        top: 0;
        transform: translate(-100%, 0);
        border-top-left-radius: 50%;
        pointer-events: none;
      }
      &:before {
        top: 40%;
        left: 50%;
        transform: translate(-50%, -50%);
        border-width: 0 @tri-sml-a @tri-sml-b @tri-sml-a;
        border-color: transparent transparent @arrowcolor transparent;
      }
      &:active:before {
        border-bottom-color: #333;
      }
    }
    a.up:hover:before { top: @dpad-arrow-move; }
    
    a.down {
      bottom: 0;
      left: 50%;    
      transform: translate(-50%, 0);
      border-radius: 50% 50% @dpad-radius @dpad-radius; 
      &:hover {
        background: linear-gradient(180deg, @dpad-fg 0%, @dpad-fg-hover 50%);
      }
      &:after {
        right: 0;
        bottom: 0;
        transform: translate(100%, 0);
        border-bottom-right-radius: 50%;
        pointer-events: none;
      }
      &:before {
        bottom: 40%;
        left: 50%;
        transform: translate(-50%, 50%);
        border-width: @tri-sml-b @tri-sml-a 0px @tri-sml-a;
        border-color: @arrowcolor transparent transparent transparent;
      }
      &:active:before {
        border-top-color: #333;
      }
    }
    a.down:hover:before { bottom: @dpad-arrow-move; }
    
    a.left {
      top: 50%;
      left: 0;    
      transform: translate(0, -50%);
      border-radius: @dpad-radius 50% 50% @dpad-radius;
      &:hover {
        background: linear-gradient(-90deg, @dpad-fg 0%, @dpad-fg-hover 50%);
      }
      &:after {
        left: 0;
        bottom: 0;
        transform: translate(0, 100%);
        border-bottom-left-radius: 50%;
        pointer-events: none;
      }
      &:before {
        left: 40%;
        top: 50%;
        transform: translate(-50%, -50%);
        border-width: @tri-sml-a @tri-sml-b @tri-sml-a 0;
        border-color: transparent @arrowcolor transparent transparent;
      }
      &:active:before {
        border-right-color: #333;
      }
    }
    a.left:hover:before { left: @dpad-arrow-move; }
    
    a.right {
      top: 50%;
      right: 0;    
      transform: translate(0, -50%);  
      border-radius: 50% @dpad-radius @dpad-radius 50%;
      &:hover {
        background: linear-gradient(90deg, @dpad-fg 0%, @dpad-fg-hover 50%);
      }
      &:after {
        right: 0;
        top: 0;
        transform: translate(0, -100%);
        border-top-right-radius: 50%;      
        pointer-events: none;
      }
      &:before {
        right: 40%;
        top: 50%;
        transform: translate(50%, -50%);
        border-width: @tri-sml-a 0 @tri-sml-a @tri-sml-b;
        border-color: transparent transparent transparent @arrowcolor;
      }
      &:active:before {
        border-left-color: #333;
      }
    }
    a.right:hover:before { right: @dpad-arrow-move; }  
  }
  .d-pad.up a.up:before { border-bottom-color: #333; }
  .d-pad.down a.down:before { border-top-color: #333; }
  .d-pad.left a.left:before { border-right-color: #333; }
  .d-pad.right a.right:before { border-left-color: #333; }
  
  .blue {
    @c: #1843ca;
    @c-h: #143cb9;
    @c-t: #ccc;
    @c-t-a: rgba(255,255,255,1);
    .d-pad {    
      &:before, a { background: @c; }
      &:after { display: block; background: @c-t; } 
      a:after { border-radius: 10%; }
      a.up:hover { background: linear-gradient(0deg, @c 0%, @c-h 50%); }
      a.right:hover { background: linear-gradient(90deg, @c 0%, @c-h 50%); }
      a.down:hover { background: linear-gradient(180deg, @c 0%, @c-h 50%); }
      a.left:hover { background: linear-gradient(-90deg, @c 0%, @c-h 50%); }
      a.up:before { border-bottom-color: @c-t; }
      a.right:before { border-left-color: @c-t; }    
      a.down:before { border-top-color: @c-t; }
      a.left:before { border-right-color: @c-t; }
      a.up:active:before { border-bottom-color: @c-t-a; }
      a.right:active:before { border-left-color: @c-t-a; }    
      a.down:active:before { border-top-color: @c-t-a; }
      a.left:active:before { border-right-color: @c-t-a; }
    }
  }
  
  // set direction active state
  
  .d-pad.up a.up:before { border-bottom-color: #333; }
  .d-pad.down a.down:before { border-top-color: #333; }
  .d-pad.left a.left:before { border-right-color: #333; }
  .d-pad.right a.right:before { border-left-color: #333; }
  
  .o-pad.up a.up:after { border-bottom-color: #333; }
  .o-pad.down a.down:after { border-top-color: #333; }
  .o-pad.left a.left:after { border-right-color: #333; }
  .o-pad.right a.right:after { border-left-color: #333; }

================================================
FILE: data/www/index.html
================================================
<!doctype html>
<html lang="en">

<head>
  <meta charset="utf-8">
  <meta name="viewport" content="width=device-width, initial-scale=1">
  <title>Mural</title>
  <link href="https://cdn.jsdelivr.net/npm/bootstrap@5.2.0/dist/css/bootstrap.min.css" rel="stylesheet"
    integrity="sha384-gH2yIJqKdNHPEq0n4Mqa/HGKIhSkIHeL5AyhkYV8i59U5AR6csBvApHHNl/vI1Bx" crossorigin="anonymous">
  <link rel="stylesheet" href="https://cdn.jsdelivr.net/npm/bootstrap-icons@1.9.1/font/bootstrap-icons.css">
  <link rel="stylesheet/less" type="text/css" href="dpad.less" />
  <link href="main.css" rel="stylesheet">
  <style>
    .bd-placeholder-img {
      font-size: 1.125rem;
      text-anchor: middle;
      -webkit-user-select: none;
      -moz-user-select: none;
      user-select: none;
    }

    @media (min-width: 768px) {
      .bd-placeholder-img-lg {
        font-size: 3.5rem;
      }
    }

    .b-example-divider {
      height: 3rem;
      background-color: rgba(0, 0, 0, .1);
      border: solid rgba(0, 0, 0, .15);
      border-width: 1px 0;
      box-shadow: inset 0 .5em 1.5em rgba(0, 0, 0, .1), inset 0 .125em .5em rgba(0, 0, 0, .15);
    }

    .b-example-vr {
      flex-shrink: 0;
      width: 1.5rem;
      height: 100vh;
    }

    .bi {
      vertical-align: -.125em;
      fill: currentColor;
    }

    .nav-scroller {
      position: relative;
      z-index: 2;
      height: 2.75rem;
      overflow-y: hidden;
    }

    .nav-scroller .nav {
      display: flex;
      flex-wrap: nowrap;
      padding-bottom: 1rem;
      margin-top: -1px;
      overflow-x: auto;
      text-align: center;
      white-space: nowrap;
      -webkit-overflow-scrolling: touch;
    }
  </style>
</head>

<body class="text-center">
  <script src="https://cdn.jsdelivr.net/npm/bootstrap@5.2.0/dist/js/bootstrap.bundle.min.js"
    integrity="sha384-A3rJD856KowSb7dwlZdYEkO39Gagi7vIsF0jrRAoQmDKKtQBHUuLZ9AsSv4jD4Xa"
    crossorigin="anonymous"></script>
  <script src="https://code.jquery.com/jquery-3.6.0.min.js" crossorigin="anonymous"></script>
  <script src="https://cdnjs.cloudflare.com/ajax/libs/jquery-throttle-debounce/1.1/jquery.ba-throttle-debounce.min.js" crossorigin="anonymous"></script>
  <script src="https://cdn.jsdelivr.net/npm/less" ></script>
  <script src="https://cdnjs.cloudflare.com/ajax/libs/paper.js/0.12.17/paper-full.min.js" integrity="sha512-NApOOz1j2Dz1PKsIvg1hrXLzDFd62+J0qOPIhm8wueAnk4fQdSclq6XvfzvejDs6zibSoDC+ipl1dC66m+EoSQ==" crossorigin="anonymous" referrerpolicy="no-referrer"></script>
  <script src="main.js" type="module"></script>
  <main class="form-signin w-100 m-auto">
      <div id="loadingSlide" class="muralSlide" style="display:none;">
        <div class="spinner-border mb-5 loading" role="status"></div>
      </div>
      <div id="retractBeltsSlide" class="muralSlide" style="display:none;">
        <h3 class="mb-2 fw-normal">Retract belts</h3>
        <h6 class="mb-5"><small class="text-muted">Place the belt loops on the homing screws and retract the belts until the motors stall. Don't let the motors stall for too long.</small></h6>
        <div class="form-check form-switch mb-5">
          <input class="form-check-input" style="transform: scale(2);" type="checkbox" role="switch" id="leftMotorToggle">
          <label class="form-check-label" for="leftMotorToggle">Left motor</label>
        </div>
        <div class="form-check form-switch mb-5">
          <input class="form-check-input" style="transform: scale(2);" type="checkbox" role="switch" id="rightMotorToggle">
          <label class="form-check-label" for="rightMotorToggle">Right motor</label>
        </div>
        <button class="w-100 btn btn-lg btn-primary mb-5" id="beltsRetracted">Belts are retracted</button>
      </div>
      <div id="distanceBetweenAnchorsSlide" class="muralSlide" style="display:none;">
        <h3 class="mb-2 fw-normal">Distance between hangers</h3>
        <h6 class="mb-5"><small class="text-muted">Distance between the two nails on which you are hanging Mural, in millimeters</small></h6>
        <input type="number" class="form-control mb-5" id="distanceInput">
        <button class="w-100 btn btn-lg btn-primary mb-5" id="setDistance">Set distance</button>
        <div style="position:fixed; top: 10px; right: 10px;" data-bs-toggle="modal" data-bs-target="#toolsModal"><i class="bi-gear fs-2"></i></div>
      </div>
      <div id="extendToHomeSlide" class="muralSlide" style="display:none;">
        <h3 class="mb-2 fw-normal">Extend belts</h3>
        <h6 class="mb-5"><small class="text-muted">The belts will extend to their home position. Make sure the belts are unobstructed and the motors do not skip, or the drawing accuracy may be affected</small></h6>
        <button class="w-100 btn btn-lg btn-primary mb-5" id="extendToHome">Extend to home position</button>
        <div class="spinner-border mb-5 loading" id="extendingSpinner" role="status" style="visibility:hidden;"></div>
      </div>
      <div id="penCalibrationSlide" class="muralSlide" style="display:none;">
        <h3 class="mb-2 fw-normal">Pen calibration</h3>
        <h6 class="mb-5"><small class="text-muted">Insert the pen so it's close to, but not touching the wall and secure it with a bolt. Then, adjust the pen position so the pen is touching the wall</small></h6>
        <input type="range" class="form-range mb-5 text-center" min="0" max="90" id="servoRange" value="0">
        <div class="btn-group mb-3 btn-group-lg" role="group">
          <div class="btn-group me-3" role="group">
            <button type="button" class="btn btn-primary fs-4" id="penMinus">-</button>
          </div>
          <div class="btn-group me-3" role="group">
            <button type="button" class="btn btn-primary fs-4" id="penPlus">+</button>
          </div>
        </div>
        <button class="w-100 btn btn-lg btn-primary mb-5" id="setPenDistance">Pen is touching the wall</button>
      </div>
      <div id="svgUploadSlide" class="muralSlide" style="display:none;">
        <h3 class="mb-2 fw-normal">Select SVG Image</h3>
        <h6 class="mb-2"><small class="text-muted">Use black and white line art SVGs for now</small></h6>
        <img id="sourceSvg" class="img-thumbnail mb-2 svg-control" style="display:none;width:100%;">
        <div class="container svg-control mb-2" style="display: none;">
          <div class="row">
            <div class="col-10 align-self-center">
              <div class="set blue">
                <nav class="d-pad">
                  <a class="up" href="#"></a>
                  <a class="right" href="#"></a>
                  <a class="down" href="#"></a>
                  <a class="left" href="#"></a>  
                </nav>
              </div>
            </div>
            <div class="col-2 align-self-center">
              <button type="button" class="btn btn-primary mb-2" id="zoomIn"><i class="bi-zoom-in fs-2"></i></button>
              <button type="button" class="btn btn-primary mb-2" id="zoomOut"><i class="bi-zoom-out fs-2"></i></button>
              <button type="button" class="btn btn-primary" id="resetTransform"><i class="bi-arrow-counterclockwise fs-2"></i></button>
            </div>
          </div>
          <div class="row">
            <h6><small class="text-muted" id="transformText"></small></h6>
          </div>
        </div>
        <input class="form-control form-control-lg mb-2" id="uploadSvg" type="file" accept=".svg">
        <button class="w-100 btn btn-lg btn-primary mb-6" id="preview" disabled>Preview drawing</button>
      </div>
      <div id="chooseRendererSlide" class="muralSlide" style="display:none;">
        <h3 class="mb-2 fw-normal">Choose render type</h3>
        <button class="w-100 btn btn-lg btn-primary mb-5 mt-5" id="pathTracing">Path Tracing<br/><sub>Works well for most drawings</sub></button>
        <button class="w-100 btn btn-lg btn-primary mb-5" id="vectorRasterVector">Vector → Raster → Vector<br/><sub>Preserves stroke width</sub></button>
        <button class="w-100 btn btn-lg btn-secondary mt-3 backToSvgSelect">Back</button>
      </div>
      <div id="drawingPreviewSlide" class="muralSlide" style="display:none;">
        <h3 class="mb-2 fw-normal">Drawing preview</h3>
        <img id="previewSvg" class="img-thumbnail mb-2 svg-preview" style="display:none;">
        <div class="progress mb-2" style="height: 20px;">
          <div class="progress-bar progress-bar-striped progress-bar-animated" role="progressbar" id="progressBar" style="width: 100%;" aria-valuenow="100" aria-valuemin="0" aria-valuemax="100"></div>
        </div>
        <h6 class="mb-2 fw-normal svg-preview" style="display: none;" id="distances"></h6>
        <label for="infillDensity" class="form-label mb-0">Infill Density</label>
        <input type="range" class="form-range mb-2 text-center" min="0" max="4" step="1" id="infillDensity" value="0">
        <label for="turdSize" class="form-label mb-0">Despeckle</label>
        <input type="range" class="form-range mb-2 text-center" min="2" max="200" step="11" id="turdSize" value="2">
        <input class="form-check-input mb-2" type="checkbox" id="flattenPathsCheckbox">
        <label class="form-check-label" for="flattenPathsCheckbox">Flatten paths</label>
        <button class="w-100 btn btn-lg btn-primary mb-2" id="acceptSvg" disabled>Accept</button>
        <button class="w-100 btn btn-lg btn-secondary mb-5 backToSvgSelect">Back</button>
      </div>
      <div id="uploadProgress" class="muralSlide" style="display:none;">
        <h3 class="mb-2 fw-normal">Uploading...</h3>
        <div class="progress mb-2" id="uploadProgress" role="progressbar" aria-label="Upload progress" aria-valuenow="0" aria-valuemin="0" aria-valuemax="100">
          <div class="progress-bar" style="width: 0%"></div>
        </div>
        <div class="progress mb-2" id="verificationProgress" role="progressbar" aria-label="Verification progress" aria-valuenow="0" aria-valuemin="0" aria-valuemax="100">
          <div class="progress-bar bg-success" style="width: 0%"></div>
        </div>
      </div>
      <div id="beginDrawingSlide" class="muralSlide" style="display: none;">
        <h3 class="mb-5 fw-normal">Mural is ready!</h3>
        <button class="w-100 btn btn-lg btn-primary mb-5" id="beginDrawing">Begin Drawing</button>
        <button class="w-100 btn btn-lg btn-secondary mb-5" id="reset">Reset</button>
      </div>
      <div id="drawingBegan" class="muralSlide" style="display: none;">
        <h3 class="mb-2 fw-normal">Drawing Started</h3>
        <h6 class="mb-5"><small class="text-muted">Mural will not be accessible via your browser while the drawing is in progress. Please refresh the page once the drawing is finished.</small></h6>
      </div>
      <div class="mt-5"><a href="https://github.com/nikivanov/mural" class="link-primary">Mural</a></div>
  </main>
  <div class="modal fade" id="toolsModal" tabindex="-1" role="dialog" aria-labelledby="toolsModalLabel" aria-hidden="true">
    <div class="modal-dialog" role="document">
      <div class="modal-content">
        <div class="modal-header">
          <h5 class="modal-title" id="toolsModalLabel">Tools</h5>
          <button type="button" class="btn-close" data-bs-dismiss="modal" aria-label="Close"></button>
        </div>
        <div class="modal-body">
          <label for="leftMotorTool" class="form-label">Left Motor</label>
          <input type="range" class="form-range mb-5 text-center" min="-1" max="1" id="leftMotorTool" value="0">
          <label for="rightMotorTool" class="form-label">Right Motor</label>
          <input type="range" class="form-range mb-5 text-center" min="-1" max="1" id="rightMotorTool" value="0">
          <button class="w-100 btn btn-lg btn-primary mb-5" id="parkServoTool">Park Servo</button>
          <button class="w-100 btn btn-lg btn-primary mb-5" id="estepsTool">Extend 1000mm (E-steps calibration)</button>
        </div>
        <div class="modal-footer">
          <button type="button" class="btn btn-primary" data-bs-dismiss="modal">Close</button>
        </div>
      </div>
    </div>
  </div>
  
</body>

</html>

================================================
FILE: data/www/main.css
================================================
html,
body {
  height: 100%;
}

body {
  display: flex;
  align-items: center;
  padding-top: 40px;
  padding-bottom: 40px;
  background-color: #f5f5f5;
}

.form-signin {
  max-width: 330px;
  padding: 15px;
}


================================================
FILE: data/www/main.js
================================================
import * as svgControl from './svgControl.js';
import * as client from './client.js';

let currentState = null;

let currentWorker = null;

window.onload = function () {
    init();
};

let uploadConvertedCommands = null;

async function checkIfExtendedToHome(extendToHomeTime) {
    await new Promise(r => setTimeout(r, extendToHomeTime * 1000));

    const waitPeriod = 2000;
    let done = false;
    while (!done) {
        try {
            const state = await $.get("/getState");
            if (state.phase !== 'ExtendToHome') {
                adaptToState(state);
                done = true;
            } else {
                await new Promise(r => setTimeout(r, waitPeriod));
            }
        } catch (err) {
            alert("Failed to get current phase: " + err);
            location.reload();
        }
    }
}

function init() {
    function doneWithPhase(custom) {
        $(".muralSlide").hide();
        $("#loadingSlide").show();
        if (!custom) {
            custom = {
                url: "/doneWithPhase",
                data: {},
                commandName: "Done With Phase",
            };
        }

        $.post(custom.url, custom.data || {}, function(state) {
            adaptToState(state);
        }).fail(function() {
            alert(`${custom.commandName} command failed`);
            location.reload();
        });
    }

    $("#beltsRetracted").click(async function() { 
        await client.leftRetractUp();
        await client.rightRetractUp();
        doneWithPhase();
    });

    $("#setDistance").click(function() {
        const inputValue = parseInt($("#distanceInput").val());
        if (isNaN(inputValue)) {
            throw new Error("input value is not a number");
        }

        doneWithPhase({
            url: "/setTopDistance",
            data: {distance: inputValue},
            commandName: "Set Top Distance",
        });
    });

    $("#leftMotorToggle").change(function() {
        if (this.checked) {
            client.leftRetractDown(); 
        } else {
            client.leftRetractUp();
        }
    });

    $("#rightMotorToggle").change(function() {
        if (this.checked) {
            client.rightRetractDown(); 
        } else {
            client.rightRetractUp();
        }
    });

    $("#extendToHome").click(function() {
        $(this).prop( "disabled", true);
        $("#extendingSpinner").css('visibility', 'visible');
        $.post("/extendToHome", {})
        .always(async function(res) {
            const extendToHomeTime = parseInt(res);
            await checkIfExtendedToHome(extendToHomeTime);
        });
    });
    
    function getServoValueFromInputValue() {
        const inputValue = parseInt($("#servoRange").val());
        const value = 90 - inputValue;
        let normalizedValue;
        if (value < 0) {
            normalizedValue = 0;
        } else if (value > 90) {
            normalizedValue = 90;
        } else {
            normalizedValue = value;
        }

        return normalizedValue;
    }

    $("#servoRange").on('input', $.throttle(250, function (e) {
        const servoValue = getServoValueFromInputValue();
        $.post("/setServo", {angle: servoValue});
    }));

    const stepVaule = 5;
    $("#penMinus").click(function() {
        $("#servoRange")[0].stepDown(stepVaule);
        $("#servoRange").trigger('input');
    });

    $("#penPlus").click(function() {
        $("#servoRange")[0].stepUp(stepVaule);
        $("#servoRange").trigger('input');
    });

    $("#setPenDistance").click(function () {
        const inputValue = getServoValueFromInputValue();
        doneWithPhase({
            url: "/setPenDistance",
            data: {angle: inputValue},
            commandName: "Set Pen Distance",
        });
    });

    async function getUploadedSvgString() {
        const [file] = $("#uploadSvg")[0].files;
        if (file) {
            return await file.text();
        } else {
            return null;
        }
    }

    $("#uploadSvg").change(async function() {
        const svgString = await getUploadedSvgString();
        if (svgString) {
            svgControl.setSvgString(svgString, currentState);

            $(".svg-control").show();
            $("#preview").removeAttr("disabled");
        } else {
            $("#preview").attr("disabled", "disabled");
            $(".svg-control").hide();
            $("#infillDensity").val(0);
            $("#turdSize").val(2);
        }
    });

    
    let currentPreviewId = 0;
    let rendererFn = null;

    async function render_VectorRasterVector() {
        if (currentWorker) {
            console.log("Terminating previous worker");
            currentWorker.terminate();
        }
        currentPreviewId++;
        const thisPreviewId = currentPreviewId;

        const svgString = await getUploadedSvgString();
        if (!svgString) {
            throw new Error('No SVG string');
        }

        $("#progressBar").text("Rasterizing");
        const raster = await svgControl.getCurrentSvgImageData();

        const vectorizeRequest = {
            type: 'vectorize',
            raster,
            turdSize: getTurdSize(),
        };

        if (currentPreviewId == thisPreviewId) {
            currentWorker = new Worker(`./worker/worker.js?v=${Date.now()}`);

            currentWorker.onmessage = (e) => {
                if (e.data.type === 'status') {
                    $("#progressBar").text(e.data.payload);
                } else if (e.data.type === 'vectorizer') {
                    const vectorizedSvg = e.data.payload.svg;
                    const scale = svgControl.getRenderScale();
                    renderSvgInWorker(
                        currentWorker,
                        vectorizedSvg,
                        svgControl.getTargetWidth() * scale,
                        svgControl.getTargetHeight() * scale,
                    );
                }
                else if (e.data.type === 'log') {
                    console.log(`Worker: ${e.data.payload}`);
                }
            }

            currentWorker.postMessage(vectorizeRequest);
        }
    }

    async function render_PathTracing() {
        if (currentWorker) {
            console.log("Terminating previous worker");
            currentWorker.terminate();
        }
        currentPreviewId++;
        const thisPreviewId = currentPreviewId;

        const svgString = await getUploadedSvgString();
        if (!svgString) {
            throw new Error('No SVG string');
        }

        if (currentPreviewId == thisPreviewId) {
            currentWorker = new Worker(`./worker/worker.js?v=${Date.now()}`);
            currentWorker.onmessage = (e) => {
                if (e.data.type === 'status') {
                    $("#progressBar").text(e.data.payload);
                }
                else if (e.data.type === 'log') {
                    console.log(`Worker: ${e.data.payload}`);
                }
            }

            const renderSvg = svgControl.getRenderSvg();
            const renderSvgString = new XMLSerializer().serializeToString(renderSvg);
            renderSvgInWorker(currentWorker, renderSvgString, svgControl.getTargetWidth(), svgControl.getTargetHeight());
        }
    }

    function renderSvgInWorker(worker, svg, svgWidth, svgHeight) {
        const svgJson = svgControl.getSvgJson(svg);
       
        const renderRequest = {
            type: "renderSvg",
            svgJson,
            width: svgControl.getTargetWidth(),
            height: svgControl.getTargetHeight(),
            svgWidth,
            svgHeight,
            homeX: currentState.homeX,
            homeY: currentState.homeY,
            infillDensity: getInfillDensity(),
            flattenPaths: getFlattenPaths(),
        }

        worker.onmessage = (e) => {
            if (e.data.type === 'status') {
                $("#progressBar").text(e.data.payload);
            } else if (e.data.type === 'renderer') {
                console.log("Worker finished!");

                uploadConvertedCommands = e.data.payload.commands.join('\n');
                const resultSvgJson = e.data.payload.svgJson;
                const resultDataUrl = svgControl.convertJsonToDataURL(resultSvgJson, svgControl.getTargetWidth(), svgControl.getTargetHeight());

                const totalDistanceM = +(e.data.payload.distance / 1000).toFixed(1);
                const drawDistanceM = +(e.data.payload.drawDistance / 1000).toFixed(1);
                
                deactivateProgressBar();
                $("#previewSvg").attr("src", resultDataUrl);
                $("#distances").text(`Total: ${totalDistanceM}m / Draw: ${drawDistanceM}m`);
                $(".svg-preview").show();
                $("#acceptSvg").removeAttr("disabled");
            }
        };

        worker.postMessage(renderRequest);
    }

    function activateProgressBar() {
        const bar = $("#progressBar");
        bar.addClass("progress-bar-striped");
        bar.addClass("progress-bar-animated");
        bar.removeClass("bg-success");
        bar.text("");
    }

    function deactivateProgressBar() {
        const bar = $("#progressBar");
        bar.removeClass("progress-bar-striped");
        bar.removeClass("progress-bar-animated");
        bar.addClass("bg-success");
        bar.text("Success");
    }


    $("#infillDensity,#turdSize,#flattenPathsCheckbox").on('input change', async function() {
        activateProgressBar();
        $("#acceptSvg").attr("disabled", "disabled");
        await rendererFn();
    });

    $("#preview").click(async function() {
        $("#svgUploadSlide").hide();
        $("#chooseRendererSlide").show();
    });

    $("#pathTracing").click(async function() {
        $("label[for='turdSize'],#turdSize").hide();
        $("label[for='flattenPathsCheckbox'],#flattenPathsCheckbox").show();

        $("#chooseRendererSlide").hide();
        $("#drawingPreviewSlide").show();
        rendererFn = render_PathTracing;
        await rendererFn();
    });

    $("#vectorRasterVector").click(async function() {
        $("#flattenPathsCheckbox").prop("checked", false);
        $("label[for='turdSize'],#turdSize").show();
        $("label[for='flattenPathsCheckbox'],#flattenPathsCheckbox").hide();

        $("#chooseRendererSlide").hide();
        $("#drawingPreviewSlide").show();
        rendererFn = render_VectorRasterVector;
        await rendererFn();
    });

    $(".backToSvgSelect").click(function() {
        uploadConvertedCommands = null;

        $(".loading").show();
        activateProgressBar();
        $("#previewSvg").removeAttr("src");
        $(".svg-preview").hide();
        $("#acceptSvg").attr("disabled", "disabled");

        $("#svgUploadSlide").show();
        $("#drawingPreviewSlide").hide();
        $("#chooseRendererSlide").hide();
    });
    
    $("#acceptSvg").click(function() {
        if (!uploadConvertedCommands) {
            throw new Error('Commands are empty');
        }
        $("#acceptSvg").attr("disabled", "disabled");

        const commandsBlob = new Blob([uploadConvertedCommands], {
            type: "text/plain"
        });

        $(".muralSlide").hide();
        $("#uploadProgress").show();

        const formData = new FormData();
        formData.append("commands", commandsBlob);

        $.ajax({
            url: "/uploadCommands",
            data: formData,
            processData: false,
            contentType: false,
            type: 'POST',
            success: function(data) {
                verifyUpload(data);
            },
            error: function(err) {
                alert('Upload to Mural failed! ' + err);
                window.location.reload();
            },
            xhr: function () {
                var xhr = new window.XMLHttpRequest();

                xhr.upload.addEventListener("progress", function (evt) {
                    if (evt.lengthComputable) {
                        var percentComplete = evt.loaded / evt.total;
                        percentComplete = parseInt(percentComplete * 100);
                        $("#uploadProgress").attr("aria-valuemax", evt.total.toString());
                        $("#uploadProgress").attr("aria-valuenow", evt.loaded.toString());
                        $("#uploadProgress > .progress-bar").attr("style", `width: ${percentComplete}%`);
                    }
                }, false);

                return xhr;
            },
        });
    });



    $("#beginDrawing").click(function() {
        $(".muralSlide").hide();
        $("#drawingBegan").show();
        $.post("/run", {});
    });

    $("#reset").click(function() {
        doneWithPhase();
        location.reload();
    });

    $("#leftMotorTool").on('input', function() {
        const leftMotorDir = parseInt($("#leftMotorTool").val());
        if (leftMotorDir <= -1) {
            client.leftRetractDown(); 
        } else if (leftMotorDir >= 1) {
            client.leftExtendDown();
        } else {
            client.leftRetractUp();
        }
    });

    $("#rightMotorTool").on('input', function() {
        const rightMotorDir = parseInt($("#rightMotorTool").val());
        if (rightMotorDir <= -1) {
            client.rightRetractDown(); 
        } else if (rightMotorDir >= 1) {
            client.rightExtendDown();
        } else {
            client.rightRetractUp();
        }
    });

    $("#parkServoTool").click(function() {
        $.post("/setServo", {angle: 0});
    });

    $("#estepsTool").click(function() {
        $.post("/estepsCalibration", {});
    });

    const toolsModal = $("#toolsModal")[0];

    toolsModal.addEventListener('hidden.bs.modal', function (event) {
        client.rightRetractUp();
        client.leftRetractUp();
    });

    svgControl.initSvgControl();

    $("#loadingSlide").show();

    // adaptToState({
    //     phase: "BeginDrawing",
    //     topDistance: 1727,
    //     safeWidth: 1000,
    //     homeX: 0,
    //     homeY: 0,
    // });

    $.get("/getState", function(data) {
        adaptToState(data);
    }).fail(function() {
        alert("Failed to retrieve state");
    });
}

function verifyUpload(state) {
    $.ajax({
            url: "/downloadCommands",
            processData: false,
            contentType: false,
            type: 'GET',
            success: function(data) {
                const receivedData = data.split('\n');
                const sentData = uploadConvertedCommands.split('\n');
                if (receivedData.length !== sentData.length) {
                    alert("Data verification failed");
                    window.location.reload();
                    return;
                }
                for (let i = 0; i < receivedData.length; i++) {
                    if (receivedData[i] !== sentData[i]) {
                        alert("Data verification failed");
                        window.location.reload();
                        return;
                    }
                }
                setTimeout(function() {
                    adaptToState(state);
                }, 1000);
            },
            error: function(err) {
                alert('Failed to download commands from Mural! ' + err);
                window.location.reload();
            },
            xhr: function () {
                var xhr = new window.XMLHttpRequest();
                xhr.addEventListener("progress", function (evt) {
                    if (evt.lengthComputable) {
                        var percentComplete = evt.loaded / evt.total;
                        percentComplete = parseInt(percentComplete * 100);
                        $("#verificationProgress").attr("aria-valuemax", evt.total.toString());
                        $("#verificationProgress").attr("aria-valuenow", evt.loaded.toString());
                        $("#verificationProgress > .progress-bar").attr("style", `width: ${percentComplete}%`);
                    }
                }, false);

                return xhr;
            },
        });
    
}

function adaptToState(state) {
    $(".muralSlide").hide();
    currentState = state;
    switch(state.phase) {
        case "RetractBelts":
            $("#retractBeltsSlide").show();
            break;
        case "SetTopDistance":
            $("#distanceBetweenAnchorsSlide").show();
            break;
        case "ExtendToHome":
            $("#extendToHomeSlide").show();
            if (state.moving || state.startedHoming) {
                $("#extendToHome").prop( "disabled", true);
                $("#extendingSpinner").css('visibility', 'visible');
                checkIfExtendedToHome();
            }
            break;
        case "PenCalibration":
            $.post("/setServo", {angle: 90});
            $("#penCalibrationSlide").show();
            break;
        case "SvgSelect":
            $("#svgUploadSlide").show();
            break;
        case "BeginDrawing":
            $("#beginDrawingSlide").show();
            break;
        default:
            alert("Unrecognized phase");
    }
}

function getInfillDensity() {
    const density = parseInt($("#infillDensity").val());
    if ([0, 1, 2, 3, 4].includes(density)) {
        return density;
    } else {
        throw new Error('Invalid density');
    }
}

function getTurdSize() {
    return parseInt($("#turdSize").val());
}

function getFlattenPaths() {
    return $("#flattenPathsCheckbox").is(":checked");
}

================================================
FILE: data/www/svgControl.js
================================================
document.body.addEventListener("click", function(e) {
	if(e.target && e.target.nodeName == "A" && e.target.parentElement.className == 'd-pad') {
        const validDirection = ["up", "down", "left", "right"];
        if (validDirection.includes(e.target.className)) {
            requestChangeInTransform(e.target.className);
        }
	}
});

export const renderScale = 2;

export function initSvgControl() {
    $("#zoomIn").click(function() {
        requestChangeInTransform("in");
    });
    
    $("#zoomOut").click(function() {
        requestChangeInTransform("out");
    });
    
    $("#resetTransform").click(function() {
        requestChangeInTransform("reset");
    });
}

const affineTransform = [1, 0, 0, 1, 0, 0];
// nudge by this fraction of the viewport's width and height
const nudgeByFactor = 0.025;
const zoomByFactor = 0.05;
function requestChangeInTransform(direction) {
    switch (direction) {
        case "up":
            affineTransform[5] = affineTransform[5] - nudgeByFactor;
            break;
        case "down":
            affineTransform[5] = affineTransform[5] + nudgeByFactor;
            break;
        case "left":
            affineTransform[4] = affineTransform[4] - nudgeByFactor;
            break;
        case "right":
            affineTransform[4] = affineTransform[4] + nudgeByFactor;
            break;
        case "in":
            affineTransform[0] = affineTransform[0] + zoomByFactor;
            affineTransform[3] = affineTransform[3] + zoomByFactor;
            break;
        case "out":
            affineTransform[0] = affineTransform[0] - zoomByFactor;
            affineTransform[3] = affineTransform[3] - zoomByFactor;
            break;
        case "reset":
            resetTransform();
            break;
        default:
            console.log("Unrecognized transform direction");
            return;
    }
    applyTransform();
}

function resetTransform() {
    affineTransform[0] = 1;
    affineTransform[3] = 1;
    affineTransform[4] = 0;
    affineTransform[5] = 0;
}

let originalSvg;
let transformedSvg;
let currentWidth;
let currentHeight;
export function setSvgString(svgString, currentState) {
    resetTransform();

    originalSvg = new DOMParser().parseFromString(svgString, 'image/svg+xml');
    currentWidth = currentState.safeWidth;
    normalizeSvg();
    applyTransform();
}

const transformGroupID = "muralTransformGroup";
function normalizeSvg() {
    const svgElement = originalSvg.documentElement;
    let width, height;

    if (svgElement.hasAttribute("width") && svgElement.hasAttribute("height")) {
        width = convertUnitsToPx(svgElement.getAttribute("width"));
        height = convertUnitsToPx(svgElement.getAttribute("height"));
    }
    
    if (svgElement.hasAttribute("viewBox")) {
        if (!width || !height) {
            const viewBox = svgElement.getAttribute("viewBox").split(/[\s,]/).filter(s => s != "");;
            width = parseFloat(viewBox[2]);
            height = parseFloat(viewBox[3]);
        }
    } else {
        svgElement.setAttribute("viewBox", `0, 0, ${width}, ${height}`);
    }
    
    if (!width || !height) {
        throw new Error("Invalid SVG");
    }

    currentHeight = currentWidth / width * height;

    svgElement.setAttribute("width", currentWidth);
    svgElement.setAttribute("height", currentHeight);

    const transformGroup = document.createElementNS("http://www.w3.org/2000/svg", "g");
    transformGroup.id = transformGroupID;
    while (svgElement.firstChild) {
        transformGroup.appendChild(svgElement.firstChild);
    }
    svgElement.appendChild(transformGroup);
}

function convertUnitsToPx(dimension) {
    const unitConversionFactors = {
        pt: 1.3333,    // Points to pixels
        pc: 16,        // Picas to pixels
        in: 96,        // Inches to pixels
        cm: 37.795,    // Centimeters to pixels
        mm: 3.7795,    // Millimeters to pixels
        px: 1,         // Pixels to pixels
    };

    const match = dimension.match(/([\d.]+)([a-z%]*)/i);
    if (!match) {
        alert("Invalid SVG");
        throw new Error(`Invalid dimension: "${dimension}"`);
    }
    const value = parseFloat(match[1]);
    const unit = match[2] || "px"; // Default to pixels if no unit is provided
    const conversionFactor = unitConversionFactors[unit] || 1;
    return value * conversionFactor; // Convert to pixels
}

export function getTargetWidth() {
    return currentWidth;
}

export function getTargetHeight() {
    return currentHeight;
}

export function getRenderScale() {
    return renderScale;
}

export function getRenderSvg() {
    return makeTransformedSvgWithHeight()[0];
}

function applyTransform() {
    updateTransformText();

    const [clonedSvg, newHeight] = makeTransformedSvgWithHeight();
    currentHeight = newHeight;
    
    const svgString = new XMLSerializer().serializeToString(clonedSvg);
    const svgDataURL = `data:image/svg+xml;base64,${btoa(svgString)}`;
    $("#sourceSvg")[0].src = svgDataURL;

    transformedSvg = clonedSvg;
}

function makeTransformedSvgWithHeight() {
    const clonedSvg = originalSvg.cloneNode(true);
    const svgElement = clonedSvg.documentElement;

    const viewBox = svgElement.getAttribute("viewBox").split(/[\s,]/).filter(s => s != "");
    const vbWidth = parseFloat(viewBox[2]);
    const vbHeight = parseFloat(viewBox[3]);

    const scaledAffine = [...affineTransform];
    scaledAffine[4] = scaledAffine[4] * vbWidth;

    let newHeight = parseFloat(svgElement.getAttribute("height"));
    if (scaledAffine[5] > 0) {
        // when shifting down increase height
        const heightOffset = scaledAffine[5] * newHeight;
        newHeight = newHeight + heightOffset;
        svgElement.setAttribute("height", newHeight);

        scaledAffine[5] = scaledAffine[5] * vbHeight;
        viewBox[3] = vbHeight + scaledAffine[5];
        svgElement.setAttribute("viewBox", viewBox.join(", "));
    } else {
        scaledAffine[5] = scaledAffine[5] * vbHeight;
    }

    const transfromGroup = clonedSvg.getElementById(transformGroupID);
    transfromGroup.setAttribute("transform", `matrix(${scaledAffine.join(", ")})`);

    return [clonedSvg, newHeight];
}

function updateTransformText() {
    function normalizeNumber(num) {
        return +num.toFixed(2);
    }
    $("#transformText").text(`(${normalizeNumber(affineTransform[4] * 100)}, ${normalizeNumber(affineTransform[5] * 100)}) ${normalizeNumber(affineTransform[0])}x`);
}

export async function getCurrentSvgImageData() {
    const scaledHeight = currentHeight * renderScale;
    const scaledWidth = currentWidth * renderScale;
    
    const svgString = new XMLSerializer().serializeToString(transformedSvg);

    const canvas = new OffscreenCanvas(scaledWidth, scaledHeight);
    const canvasContext = canvas.getContext("2d",);
    const img = await loadImage(`data:image/svg+xml;base64,${btoa(svgString)}`);

    const bitmap = await createImageBitmap(img, {resizeHeight: scaledHeight, resizeWidth: scaledWidth});

    canvasContext.drawImage(bitmap, 0, 0, scaledWidth, scaledHeight);
    
    const imageData = canvasContext.getImageData(0, 0, canvas.width, canvas.height);
    
    return imageData;
}

async function loadImage(src) {
    return new Promise((resolve, reject) => {
        const img = new Image();
        img.onload = () => resolve(img);
        img.onerror = reject;
        img.src = src;
    });
}

export function getSvgJson(svgString) {
    const size = new paper.Size(Number.MAX_SAFE_INTEGER, Number.MAX_SAFE_INTEGER);
    paper.setup(size);
    const svg = paper.project.importSVG(svgString, {
        expandShapes: true,
        applyMatrix: true,
    });
    const json = svg.exportJSON();
    paper.project.remove();

    return json;
}

export function convertJsonToDataURL(json, width, height) {
    $("#previewCanvas").remove();
    $(document.body).append(`<canvas id="previewCanvas" width="${width}" height="${height}" style="display: none;"></canvas>`);
    
    paper.setup($("#previewCanvas")[0]);
    paper.project.importJSON(json);
    paper.view.draw();

    const dataURL = $("#previewCanvas")[0].toDataURL();
    
    paper.project.remove();
    $("#previewCanvas").remove();

    return dataURL;
}





================================================
FILE: images/doc/kinematic_model1.drawio
================================================
<mxfile host="app.diagrams.net" agent="Mozilla/5.0 (Macintosh; Intel Mac OS X 10_15_7) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/136.0.0.0 Safari/537.36" version="27.0.9">
  <diagram name="Page-1" id="uI_OCheiNeMay8VbvTcP">
    <mxGraphModel grid="1" page="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="1" pageScale="1" pageWidth="850" pageHeight="1100" math="0" shadow="0">
      <root>
        <mxCell id="0" />
        <mxCell id="1" parent="0" />
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-5" value="" style="shape=sumEllipse;perimeter=ellipsePerimeter;whiteSpace=wrap;html=1;backgroundOutline=1;" vertex="1" parent="1">
          <mxGeometry x="60" y="150" width="30" height="30" as="geometry" />
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-6" value="" style="shape=sumEllipse;perimeter=ellipsePerimeter;whiteSpace=wrap;html=1;backgroundOutline=1;" vertex="1" parent="1">
          <mxGeometry x="790" y="150" width="30" height="30" as="geometry" />
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-8" value="" style="endArrow=none;html=1;rounded=0;entryX=0.533;entryY=0.567;entryDx=0;entryDy=0;entryPerimeter=0;exitX=1;exitY=0;exitDx=0;exitDy=0;" edge="1" parent="1" source="m5EwUfMTjH4Hw6mmDvRn-1" target="m5EwUfMTjH4Hw6mmDvRn-5">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="400" y="450" as="sourcePoint" />
            <mxPoint x="450" y="400" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-9" value="" style="endArrow=none;html=1;rounded=0;entryX=0.5;entryY=0.5;entryDx=0;entryDy=0;entryPerimeter=0;exitX=0;exitY=0;exitDx=0;exitDy=0;" edge="1" parent="1" source="m5EwUfMTjH4Hw6mmDvRn-2" target="m5EwUfMTjH4Hw6mmDvRn-6">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="400" y="450" as="sourcePoint" />
            <mxPoint x="450" y="400" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-24" value="Q" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1">
          <mxGeometry x="330" y="360" width="60" height="30" as="geometry" />
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-30" value="" style="group;rotation=10;" vertex="1" connectable="0" parent="1">
          <mxGeometry x="160" y="380" width="360" height="185" as="geometry" />
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-10" value="" style="endArrow=none;html=1;rounded=0;" edge="1" parent="m5EwUfMTjH4Hw6mmDvRn-30" source="m5EwUfMTjH4Hw6mmDvRn-12">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="192" y="11" as="sourcePoint" />
            <mxPoint x="168" y="149" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-1" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;rotation=10;opacity=50;" vertex="1" parent="m5EwUfMTjH4Hw6mmDvRn-30">
          <mxGeometry x="11" y="-25" width="60" height="60" as="geometry" />
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-2" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;rotation=10;opacity=50;" vertex="1" parent="m5EwUfMTjH4Hw6mmDvRn-30">
          <mxGeometry x="306" y="27" width="60" height="60" as="geometry" />
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-3" value="" style="shape=orEllipse;perimeter=ellipsePerimeter;whiteSpace=wrap;html=1;backgroundOutline=1;rotation=55;opacity=50;" vertex="1" parent="m5EwUfMTjH4Hw6mmDvRn-30">
          <mxGeometry x="177" y="32" width="20" height="20" as="geometry" />
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-11" value="" style="endArrow=none;html=1;rounded=0;exitX=1;exitY=0;exitDx=0;exitDy=0;entryX=0;entryY=0;entryDx=0;entryDy=0;" edge="1" parent="m5EwUfMTjH4Hw6mmDvRn-30" source="m5EwUfMTjH4Hw6mmDvRn-1" target="m5EwUfMTjH4Hw6mmDvRn-2">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="241" y="81" as="sourcePoint" />
            <mxPoint x="299" y="40" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-13" value="" style="endArrow=none;html=1;rounded=0;" edge="1" parent="m5EwUfMTjH4Hw6mmDvRn-30" target="m5EwUfMTjH4Hw6mmDvRn-12">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="192" y="11" as="sourcePoint" />
            <mxPoint x="168" y="149" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-12" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;rotation=10;" vertex="1" parent="m5EwUfMTjH4Hw6mmDvRn-30">
          <mxGeometry x="162" y="149" width="10" height="10" as="geometry" />
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-19" value="" style="endArrow=none;html=1;rounded=0;" edge="1" parent="m5EwUfMTjH4Hw6mmDvRn-30">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="184" y="-1" as="sourcePoint" />
            <mxPoint x="200" y="23" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-20" value="" style="endArrow=none;html=1;rounded=0;" edge="1" parent="m5EwUfMTjH4Hw6mmDvRn-30">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="181" y="19" as="sourcePoint" />
            <mxPoint x="204" y="3" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-21" value="(pulley)" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;rotation=10;" vertex="1" parent="m5EwUfMTjH4Hw6mmDvRn-30">
          <mxGeometry x="3" y="34" width="60" height="30" as="geometry" />
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-22" value="(pulley)" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;rotation=10;" vertex="1" parent="m5EwUfMTjH4Hw6mmDvRn-30">
          <mxGeometry x="299" y="86" width="60" height="30" as="geometry" />
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-29" value="(pen center)" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;rotation=10;" vertex="1" parent="m5EwUfMTjH4Hw6mmDvRn-30">
          <mxGeometry x="128" y="47" width="60" height="30" as="geometry" />
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-23" value="m" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="m5EwUfMTjH4Hw6mmDvRn-30">
          <mxGeometry x="150" y="149" width="60" height="30" as="geometry" />
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-36" value="" style="shape=curlyBracket;whiteSpace=wrap;html=1;rounded=1;labelPosition=left;verticalLabelPosition=middle;align=right;verticalAlign=middle;rotation=10;" vertex="1" parent="m5EwUfMTjH4Hw6mmDvRn-30">
          <mxGeometry x="153" y="5" width="10" height="30" as="geometry" />
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-38" value="d_p" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="m5EwUfMTjH4Hw6mmDvRn-30">
          <mxGeometry x="112" y="2" width="60" height="30" as="geometry" />
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-35" value="" style="shape=curlyBracket;whiteSpace=wrap;html=1;rounded=1;flipH=1;labelPosition=right;verticalLabelPosition=middle;align=left;verticalAlign=middle;rotation=11;" vertex="1" parent="m5EwUfMTjH4Hw6mmDvRn-30">
          <mxGeometry x="203.88" y="15.670000000000002" width="20" height="150" as="geometry" />
        </mxCell>
        <mxCell id="m5EwUfMTjH4Hw6mmDvRn-37" value="d_m" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="m5EwUfMTjH4Hw6mmDvRn-30">
          <mxGeometry x="208.88" y="81" width="60" height="30" as="geometry" />
        </mxCell>
        <mxCell id="OY2j0D1znraPUxaiwNrB-27" value="F_G" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="m5EwUfMTjH4Hw6mmDvRn-30">
          <mxGeometry x="102" y="155" width="60" height="30" as="geometry" />
        </mxCell>
        <mxCell id="OY2j0D1znraPUxaiwNrB-1" value="" style="verticalLabelPosition=bottom;verticalAlign=top;html=1;shape=mxgraph.basic.arc;startAngle=0.24823168451121255;endAngle=0.40955433894124044;" vertex="1" parent="1">
          <mxGeometry x="7.25" y="107.25" width="135.5" height="115.5" as="geometry" />
        </mxCell>
        <mxCell id="OY2j0D1znraPUxaiwNrB-2" value="" style="endArrow=none;dashed=1;html=1;dashPattern=1 3;strokeWidth=2;rounded=0;entryX=0.495;entryY=0.49;entryDx=0;entryDy=0;entryPerimeter=0;exitX=0.443;exitY=0.51;exitDx=0;exitDy=0;exitPerimeter=0;" edge="1" parent="1" source="m5EwUfMTjH4Hw6mmDvRn-5" target="m5EwUfMTjH4Hw6mmDvRn-6">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="120" y="180" as="sourcePoint" />
            <mxPoint x="330" y="310" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="OY2j0D1znraPUxaiwNrB-3" value="" style="verticalLabelPosition=bottom;verticalAlign=top;html=1;shape=mxgraph.basic.arc;startAngle=0.6435868456459786;endAngle=0.7516075710155771;" vertex="1" parent="1">
          <mxGeometry x="731.13" y="91.13" width="147.75" height="147.75" as="geometry" />
        </mxCell>
        <mxCell id="OY2j0D1znraPUxaiwNrB-22" value="phi_L" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1">
          <mxGeometry x="82.75" y="170" width="60" height="30" as="geometry" />
        </mxCell>
        <mxCell id="OY2j0D1znraPUxaiwNrB-23" value="phi_R" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1">
          <mxGeometry x="730" y="160" width="60" height="30" as="geometry" />
        </mxCell>
        <mxCell id="OY2j0D1znraPUxaiwNrB-24" value="" style="endArrow=classic;html=1;rounded=0;" edge="1" parent="1">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="244" y="354" as="sourcePoint" />
            <mxPoint x="213" y="312" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="OY2j0D1znraPUxaiwNrB-25" value="F_L" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1">
          <mxGeometry x="211" y="310" width="60" height="30" as="geometry" />
        </mxCell>
        <mxCell id="OY2j0D1znraPUxaiwNrB-26" value="F_R" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1">
          <mxGeometry x="444" y="360" width="60" height="30" as="geometry" />
        </mxCell>
        <mxCell id="OY2j0D1znraPUxaiwNrB-28" value="" style="endArrow=classic;html=1;rounded=0;" edge="1" parent="1">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="467" y="395" as="sourcePoint" />
            <mxPoint x="507" y="365" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="OY2j0D1znraPUxaiwNrB-29" value="" style="endArrow=classic;html=1;rounded=0;exitX=0;exitY=0.25;exitDx=0;exitDy=0;" edge="1" parent="1" source="m5EwUfMTjH4Hw6mmDvRn-23">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="110" y="330" as="sourcePoint" />
            <mxPoint x="310" y="570" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="OY2j0D1znraPUxaiwNrB-30" value="" style="shape=curlyBracket;whiteSpace=wrap;html=1;rounded=1;flipH=1;labelPosition=right;verticalLabelPosition=middle;align=left;verticalAlign=middle;rotation=-80;" vertex="1" parent="1">
          <mxGeometry x="358" y="194" width="20" height="256.32" as="geometry" />
        </mxCell>
        <mxCell id="OY2j0D1znraPUxaiwNrB-31" value="" style="endArrow=none;dashed=1;html=1;dashPattern=1 3;strokeWidth=2;rounded=0;exitX=1;exitY=0;exitDx=0;exitDy=0;" edge="1" parent="1" source="m5EwUfMTjH4Hw6mmDvRn-1">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="280" y="350" as="sourcePoint" />
            <mxPoint x="244" y="354" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="OY2j0D1znraPUxaiwNrB-32" value="" style="endArrow=none;dashed=1;html=1;dashPattern=1 3;strokeWidth=2;rounded=0;entryX=0;entryY=0;entryDx=0;entryDy=0;" edge="1" parent="1" target="m5EwUfMTjH4Hw6mmDvRn-2">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="467" y="395" as="sourcePoint" />
            <mxPoint x="248" y="360" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="OY2j0D1znraPUxaiwNrB-34" value="s" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1">
          <mxGeometry x="340" y="291" width="60" height="30" as="geometry" />
        </mxCell>
      </root>
    </mxGraphModel>
  </diagram>
</mxfile>


================================================
FILE: images/doc/tangent_point.drawio
================================================
<mxfile host="app.diagrams.net" agent="Mozilla/5.0 (Macintosh; Intel Mac OS X 10_15_7) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/136.0.0.0 Safari/537.36" version="27.0.9">
  <diagram name="Page-1" id="JntVAdGJVKhrkGMVg9V-">
    <mxGraphModel grid="1" page="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="1" pageScale="1" pageWidth="850" pageHeight="1100" math="0" shadow="0">
      <root>
        <mxCell id="0" />
        <mxCell id="1" parent="0" />
        <mxCell id="W8-vzGq-EH7mcyE8-KKW-1" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;" vertex="1" parent="1">
          <mxGeometry x="320" y="320" width="160" height="160" as="geometry" />
        </mxCell>
        <mxCell id="W8-vzGq-EH7mcyE8-KKW-3" value="" style="shape=sumEllipse;perimeter=ellipsePerimeter;whiteSpace=wrap;html=1;backgroundOutline=1;" vertex="1" parent="1">
          <mxGeometry x="160" y="70" width="30" height="30" as="geometry" />
        </mxCell>
        <mxCell id="W8-vzGq-EH7mcyE8-KKW-2" value="" style="endArrow=none;html=1;rounded=0;entryX=1;entryY=0;entryDx=0;entryDy=0;exitX=0.502;exitY=0.5;exitDx=0;exitDy=0;exitPerimeter=0;" edge="1" parent="1" source="W8-vzGq-EH7mcyE8-KKW-3" target="W8-vzGq-EH7mcyE8-KKW-1">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="180" y="80" as="sourcePoint" />
            <mxPoint x="450" y="400" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="W8-vzGq-EH7mcyE8-KKW-4" value="" style="endArrow=none;html=1;strokeWidth=1;rounded=0;exitX=1;exitY=0;exitDx=0;exitDy=0;" edge="1" parent="1" source="W8-vzGq-EH7mcyE8-KKW-1">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="550" y="280" as="sourcePoint" />
            <mxPoint x="400" y="400" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="W8-vzGq-EH7mcyE8-KKW-6" value="" style="endArrow=none;html=1;strokeWidth=1;rounded=0;entryX=1;entryY=0;entryDx=0;entryDy=0;" edge="1" parent="1" target="W8-vzGq-EH7mcyE8-KKW-1">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="399" y="345" as="sourcePoint" />
            <mxPoint x="490" y="320" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="W8-vzGq-EH7mcyE8-KKW-9" value="" style="endArrow=none;html=1;strokeWidth=1;rounded=0;entryX=1;entryY=0;entryDx=0;entryDy=0;" edge="1" parent="1" target="W8-vzGq-EH7mcyE8-KKW-1">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="457" y="400" as="sourcePoint" />
            <mxPoint x="457" y="343" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="W8-vzGq-EH7mcyE8-KKW-10" value="" style="endArrow=none;dashed=1;html=1;dashPattern=1 3;strokeWidth=1;rounded=0;exitX=0.5;exitY=0;exitDx=0;exitDy=0;" edge="1" parent="1" source="W8-vzGq-EH7mcyE8-KKW-1">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="410" y="290" as="sourcePoint" />
            <mxPoint x="400" y="480" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="W8-vzGq-EH7mcyE8-KKW-11" value="" style="endArrow=none;dashed=1;html=1;dashPattern=1 3;strokeWidth=1;rounded=0;exitX=1;exitY=0.5;exitDx=0;exitDy=0;entryX=0;entryY=0.5;entryDx=0;entryDy=0;" edge="1" parent="1" source="W8-vzGq-EH7mcyE8-KKW-1" target="W8-vzGq-EH7mcyE8-KKW-1">
          <mxGeometry width="50" height="50" relative="1" as="geometry">
            <mxPoint x="250" y="340" as="sourcePoint" />
            <mxPoint x="250" y="500" as="targetPoint" />
          </mxGeometry>
        </mxCell>
        <mxCell id="W8-vzGq-EH7mcyE8-KKW-12" value="r" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1">
          <mxGeometry x="395" y="350" width="60" height="30" as="geometry" />
        </mxCell>
        <mxCell id="W8-vzGq-EH7mcyE8-KKW-13" value="q" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1">
          <mxGeometry x="390" y="320" width="60" height="30" as="geometry" />
        </mxCell>
        <mxCell id="W8-vzGq-EH7mcyE8-KKW-14" value="q" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1">
          <mxGeometry x="433" y="360" width="60" height="30" as="geometry" />
        </mxCell>
        <mxCell id="W8-vzGq-EH7mcyE8-KKW-15" value="(pulley)" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1">
          <mxGeometry x="340" y="430" width="60" height="30" as="geometry" />
        </mxCell>
      </root>
    </mxGraphModel>
  </diagram>
</mxfile>


================================================
FILE: include/README
================================================

This directory is intended for project header files.

A header file is a file containing C declarations and macro definitions
to be shared between several project source files. You request the use of a
header file in your project source file (C, C++, etc) located in `src` folder
by including it, with the C preprocessing directive `#include'.

```src/main.c

#include "header.h"

int main (void)
{
 ...
}
```

Including a header file produces the same results as copying the header file
into each source file that needs it. Such copying would be time-consuming
and error-prone. With a header file, the related declarations appear
in only one place. If they need to be changed, they can be changed in one
place, and programs that include the header file will automatically use the
new version when next recompiled. The header file eliminates the labor of
finding and changing all the copies as well as the risk that a failure to
find one copy will result in inconsistencies within a program.

In C, the usual convention is to give header files names that end with `.h'.
It is most portable to use only letters, digits, dashes, and underscores in
header file names, and at most one dot.

Read more about using header files in official GCC documentation:

* Include Syntax
* Include Operation
* Once-Only Headers
* Computed Includes

https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html


================================================
FILE: lib/README
================================================

This directory is intended for project specific (private) libraries.
PlatformIO will compile them to static libraries and link into executable file.

The source code of each library should be placed in a an own separate directory
("lib/your_library_name/[here are source files]").

For example, see a structure of the following two libraries `Foo` and `Bar`:

|--lib
|  |
|  |--Bar
|  |  |--docs
|  |  |--examples
|  |  |--src
|  |     |- Bar.c
|  |     |- Bar.h
|  |  |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html
|  |
|  |--Foo
|  |  |- Foo.c
|  |  |- Foo.h
|  |
|  |- README --> THIS FILE
|
|- platformio.ini
|--src
   |- main.c

and a contents of `src/main.c`:
```
#include <Foo.h>
#include <Bar.h>

int main (void)
{
  ...
}

```

PlatformIO Library Dependency Finder will find automatically dependent
libraries scanning project source files.

More information about PlatformIO Library Dependency Finder
- https://docs.platformio.org/page/librarymanager/ldf.html


================================================
FILE: partitions.csv
================================================
# ESP-IDF Partition Table
# Name,   Type, SubType, Offset,  Size, Flags
nvs,      data, nvs,     0x9000,  0x6000,
phy_init, data, phy,     0xf000,  0x1000,
factory,  app,  factory, 0x10000, 1200K,
spiffs, data, spiffs, 0x13C000, 2800K,

================================================
FILE: platformio.ini
================================================
; PlatformIO Project Configuration File
;
;   Build options: build flags, source filter
;   Upload options: custom upload port, speed and extra flags
;   Library options: dependencies, extra library storages
;   Advanced options: extra scripting
;
; Please visit documentation for the other options and examples
; https://docs.platformio.org/page/projectconf.html

[env:esp32dev]
platform = espressif32
board = esp32dev
board_build.filesystem = littlefs
board_build.partitions = partitions.csv
monitor_filters = esp32_exception_decoder
extra_scripts = build.py
framework = arduino

lib_deps = 
	https://github.com/tzapu/WiFiManager.git@2.0.17
	https://github.com/ESP32Async/ESPAsyncWebServer.git@^3.7.4
	https://github.com/madhephaestus/ESP32Servo.git@^3.0.9
	https://github.com/adafruit/Adafruit_SSD1306.git@^2.5.13
	waspinator/AccelStepper@^1.64
	bblanchon/ArduinoJson@^5.13.4


================================================
FILE: src/display.cpp
================================================
#include "display.h"
#include <Adafruit_SSD1306.h>

#define SCREEN_WIDTH 128 // OLED display width, in pixels
#define SCREEN_HEIGHT 64 // OLED display height, in pixels
Display::Display() {
    display = new Adafruit_SSD1306(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, -1);
    if (!display->begin(SSD1306_SWITCHCAPVCC, 0x3C))
    { // Address 0x3D for 128x64
        Serial.println(F("SSD1306 allocation failed"));
        throw std::invalid_argument("not ready");
    }
    delay(2000);
    display->setRotation(2);
    display->clearDisplay();
    display->setTextColor(WHITE);
    display->setTextSize(1);
    display->display();
}

void Display::displayText(String text)
{
    int16_t x1;
    int16_t y1;
    uint16_t width;
    uint16_t height;

    display->getTextBounds(text, 0, 0, &x1, &y1, &width, &height);

    // display on horizontal and vertical center
    display->clearDisplay(); // clear display
    display->setCursor((SCREEN_WIDTH - width) / 2, (SCREEN_HEIGHT - height) / 2);
    display->println(text); // text to display
    display->display();
    Serial.println("Displayed " + text);
}

void Display::displayHomeScreen(String ipLine, String orLine, String mdnsLine) {
    display->clearDisplay();

    int16_t x1;
    int16_t y1;
    uint16_t width;
    uint16_t height;

    display->getTextBounds(ipLine, 0, 0, &x1, &y1, &width, &height);
    display->setCursor((SCREEN_WIDTH - width) / 2, 10);
    display->println(ipLine);

    display->getTextBounds(orLine, 0, 0, &x1, &y1, &width, &height);
    display->setCursor((SCREEN_WIDTH - width) / 2, 10 + SCREEN_HEIGHT / 3);
    display->println(orLine);

    display->getTextBounds(mdnsLine, 0, 0, &x1, &y1, &width, &height);
    display->setCursor((SCREEN_WIDTH - width) / 2, 10 + SCREEN_HEIGHT / 3 * 2);
    display->println(mdnsLine);

    display->display();
}

================================================
FILE: src/display.h
================================================
#ifndef Display_h
#define Display_h
#include <Adafruit_SSD1306.h>

class Display {
    private:
    Adafruit_SSD1306 *display;
    public:
    Display();
    void displayText(String text);
    void displayHomeScreen(String ipLine, String orLine, String mdnsLine);
};
#endif

================================================
FILE: src/main.cpp
================================================
#include <Arduino.h>
#include <WiFiManager.h>
#include <AsyncTCP.h>
#include <ESPAsyncWebServer.h>
#include <FS.h>
#include <LittleFS.h>
#include <Wire.h>
#include <ESPmDNS.h>
#include "movement.h"
#include "runner.h"
#include "pen.h"
#include "display.h"
#include "phases/phasemanager.h"

AsyncWebServer server(80);

Movement *movement;
Runner *runner;
Pen *pen;
Display *display;

PhaseManager* phaseManager;

void notFound(AsyncWebServerRequest *request)
{
    request->send(404, "text/plain", "Not found");
}

void handleUpload(AsyncWebServerRequest *request, String filename, size_t index, uint8_t *data, size_t len, bool final) {
    phaseManager->getCurrentPhase()->handleUpload(request, filename, index, data, len, final);
}

void handleGetState(AsyncWebServerRequest *request) {
    phaseManager->respondWithState(request);
}

std::vector<const char *> menu = {"wifi", "sep"};
void setup()
{
    delay(10);
    Serial.begin(9600);

    if (!LittleFS.begin(true)) {
        Serial.println("An Error has occurred while mounting LittleFS");
        return;
    }

    display = new Display();
    Serial.println("Initialized display");

    // initialize movement right away or the motors can start creeping due to floating output
    movement = new Movement(display);
    Serial.println("Initialized steppers");

    bool resetAfterConnect = false;
    std::function<void()> serverCallback = [&] () {
        resetAfterConnect = true;
    };
    
    WiFiManager wifiManager;
    
    wifiManager.setConnectTimeout(20);
    wifiManager.setTitle("Connect to WiFi");
    wifiManager.setMenu(menu);
    wifiManager.setWebServerCallback(serverCallback);
    wifiManager.autoConnect("Mural");

    if (resetAfterConnect) {
        Serial.println("Connected to WiFi through captive portal, restarting...");
        ESP.restart();
    }
    
    Serial.println("Connected to wifi");

    MDNS.begin("mural");

    Serial.println("Started mDNS for mural");

    pen = new Pen();
    Serial.println("Initialized servo");

    runner = new Runner(movement, pen, display);
    Serial.println("Initialized runner");

    server.serveStatic("/", LittleFS, "/www/").setDefaultFile("index.html").setCacheControl("no-cache");

    server.on("/command", HTTP_POST, [](AsyncWebServerRequest *request)
              { phaseManager->getCurrentPhase()->handleCommand(request); });

    server.on("/setTopDistance", HTTP_POST, [](AsyncWebServerRequest *request)
              { phaseManager->getCurrentPhase()->setTopDistance(request); });

    server.on("/extendToHome", HTTP_POST, [](AsyncWebServerRequest *request)
              { phaseManager->getCurrentPhase()->extendToHome(request); });

    server.on("/setServo", HTTP_POST, [](AsyncWebServerRequest *request)
              { phaseManager->getCurrentPhase()->setServo(request); });

    server.on("/setPenDistance", HTTP_POST, [](AsyncWebServerRequest *request)
              { phaseManager->getCurrentPhase()->setPenDistance(request); });

    server.on("/estepsCalibration", HTTP_POST, [](AsyncWebServerRequest *request)
              { phaseManager->getCurrentPhase()->estepsCalibration(request); });

    server.on("/doneWithPhase", HTTP_POST, [](AsyncWebServerRequest *request)
              { phaseManager->getCurrentPhase()->doneWithPhase(request); });

    server.on("/run", HTTP_POST, [](AsyncWebServerRequest *request)
              { phaseManager->getCurrentPhase()->run(request); });

    server.on("/resume", HTTP_POST, [](AsyncWebServerRequest *request)
              { phaseManager->getCurrentPhase()->resumeTopDistance(request); });

    server.on("/getState", HTTP_GET, [](AsyncWebServerRequest *request)
              { handleGetState(request); });

    server.on(
        "/uploadCommands", HTTP_POST,
        [](AsyncWebServerRequest *request) {
            handleGetState(request);
        }, 
        handleUpload
    );

    server.on(
        "/downloadCommands", HTTP_GET,
        [](AsyncWebServerRequest *request) {
            request->send(LittleFS, "/commands", "text/plain");
        }
    );

    server.onNotFound(notFound);

    Serial.println("Finished setting up the server");

    phaseManager = new PhaseManager(movement, pen, runner, &server);

    server.begin();
    Serial.println("Server started");

    display->displayHomeScreen("http://" + WiFi.localIP().toString(), "or", "http://mural.local");
    
}

void loop()
{
    movement->runSteppers();
    runner->run();
    phaseManager->getCurrentPhase()->loopPhase();
}


================================================
FILE: src/movement.cpp
================================================
#include "movement.h"
#include "display.h"
#include <stdexcept>

Movement::Movement(Display *display)
{
    this->display = display;
   
    leftMotor = new AccelStepper(AccelStepper::DRIVER, LEFT_STEP_PIN, LEFT_DIR_PIN);
    leftMotor->setEnablePin(LEFT_ENABLE_PIN);
    leftMotor->setMaxSpeed(moveSpeedSteps);
    leftMotor->setPinsInverted(true);
    leftMotor->disableOutputs();

    rightMotor = new AccelStepper(AccelStepper::DRIVER, RIGHT_STEP_PIN, RIGHT_DIR_PIN);
    rightMotor->setEnablePin(RIGHT_ENABLE_PIN);
    rightMotor->setMaxSpeed(moveSpeedSteps);
    rightMotor->disableOutputs();

    topDistance = -1;
   
    moving = false;
    homed = false;
    startedHoming = false;
};

void Movement::setTopDistance(const int distance) {
    Serial.printf("Top distance set to %s\n", String(distance));
    topDistance = distance;                         // = d_pins [mm]

    minSafeY = safeYFraction * topDistance;         // = top_margin * d_pins [mm]
    minSafeXOffset = safeXFraction * topDistance;   // = side_margin * d_pins [mm]
    width = topDistance - 2 * minSafeXOffset;       // width of the drawing area [mm]
};

void Movement::resumeTopDistance(int distance /* = d_pin in mm */) {
    setTopDistance(distance);
    homed = true;

    const Point homeCoordinates = getHomeCoordinates();
    X = homeCoordinates.x;
    Y = homeCoordinates.y;

    const Lengths lengths = getBeltLengths(homeCoordinates.x, homeCoordinates.y);
    leftMotor->setCurrentPosition(lengths.left);
    rightMotor->setCurrentPosition(lengths.right);

    moving = false;
}

void Movement::setOrigin()
{
    leftMotor->setCurrentPosition(homedStepsOffset);
    rightMotor->setCurrentPosition(homedStepsOffset);
    homed = true;
};

void Movement::leftStepper(const int dir)
{
    if (dir > 0)
    {
        leftMotor->move(INFINITE_STEPS);
        leftMotor->setSpeed(printSpeedSteps);
    }
    else if (dir < 0)
    {
        leftMotor->move(-INFINITE_STEPS);
        leftMotor->setSpeed(printSpeedSteps);
    }
    else
    {
        leftMotor->setAcceleration(acceleration);
        leftMotor->stop();
    }

    moving = true;
};

void Movement::rightStepper(const int dir)
{
    if (dir > 0)
    {
        rightMotor->move(INFINITE_STEPS);
        rightMotor->setSpeed(printSpeedSteps);
    }
    else if (dir < 0)
    {
        rightMotor->move(-INFINITE_STEPS);
        rightMotor->setSpeed(printSpeedSteps);
    }
    else
    {
        rightMotor->setAcceleration(acceleration);
        rightMotor->stop();
    }

    moving = true;
};

Movement::Point Movement::getHomeCoordinates() {
    if (topDistance == -1) {
        return Point(0, 0);
    }

    return Point(width / 2, HOME_Y_OFFSET_MM);
}

int Movement::extendToHome()
{
    setOrigin();

    auto homeCoordinates = getHomeCoordinates();
    startedHoming = true;
    auto moveTime = beginLinearTravel(homeCoordinates.x, homeCoordinates.y, moveSpeedSteps);
    return int(ceil(moveTime));
};

void Movement::runSteppers()
{
    if (moving)
    {
        leftMotor->runSpeedToPosition();
        rightMotor->runSpeedToPosition();

        if (leftMotor->distanceToGo() == 0 && rightMotor->distanceToGo() == 0)
        {
            moving = false;
            //Serial.printf("Motion complete. Left steps: %ld, Right steps: %ld\n", leftMotor->currentPosition(), rightMotor->currentPosition());
        }
    }
};

inline void Movement::getLeftTangentPoint(const double frameX, const double frameY, const double gamma, double& x_PL, double& y_PL) const {
    // Input frameX and frameY are the coordinates of the pen center.
    const double s_L = d_t / 2.0;   // Distance of left and right tangent point from point Q. [mm]
    const double P_LX = s_L * cos(gamma) - d_p * sin(gamma); // [mm] distance from pen center in x
    const double P_LY = s_L * sin(gamma) + d_p * cos(gamma); // [mm] .. and y
    x_PL = frameX - P_LX;    // [mm] Left pulley tangent point in frame coordinate system.
    y_PL = frameY - P_LY;    // [mm]
}

inline void Movement::getRightTangentPoint(const double frameX, const double frameY, const double gamma, double& x_PR, double& y_PR) const {
    // Coordinates of right pulley tangent point:
    const double s_R = d_t / 2.0;
    const double P_RX = s_R * cos(gamma) + d_p * sin(gamma); // [mm]
    const double P_RY = s_R * sin(gamma) - d_p * cos(gamma); // [mm]
    x_PR = frameX + P_RX;    // [mm] Right pulley tangent point in frame coordinate system.
    y_PR = frameY + P_RY;    // [mm]
}

// Compute angles of the belts and the forces on them.
// Input: - Mural coordinates X and Y in frame coordinate system [mm].
//        - Mural inclination gamma [rad].
// Output: - belt angles phi_L, phi_R [rad], measured against the line connecting the pins.
void Movement::getBeltAngles(const double frameX, const double frameY, const double gamma, double& phi_L, double& phi_R) const {
    double x_PL;
    double y_PL;
    getLeftTangentPoint(frameX, frameY, gamma, x_PL, y_PL);
    phi_L = atan2(y_PL, x_PL);     // Angle of left belt, measured from line connecting the pins. [rad]

    double x_PR;
    double y_PR;
    getRightTangentPoint(frameX, frameY, gamma, x_PR, y_PR);
    phi_R = atan2(y_PR, topDistance - x_PR);     // Angle of left belt, measured from line connecting the pins. [rad]
}

void Movement::getBeltForces(const double phi_L, const double phi_R, double& F_L, double&F_R) const {
    // Computing the Forces. 
    // Force vectors are parallel to their belts, so the direction is given by phi_R and phi_L.
    // We assume that the bot is in a stable state (no torque), which allows us for having
    // the force vectors of left (L) and right (R) pulley meet in a single point. 
    // In this stable state the pulley forces cancel out the gravity force in x and y.
    // Note this is an approximation which is refined due to iteratively updating the values (torque, angles, forces). 
    const double F_G = mass_bot * g_constant;       // [N] Gravity force is pulling bot down. No x component.
    F_R = F_G * cos(phi_L) / sin(phi_L + phi_R);    // [N] magnitude of the force vector
    F_L = F_G * cos(phi_R) / sin(phi_L + phi_R);    // [N]
    // double F_Ly = F_L * sin(phi_L);                         // [N] components in y and x
    // double F_Lx = F_L * sin(phi_L);                         // [N] ...
    // double F_Ry = F_R * sin(phi_R);                         // [N]
    // double F_Rx = F_R * sin(phi_R);                         // [N]
}

double Movement::solveTorqueEquilibrium(const double phi_L, const double phi_R, const double F_L, const double F_R, const double gamma_init) const {
    // Solve for torque equilibrium: As the belts are pulling on two distinct point, there's a torque rotating the
    // bot around a reference point. Here, we assume this reference point corresponds to Q, where tangent line d_t
    // and mass line d_m meet.
    // In the static case the residual torque is zero, which occurs at a certain inclination gamma. The goal here is
    // to find this gamma.
    const double s_L = d_t / 2.0;   // [mm] Lenght of the effective arm for the left pulley.
    const double s_R = d_t / 2.0;   // [mm]

    double gamma_best = 99999999;
    double T_delta_best = 99999999;

    // Solver parameters.
    constexpr double gamma_step = 0.20 * PI / 180.0;   // [rad] solver step width.
    constexpr double gamma_min = -90.0 * PI / 180.0;   // [rad] Solver search range: max and min values.
    constexpr double gamma_max = 90.0 * PI / 180.0;    // [rad]
    constexpr double gamma_search_window = 2.0 * PI / 180.0;    // [rad] Solver will focus on gamma_init +- gamma_search_window.
    
    // Simple solver: finding the minimum T_delta by searching over the range specified above:
    for (double gamma = gamma_init - gamma_search_window;
            gamma > gamma_min &&
            gamma < gamma_max &&
            gamma <= gamma_init + gamma_search_window;
            gamma += gamma_step){
        const double alpha = phi_L - gamma;   // [rad] Angle between left belt and line connecting tangent points (of pulleys and belts).
        const double beta = phi_R + gamma;    // [rad] Angle between right belt and line connecting tangent points.
    
        double T_L = /* s_L * F_L = */ s_L * sin(alpha) * F_L;  // [N * mm]
        double T_R = s_R * sin(beta) * F_R;                     // [N * mm]

        // The center of mass sits under the center of line connecting the tangent points.
        double s_m = d_m * tan(gamma);                          // [mm]
        const double F_G = mass_bot * g_constant;               // [N] Gravity force is pulling bot down. No x component.
        double F_m = F_G * cos(gamma);
        double T_m = s_m * F_m;                                 // [N * mm]

        // Left pulley tries to turn the bot clockwise. Right pulley ccw. Gravity ccw if gamma is positive (i.e. the bot inclined to the right).
        double T_delta = T_R - T_L + T_m;                       // [N * mm]
        // Solve gamma for T_delta = 0.0 .
        if (abs(T_delta) < abs(T_delta_best)){
            T_delta_best = T_delta;
            gamma_best = gamma;
            // Serial.printf("  solveTorqueEquilibrium: T_delta=%1.4f @ gamma=%1.4f, T_delta_best=%1.4f @ gamma_best=%1.4f\n",
            //     T_delta, gamma, T_delta_best, gamma_best);
        } else {
            // There is only one zero crossing: terminate early if T_delta gets worse than best one so far.

            // Serial.printf("  solveTorqueEquilibrium: T_delta=%1.4f @ gamma=%1.4f, T_delta_best=%1.4f @ gamma_best=%1.4f Exit function.\n",
            //     T_delta, gamma, T_delta_best, gamma_best);
            return gamma_best;
        }
    }

    return gamma_best;
}

inline double Movement::getDilationCorrectedBeltLength(double belt_length, double F_belt) const {
    // Apply belt length correction: The belts stretch because of Mural's mass. 
    // This function returns a (shorter) length of the belt, such that with gravity the belt
    // exactly as long as required.
    const double elongation_factor = 1 + belt_elongation_coefficient * F_belt;
    const double belth_length_corrected = belt_length / elongation_factor;
    return belth_length_corrected;
}

// Calculate the lengths of the left and right belt in mm based on the input coordinates.
// input: x [mm], y [mm] ; both in image coordinate system
// output: Struct containing the target stepper position for each motor to move.
Movement::Lengths Movement::getBeltLengths(const double x, const double y) {
    // Mural rotates as it moves towards the sides. As this happens, Mural's coordinate
    // system rotates as well, which would mean straight lines become curved. Therefore, 
    // a compensation in this rotated system is computed and applied.
    // !!!! Please see KinematicModel.md for a more detailed explanation !!!!
    //
    // This function works as follows:
    // 1 Compute the belt length in the wall plane first:
    //   {
    //      compute belt angles phi_L and phi_R
    //      compute forces on both belts
    //      compute torque on mural, solve for mural inclination gamma
    //      loop (if needed)
    //      result: mural inclination, x and y correction, and belt forces
    //   }
    // 2 Compute 3D belt length: Euclidean distance due to Pulleys not being in same (wall) plane
    //   as belt anchors (pins).
    // 3 Apply dilation correction to account for non-rigid belts.


    // Coordinate systems:
    // Frame coordinate system: Outer frame defined by the belt pins. Origin is the center of the left pin.
    //      x-axis points right towards the right pin. y-axis is perpendicular to x, pointing down.
    // Image coordinate system:
    //      This coordinate system defines the actual drawing area. The origin is in the top left corner 
    //      of the image to be drawn. It is shifted by safeYFraction * d_pins down from the line connecting the pins.
    //      Additionally, it's shifted safeXFraction to the right from the y-axis of the frame coordinate system.
    //      So, in frame coordinates the origin of the image coordinate system is 
    //      (safeYFraction * d_pins, safeXFraction * d_pins).
    //      See also /images/doc/muralbot_image_positioning.svg . 

    // Pen coordinates in frame coordinate system.
    const double frameX = x + minSafeXOffset;
    const double frameY = y + minSafeY;

    double gamma = gamma_last_position;              // Inclination of the bot [rad]. 0: Bot is horizontal. gamma>0: Bot tilts to the right.
    double phi_L = 0.0;
    double phi_R = 0.0;
    double F_L = 0.0;                               // [N] magnitude of the force vector (left belt)
    double F_R = 0.0;                               // [N] magnitude of the force vector (right belt)
    constexpr int solver_max_iterations = 20;       // Maximum number of outer loop iterations of the solver.
    constexpr double gamma_delta_termination = 0.25 / 180.0 * PI; // [rad] Outer loop of solver will stop if last update is smaller than this. 
                                                                  // Value should be greater than gamma step size in solveTorqueEquilibrium.

    // Solve for belt angles phi and bot inclination gamma by running a few rounds.
    int debug_step_count = 0;
    for (int i = 0; i < solver_max_iterations; i++){
        getBeltAngles(frameX, frameY, gamma, phi_L, phi_R);

        getBeltForces(phi_L, phi_R, F_L, F_R);

        const double gamma_last = gamma;
        gamma = solveTorqueEquilibrium(phi_L, phi_R, F_L, F_R, gamma);
        // Serial.printf(" Solver loop: i=%d, frameX=%1.2f, frameY=%1.2f, phi_L=%1.4f, phi_R=%1.4f, F_L=%1.2f, F_R=%1.2f, gamma=%1.4f\n", 
        //     i, frameX, frameY, phi_L, phi_R, F_L, F_R, gamma);
        debug_step_count = i;
        if (abs(gamma_last - gamma) < gamma_delta_termination) break;
    }
    gamma_last_position = gamma;
    // Serial.printf("Solver found: frameX=%1.2f, frameY=%1.2f, phi_L=%1.4f, phi_R=%1.4f, F_L=%1.2f, F_R=%1.2f, debug_step_count=%d, gamma=%1.4f\n", 
    //     frameX, frameY, phi_L, phi_R, F_L, F_R, debug_step_count, gamma);

    double leftX, leftY;
    double rightX, rightY;
    getLeftTangentPoint(frameX, frameY, gamma, leftX, leftY);
    getRightTangentPoint(frameX, frameY, gamma, rightX, rightY);

    // Left and right leg distances flush to the wall.
    const double leftLegFlat = sqrt(pow(leftX, 2) + pow(leftY, 2));
    const double rightLegFlat = sqrt(pow(topDistance - rightX, 2) + pow(rightY, 2));

    // Left and right leg distances including the standoff length.
    double leftLeg = sqrt(pow(leftLegFlat, 2) + pow(midPulleyToWall, 2));
    double rightLeg = sqrt(pow(rightLegFlat, 2) + pow(midPulleyToWall, 2));

    leftLeg = getDilationCorrectedBeltLength(leftLeg, F_L);
    rightLeg = getDilationCorrectedBeltLength(rightLeg, F_R);
    
    const double leftLegSteps = int((leftLeg / circumference) * stepsPerRotation);
    const double rightLegSteps = int((rightLeg / circumference) * stepsPerRotation);

    return Lengths(leftLegSteps, rightLegSteps);
}

float Movement::beginLinearTravel(double x, double y, int speed)
{
    X = x;
    Y = y;
    if (topDistance == -1 || !homed) {
        Serial.println("Not ready");
        throw std::invalid_argument("not ready");
    }

    if (x < 0 || (x - 1) > width)
    {
        Serial.println("Invalid x");
        throw std::invalid_argument("Invalid x");
    }

    if (y < 0)
    {
        Serial.println("Invalid y");
        throw std::invalid_argument("Invalid y");
    }

    auto lengths = getBeltLengths(x, y);
    auto leftLegSteps = lengths.left;
    auto rightLegSteps = lengths.right;

    auto deltaLeft = int(abs(abs(leftMotor->currentPosition()) - leftLegSteps));
    auto deltaRight = int(abs(abs(rightMotor->currentPosition()) - rightLegSteps));

    float leftSpeed, rightSpeed, moveTime;
    if (deltaLeft >= deltaRight)
    {
        leftSpeed = speed;
        moveTime = deltaLeft / leftSpeed;
        rightSpeed = deltaRight / moveTime;
    }
    else
    {
        rightSpeed = speed;
        moveTime = deltaRight / rightSpeed;
        leftSpeed = deltaLeft / moveTime;
    }

    //Serial.printf("Begin movement: X(%s) Y(%s) UnsafeX(%s) UnsafeY(%s) leftLeg(%s) rightLeg(%s) deltaLeft(%s) deltaRight(%s) leftSpeed(%s) rightSpeed(%s) \n", String(x), String(y), String(unsafeX), String(unsafeY), String(leftLeg), String(rightLeg), String(deltaLeft), String(deltaRight), String(leftSpeed), String(rightSpeed));
    leftMotor->moveTo(leftLegSteps);
    leftMotor->setSpeed(leftSpeed);
    
    rightMotor->moveTo(rightLegSteps);
    rightMotor->setSpeed(rightSpeed);

    //display->displayText(String(X) + ", " + String(Y));
    // delay(sleepDurationAfterMove_ms);

    moving = true;
    return moveTime;
};

double Movement::getWidth() {
    if (topDistance == -1) {
        throw std::invalid_argument("not ready");
    }
    return width;
}

Movement::Point Movement::getCoordinates() {
    if (X == -1 || Y == -1) {
        Serial.println("Not ready to get coordinates");
        throw std::invalid_argument("not ready");
    }

    if (moving) {
        Serial.println("Can't get coordinates while moving");
        throw std::invalid_argument("not ready");
    }
    return Movement::Point(X, Y);
}

void Movement::extend1000mm() {
    const int steps = int((1000 / circumference) * stepsPerRotation);   

    leftMotor->move(steps);
    leftMotor->setSpeed(moveSpeedSteps);

    rightMotor->move(steps);
    rightMotor->setSpeed(moveSpeedSteps);

    moving = true;
}

void Movement::disableMotors() {
    leftMotor->disableOutputs();
    rightMotor->disableOutputs();
}

bool Movement::isMoving() {
    return moving;
}

bool Movement::hasStartedHoming() {
    return startedHoming;
}

int Movement::getTopDistance() {
    return topDistance;
}


================================================
FILE: src/movement.h
================================================
#ifndef Movement_h
#define Movement_h

#include "AccelStepper.h"
#include "Arduino.h" 
#include "display.h"

// Motor driver parameters.
constexpr int printSpeedSteps = 500;
constexpr int  moveSpeedSteps = 1500;
constexpr long INFINITE_STEPS = 999999999;
constexpr long acceleration = 999999999;  // Essentially infinite, causing instant stop / start
constexpr int stepsPerRotation = 200 * 8; // 1/8 microstepping

// Geometry parameters:
// Effective diameter of the pulley+belts. Use EStep calibration to refine this value.
constexpr double diameter = 12.69;          // [mm]
const double circumference = diameter * PI; // [mm]
constexpr double midPulleyToWall = 41.0;    // (Height) distance from mid of pulley to wall [mm].
constexpr float homedStepOffsetMM = 40.0;   // Length of fully retracted belt hitting stop screw.
                                            // Measured from outer edge of screw to the point
                                            // of tangency between belt and pulley. [mm]
const int homedStepsOffset = int((homedStepOffsetMM / circumference) * stepsPerRotation);
constexpr double mass_bot = 0.55;   // Mass of the mural bot [kg].
constexpr double g_constant = 9.81; // Earth's gravitational acceleration constant [m/s^2]. Please adjust when running Mural on other planets!
constexpr double d_t = 76.027;      // [mm] Distance of tangent points, where belts touch the pulleys.
                                    // Calculated as (axis distance) 85.00 - (diameter) 12.69/sqrt(2).
constexpr double d_p = 4.4866;      // [mm] distance from Q to center of pen. Calculated as diameter/(2 * sqrt(2)).
constexpr double d_m = 10.0 + d_p;  // [mm] Distance from line connecting tangent points to center of mass of bot (projected onto wall plane).
                                    // The point where d_m and d_t meet shall be called Q.
                                    // The center of mass sits roughly at the bottom of the pen opening.
constexpr double belt_elongation_coefficient = 5e-5; // [m/N] elongation of the belts under force.
const int HOME_Y_OFFSET_MM = 350;   // Y coordinate of mural home position in image coordinate system [mm].


// Margins used for transformations of the coordinate systems:
constexpr double safeYFraction = 0.2;           // Top Margin: Image top to topDistance line.
constexpr double safeXFraction = 0.2;           // Left and right margin: from draw area boundaries to line from each pin straight down.

// Variables used for debugging:
// constexpr int sleepDurationAfterMove_ms = 0;    // Delay after linear movement [ms], e.g. 50.

// ESP setup:
constexpr int LEFT_STEP_PIN = 13;
constexpr int LEFT_DIR_PIN = 12;
constexpr int LEFT_ENABLE_PIN = 14;

constexpr int RIGHT_STEP_PIN = 27;
constexpr int RIGHT_DIR_PIN = 26;
constexpr int RIGHT_ENABLE_PIN = 25;

class Movement{
private:
    int topDistance;            // Distance between pins (d_pins) [mm].
    double minSafeY;
    double minSafeXOffset;
    double width;               // width of the drawing area [mm]
    volatile bool moving;
    bool homed;
    double X = -1;              // Location of Pen in x [mm].
    double Y = -1;              // Location of Pen in y [mm].
    bool startedHoming;
    AccelStepper *leftMotor;
    AccelStepper *rightMotor;
    Display *display;
    void setOrigin();

    struct Lengths {
        int left;
        int right;
        Lengths(int left, int right) {
            this->left = left;
            this->right = right;
        }
        Lengths() {

        }
    };

    Lengths getBeltLengths(double x, double y);

    double gamma_last_position = 0.0;   // [rad] The last known inclination of the mural bot. As the angle changes only slowly 
                                        // with position we can compute updates faster by keeping track of the last solution.
    inline void getLeftTangentPoint(const double frameX, const double frameY, const double gamma, double& x_PL, double& y_PL) const;
    inline void getRightTangentPoint(const double frameX, const double frameY, const double gamma, double& x_PR, double& y_PR) const;
    void getBeltAngles(const double frameX, const double frameY, const double gamma, double& phi_L, double& phi_R) const;
    void getBeltForces(const double phi_L, const double phi_R, double& F_L, double&F_R) const;
    double solveTorqueEquilibrium(const double phi_L, const double phi_R, const double F_L, const double F_R, const double gamma_start) const;
    double getDilationCorrectedBeltLength(double belt_length, double F_belt) const;
    
public:
    Movement(Display *display);
    struct Point {
        double x;
        double y;
        Point(double x, double y) {
            this->x = x;
            this->y = y;
        }
        Point() {
        }
    };

    static double distanceBetweenPoints(Point point1, Point point2) {
        return sqrt(pow(point2.x - point1.x, 2) + pow(point2.y - point1.y, 2));
    }

    bool isMoving();
    bool hasStartedHoming();
    double getWidth();
    Point getCoordinates();
    void setTopDistance(const int distance);
    void resumeTopDistance(const int distance);
    int getTopDistance();
    void leftStepper(const int dir);
    void rightStepper(const int dir);
    int extendToHome();
    void runSteppers();
    float beginLinearTravel(double x, double y, int speed);

    // Used for calibration of the esteps.
    void extend1000mm(); 

    Point getHomeCoordinates();
    void disableMotors();
};

#endif

================================================
FILE: src/pen.cpp
================================================
#include "pen.h"

bool shouldStop(int currentDegree, int targetDegree, bool positive) {
    if (positive) {
        return currentDegree > targetDegree;
    } else {
        return currentDegree < targetDegree;
    }
}

void doSlowMove(Pen* pen, int startDegree, int targetDegree, int speedDegPerSec) {
    if (startDegree == targetDegree) {
        return;
    }

    auto startTime = millis();

    bool positive;
    if (targetDegree > startDegree) {
        positive = true;
    } else {
        positive = false;
    }

    auto currentDegree = startDegree;

    while (!(shouldStop(currentDegree, targetDegree, positive))) {
        pen->setRawValue(currentDegree);
        delay(10);

        auto currentTime = millis();
        auto deltaTime = currentTime - startTime;
        auto progressDegrees = int(double(deltaTime) / 1000 * speedDegPerSec);

        if (!positive) {
            progressDegrees = progressDegrees * -1;
        }

        currentDegree = startDegree + progressDegrees;
    }
    pen->setRawValue(targetDegree);
    delay(200);
}


Pen::Pen()
{
    servo = new Servo();
    servo->attach(2);
    servo->write(90);
    currentPosition = 90;
}

void Pen::setRawValue(int rawValue) {
    this->servo->write(rawValue);
    currentPosition = rawValue;
}

void Pen::setPenDistance(int value) {
    Serial.println("Pen distance angle set to " + String(value));
    this->penDistance = value;
}

void Pen::slowUp() {
    if (penDistance == -1) {
        throw std::invalid_argument("not ready");
    }

    doSlowMove(this, currentPosition, 90, slowSpeedDegPerSec);
    currentPosition = 90;
}

void Pen::slowDown() {
    if (penDistance == -1) {
        throw std::invalid_argument("not ready");
    }

    doSlowMove(this, currentPosition, penDistance, slowSpeedDegPerSec);
    currentPosition = penDistance;
}

bool Pen::isDown() {
    return currentPosition == penDistance;
}

================================================
FILE: src/pen.h
================================================
#ifndef Pen_h
#define Pen_h
#include <ESP32Servo.h>
const int RETRACT_DISTANCE = 20;
class Pen {
    private:
    Servo *servo;
    int penDistance = -1;
    int slowSpeedDegPerSec = 90;
    int currentPosition = 90;
    public:
    Pen();
    void setRawValue(int rawValue);
    void setPenDistance(int value);
    void slowUp();
    void slowDown();
    bool isDown();
};
#endif

================================================
FILE: src/phases/begindrawingphase.cpp
================================================
#include "begindrawingphase.h"
BeginDrawingPhase::BeginDrawingPhase(PhaseManager* manager, Runner* runner, AsyncWebServer* server) {
    this->manager = manager;
    this->runner = runner;
    this->server = server;
}

void BeginDrawingPhase::run(AsyncWebServerRequest *request) {
    runner->start();
    request->send(200, "text/plain", "OK"); 
    server->end();
}

void BeginDrawingPhase::doneWithPhase(AsyncWebServerRequest *request) {
    manager->reset();
    manager->respondWithState(request);
}

const char* BeginDrawingPhase::getName() {
    return "BeginDrawing";
}

================================================
FILE: src/phases/begindrawingphase.h
================================================
#ifndef BeginDrawingPhase_h
#define BeginDrawingPhase_h
#include "notsupportedphase.h"
#include "phasemanager.h"
class BeginDrawingPhase : public NotSupportedPhase {
    private:
    PhaseManager* manager;
    Runner* runner;
    AsyncWebServer* server;
    public:
    BeginDrawingPhase(PhaseManager* manager, Runner* runner, AsyncWebServer* server);
    const char* getName();
    void run(AsyncWebServerRequest *request);
    void doneWithPhase(AsyncWebServerRequest *request);
};
#endif

================================================
FILE: src/phases/commandhandlingphase.cpp
================================================
#include "commandhandlingphase.h"

CommandHandlingPhase::CommandHandlingPhase(Movement* movement) {
    this->movement = movement;
}

void CommandHandlingPhase::handleCommand(AsyncWebServerRequest *request) {
    auto command = request->arg("command");
    if (command == "l-ret")
    {
        movement->leftStepper(-1);
    }
    else if (command == "l-ext")
    {
        movement->leftStepper(1);
    }
    else if (command == "l-0")
    {
        movement->leftStepper(0);
    }
    else if (command == "r-ret")
    {
        movement->rightStepper(-1);
    }
    else if (command == "r-ext")
    {
        movement->rightStepper(1);
    }
    else if (command == "r-0")
    {
        movement->rightStepper(0);
    }
    else {
        request->send(400, "text/plain", "Unsupported command");    
        return;
    }

    request->send(200, "text/plain", "OK");
}

================================================
FILE: src/phases/commandhandlingphase.h
================================================
#ifndef CommandHandlingPhase_h
#define CommandHandlingPhase_h
#include "notsupportedphase.h"
#include "phasemanager.h"
class CommandHandlingPhase : public NotSupportedPhase {
    private:
    Movement* movement;
    public:
    CommandHandlingPhase(Movement* movement);
    void handleCommand(AsyncWebServerRequest *request);
};
#endif

================================================
FILE: src/phases/extendtohomephase.cpp
================================================
#include "extendtohomephase.h"
void ExtendToHomePhase::extendToHome(AsyncWebServerRequest *request) {
    auto moveTime = movement->extendToHome() + 1; // extra second of waiting for good measure
    request->send(200, "text/plain", String(moveTime));
}

ExtendToHomePhase::ExtendToHomePhase(PhaseManager* manager, Movement* movement) {
    this->manager = manager;
    this->movement = movement;
}

const char* ExtendToHomePhase::getName() {
    return "ExtendToHome";
}

void ExtendToHomePhase::loopPhase() {
    if (movement->hasStartedHoming() && !movement->isMoving()) {
        manager->setPhase(PhaseManager::PenCalibration);
    }
}

================================================
FILE: src/phases/extendtohomephase.h
================================================
#ifndef ExtendToHomePhase_h
#define ExtendToHomePhase_h
#include "notsupportedphase.h"
#include "phasemanager.h"
#include "movement.h"
class ExtendToHomePhase : public NotSupportedPhase {
    private:
    PhaseManager* manager;
    Movement* movement;
    public:
    ExtendToHomePhase(PhaseManager* manager, Movement* movement);
    void extendToHome(AsyncWebServerRequest *request);
    const char* getName();
    void loopPhase();
};
#endif

================================================
FILE: src/phases/notsupportedphase.cpp
================================================
#include "notsupportedphase.h"
void NotSupportedPhase::handleCommand(AsyncWebServerRequest *request) {
    handleNotSupported(request);
}

void NotSupportedPhase::handleUpload(AsyncWebServerRequest *request, String filename, size_t index, uint8_t *data, size_t len, bool final) {
    handleNotSupported(request);
}

void NotSupportedPhase::setTopDistance(AsyncWebServerRequest *request) {
    handleNotSupported(request);
}

void NotSupportedPhase::extendToHome(AsyncWebServerRequest *request) {
    handleNotSupported(request);
}

void NotSupportedPhase::setServo(AsyncWebServerRequest *request) {
    handleNotSupported(request);
}

void NotSupportedPhase::setPenDistance(AsyncWebServerRequest *request) {
    handleNotSupported(request);
}

void NotSupportedPhase::resumeTopDistance(AsyncWebServerRequest *request) {
    handleNotSupported(request);
}

void NotSupportedPhase::run(AsyncWebServerRequest *request) {
    handleNotSupported(request);
}

void NotSupportedPhase::doneWithPhase(AsyncWebServerRequest *request) {
    handleNotSupported(request);
}

void NotSupportedPhase::estepsCalibration(AsyncWebServerRequest *request) {
    handleNotSupported(request);
}

const char* NotSupportedPhase::getName() {
    throw std::invalid_argument("should be overridden");
}

void NotSupportedPhase::handleNotSupported(AsyncWebServerRequest *request) {
    request->send(400, "Request is not supported by the current server phase");
}

void NotSupportedPhase::loopPhase() {
    // don't throw here - most phases dont need to do anything on loop()
}

================================================
FILE: src/phases/notsupportedphase.h
================================================
#ifndef NotSupportedPhase_h
#define NotSupportedPhase_h
#include "phase.h"
class NotSupportedPhase : public Phase {
    private:
    void handleNotSupported(AsyncWebServerRequest *request);
    public:
    void handleCommand(AsyncWebServerRequest *request);
    void handleUpload(AsyncWebServerRequest *request, String filename, size_t index, uint8_t *data, size_t len, bool final);
    void setTopDistance(AsyncWebServerRequest *request);
    void extendToHome(AsyncWebServerRequest *request);
    void setServo(AsyncWebServerRequest *request);
    void setPenDistance(AsyncWebServerRequest *request);
    void resumeTopDistance(AsyncWebServerRequest *request);
    void run(AsyncWebServerRequest *request);
    void doneWithPhase(AsyncWebServerRequest *request);
    void estepsCalibration(AsyncWebServerRequest *request);
    const char* getName();
    void loopPhase();
};
#endif

================================================
FILE: src/phases/pencalibrationphase.cpp
================================================
#include "pencalibrationphase.h"
PenCalibrationPhase::PenCalibrationPhase(PhaseManager* manager, Pen* pen) {
    this->manager = manager;
    this->pen = pen;
    this->runner = runner;
}

void PenCalibrationPhase::setServo(AsyncWebServerRequest *request) {
    const AsyncWebParameter* p = request->getParam(0);
    int angle = p->value().toInt();
    pen->setRawValue(angle);
    request->send(200, "text/plain", "OK"); 
}

void PenCalibrationPhase::setPenDistance(AsyncWebServerRequest *request) {
    const AsyncWebParameter* p = request->getParam(0);
    int angle = p->value().toInt();
    pen->setPenDistance(angle);
    pen->slowUp();
    manager->setPhase(PhaseManager::BeginDrawing);
    manager->respondWithState(request);
}

const char* PenCalibrationPhase::getName() {
    return "PenCalibration";
}

================================================
FILE: src/phases/pencalibrationphase.h
================================================
#ifndef PenCalibrationPhase_h
#define PenCalibrationPhase_h
#include "notsupportedphase.h"
#include "phasemanager.h"
#include "pen.h"
class PenCalibrationPhase : public NotSupportedPhase {
    private:
    PhaseManager* manager;
    Pen* pen;
    Runner* runner;
    public:
    PenCalibrationPhase(PhaseManager* manager, Pen* pen);
    void setServo(AsyncWebServerRequest *request);
    void setPenDistance(AsyncWebServerRequest *request);
    const char* getName();
    
};
#endif

================================================
FILE: src/phases/phase.h
================================================
#ifndef Phase_h
#define Phase_h
#include <ESPAsyncWebServer.h>
class Phase {
    public:
    virtual void handleCommand(AsyncWebServerRequest *request) = 0;
    virtual void handleUpload(AsyncWebServerRequest *request, String filename, size_t index, uint8_t *data, size_t len, bool final) = 0;
    virtual void setTopDistance(AsyncWebServerRequest *request) = 0;
    virtual void extendToHome(AsyncWebServerRequest *request) = 0;
    virtual void setServo(AsyncWebServerRequest *request) = 0;
    virtual void setPenDistance(AsyncWebServerRequest *request) = 0;
    virtual void resumeTopDistance(AsyncWebServerRequest *request) = 0;
    virtual void run(AsyncWebServerRequest *request) = 0;
    virtual void doneWithPhase(AsyncWebServerRequest *request) = 0;
    virtual void estepsCalibration(AsyncWebServerRequest *request) = 0;
    virtual const char* getName() = 0;
    virtual void loopPhase() = 0;
};
#endif

================================================
FILE: src/phases/phasemanager.cpp
================================================
#include "phasemanager.h"
#include "retractbeltsphase.h"
#include "settopdistancephase.h"
#include "extendtohomephase.h"
#include "pencalibrationphase.h"
#include "svgselectphase.h"
#include "begindrawingphase.h"
#include "AsyncJson.h"
#include "ArduinoJson.h"
#include <stdexcept>

PhaseManager::PhaseManager(Movement* movement, Pen* pen, Runner* runner, AsyncWebServer* server) {
    retractBeltsPhase = new RetractBeltsPhase(this, movement);
    setTopDistancePhase = new SetTopDistancePhase(this, movement, pen);
    extendToHomePhase = new ExtendToHomePhase(this, movement);
    penCalibrationPhase = new PenCalibrationPhase(this, pen);
    svgSelectPhase = new SvgSelectPhase(this);
    beginDrawingPhase = new BeginDrawingPhase(this, runner, server);

    this->movement = movement;
    reset();
}

Phase* PhaseManager::getCurrentPhase() {
    return currentPhase;
}

void PhaseManager::setPhase(PhaseNames name) {
    Serial.print("Switching current phase to ");
    switch (name) {
        case PhaseNames::RetractBelts:
            Serial.println("RetractBelts");
            currentPhase = retractBeltsPhase;
            break;
        case PhaseNames::SetTopDistance:
            Serial.println("SetTopDistance");
            currentPhase = setTopDistancePhase;
            break;
        case PhaseNames::ExtendToHome:
            Serial.println("ExtendToHome");
            currentPhase = extendToHomePhase;
            break;
        case PhaseNames::PenCalibration:
            Serial.println("PenCalibration");
            currentPhase = penCalibrationPhase;
            break;
        case PhaseNames::SvgSelect:
            Serial.println("SvgSelect");
            currentPhase = svgSelectPhase;
            break;
        case PhaseNames::BeginDrawing:
            Serial.println("BeginDrawing");
            currentPhase = beginDrawingPhase;
            break;
        default:
            throw std::invalid_argument("Invalid Phase");
    }
}

void PhaseManager::respondWithState(AsyncWebServerRequest *request) {
    auto currentPhase = getCurrentPhase()->getName();
    auto moving = movement->isMoving();
    auto startedHoming = movement->hasStartedHoming();
    auto homePosition = movement->getHomeCoordinates();

    auto topDistance = movement->getTopDistance();
    auto safeWidth = topDistance != -1 ? movement->getWidth() : -1;

    AsyncResponseStream *response = request->beginResponseStream("application/json");
    DynamicJsonBuffer jsonBuffer;
    JsonObject &root = jsonBuffer.createObject();

    root["phase"] = currentPhase;
    root["moving"] = moving;
    root["topDistance"] = topDistance;
    root["safeWidth"] = safeWidth;
    root["homeX"] = homePosition.x;
    root["homeY"] = homePosition.y;

    root.printTo(*response);
    request->send(response);
}

void PhaseManager::reset() {
    setPhase(PhaseManager::SetTopDistance);
}

================================================
FILE: src/phases/phasemanager.h
================================================
#ifndef PhaseManager_H
#define PhaseManager_H
#include "phase.h"
#include "movement.h"
#include "pen.h"
#include "runner.h"
#include <ESPAsyncWebServer.h>
class PhaseManager {
    private:
    Phase* currentPhase;
    Phase* retractBeltsPhase;
    Phase* setTopDistancePhase;
    Phase* extendToHomePhase;
    Phase* penCalibrationPhase;
    Phase* svgSelectPhase;
    Phase* beginDrawingPhase;
    Movement* movement;
    public:
    enum PhaseNames {RetractBelts, SetTopDistance, ExtendToHome, PenCalibration, SvgSelect, BeginDrawing};
    PhaseManager(Movement* movement, Pen* pen, Runner* runner, AsyncWebServer* server);
    Phase* getCurrentPhase();
    void setPhase(PhaseNames name);
    void respondWithState(AsyncWebServerRequest *request);
    void reset();
};
#endif

================================================
FILE: src/phases/retractbeltsphase.cpp
================================================
#include "retractbeltsphase.h"
#include "commandhandlingphase.h"
RetractBeltsPhase::RetractBeltsPhase(PhaseManager* manager, Movement* movement) : CommandHandlingPhase(movement) {
    this->manager = manager;
    this->movement = movement;
}

void RetractBeltsPhase::doneWithPhase(AsyncWebServerRequest *request) {
    manager->setPhase(PhaseManager::ExtendToHome);
    manager->respondWithState(request);
}

const char* RetractBeltsPhase::getName() {
    return "RetractBelts";
}

================================================
FILE: src/phases/retractbeltsphase.h
================================================
#ifndef RetractBelts_h
#define RetractBelts_h
#include "commandhandlingphase.h"
#include "phasemanager.h"
#include "movement.h"
#include "pen.h"
class RetractBeltsPhase : public CommandHandlingPhase {
    private:
    PhaseManager* manager;
    Movement* movement;
    public:
    RetractBeltsPhase(PhaseManager* manager, Movement* movement);
    void doneWithPhase(AsyncWebServerRequest *request);
    const char* getName();
};
#endif

================================================
FILE: src/phases/settopdistancephase.cpp
================================================
#include "settopdistancephase.h"
#include "commandhandlingphase.h"
SetTopDistancePhase::SetTopDistancePhase(PhaseManager* manager, Movement* movement, Pen* pen) : CommandHandlingPhase(movement) {
    this->manager = manager;
    this->movement = movement;
    this->pen = pen;
}

void SetTopDistancePhase::setTopDistance(AsyncWebServerRequest *request) {
    const AsyncWebParameter* p = request->getParam(0);
    int distance = p->value().toInt();
    Serial.println("Setting distance");
    movement->setTopDistance(distance); 
    manager->setPhase(PhaseManager::SvgSelect);
    manager->respondWithState(request);
}

void SetTopDistancePhase::setServo(AsyncWebServerRequest *request) {
    const AsyncWebParameter* p = request->getParam(0);
    int angle = p->value().toInt();
    pen->setRawValue(angle);
    request->send(200, "text/plain", "OK"); 
}

void SetTopDistancePhase::estepsCalibration(AsyncWebServerRequest* request) {
    Serial.println("Extending 1000mm");
    movement->extend1000mm();
    request->send(200, "text/plain", "OK");
}

const char* SetTopDistancePhase::getName() {
    return "SetTopDistance";
}

================================================
FILE: src/phases/settopdistancephase.h
================================================
#ifndef SetDistancePhase_h
#define SetDistancePhase_h
#include "commandhandlingphase.h"
#include "phasemanager.h"
#include "movement.h"
class SetTopDistancePhase : public CommandHandlingPhase {
    private:
    PhaseManager* manager;
    Movement* movement;
    Pen* pen;
    public:
    SetTopDistancePhase(PhaseManager* manager, Movement* movement, Pen* pen);
    void setTopDistance(AsyncWebServerRequest *request);
    void setServo(AsyncWebServerRequest *request);
    void estepsCalibration(AsyncWebServerRequest *request);
    const char* getName();
};
#endif

================================================
FILE: src/phases/svgselectphase.cpp
================================================
#include "svgselectphase.h"
#include "LittleFS.h"

SvgSelectPhase::SvgSelectPhase(PhaseManager* manager) {
    this->manager = manager;
}

void SvgSelectPhase::handleUpload(AsyncWebServerRequest *request, String filename, size_t index, uint8_t *data, size_t len, bool final)
{
    if (!index)
    {
        if (LittleFS.exists("/commands")) {
            LittleFS.remove("/commands");
        }

        Serial.printf("%d bytes total, %d bytes free\n",  LittleFS.totalBytes(), LittleFS.totalBytes() - LittleFS.usedBytes());
        Serial.printf("Upload size: %d bytes\n", request->contentLength());

        if (LittleFS.totalBytes() -  LittleFS.usedBytes() < request->contentLength()) {
            Serial.println("Not enough space on LittleFS");
            request->send(400, "text/plain", "Not enough space for upload");
            return;
        }
            
        request->_tempFile = LittleFS.open("/commands", "w");
        Serial.println("Upload started");
    }

    if (len)
    {
        // stream the incoming chunk to the opened file
        request->_tempFile.write(data, len);
    }

    if (final)
    {
        request->_tempFile.close();
        Serial.println("Upload finished");
        manager->setPhase(PhaseManager::RetractBelts);
    }
}

const char* SvgSelectPhase::getName() {
    return "SvgSelect";
}

================================================
FILE: src/phases/svgselectphase.h
================================================
#ifndef SvgSelectPhase_h
#define SvgSelectPhase_h
#include "notsupportedphase.h"
#include "phasemanager.h"
class SvgSelectPhase : public NotSupportedPhase {
    private:
    PhaseManager* manager;
    public:
    SvgSelectPhase(PhaseManager* manager);
    void handleUpload(AsyncWebServerRequest *request, String filename, size_t index, uint8_t *data, size_t len, bool final);
    const char* getName();
};
#endif

================================================
FILE: src/runner.cpp
================================================
#include "runner.h"
#include "tasks/movementtask.h"
#include "tasks/interpolatingmovementtask.h"
#include "tasks/pentask.h"
#include "pen.h"
#include "display.h"
#include "LittleFS.h"
using namespace std;

Runner::Runner(Movement *movement, Pen *pen, Display *display) {
    stopped = true;
    this->movement = movement;
    this->pen = pen;
    this->display = display;
}

void Runner::initTaskProvider() {
    openedFile = LittleFS.open("/commands");
    if (!openedFile || !openedFile.available()) {
        Serial.println("Failed to open file");
        throw std::invalid_argument("No File");
    }

    auto line = openedFile.readStringUntil('\n');
    if (line.charAt(0) == 'd') {
        totalDistance = line.substring(1, line.length() - 1).toDouble();
    } else {
        Serial.println("Bad file - no distance");
        throw std::invalid_argument("bad file");
    }

    auto heightLine = openedFile.readStringUntil('\n');
    if (heightLine.charAt(0) == 'h') {
        auto height = heightLine.substring(1, heightLine.length() - 1).toDouble();
        // we actually dont need it, just validating
    } else {
        Serial.println("Bad file - no height");
        throw std::invalid_argument("bad file");
    }

    Serial.println("Total distance to travel: " + String(totalDistance));

    distanceSoFar = 0;
    progress = -1; // so 0% appears right away
    startPosition = movement->getCoordinates();

    auto homeCoordinates = movement->getHomeCoordinates();
    finishingSequence[0] = new InterpolatingMovementTask(movement, homeCoordinates);
}

void Runner::start() {
    initTaskProvider();
    currentTask = getNextTask();
    currentTask->startRunning();
    stopped = false;
}

Task *Runner::getNextTask()
{
    if (openedFile.available())
    {
        auto line = openedFile.readStringUntil('\n');
        if (line.charAt(0) == 'p')
        {
            if (line.charAt(1) == '1')
            {
                //Serial.println("Pen down");
                return new PenTask(false, pen);
            }
            else
            {
                //Serial.println("Pen up");
                return new PenTask(true, pen);
            }
        }
        else
        {
            auto x = line.substring(0, line.indexOf(" ")).toDouble();
            auto y = line.substring(line.indexOf(" ") + 1).toDouble();
            targetPosition = Movement::Point(x, y);
            return new InterpolatingMovementTask(movement, targetPosition);
        }
    }
    else
    {
        if (sequenceIx < (end(finishingSequence) - begin(finishingSequence))) {
            auto currentIx = sequenceIx;
            sequenceIx = sequenceIx + 1;
            return finishingSequence[currentIx];
        } else {
            // DistanceState::storeDistance(movement->getTopDistance());
            delay(200);
            ESP.restart();
            // unreachable
            return NULL;
        }
    }
}

void Runner::run()
{
    if (stopped)
    {
        return;
    }

    if (currentTask->isDone())
    {
        if (currentTask->name() == InterpolatingMovementTask::NAME) {
            auto distanceCovered = Movement::distanceBetweenPoints(startPosition, targetPosition);
            distanceSoFar += distanceCovered;
            startPosition = targetPosition;
            auto newProgress = int(floor(distanceSoFar / totalDistance * 100));
            if (newProgress > 100) {
                newProgress = 100;
            }
            if (progress != newProgress) {
                Serial.println("Progress: " + String(newProgress));
                progress = newProgress;
                display->displayText(String(progress) + "%");
            }

        }
        delete currentTask;
        currentTask = getNextTask();
        if (currentTask != NULL)
        {
            currentTask->startRunning();
        }
        else
        {
            stopped = true;
        }
    }
}

void Runner::dryRun() {
    initTaskProvider();
    auto task = getNextTask();
    auto index = 1;
    while (task != NULL) {
        //Serial.println(String(index));
        index = index + 1;
        delete task;
        task = getNextTask();
    }
    Serial.println("All done");
}

================================================
FILE: src/runner.h
================================================
#ifndef Runner_h
#define Runner_h
#include "movement.h"
#include "tasks/task.h"
#include "pen.h"
#include "display.h"
#include "LittleFS.h"
class Runner {
    private:
    Movement *movement;
    Pen *pen;
    Display *display;
    void initTaskProvider();
    Task* getNextTask();
    Task* currentTask;
    bool stopped;
    File openedFile;
    double totalDistance;
    double distanceSoFar;
    Movement::Point startPosition;
    Movement::Point targetPosition;
    int progress;
    Task *finishingSequence[1];
    int sequenceIx = 0;
    public:
    Runner(Movement *movement, Pen *pen, Display *display);
    void start();
    void run();
    void dryRun();
};
#endif

================================================
FILE: src/tasks/interpolatingmovementtask.cpp
================================================
#include "movement.h"
#include "interpolatingmovementtask.h"
const char* InterpolatingMovementTask::NAME = "InterpolatingMovementTask";

Movement::Point getNextIncrement(Movement::Point currentPosition, Movement::Point target) {
    auto distanceBetween = Movement::distanceBetweenPoints(currentPosition, target);
    if (distanceBetween <= INCREMENT) {
        return target;
    }

    auto nextX = currentPosition.x + (INCREMENT / distanceBetween) * (target.x - currentPosition.x);
    auto nextY = currentPosition.y + (INCREMENT / distanceBetween) * (target.y - currentPosition.y);

    return Movement::Point(nextX, nextY);
}

bool arePointsEqual(Movement::Point point1, Movement::Point point2) {
    return point1.x == point2.x && point1.y == point2.y;
}

InterpolatingMovementTask::InterpolatingMovementTask(Movement *movement, Movement::Point target) {
    this->target = target;
    this->movement = movement;
}

void InterpolatingMovementTask::startRunning() {
    Serial.printf("Starting the move to %.1f, %.1f\n", target.x, target.y);
    auto currentCoordinates = movement->getCoordinates();
    auto incrementPoint = getNextIncrement(currentCoordinates, target);
    movement->beginLinearTravel(incrementPoint.x, incrementPoint.y, printSpeedSteps);
}

bool InterpolatingMovementTask::isDone() {
    if (movement->isMoving()) {
        return false;
    }

    auto currentPosition = movement->getCoordinates();
    if (arePointsEqual(currentPosition, target)) {
        return true;
    }

    auto incrementPoint = getNextIncrement(movement->getCoordinates(), target);
    movement->beginLinearTravel(incrementPoint.x, incrementPoint.y, printSpeedSteps);
    
    return false;
}



================================================
FILE: src/tasks/interpolatingmovementtask.h
================================================
#ifndef InterpolatingMovementTask_h
#define InterpolatingMovementTask_h
#include "movement.h"
#include "task.h"
const double INCREMENT = 1;
class InterpolatingMovementTask : public Task {
    private:
    Movement *movement;
    Movement::Point target;
    Movement::Point position;
    public:
    const static char* NAME;
    InterpolatingMovementTask(Movement *movement, Movement::Point target);
    bool isDone();
    void startRunning();
    const char* name() {
        return NAME;
    }
};
#endif

================================================
FILE: src/tasks/movementtask.cpp
================================================
#include "movementtask.h"
MovementTask::MovementTask(int x, int y, Movement *movement) {
    this->x = x;
    this->y = y;
    this->movement = movement;
}

void MovementTask::startRunning() {
    movement->beginLinearTravel(x, y, printSpeedSteps);
}

bool MovementTask::isDone() {
    return !(movement->isMoving());
}

================================================
FILE: src/tasks/movementtask.h
================================================
#ifndef MovementTask_h
#define MovementTask_h
#include "movement.h"
#include "task.h"
class MovementTask : public Task {
    private:
    const char* NAME = "MovementTask";
    Movement *movement;
    int x;
    int y;
    public:
    MovementTask(int x, int y, Movement *movement);
    bool isDone();
    void startRunning();
    const char* name() {
        return NAME;
    }
};
#endif

================================================
FILE: src/tasks/pentask.cpp
================================================
#include "pentask.h"
PenTask::PenTask(bool up, Pen *pen) {
    this->up = up;
    this->pen = pen;
}

void PenTask::startRunning() {
    Serial.println("Starting pen task " + String(up));
    if (up) {
        Serial.println("Pen is going up");
        pen->slowUp();
    } else {
        Serial.println("Pen is going down");
        pen->slowDown();
    }
    Serial.println("Pen task ran");
}

bool PenTask::isDone() {
    Serial.println("Pen task is done");
    return true;
}

================================================
FILE: src/tasks/pentask.h
================================================
#ifndef PenTask_h
#define PenTask_h
#include "pen.h"
#include "task.h"
class PenTask : public Task {
    private:
    const char* NAME = "PenTask";
    Pen *pen;
    bool up;
    public:
    PenTask(bool up, Pen *pen);
    bool isDone();
    void startRunning();
    const char* name() {
        return NAME;
    }
};
#endif

================================================
FILE: src/tasks/task.h
================================================
#ifndef Task_h
#define Task_h
class Task {
    public:
    virtual void startRunning() = 0;
    virtual bool isDone() = 0;
    virtual const char* name() = 0;
};
#endif

================================================
FILE: test/README
================================================

This directory is intended for PlatformIO Unit Testing and project tests.

Unit Testing is a software testing method by which individual units of
source code, sets of one or more MCU program modules together with associated
control data, usage procedures, and operating procedures, are tested to
determine whether they are fit for use. Unit testing finds problems early
in the development cycle.

More information about PlatformIO Unit Testing:
- https://docs.platformio.org/page/plus/unit-testing.html


================================================
FILE: tsc/package.json
================================================
{
  "name": "mural",
  "version": "1.0.0",
  "description": "",
  "main": "main.js",
  "scripts": {
    "build": "webpack --mode=production --node-env=production",
    "test": "echo \"Error: no test specified\" && exit 1"
  },
  "keywords": [],
  "author": "Nik Ivanov",
  "license": "GPL",
  "devDependencies": {
    "@types/jsdom": "^21.1.7",
    "@types/node": "^20.10.1",
    "@types/webpack": "^5.28.5",
    "@webpack-cli/generators": "^3.0.7",
    "clean-webpack-plugin": "^4.0.0",
    "copy-webpack-plugin": "^11.0.0",
    "declaration-bundler-webpack-plugin": "^1.0.3",
    "ts-loader": "^9.5.1",
    "typescript": "5.0.4",
    "webpack": "^5.89.0",
    "webpack-cli": "^5.1.4"
  },
  "dependencies": {
    "canvas": "^2.11.2",
    "jsdom": "^24.1.1",
    "paper": "0.12.17",
    "paper-jsdom": "0.12.17"
  }
}


================================================
FILE: tsc/src/deduplicator.ts
================================================
import { Command } from "./types";
import { getLastPoint } from "./utils";

export function dedupeCommands(commands: Command[]): Command[] {
    const dedupedCommands: Command[] = [];
    for (const command of commands) {
        if (typeof command === 'string') {
            if (dedupedCommands.length === 0 || dedupedCommands[dedupedCommands.length - 1] !== command) {
                dedupedCommands.push(command);
            }
        } else {
            const lastCommand = getLastPoint(dedupedCommands);
            if (lastCommand) {
                if (command.x !== lastCommand.x || command.y !== lastCommand.y) {
                    dedupedCommands.push(command);
                } 
            } else {
                dedupedCommands.push(command);
            }
        }
    }

    const filteredCommands: Command[] = [];
    for (let i = 0; i < dedupedCommands.length; i++) {
        if (i == 0) {
            filteredCommands.push(dedupedCommands[0]);
        } else {
            const currentCommand = dedupedCommands[i];
            const previousCommand = filteredCommands[filteredCommands.length - 1];
            if (previousCommand === 'p0' && currentCommand === 'p1') {
                //verify that we were p1 before that last p0
                for (let i = filteredCommands.length - 2; i >= 0; i--) {
                    const command = filteredCommands[i];
                    if (typeof command === 'string' && command.charAt(0) === 'p') {
                        if (command.charAt(1) === '1') {
                            // all is well
                            break;
                        } else {
                            throw new Error('Inconsistent pen movement');
                        }
                    }
                }
                filteredCommands.pop();
            } else {
                filteredCommands.push(currentCommand);
            }
        }
    }


    return filteredCommands;
}

================================================
FILE: tsc/src/flattener.ts
================================================
import {loadPaper} from './paperLoader';
import { updateStatusFn } from './types';

const paper = loadPaper();

export function flattenPaths(paths: paper.PathItem[], updateStatusFn: updateStatusFn) {
    updateStatusFn("Sorting paths");
    paths.sort((a, b) => a.isAbove(b) ? -1 : 1);

    const count = paths.length;
    for (let currentPathIx = 0; currentPathIx < paths.length - 1; currentPathIx++) {
        updateStatusFn(`Flattening paths: ${currentPathIx + 1} / ${count}`)
        const currentPath = paths[currentPathIx];
        for (let modifiedPathIx = currentPathIx + 1; modifiedPathIx < paths.length; modifiedPathIx++) {
            const pathToModify = paths[modifiedPathIx];
            const modifiedPath = pathToModify.subtract(currentPath, {
                insert: false,
            });
            paths[modifiedPathIx] = modifiedPath;
        }
    }
}

================================================
FILE: tsc/src/generator.ts
================================================
import { loadPaper } from './paperLoader';

const paper = loadPaper();

export function generatePaths(svg: paper.Item): paper.PathItem[] {
    return generatePathsRecursive(svg);
}

function generatePathsRecursive(item: paper.Item): paper.PathItem[] {
    const paths: paper.PathItem[] = [];
    for (const child of item.children) {
        if (child instanceof paper.Group) {
            const innerPaths = generatePathsRecursive(child);
            paths.push(...innerPaths);
        } else if (child instanceof paper.Path || child instanceof paper.CompoundPath) {
            
            paths.push(child);
        }
    }

    return paths;
}



================================================
FILE: tsc/src/infill.ts
================================================
import { loadPaper } from './paperLoader';
import { InfillDensity, InfilledPath } from './types';

const paper = loadPaper();

const infillDensityToSpacingMap = new Map<Exclude<InfillDensity, 0>, number>([
    [1, 20],
    [2, 15],
    [3, 10],
    [4, 7],
]);

const infillAngle = Math.PI / 4;

export function generateInfills(pathsToInfill: paper.PathItem[], infillDensity: InfillDensity): InfilledPath[] {
    const view = paper.project.view;
    const xOffset = view.size.height * Math.tan(infillAngle);
    const lines: paper.Path.Line[] = [];

    let minInfillLength = 1000;
    if (infillDensity != 0) {
        const infillSpacing = infillDensityToSpacingMap.get(infillDensity)!;
        minInfillLength = Math.floor(infillSpacing);
        const infillXSpacing = infillSpacing * Math.sqrt(2);
        for (let currentX = -xOffset; currentX < view.size.width; currentX = currentX + infillXSpacing) {
            lines.push(new paper.Path.Line({x: currentX, y: 0}, {x: currentX + xOffset, y: view.size.height}));
            lines.push(new paper.Path.Line({x: currentX, y: view.size.height}, {x: currentX + xOffset, y: 0}));
        }
    }

    const boundsPath = new paper.Path.Rectangle(view.bounds);
    
    const infilledPaths = pathsToInfill.map(path => {
        if (path.fillColor && path.fillColor.toCSS(true) === '#ffffff' && !path.strokeColor) {
            return null;
        }

        const outlinePaths: paper.Path[] = [];
        
        if (path instanceof paper.Path) {
            if (path.firstSegment && path.lastSegment) {
                outlinePaths.push(path);
            }
            
        } else if (path instanceof paper.CompoundPath) {
            const unwoundPaths = unwrapCompoundPath(path).filter(p => p.firstSegment && p.lastSegment);
            outlinePaths.push(...unwoundPaths);
        } else {
            throw new Error("Path item is neither a Path or CompoundPath");
        }

        const infillPaths: paper.Path[] = [];

        if (!path.fillColor || path.fillColor.toCSS(true) !== '#ffffff') {
            for (const line of lines) {
                const intersections = [...path.getIntersections(line), ...boundsPath.getIntersections(line)].filter(i => i.point.isInside(boundsPath.bounds));

                intersections.sort((a, b) => a.point.x - b.point.x);

                let currentLineGroup: paper.Point[] = [];
                function saveCurrentLineAsPath() {
                    if (currentLineGroup.length > 1) {
                        const infillLine = new paper.Path.Line(currentLineGroup[0], currentLineGroup[currentLineGroup.length - 1]);
                        if (infillLine.length > minInfillLength) {
                            infillPaths.push(infillLine);
                        }
                    }
                }

                for (const intersection of intersections) {
                    if (currentLineGroup.length === 0) {
                        currentLineGroup.push(intersection.point);
                    } else {
                        const previousPoint = currentLineGroup[currentLineGroup.length - 1];
                        const thisPoint = intersection.point;
                        const midPoint = getMidPoint(previousPoint, thisPoint);
                        if (path.contains(midPoint)) {
                            currentLineGroup.push(thisPoint);
                        } else {
                            saveCurrentLineAsPath();
                            currentLineGroup = [thisPoint];
                        }
                    }
                }
                saveCurrentLineAsPath();
            }
        }

        const infilledPath: InfilledPath = {
            originalPath: path,
            infillPaths,
            outlinePaths,
        };

        return infilledPath;
    }).filter((ip) => !!ip) as InfilledPath[];

    return infilledPaths;
}

function getMidPoint(point1: paper.Point, point2: paper.Point): paper.Point {
    return new paper.Point(
        point1.x + (point2.x - point1.x) / 2,
        point1.y + (point2.y - point1.y) / 2,
    );
}

function unwrapCompoundPath(path: paper.CompoundPath) {
    const paths: paper.Path[] = [];
    for (const child of path.children) {
        if (child instanceof paper.Path) {
            paths.push(child);
        } else if (child instanceof paper.CompoundPath) {
            paths.push(...unwrapCompoundPath(child));
        }
    }

    return paths;
}


================================================
FILE: tsc/src/main.ts
================================================
import { renderCommandsToSvgJson } from "./toSvgJson";
import { renderSvgJsonToCommands } from "./toCommands";
import { vectorizeImageData } from './vectorizer';
import { InfillDensities, RequestTypes } from "./types";

const updateStatusFn = (status: string) => {
    self.postMessage({
        type: "status",
        payload: status,
    });
};

self.onmessage = async (e: MessageEvent<any>) => {
    if (isVectorizeRequest(e.data)) {
        vectorize(e.data);
    } else if (isRenderSvgRequest(e.data)) {
        await render(e.data);
    } else {
        throw new Error("Bad request");
    }
};

function vectorize(request: RequestTypes.VectorizeRequest) {
    updateStatusFn("Vectorizing");
    const svgString = vectorizeImageData(request.raster, request.turdSize);
    self.postMessage({
        type: "vectorizer",
        payload: {
            svg: svgString,
        }
    });
}

async function render(request: RequestTypes.RenderSVGRequest) {
    const renderResult = await renderSvgJsonToCommands(
        request,
        updateStatusFn,
    )
    const resultSvgJson = renderCommandsToSvgJson(renderResult.commands, request.width, request.height, updateStatusFn);
    self.postMessage({
        type: "renderer",
        payload: {
            commands: renderResult.commands,
            svgJson: resultSvgJson,
            distance: renderResult.distance,
            drawDistance: renderResult.drawDistance,
        }
    });
}

function isVectorizeRequest(obj: any): obj is RequestTypes.VectorizeRequest {
    if (!('type' in obj) || obj.type !== 'vectorize') {
        return false;
    }

    if (!('raster' in obj) || typeof obj.raster !== 'object') {
        return false;
    }

    if (!('turdSize' in obj) || typeof obj.turdSize !== 'number') {
        return false;
    }

    return true;
}


function isRenderSvgRequest(obj: any): obj is RequestTypes.RenderSVGRequest {
    if (!('type' in obj) || obj.type !== 'renderSvg') {
        return false;
    }

    if (!('svgJson' in obj) || typeof obj.svgJson !== 'string') {
        return false;
    }

    if (!('width' in obj) || typeof obj.width !== 'number') {
        return false;
    }

    if (!('height' in obj) || typeof obj.height !== 'number') {
        return false;
    }

    if (!('svgWidth' in obj) || typeof obj.svgWidth !== 'number') {
        return false;
    }

    if (!('svgHeight' in obj) || typeof obj.svgHeight !== 'number') {
        return false;
    }

    if (!('homeX' in obj) || typeof obj.homeX !== 'number') {
        return false;
    }

    if (!('homeY' in obj) || typeof obj.homeY !== 'number') {
        return false;
    }

    if (!('infillDensity' in obj) || typeof obj.infillDensity !== 'number' || !InfillDensities.includes(obj.infillDensity)) {
        return false;
    }

    if (!('flattenPaths' in obj) || typeof obj.flattenPaths !== 'boolean') {
        return false;
    }

    return true;
}



================================================
FILE: tsc/src/measurer.ts
================================================
import { Command } from "./types";
import { distanceBetweenPoints, getLastPoint } from "./utils";

export function measureDistance(dedupedCommands: Command[]) {
    let totalDistance = 0;
    let drawDistance = 0;
    let penUp = true;

    for (let i = 1; i < dedupedCommands.length; i++) {
        const command = dedupedCommands[i];

        if (typeof command !== 'string') {
            const lastCommand = getLastPoint(dedupedCommands.slice(0, i));
            if (lastCommand) {
                if (command.x !== lastCommand.x || command.y !== lastCommand.y) {
                    const distance = distanceBetweenPoints(lastCommand, command);
                    totalDistance += distance;

                    if (!penUp) {
                        drawDistance += distance;
                    }
                }
            }
        } else {
            if (command === 'p0') {
                penUp = true;
            } else if (command === 'p1') {
                penUp = false;
            }
        }
    }

    return {
        totalDistance,
        drawDistance,
    };
}

================================================
FILE: tsc/src/optimizer.ts
================================================
import { loadPaper } from "./paperLoader";
import { InfilledPath } from "./types";

const paper = loadPaper();

export function optimizePaths(infilledPaths: InfilledPath[], start_x: number, start_y: number): paper.Path[] {
    const paths: paper.Path[] = [];

    function getLastPoint() {
        if (paths.length === 0) {
            throw new Error('no points found');
        }

        const lastPath = paths[paths.length - 1];
        return lastPath.closed ? lastPath.firstSegment.point : lastPath.lastSegment.point;
    }
    
    const infilledPathsCopy = [...infilledPaths];

    while (infilledPathsCopy.length > 0) {
        
        const infilledPathToProcess = getClosestInfilledPath(infilledPathsCopy, paths.length > 0 ? getLastPoint() : new paper.Point(start_x, start_y));
        const infilledPathIndex = infilledPathToProcess.infilledPathIndex;
        let outlinePathIndex = infilledPathToProcess.index;

        const infilledPath = infilledPathsCopy[infilledPathIndex];
        const outlinePathsCopy = [...infilledPath.outlinePaths];

        while (outlinePathsCopy.length > 0)
        {
            const currentOutlinePath = outlinePathsCopy[outlinePathIndex];
            paths.push(currentOutlinePath);

            outlinePathsCopy.splice(outlinePathIndex, 1);

            const nextPath = getClosestPath(outlinePathsCopy, getLastPoint(), false);
            if (nextPath) {
                outlinePathIndex = nextPath.index;
            }
        }

        const infillsCopy = [...infilledPath.infillPaths];
        while (infillsCopy.length > 0) {
            const nextInfill = getClosestPath(infillsCopy, getLastPoint(), true);
            
            if (nextInfill.reverse) {
                nextInfill.path.reverse();
            } 

            paths.push(nextInfill.path);

            infillsCopy.splice(nextInfill.index, 1);
        }

        infilledPathsCopy.splice(infilledPathIndex, 1);
    }
    return paths;
}

function getClosestInfilledPath(infilledPaths: InfilledPath[], lastPoint: paper.Point) {
    const infilledPathsCost = infilledPaths.map((ip, index) => {
        // this could be optimized by considering all segments (and potentially drawing segments in reverse)
        // at the expense of compute
        
        const closestOutlinePath = getClosestPath(ip.outlinePaths, lastPoint, false);
        return {
            infilledPath: ip,
            infilledPathIndex: index,
            ...closestOutlinePath,
        }
    });

    return infilledPathsCost.sort((a, b) => a.cost - b.cost)[0];
}

function getClosestPath(paths: paper.Path[], lastPoint: paper.Point, canReverse: boolean) {
    const pathCosts = paths.map((p, index) => {
        const startPoint = p.firstSegment.point;
        // cheaper to keep it squared
        const startPointCost = startPoint.getDistance(lastPoint, true);

        if (canReverse) {
            const endPoint = p.lastSegment.point;
            const endPointCost = endPoint.getDistance(lastPoint, true);

            if (endPointCost >= startPointCost) {
                return {path: p, cost: startPointCost, index, reverse: false};
            } else {
                return {path: p, cost: endPointCost, index, reverse: true};
            }
        } else {
            return {path: p, cost: startPointCost, index, reverse: false};
        }
    });

    return pathCosts.sort((a, b) => a.cost - b.cost)[0];
}



================================================
FILE: tsc/src/paperLoader.ts
================================================
import paper from 'paper';
import { env } from 'process';

let loaded = false;
export function loadPaper(): paper.PaperScope {
    if (env && env["server"]) {
        const paperModule = require("paper");
        return paperModule;
    } else {
        if (!loaded) {
            importScripts("https://cdnjs.cloudflare.com/ajax/libs/paper.js/0.12.17/paper-full.min.js");
            (self.paper as any as paper.PaperScope).install(self);
            loaded = true;
        }
    
        return self.paper as any as paper.PaperScope;
    }
    
}

================================================
FILE: tsc/src/renderer.ts
================================================
import { Command } from './types';
import { loadPaper } from './paperLoader';

const paper = loadPaper();

export function renderPathsToCommands(paths: paper.Path[], width: number, height: number): Command[] {
    const viewRectangle = new paper.Rectangle(0, 0, width, height);
    return paths.flatMap(p => {
        if (p.segments.length < 2) {
            return [];
        }

        const commands: Command[] = ['p0'];
        let started = false;
        let firstSegment: paper.Segment | null = null;
        for (const segment of p.segments) {
            if (viewRectangle.contains(segment.point)) {
                commands.push({
                    x: segment.point.x,
                    y: segment.point.y,
                }); 
                if (!started) {
                    firstSegment = segment;
                    commands.push('p1');
                    started = true;
                }
            }
            
        }
        
        if (firstSegment && p.closed) {
            commands.push({
                x: firstSegment.point.x,
                y: firstSegment.point.y,
            }); 
        }

        return commands;
    });
}



================================================
FILE: tsc/src/tester.ts
================================================
import { renderCommandsToSvgJson } from "./toSvgJson";
import { vectorizeImageData } from './vectorizer';
import { renderSvgJsonToCommands } from "./toCommands";
import path from 'path';
import * as fs from 'fs';
import {loadImage, createCanvas} from 'canvas';
import { loadPaper } from './paperLoader';
import { RequestTypes } from "./types";

const paper = loadPaper();

const width = 1000;
const renderScaleFactor = 2;

function updater(status: string) {
    console.log(status);
}

async function main_vectorRasterVector() {
    const dirPath = path.join(__dirname, '../svgs');
    const inDir = fs.opendirSync(dirPath);

    const outDirPath = path.join(__dirname, '../svgs/out/');
    

    let dirEntry = inDir.readSync();
    while (dirEntry) {
        if (dirEntry.isFile() && dirEntry.name.endsWith(".svg")) {
            if (dirEntry.name == "finitecurve.svg") {
                console.log(`processing ${dirEntry.name}`);

                const file = fs.readFileSync(path.join(dirEntry.path, dirEntry.name));
                const svgString = file.toString();
                const [imageData, svgWidth, svgHeight] = await getImageData(svgString, renderScaleFactor);

                const vectorizedSvg = vectorizeImageData(imageData, 2);
                const vectorizedJson = convertSvgToSvgJson(vectorizedSvg);

                const height = Math.floor(svgHeight * (width / svgWidth));
                
                const request: RequestTypes.RenderSVGRequest = {
                    svgJson: vectorizedJson,
                    height,
                    width,
                    svgWidth: width * renderScaleFactor,
                    svgHeight: height * renderScaleFactor,
                    homeX: 0,
                    homeY: 0,
                    infillDensity: 4,
                    type: 'renderSvg',
                    flattenPaths: false,
                };
                const result = await renderSvgJsonToCommands(request, updater);
                const resultSvgJsonString = renderCommandsToSvgJson(result.commands, width, height, updater);
                const resultSvg = convertSvgJsonToSvg(resultSvgJsonString, width, height);
                const fullResultPath = path.join(outDirPath, dirEntry.name);
                fs.writeFileSync(fullResultPath, resultSvg);
            }
            
        }
        dirEntry = inDir.readSync();
    }
};

async function getImageData(svgString: string, renderScaleFactor: number): Promise<[ImageData, number, number]> {
    const jsdom = require("jsdom");
    const window = new jsdom.JSDOM().window;
    const parser = new window.DOMParser();
    const serializer = new window.XMLSerializer();

    const svgDoc = parser.parseFromString(svgString, 'image/svg+xml');
    const svgElement = svgDoc.documentElement;
    const svgWidth = parseFloat(svgElement.getAttribute('width')!);
    const svgHeight = parseFloat(svgElement.getAttribute('height')!);
    
    const scale = Math.min(width / svgWidth) * renderScaleFactor;
    const scaledHeight = svgHeight * scale;
    const scaledWidth = svgWidth * scale;

    svgElement.setAttribute('width', scaledWidth.toString());
    svgElement.setAttribute('height', scaledHeight.toString());

    const scaledSvgString = serializer.serializeToString(svgElement);

    const image = await loadImage(`data:image/svg+xml;base64,${btoa(scaledSvgString)}`);
    
    const canvas = createCanvas(scaledWidth, scaledHeight);
    const ctx = canvas.getContext('2d');
    
    // Draw the image onto the canvas
    ctx.drawImage(image, 0, 0, scaledWidth, scaledHeight);
    
    // Get the ImageData from the canvas
    const imageData = ctx.getImageData(0, 0, canvas.width, canvas.height);
    const dataMap = new Map();
    for (const val of imageData.data) {
        if (!dataMap.has(val)) {
            dataMap.set(val, 1);
        } else {
            dataMap.set(val, dataMap.get(val) + 1);
        }
    }
    const kvps = Array.from(dataMap);
    kvps.sort((a, b) => b[1] - a[1]);
    const fullImageData: ImageData = { ...imageData, colorSpace: "srgb", height: canvas.height, width: canvas.width};

    return [fullImageData, svgWidth, svgHeight];
}

async function main_pathTracer() {
    const dirPath = path.join(__dirname, '../svgs');
    const inDir = fs.opendirSync(dirPath);

    const outDirPath = path.join(__dirname, '../svgs/out/');
    

    let dirEntry = inDir.readSync();
    while (dirEntry) {
        if (dirEntry.isFile() && dirEntry.name.endsWith(".svg")) {
            if (dirEntry.name == "finitecurve.svg") {
                console.log(`processing ${dirEntry.name}`);

                const file = fs.readFileSync(path.join(dirEntry.path, dirEntry.name));
                const svgString = file.toString();

                const jsdom = require("jsdom");
                const window = new jsdom.JSDOM().window;
                const parser = new window.DOMParser();

                const svgDoc = parser.parseFromString(svgString, 'image/svg+xml');
                const svgElement = svgDoc.documentElement;
                const svgWidth = parseFloat(svgElement.getAttribute('width')!);
                const svgHeight = parseFloat(svgElement.getAttribute('height')!);

                const height = Math.floor(svgHeight * (width / svgWidth));

                const svgJson = convertSvgToSvgJson(svgString);
                const request: RequestTypes.RenderSVGRequest = {
                    svgJson: svgJson,
                    height,
                    width,
                    svgWidth,
                    svgHeight,
                    homeX: 0,
                    homeY: 0,
                    infillDensity: 0,
                    type: 'renderSvg',
                    flattenPaths: false,
                };
                const result = await renderSvgJsonToCommands(request, updater);
                fs.writeFileSync(path.join(__dirname, '../svgs/out/commands.txt'), result.commands.join('\n'));
                const resultSvgJsonString = renderCommandsToSvgJson(result.commands, width, height, updater);
                const resultSvg = convertSvgJsonToSvg(resultSvgJsonString, width, height);
                const fullResultPath = path.join(outDirPath, dirEntry.name);
                fs.writeFileSync(fullResultPath, resultSvg);
            }
            
        }
        dirEntry = inDir.readSync();
    }
}

function convertSvgToSvgJson(svgString: string) {
    const size = new paper.Size(Number.MAX_SAFE_INTEGER, Number.MAX_SAFE_INTEGER);
    paper.setup(size);
    const svg = paper.project.importSVG(svgString, {
        expandShapes: true,
        applyMatrix: true,
    });
    const json = svg.exportJSON();
    paper.project.remove();

    return json;
}

function convertSvgJsonToSvg(svgJson: string, width: number, height: number): string {
    const size = new paper.Size(width, height);
    paper.setup(size);
    paper.project.importJSON(svgJson);
    const svg = paper.project.exportSVG({
        asString: true,
    }) as string;
    paper.project.remove();
    return svg;
}

main_pathTracer();



================================================
FILE: tsc/src/toCommands.ts
================================================
import { Command, RequestTypes, updateStatusFn } from './types';
import { generatePaths } from './generator';
import { generateInfills } from './infill';
import { optimizePaths } from './optimizer';
import { renderPathsToCommands } from './renderer';
import { trimCommands } from './trimmer';
import { dedupeCommands } from './deduplicator';
import { measureDistance } from './measurer';
import { loadPaper } from './paperLoader';
import { flattenPaths } from './flattener';

const paper = loadPaper();

export async function renderSvgJsonToCommands(
    request: RequestTypes.RenderSVGRequest,
    updateStatusFn: updateStatusFn,
) {
    paper.setup({width: request.width, height: request.height});

    updateStatusFn("Importing");
    const svg = paper.project.importJSON(request.svgJson);

    // scale the document so its coordinates match the world 1:1, in mm
    const projectToViewRatio = request.width / request.svgWidth;

    console.log(`Scaling by ${projectToViewRatio}`);
    svg.scale(projectToViewRatio, {x: 0, y: 0});
    svg.applyMatrix = true;

    updateStatusFn("Generating paths");
    const paths = generatePaths(svg);

    paths.forEach(p => p.flatten(0.5));

    if (request.flattenPaths) {
        flattenPaths(paths, updateStatusFn);
    }

    updateStatusFn("Generating infill");
    const pathsWithInfills = generateInfills(paths, request.infillDensity);

    updateStatusFn("Optimizing paths");
    const optimizedPaths = optimizePaths(pathsWithInfills, request.homeX, request.homeY);

    updateStatusFn("Generating commands");
    const commands = renderPathsToCommands(optimizedPaths, request.width, request.height);
    commands.push('p0');

    const trimmedCommands = trimCommands(commands);

    updateStatusFn("Simplifying commands");

    const dedupedCommands = dedupeCommands(trimmedCommands);

    updateStatusFn("Measuring total distance");
    dedupedCommands.unshift(`h${request.height}`);
    const distances = measureDistance(dedupedCommands);
    const totalDistance = +distances.totalDistance.toFixed(1);
    dedupedCommands.unshift(`d${totalDistance}`);

    const commandStrings = dedupedCommands.map(stringifyCommand);
    return {
        commands: commandStrings,
        distance: totalDistance,
        drawDistance: +distances.drawDistance.toFixed(1),
    };
}

function stringifyCommand(cmd: Command): string {
    if (typeof cmd === 'string') {
        return cmd;
    } else {
        return `${cmd.x} ${cmd.y}`;
    }
}


================================================
FILE: tsc/src/toSvgJson.ts
================================================
import { loadPaper } from './paperLoader';
import {updateStatusFn} from './types';

const paper = loadPaper();

export function renderCommandsToSvgJson(commands: string[], width: number, height: number, updateStatusFn: updateStatusFn): string {
    updateStatusFn("Rendering result");
    const size = new paper.Size(width, height);
    paper.setup(size);

    const layer = paper.project.activeLayer;

    let pathPoints: paper.Point[] = [];

    let penUp = true;
    function handlePenChange(newPenUp: boolean) {
        if (penUp === newPenUp) {
            // no change in state, nothing to do
            return;
        }

        if (penUp) {
            // the pen was up, now it's down
            // discard whatever points we've accumulated while not drawing except the last one, which
            // is our starting

            penUp = false;
            if (pathPoints.length > 1) {
                pathPoints = [pathPoints[pathPoints.length - 1]];
            }
        } else {
            penUp = true;
            // then pen was down, now it's up
            // create a path out of path points we've traveled so far
            if (pathPoints.length > 1) {
                const segments = pathPoints.map(p => new paper.Segment(p));
                const path = new paper.Path(segments);
                path.fillColor = new paper.Color('transparent');
                path.strokeColor = new paper.Color('black');
                layer.addChild(path);

                pathPoints = [pathPoints[pathPoints.length - 1]];
            }
        }
    }
    
    for (const command of commands) {
        const firstChar = command.charAt(0);
        if (firstChar === 'd') {
            console.log(`Total distance ${command.slice(1)}`);
            continue;
        } else if (firstChar === 'h') {
            console.log(`Drawing height is ${command.slice(1)}`);
            continue;
        } else if (firstChar === 'p') {
            const secondChar = command.charAt(1);
            if (secondChar === '1') {
                handlePenChange(false);
            } else if (secondChar === '0') {
                handlePenChange(true);
            }
        }
        else {
            const coords = command.split(' ');
            const x = parseFloat(coords[0]);
            const y = parseFloat(coords[1]);
            pathPoints.push(new paper.Point(x, y));
        }
    }

    handlePenChange(true);

    const backgroundPath = new paper.Path([
        new paper.Segment({x: 0, y: 0}),
        new paper.Segment({x: width, y: 0}),
        new paper.Segment({x: width, y: height}),
        new paper.Segment({x: 0, y: height}),
        new paper.Segment({x: 0, y: 0}),
    ]);
    backgroundPath.fillColor = new paper.Color('#ffffff');
    backgroundPath.strokeColor = new paper.Color('transparent');
    layer.addChild(backgroundPath);
    backgroundPath.sendToBack();
    
    return paper.project.exportJSON({
        asString: true,
    });
}

================================================
FILE: tsc/src/tracer.js
================================================
/**
 * Ported from POTrace: https://github.com/kilobtye/potrace
 */

/* Copyright (C) 2001-2013 Peter Selinger.
 *
 * A javascript port of Potrace (http://potrace.sourceforge.net).
 * 
 * Licensed under the GPL
 * 
 * Usage
 *   loadImageFromFile(file) : load image from File API
 *   loadImageFromUrl(url): load image from URL
 *     because of the same-origin policy, can not load image from another domain.
 *     input color/grayscale image is simply converted to binary image. no pre-
 *     process is performed.
 * 
 *   setParameter({para1: value, ...}) : set parameters
 *     parameters:
 *        turnpolicy ("black" / "white" / "left" / "right" / "minority" / "majority")
 *          how to resolve ambiguities in path decomposition. (default: "minority")       
 *        turdsize
 *          suppress speckles of up to this size (default: 2)
 *        optcurve (true / false)
 *          turn on/off curve optimization (default: true)
 *        alphamax
 *          corner threshold parameter (default: 1)
 *        opttolerance 
 *          curve optimization tolerance (default: 0.2)
 *       
 *   process(callback) : wait for the image be loaded, then run potrace algorithm,
 *                       then call callback function.
 * 
 *   getSVG(size, opt_type) : return a string of generated SVG image.
 *                                    result_image_size = original_image_size * size
 *                                    optional parameter opt_type can be "curve"
 */

export var Potrace = (function () {

    function Point(x, y) {
        this.x = x;
        this.y = y;
    }

    Point.prototype.copy = function () {
        return new Point(this.x, this.y);
    };

    function Bitmap(w, h) {
        this.w = w;
        this.h = h;
        this.size = w * h;
        this.arraybuffer = new ArrayBuffer(this.size);
        this.data = new Int8Array(this.arraybuffer);
    }

    Bitmap.prototype.at = function (x, y) {
        return (x >= 0 && x < this.w && y >= 0 && y < this.h) &&
            this.data[this.w * y + x] === 1;
    };

    Bitmap.prototype.index = function (i) {
        var point = new Point();
        point.y = Math.floor(i / this.w);
        point.x = i - point.y * this.w;
        return point;
    };

    Bitmap.prototype.flip = function (x, y) {
        if (this.at(x, y)) {
            this.data[this.w * y + x] = 0;
        } else {
            this.data[this.w * y + x] = 1;
        }
    };

    Bitmap.prototype.copy = function () {
        var bm = new Bitmap(this.w, this.h), i;
        for (i = 0; i < this.size; i++) {
            bm.data[i] = this.data[i];
        }
        return bm;
    };

    function Path() {
        this.area = 0;
        this.len = 0;
        this.curve = {};
        this.pt = [];
        this.minX = 100000;
        this.minY = 100000;
        this.maxX = -1;
        this.maxY = -1;
    }

    function Curve(n) {
        this.n = n;
        this.tag = new Array(n);
        this.c = new Array(n * 3);
        this.alphaCurve = 0;
        this.vertex = new Array(n);
        this.alpha = new Array(n);
        this.alpha0 = new Array(n);
        this.beta = new Array(n);
    }

    var bm = null,
        pathlist = [],
        callback,
        info = {
            isReady: false,
            turnpolicy: "minority",
            turdsize: 2,
            optcurve: true,
            alphamax: 1,
            opttolerance: 0.2
        };

    function setParameter(obj) {
        var key;
        for (key in obj) {
            if (obj.hasOwnProperty(key)) {
                info[key] = obj[key];
            }
        }
    }

    function setBitmap(width, height, data) {
        clear();
        bm = new Bitmap(width, height);
        bm.data = data;
        info.isReady = true;
        bmToPathlist();
        processPath();
    }

    function bmToPathlist() {
        var bm1 = bm.copy(),
            currentPoint = new Point(0, 0),
            path;

        function findNext(point) {
            var i = bm1.w * point.y + point.x;
            while (i < bm1.size && bm1.data[i] !== 1) {
                i++;
            }
            return i < bm1.size && bm1.index(i);
        }

        function majority(x, y) {
            var i, a, ct;
            for (i = 2; i < 5; i++) {
            
Download .txt
gitextract_5fn61nmk/

├── .devcontainer/
│   ├── Containerfile
│   └── devcontainer.json
├── .gitignore
├── .vscode/
│   ├── extensions.json
│   ├── launch.json
│   ├── settings.json
│   └── tasks.json
├── BOM.md
├── KinematicModel.md
├── LICENSE.md
├── README.md
├── STLs/
│   ├── PD clamp.stl
│   ├── black parts.3mf
│   ├── bottom.stl
│   ├── cover.stl
│   ├── idler.stl
│   ├── left belt loop.stl
│   ├── left motor carrier.stl
│   ├── mural v1.1.step
│   ├── pen.stl
│   ├── right belt loop.stl
│   ├── right motor carrier.stl
│   ├── servo clamp.stl
│   ├── servo pen driver.stl
│   └── white parts.3mf
├── build.py
├── data/
│   └── www/
│       ├── client.js
│       ├── dpad.less
│       ├── index.html
│       ├── main.css
│       ├── main.js
│       └── svgControl.js
├── images/
│   └── doc/
│       ├── kinematic_model1.drawio
│       └── tangent_point.drawio
├── include/
│   └── README
├── lib/
│   └── README
├── partitions.csv
├── platformio.ini
├── src/
│   ├── display.cpp
│   ├── display.h
│   ├── main.cpp
│   ├── movement.cpp
│   ├── movement.h
│   ├── pen.cpp
│   ├── pen.h
│   ├── phases/
│   │   ├── begindrawingphase.cpp
│   │   ├── begindrawingphase.h
│   │   ├── commandhandlingphase.cpp
│   │   ├── commandhandlingphase.h
│   │   ├── extendtohomephase.cpp
│   │   ├── extendtohomephase.h
│   │   ├── notsupportedphase.cpp
│   │   ├── notsupportedphase.h
│   │   ├── pencalibrationphase.cpp
│   │   ├── pencalibrationphase.h
│   │   ├── phase.h
│   │   ├── phasemanager.cpp
│   │   ├── phasemanager.h
│   │   ├── retractbeltsphase.cpp
│   │   ├── retractbeltsphase.h
│   │   ├── settopdistancephase.cpp
│   │   ├── settopdistancephase.h
│   │   ├── svgselectphase.cpp
│   │   └── svgselectphase.h
│   ├── runner.cpp
│   ├── runner.h
│   └── tasks/
│       ├── interpolatingmovementtask.cpp
│       ├── interpolatingmovementtask.h
│       ├── movementtask.cpp
│       ├── movementtask.h
│       ├── pentask.cpp
│       ├── pentask.h
│       └── task.h
├── test/
│   └── README
└── tsc/
    ├── package.json
    ├── src/
    │   ├── deduplicator.ts
    │   ├── flattener.ts
    │   ├── generator.ts
    │   ├── infill.ts
    │   ├── main.ts
    │   ├── measurer.ts
    │   ├── optimizer.ts
    │   ├── paperLoader.ts
    │   ├── renderer.ts
    │   ├── tester.ts
    │   ├── toCommands.ts
    │   ├── toSvgJson.ts
    │   ├── tracer.js
    │   ├── trimmer.ts
    │   ├── types.ts
    │   ├── utils.ts
    │   └── vectorizer.ts
    ├── tsconfig.json
    └── webpack.config.js
Download .txt
SYMBOL INDEX (121 symbols across 43 files)

FILE: data/www/client.js
  function leftRetractDown (line 1) | async function leftRetractDown() {
  function leftExtendDown (line 5) | async function leftExtendDown() {
  function rightRetractDown (line 9) | async function rightRetractDown() {
  function rightExtendDown (line 13) | async function rightExtendDown() {
  function leftRetractUp (line 17) | async function leftRetractUp() {
  function leftExtendUp (line 21) | async function leftExtendUp() {
  function rightRetractUp (line 25) | async function rightRetractUp() {
  function rightExtendUp (line 29) | async function rightExtendUp() {
  function postCommand (line 33) | async function postCommand(command) {

FILE: data/www/main.js
  function checkIfExtendedToHome (line 14) | async function checkIfExtendedToHome(extendToHomeTime) {
  function init (line 35) | function init() {
  function verifyUpload (line 464) | function verifyUpload(state) {
  function adaptToState (line 511) | function adaptToState(state) {
  function getInfillDensity (line 544) | function getInfillDensity() {
  function getTurdSize (line 553) | function getTurdSize() {
  function getFlattenPaths (line 557) | function getFlattenPaths() {

FILE: data/www/svgControl.js
  function initSvgControl (line 12) | function initSvgControl() {
  function requestChangeInTransform (line 30) | function requestChangeInTransform(direction) {
  function resetTransform (line 62) | function resetTransform() {
  function setSvgString (line 73) | function setSvgString(svgString, currentState) {
  function normalizeSvg (line 83) | function normalizeSvg() {
  function convertUnitsToPx (line 119) | function convertUnitsToPx(dimension) {
  function getTargetWidth (line 140) | function getTargetWidth() {
  function getTargetHeight (line 144) | function getTargetHeight() {
  function getRenderScale (line 148) | function getRenderScale() {
  function getRenderSvg (line 152) | function getRenderSvg() {
  function applyTransform (line 156) | function applyTransform() {
  function makeTransformedSvgWithHeight (line 169) | function makeTransformedSvgWithHeight() {
  function updateTransformText (line 200) | function updateTransformText() {
  function getCurrentSvgImageData (line 207) | async function getCurrentSvgImageData() {
  function loadImage (line 226) | async function loadImage(src) {
  function getSvgJson (line 235) | function getSvgJson(svgString) {
  function convertJsonToDataURL (line 248) | function convertJsonToDataURL(json, width, height) {

FILE: src/display.h
  function class (line 5) | class Display {

FILE: src/main.cpp
  function notFound (line 24) | void notFound(AsyncWebServerRequest *request)
  function handleUpload (line 29) | void handleUpload(AsyncWebServerRequest *request, String filename, size_...
  function handleGetState (line 33) | void handleGetState(AsyncWebServerRequest *request) {
  function setup (line 38) | void setup()
  function loop (line 145) | void loop()

FILE: src/movement.h
  function class (line 52) | class Movement{
  function Point (line 93) | struct Point {
  function distanceBetweenPoints (line 104) | static double distanceBetweenPoints(Point point1, Point point2) {

FILE: src/pen.cpp
  function shouldStop (line 3) | bool shouldStop(int currentDegree, int targetDegree, bool positive) {
  function doSlowMove (line 11) | void doSlowMove(Pen* pen, int startDegree, int targetDegree, int speedDe...

FILE: src/pen.h
  function class (line 5) | class Pen {

FILE: src/phases/begindrawingphase.h
  function class (line 5) | class BeginDrawingPhase : public NotSupportedPhase {

FILE: src/phases/commandhandlingphase.h
  function class (line 5) | class CommandHandlingPhase : public NotSupportedPhase {

FILE: src/phases/extendtohomephase.h
  function class (line 6) | class ExtendToHomePhase : public NotSupportedPhase {

FILE: src/phases/notsupportedphase.h
  function class (line 4) | class NotSupportedPhase : public Phase {

FILE: src/phases/pencalibrationphase.h
  function class (line 6) | class PenCalibrationPhase : public NotSupportedPhase {

FILE: src/phases/phase.h
  function class (line 4) | class Phase {

FILE: src/phases/phasemanager.cpp
  function Phase (line 24) | Phase* PhaseManager::getCurrentPhase() {

FILE: src/phases/phasemanager.h
  function class (line 8) | class PhaseManager {

FILE: src/phases/retractbeltsphase.h
  function class (line 7) | class RetractBeltsPhase : public CommandHandlingPhase {

FILE: src/phases/settopdistancephase.h
  function class (line 6) | class SetTopDistancePhase : public CommandHandlingPhase {

FILE: src/phases/svgselectphase.h
  function class (line 5) | class SvgSelectPhase : public NotSupportedPhase {

FILE: src/runner.cpp
  function Task (line 58) | Task *Runner::getNextTask()

FILE: src/runner.h
  function class (line 8) | class Runner {

FILE: src/tasks/interpolatingmovementtask.cpp
  function getNextIncrement (line 5) | Movement::Point getNextIncrement(Movement::Point currentPosition, Moveme...
  function arePointsEqual (line 17) | bool arePointsEqual(Movement::Point point1, Movement::Point point2) {

FILE: src/tasks/interpolatingmovementtask.h
  function class (line 6) | class InterpolatingMovementTask : public Task {

FILE: src/tasks/movementtask.h
  function class (line 5) | class MovementTask : public Task {

FILE: src/tasks/pentask.h
  function class (line 5) | class PenTask : public Task {

FILE: src/tasks/task.h
  function class (line 3) | class Task {

FILE: tsc/src/deduplicator.ts
  function dedupeCommands (line 4) | function dedupeCommands(commands: Command[]): Command[] {

FILE: tsc/src/flattener.ts
  function flattenPaths (line 6) | function flattenPaths(paths: paper.PathItem[], updateStatusFn: updateSta...

FILE: tsc/src/generator.ts
  function generatePaths (line 5) | function generatePaths(svg: paper.Item): paper.PathItem[] {
  function generatePathsRecursive (line 9) | function generatePathsRecursive(item: paper.Item): paper.PathItem[] {

FILE: tsc/src/infill.ts
  function generateInfills (line 15) | function generateInfills(pathsToInfill: paper.PathItem[], infillDensity:...
  function getMidPoint (line 101) | function getMidPoint(point1: paper.Point, point2: paper.Point): paper.Po...
  function unwrapCompoundPath (line 108) | function unwrapCompoundPath(path: paper.CompoundPath) {

FILE: tsc/src/main.ts
  function vectorize (line 23) | function vectorize(request: RequestTypes.VectorizeRequest) {
  function render (line 34) | async function render(request: RequestTypes.RenderSVGRequest) {
  function isVectorizeRequest (line 51) | function isVectorizeRequest(obj: any): obj is RequestTypes.VectorizeRequ...
  function isRenderSvgRequest (line 68) | function isRenderSvgRequest(obj: any): obj is RequestTypes.RenderSVGRequ...

FILE: tsc/src/measurer.ts
  function measureDistance (line 4) | function measureDistance(dedupedCommands: Command[]) {

FILE: tsc/src/optimizer.ts
  function optimizePaths (line 6) | function optimizePaths(infilledPaths: InfilledPath[], start_x: number, s...
  function getClosestInfilledPath (line 60) | function getClosestInfilledPath(infilledPaths: InfilledPath[], lastPoint...
  function getClosestPath (line 76) | function getClosestPath(paths: paper.Path[], lastPoint: paper.Point, can...

FILE: tsc/src/paperLoader.ts
  function loadPaper (line 5) | function loadPaper(): paper.PaperScope {

FILE: tsc/src/renderer.ts
  function renderPathsToCommands (line 6) | function renderPathsToCommands(paths: paper.Path[], width: number, heigh...

FILE: tsc/src/tester.ts
  function updater (line 15) | function updater(status: string) {
  function main_vectorRasterVector (line 19) | async function main_vectorRasterVector() {
  function getImageData (line 65) | async function getImageData(svgString: string, renderScaleFactor: number...
  function main_pathTracer (line 110) | async function main_pathTracer() {
  function convertSvgToSvgJson (line 163) | function convertSvgToSvgJson(svgString: string) {
  function convertSvgJsonToSvg (line 176) | function convertSvgJsonToSvg(svgJson: string, width: number, height: num...

FILE: tsc/src/toCommands.ts
  function renderSvgJsonToCommands (line 14) | async function renderSvgJsonToCommands(
  function stringifyCommand (line 69) | function stringifyCommand(cmd: Command): string {

FILE: tsc/src/toSvgJson.ts
  function renderCommandsToSvgJson (line 6) | function renderCommandsToSvgJson(commands: string[], width: number, heig...

FILE: tsc/src/tracer.js
  function Point (line 41) | function Point(x, y) {
  function Bitmap (line 50) | function Bitmap(w, h) {
  function Path (line 86) | function Path() {
  function Curve (line 97) | function Curve(n) {
  function setParameter (line 120) | function setParameter(obj) {
  function setBitmap (line 129) | function setBitmap(width, height, data) {
  function bmToPathlist (line 138) | function bmToPathlist() {
  function processPath (line 260) | function processPath() {
  function process (line 1178) | function process(c) {
  function clear (line 1192) | function clear() {
  function getSVG (line 1199) | function getSVG(size, opt_type) {

FILE: tsc/src/trimmer.ts
  function trimCommands (line 3) | function trimCommands<T extends Command>(commands: T[], precision = 1): ...

FILE: tsc/src/types.ts
  type updateStatusFn (line 2) | type updateStatusFn = (status: string) => void;
  type CoordinateCommand (line 4) | type CoordinateCommand = {
  type PenUpCommand (line 9) | type PenUpCommand = 'p0';
  type PenDownCommand (line 10) | type PenDownCommand = 'p1';
  type DistanceCommand (line 11) | type DistanceCommand = `d${number}`
  type HeightCommand (line 12) | type HeightCommand = `h${number}`;
  type Command (line 14) | type Command = CoordinateCommand | PenUpCommand | PenDownCommand | Dista...
  type InfilledPath (line 16) | type InfilledPath = {
  type InfillDensity (line 22) | type InfillDensity = 0 | 1 | 2 | 3 | 4;
  type RenderSVGRequest (line 26) | type RenderSVGRequest = {
  type VectorizeRequest (line 39) | type VectorizeRequest = {

FILE: tsc/src/utils.ts
  function getLastPoint (line 8) | function getLastPoint(commandList: Command[]) : CoordinateCommand | unde...
  function distanceBetweenPoints (line 21) | function distanceBetweenPoints(cmd1: CoordinateCommand, cmd2: Coordinate...
  function distanceBetweenPointsSquared (line 25) | function distanceBetweenPointsSquared(cmd1: CoordinateCommand, cmd2: Coo...
  function isPathWhiteOnly (line 29) | function isPathWhiteOnly(path: paper.PathItem): boolean {

FILE: tsc/src/vectorizer.ts
  constant WHITE_COLOR (line 7) | const WHITE_COLOR = new paper.Color("#FFFFFF");
  function vectorizeImageData (line 9) | function vectorizeImageData(imageData: ImageData, turdSize: number): str...
  function createPathsFromColorMatrix (line 31) | function createPathsFromColorMatrix(colorMatrix: paper.Color[][], turdSi...
  function colorDistance (line 58) | function colorDistance(color1: paper.Color, color2: paper.Color) {
Condensed preview — 94 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (259K chars).
[
  {
    "path": ".devcontainer/Containerfile",
    "chars": 1273,
    "preview": "ARG VARIANT=bookworm\nFROM mcr.microsoft.com/vscode/devcontainers/base:${VARIANT}\n\nENV DEBIAN_FRONTEND=noninteractive\nRUN"
  },
  {
    "path": ".devcontainer/devcontainer.json",
    "chars": 790,
    "preview": "{\n\t\"name\": \"PlatformIO (Community)\",\n\t\"build\": {\n\t\t\"dockerfile\": \"Containerfile\",\n\t\t\"context\": \".\",\n\t\t\"args\": {\n\t\t\t\"FEDO"
  },
  {
    "path": ".gitignore",
    "chars": 137,
    "preview": ".pio\ndata/www/worker/*\ntsc/node_modules\ntsc/package-lock.json\ntsc/dist\ntsc/dist_packed\ntsc/svgs/*\n.DS_Store\n.vscode/c_cp"
  },
  {
    "path": ".vscode/extensions.json",
    "chars": 274,
    "preview": "{\n    // See http://go.microsoft.com/fwlink/?LinkId=827846\n    // for the documentation about the extensions.json format"
  },
  {
    "path": ".vscode/launch.json",
    "chars": 2143,
    "preview": "// AUTOMATICALLY GENERATED FILE. PLEASE DO NOT MODIFY IT MANUALLY\n//\n// PlatformIO Debugging Solution\n//\n// Documentatio"
  },
  {
    "path": ".vscode/settings.json",
    "chars": 1361,
    "preview": "{\n    \"files.associations\": {\n        \"*.tcc\": \"cpp\",\n        \"array\": \"cpp\",\n        \"atomic\": \"cpp\",\n        \"bitset\":"
  },
  {
    "path": ".vscode/tasks.json",
    "chars": 214,
    "preview": "{\n\t\"version\": \"2.0.0\",\n\t\"tasks\": [\n\t\t{\n\t\t\t\"type\": \"typescript\",\n\t\t\t\"tsconfig\": \"tsc/tsconfig.json\",\n\t\t\t\"problemMatcher\":"
  },
  {
    "path": "BOM.md",
    "chars": 2091,
    "preview": "# Bill of Materials\nAll parts can be found on Amazon, AliExpress, Ebay etc. Make sure the items you're ordering match th"
  },
  {
    "path": "KinematicModel.md",
    "chars": 6931,
    "preview": "# Mural Kinematic Model\n\nThe Mural bot is suspended on two belts. As it moves across the wall it rotates slightly,\nin pa"
  },
  {
    "path": "LICENSE.md",
    "chars": 13816,
    "preview": "## Creative Commons Attribution-NonCommercial 4.0 International Public License\n\nBy exercising the Licensed Rights (defin"
  },
  {
    "path": "README.md",
    "chars": 1191,
    "preview": "# [getmural.me](https://getmural.me)\n\nPlease find the main documentation on https://getmural.me. \n\n# Additional Informat"
  },
  {
    "path": "build.py",
    "chars": 345,
    "preview": "import os\nImport(\"env\")\n\nprint(\"Transpiling TS code\")\nenv.Execute(\"rm data/www/worker/* || true\")\ncurrentPath = os.getcw"
  },
  {
    "path": "data/www/client.js",
    "chars": 759,
    "preview": "export async function leftRetractDown() {\n    await postCommand(\"l-ret\");\n}\n\nexport async function leftExtendDown() {\n  "
  },
  {
    "path": "data/www/dpad.less",
    "chars": 6924,
    "preview": ".set {\n    overflow: hidden;\n    text-align: center;\n   .d-pad { margin-right: 40px; }\n   .d-pad, .o-pad {\n      display"
  },
  {
    "path": "data/www/index.html",
    "chars": 12137,
    "preview": "<!doctype html>\n<html lang=\"en\">\n\n<head>\n  <meta charset=\"utf-8\">\n  <meta name=\"viewport\" content=\"width=device-width, i"
  },
  {
    "path": "data/www/main.css",
    "chars": 210,
    "preview": "html,\nbody {\n  height: 100%;\n}\n\nbody {\n  display: flex;\n  align-items: center;\n  padding-top: 40px;\n  padding-bottom: 40"
  },
  {
    "path": "data/www/main.js",
    "chars": 17523,
    "preview": "import * as svgControl from './svgControl.js';\nimport * as client from './client.js';\n\nlet currentState = null;\n\nlet cur"
  },
  {
    "path": "data/www/svgControl.js",
    "chars": 8265,
    "preview": "document.body.addEventListener(\"click\", function(e) {\n\tif(e.target && e.target.nodeName == \"A\" && e.target.parentElement"
  },
  {
    "path": "images/doc/kinematic_model1.drawio",
    "chars": 13270,
    "preview": "<mxfile host=\"app.diagrams.net\" agent=\"Mozilla/5.0 (Macintosh; Intel Mac OS X 10_15_7) AppleWebKit/537.36 (KHTML, like G"
  },
  {
    "path": "images/doc/tangent_point.drawio",
    "chars": 4808,
    "preview": "<mxfile host=\"app.diagrams.net\" agent=\"Mozilla/5.0 (Macintosh; Intel Mac OS X 10_15_7) AppleWebKit/537.36 (KHTML, like G"
  },
  {
    "path": "include/README",
    "chars": 1386,
    "preview": "\nThis directory is intended for project header files.\n\nA header file is a file containing C declarations and macro defin"
  },
  {
    "path": "lib/README",
    "chars": 1037,
    "preview": "\nThis directory is intended for project specific (private) libraries.\nPlatformIO will compile them to static libraries a"
  },
  {
    "path": "partitions.csv",
    "chars": 235,
    "preview": "# ESP-IDF Partition Table\n# Name,   Type, SubType, Offset,  Size, Flags\nnvs,      data, nvs,     0x9000,  0x6000,\nphy_in"
  },
  {
    "path": "platformio.ini",
    "chars": 879,
    "preview": "; PlatformIO Project Configuration File\n;\n;   Build options: build flags, source filter\n;   Upload options: custom uploa"
  },
  {
    "path": "src/display.cpp",
    "chars": 1830,
    "preview": "#include \"display.h\"\n#include <Adafruit_SSD1306.h>\n\n#define SCREEN_WIDTH 128 // OLED display width, in pixels\n#define SC"
  },
  {
    "path": "src/display.h",
    "chars": 273,
    "preview": "#ifndef Display_h\n#define Display_h\n#include <Adafruit_SSD1306.h>\n\nclass Display {\n    private:\n    Adafruit_SSD1306 *di"
  },
  {
    "path": "src/main.cpp",
    "chars": 4507,
    "preview": "#include <Arduino.h>\n#include <WiFiManager.h>\n#include <AsyncTCP.h>\n#include <ESPAsyncWebServer.h>\n#include <FS.h>\n#incl"
  },
  {
    "path": "src/movement.cpp",
    "chars": 17894,
    "preview": "#include \"movement.h\"\n#include \"display.h\"\n#include <stdexcept>\n\nMovement::Movement(Display *display)\n{\n    this->displa"
  },
  {
    "path": "src/movement.h",
    "chars": 5490,
    "preview": "#ifndef Movement_h\n#define Movement_h\n\n#include \"AccelStepper.h\"\n#include \"Arduino.h\" \n#include \"display.h\"\n\n// Motor dr"
  },
  {
    "path": "src/pen.cpp",
    "chars": 1903,
    "preview": "#include \"pen.h\"\n\nbool shouldStop(int currentDegree, int targetDegree, bool positive) {\n    if (positive) {\n        retu"
  },
  {
    "path": "src/pen.h",
    "chars": 380,
    "preview": "#ifndef Pen_h\n#define Pen_h\n#include <ESP32Servo.h>\nconst int RETRACT_DISTANCE = 20;\nclass Pen {\n    private:\n    Servo "
  },
  {
    "path": "src/phases/begindrawingphase.cpp",
    "chars": 577,
    "preview": "#include \"begindrawingphase.h\"\nBeginDrawingPhase::BeginDrawingPhase(PhaseManager* manager, Runner* runner, AsyncWebServe"
  },
  {
    "path": "src/phases/begindrawingphase.h",
    "chars": 490,
    "preview": "#ifndef BeginDrawingPhase_h\n#define BeginDrawingPhase_h\n#include \"notsupportedphase.h\"\n#include \"phasemanager.h\"\nclass B"
  },
  {
    "path": "src/phases/commandhandlingphase.cpp",
    "chars": 871,
    "preview": "#include \"commandhandlingphase.h\"\n\nCommandHandlingPhase::CommandHandlingPhase(Movement* movement) {\n    this->movement ="
  },
  {
    "path": "src/phases/commandhandlingphase.h",
    "chars": 335,
    "preview": "#ifndef CommandHandlingPhase_h\n#define CommandHandlingPhase_h\n#include \"notsupportedphase.h\"\n#include \"phasemanager.h\"\nc"
  },
  {
    "path": "src/phases/extendtohomephase.cpp",
    "chars": 640,
    "preview": "#include \"extendtohomephase.h\"\nvoid ExtendToHomePhase::extendToHome(AsyncWebServerRequest *request) {\n    auto moveTime "
  },
  {
    "path": "src/phases/extendtohomephase.h",
    "chars": 443,
    "preview": "#ifndef ExtendToHomePhase_h\n#define ExtendToHomePhase_h\n#include \"notsupportedphase.h\"\n#include \"phasemanager.h\"\n#includ"
  },
  {
    "path": "src/phases/notsupportedphase.cpp",
    "chars": 1549,
    "preview": "#include \"notsupportedphase.h\"\nvoid NotSupportedPhase::handleCommand(AsyncWebServerRequest *request) {\n    handleNotSupp"
  },
  {
    "path": "src/phases/notsupportedphase.h",
    "chars": 883,
    "preview": "#ifndef NotSupportedPhase_h\n#define NotSupportedPhase_h\n#include \"phase.h\"\nclass NotSupportedPhase : public Phase {\n    "
  },
  {
    "path": "src/phases/pencalibrationphase.cpp",
    "chars": 812,
    "preview": "#include \"pencalibrationphase.h\"\nPenCalibrationPhase::PenCalibrationPhase(PhaseManager* manager, Pen* pen) {\n    this->m"
  },
  {
    "path": "src/phases/pencalibrationphase.h",
    "chars": 482,
    "preview": "#ifndef PenCalibrationPhase_h\n#define PenCalibrationPhase_h\n#include \"notsupportedphase.h\"\n#include \"phasemanager.h\"\n#in"
  },
  {
    "path": "src/phases/phase.h",
    "chars": 914,
    "preview": "#ifndef Phase_h\n#define Phase_h\n#include <ESPAsyncWebServer.h>\nclass Phase {\n    public:\n    virtual void handleCommand("
  },
  {
    "path": "src/phases/phasemanager.cpp",
    "chars": 2878,
    "preview": "#include \"phasemanager.h\"\n#include \"retractbeltsphase.h\"\n#include \"settopdistancephase.h\"\n#include \"extendtohomephase.h\""
  },
  {
    "path": "src/phases/phasemanager.h",
    "chars": 778,
    "preview": "#ifndef PhaseManager_H\n#define PhaseManager_H\n#include \"phase.h\"\n#include \"movement.h\"\n#include \"pen.h\"\n#include \"runner"
  },
  {
    "path": "src/phases/retractbeltsphase.cpp",
    "chars": 480,
    "preview": "#include \"retractbeltsphase.h\"\n#include \"commandhandlingphase.h\"\nRetractBeltsPhase::RetractBeltsPhase(PhaseManager* mana"
  },
  {
    "path": "src/phases/retractbeltsphase.h",
    "chars": 435,
    "preview": "#ifndef RetractBelts_h\n#define RetractBelts_h\n#include \"commandhandlingphase.h\"\n#include \"phasemanager.h\"\n#include \"move"
  },
  {
    "path": "src/phases/settopdistancephase.cpp",
    "chars": 1128,
    "preview": "#include \"settopdistancephase.h\"\n#include \"commandhandlingphase.h\"\nSetTopDistancePhase::SetTopDistancePhase(PhaseManager"
  },
  {
    "path": "src/phases/settopdistancephase.h",
    "chars": 566,
    "preview": "#ifndef SetDistancePhase_h\n#define SetDistancePhase_h\n#include \"commandhandlingphase.h\"\n#include \"phasemanager.h\"\n#inclu"
  },
  {
    "path": "src/phases/svgselectphase.cpp",
    "chars": 1336,
    "preview": "#include \"svgselectphase.h\"\n#include \"LittleFS.h\"\n\nSvgSelectPhase::SvgSelectPhase(PhaseManager* manager) {\n    this->man"
  },
  {
    "path": "src/phases/svgselectphase.h",
    "chars": 413,
    "preview": "#ifndef SvgSelectPhase_h\n#define SvgSelectPhase_h\n#include \"notsupportedphase.h\"\n#include \"phasemanager.h\"\nclass SvgSele"
  },
  {
    "path": "src/runner.cpp",
    "chars": 4207,
    "preview": "#include \"runner.h\"\n#include \"tasks/movementtask.h\"\n#include \"tasks/interpolatingmovementtask.h\"\n#include \"tasks/pentask"
  },
  {
    "path": "src/runner.h",
    "chars": 675,
    "preview": "#ifndef Runner_h\n#define Runner_h\n#include \"movement.h\"\n#include \"tasks/task.h\"\n#include \"pen.h\"\n#include \"display.h\"\n#i"
  },
  {
    "path": "src/tasks/interpolatingmovementtask.cpp",
    "chars": 1696,
    "preview": "#include \"movement.h\"\n#include \"interpolatingmovementtask.h\"\nconst char* InterpolatingMovementTask::NAME = \"Interpolatin"
  },
  {
    "path": "src/tasks/interpolatingmovementtask.h",
    "chars": 504,
    "preview": "#ifndef InterpolatingMovementTask_h\n#define InterpolatingMovementTask_h\n#include \"movement.h\"\n#include \"task.h\"\nconst do"
  },
  {
    "path": "src/tasks/movementtask.cpp",
    "chars": 319,
    "preview": "#include \"movementtask.h\"\nMovementTask::MovementTask(int x, int y, Movement *movement) {\n    this->x = x;\n    this->y = "
  },
  {
    "path": "src/tasks/movementtask.h",
    "chars": 388,
    "preview": "#ifndef MovementTask_h\n#define MovementTask_h\n#include \"movement.h\"\n#include \"task.h\"\nclass MovementTask : public Task {"
  },
  {
    "path": "src/tasks/pentask.cpp",
    "chars": 479,
    "preview": "#include \"pentask.h\"\nPenTask::PenTask(bool up, Pen *pen) {\n    this->up = up;\n    this->pen = pen;\n}\n\nvoid PenTask::star"
  },
  {
    "path": "src/tasks/pentask.h",
    "chars": 324,
    "preview": "#ifndef PenTask_h\n#define PenTask_h\n#include \"pen.h\"\n#include \"task.h\"\nclass PenTask : public Task {\n    private:\n    co"
  },
  {
    "path": "src/tasks/task.h",
    "chars": 168,
    "preview": "#ifndef Task_h\n#define Task_h\nclass Task {\n    public:\n    virtual void startRunning() = 0;\n    virtual bool isDone() = "
  },
  {
    "path": "test/README",
    "chars": 504,
    "preview": "\nThis directory is intended for PlatformIO Unit Testing and project tests.\n\nUnit Testing is a software testing method by"
  },
  {
    "path": "tsc/package.json",
    "chars": 819,
    "preview": "{\n  \"name\": \"mural\",\n  \"version\": \"1.0.0\",\n  \"description\": \"\",\n  \"main\": \"main.js\",\n  \"scripts\": {\n    \"build\": \"webpac"
  },
  {
    "path": "tsc/src/deduplicator.ts",
    "chars": 1958,
    "preview": "import { Command } from \"./types\";\nimport { getLastPoint } from \"./utils\";\n\nexport function dedupeCommands(commands: Com"
  },
  {
    "path": "tsc/src/flattener.ts",
    "chars": 874,
    "preview": "import {loadPaper} from './paperLoader';\nimport { updateStatusFn } from './types';\n\nconst paper = loadPaper();\n\nexport f"
  },
  {
    "path": "tsc/src/generator.ts",
    "chars": 649,
    "preview": "import { loadPaper } from './paperLoader';\n\nconst paper = loadPaper();\n\nexport function generatePaths(svg: paper.Item): "
  },
  {
    "path": "tsc/src/infill.ts",
    "chars": 4471,
    "preview": "import { loadPaper } from './paperLoader';\nimport { InfillDensity, InfilledPath } from './types';\n\nconst paper = loadPap"
  },
  {
    "path": "tsc/src/main.ts",
    "chars": 2925,
    "preview": "import { renderCommandsToSvgJson } from \"./toSvgJson\";\nimport { renderSvgJsonToCommands } from \"./toCommands\";\nimport { "
  },
  {
    "path": "tsc/src/measurer.ts",
    "chars": 1090,
    "preview": "import { Command } from \"./types\";\nimport { distanceBetweenPoints, getLastPoint } from \"./utils\";\n\nexport function measu"
  },
  {
    "path": "tsc/src/optimizer.ts",
    "chars": 3425,
    "preview": "import { loadPaper } from \"./paperLoader\";\nimport { InfilledPath } from \"./types\";\n\nconst paper = loadPaper();\n\nexport f"
  },
  {
    "path": "tsc/src/paperLoader.ts",
    "chars": 548,
    "preview": "import paper from 'paper';\nimport { env } from 'process';\n\nlet loaded = false;\nexport function loadPaper(): paper.PaperS"
  },
  {
    "path": "tsc/src/renderer.ts",
    "chars": 1174,
    "preview": "import { Command } from './types';\nimport { loadPaper } from './paperLoader';\n\nconst paper = loadPaper();\n\nexport functi"
  },
  {
    "path": "tsc/src/tester.ts",
    "chars": 7111,
    "preview": "import { renderCommandsToSvgJson } from \"./toSvgJson\";\nimport { vectorizeImageData } from './vectorizer';\nimport { rende"
  },
  {
    "path": "tsc/src/toCommands.ts",
    "chars": 2481,
    "preview": "import { Command, RequestTypes, updateStatusFn } from './types';\nimport { generatePaths } from './generator';\nimport { g"
  },
  {
    "path": "tsc/src/toSvgJson.ts",
    "chars": 2973,
    "preview": "import { loadPaper } from './paperLoader';\nimport {updateStatusFn} from './types';\n\nconst paper = loadPaper();\n\nexport f"
  },
  {
    "path": "tsc/src/tracer.js",
    "chars": 40080,
    "preview": "/**\n * Ported from POTrace: https://github.com/kilobtye/potrace\n */\n\n/* Copyright (C) 2001-2013 Peter Selinger.\n *\n * A "
  },
  {
    "path": "tsc/src/trimmer.ts",
    "chars": 386,
    "preview": "import { Command } from \"./types\";\n\nexport function trimCommands<T extends Command>(commands: T[], precision = 1): Comma"
  },
  {
    "path": "tsc/src/types.ts",
    "chars": 1096,
    "preview": "\nexport type updateStatusFn = (status: string) => void;\n\nexport type CoordinateCommand = {\n    x: number;\n    y: number;"
  },
  {
    "path": "tsc/src/utils.ts",
    "chars": 1581,
    "preview": "import { Command, CoordinateCommand } from \"./types\";\n//import path from 'path';\n//import * as fs from 'fs';\nimport {loa"
  },
  {
    "path": "tsc/src/vectorizer.ts",
    "chars": 1941,
    "preview": "import { loadPaper } from './paperLoader';\nimport {Potrace} from './tracer';\n\n\nconst paper = loadPaper();\n\nconst WHITE_C"
  },
  {
    "path": "tsc/tsconfig.json",
    "chars": 12132,
    "preview": "{\n  \"compilerOptions\": {\n    /* Visit https://aka.ms/tsconfig to read more about this file */\n\n    /* Projects */\n    //"
  },
  {
    "path": "tsc/webpack.config.js",
    "chars": 1334,
    "preview": "// Generated using webpack-cli https://github.com/webpack/webpack-cli\n\nconst path = require('path');\n\nconst isProduction"
  }
]

// ... and 14 more files (download for full content)

About this extraction

This page contains the full source code of the nikivanov/mural GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 94 files (27.5 MB), approximately 64.7k tokens, and a symbol index with 121 extracted functions, classes, methods, constants, and types. Use this with OpenClaw, Claude, ChatGPT, Cursor, Windsurf, or any other AI tool that accepts text input. You can copy the full output to your clipboard or download it as a .txt file.

Extracted by GitExtract — free GitHub repo to text converter for AI. Built by Nikandr Surkov.

Copied to clipboard!