Merge branch 'chairAdjust' into dev - chairAdjust tracking + pcb
6
.gitignore
vendored
@ -38,5 +38,11 @@ yarn-error.log*
|
|||||||
.env.production.local
|
.env.production.local
|
||||||
|
|
||||||
|
|
||||||
|
#kicad
|
||||||
|
**/*-backups/*.zip
|
||||||
|
\#auto_saved_files\#
|
||||||
|
*.lck
|
||||||
|
|
||||||
|
|
||||||
# other
|
# other
|
||||||
octave-workspace
|
octave-workspace
|
||||||
|
66
README.md
@ -10,8 +10,8 @@ The projects in the folders `board_control/` and `board_motorctl/` are no longer
|
|||||||
<img src="doc/2023.09.09_armchair-frame.jpg" alt="Photo machine" style="width:60%;"><br>
|
<img src="doc/2023.09.09_armchair-frame.jpg" alt="Photo machine" style="width:60%;"><br>
|
||||||
*Photo of the built frame that carries the armchair*
|
*Photo of the built frame that carries the armchair*
|
||||||
|
|
||||||
|
<br>
|
||||||
|
|
||||||
# Overview
|
|
||||||
## Current Features
|
## Current Features
|
||||||
- **Control Modes:**
|
- **Control Modes:**
|
||||||
- **Joystick:** Control movement via hardware joystick mounted on the right armrest
|
- **Joystick:** Control movement via hardware joystick mounted on the right armrest
|
||||||
@ -46,7 +46,7 @@ The projects in the folders `board_control/` and `board_motorctl/` are no longer
|
|||||||
- **Electric Chair Adjustment:** Control 4 Relays powering motors that adjust the chair rest positions
|
- **Electric Chair Adjustment:** Control 4 Relays powering motors that adjust the chair rest positions
|
||||||
- **Wi-Fi:**
|
- **Wi-Fi:**
|
||||||
- Hosts wireless network
|
- Hosts wireless network
|
||||||
- Webserver with webroot in SPIFFS
|
- Web server with webroot in SPIFFS
|
||||||
- HTTP API for controlling the chair (remote control)
|
- HTTP API for controlling the chair (remote control)
|
||||||
- **React web-app:** Virtual joystick sending data to http-API (placed in SPIFFS)
|
- **React web-app:** Virtual joystick sending data to http-API (placed in SPIFFS)
|
||||||
|
|
||||||
@ -69,15 +69,31 @@ The projects in the folders `board_control/` and `board_motorctl/` are no longer
|
|||||||
- Chair adjustment
|
- Chair adjustment
|
||||||
- Simple App
|
- Simple App
|
||||||
|
|
||||||
|
<br>
|
||||||
|
|
||||||
## Hardware Setup / Electrical
|
## Hardware Setup / Electrical
|
||||||
### PCB
|
### Control-PCB
|
||||||
The firmware is designed for an ESP32 microcontroller integrated into a custom PCB developed here: [Project Work 2020](https://pfusch.zone/project-work-2020)
|
The firmware is designed for an ESP32 microcontroller integrated into a custom PCB developed here: [Project Work 2020](https://pfusch.zone/project-work-2020)
|
||||||
|
|
||||||
### Connection Plan
|
### Connection Plan
|
||||||
A detailed diagram illustrating all components and wiring can be found in the file [connection-plan.drawio.pdf](connection-plan.drawio.pdf).
|
A detailed diagram illustrating all components and wiring can be found in the file [connection-plan.drawio.pdf](connection-plan.drawio.pdf).
|
||||||
For more details refer to the documentation on the [website](https://pfusch.zone/electric-armchair-v2).
|
For more details refer to the documentation on the [website](https://pfusch.zone/electric-armchair-v2).
|
||||||
|
|
||||||
|
### Chair-Adjust Relay-Board
|
||||||
|
A custom pcb with relays and protection for controlling the 2 motors that adjust the rest positions of the armchair was created in this repository as well:
|
||||||
|
Date: 2024.09.08
|
||||||
|
Folder: [hardware/chairAdjust-relayBoard](hardware/chairAdjust-relayBoard)
|
||||||
|
Schematic: [hardware/chairAdjust-relayBoard/export/schematic.pdf](hardware/chairAdjust-relayBoard/export/schematic.pdf)
|
||||||
|
<br>
|
||||||
|
<br>
|
||||||
|
<p align="center">
|
||||||
|
<img src="hardware/chairAdjust-relayBoard/export/layout.svg" style="width: 40%;">
|
||||||
|
<img src="hardware/chairAdjust-relayBoard/export/layout.jpg" width="36%" />
|
||||||
|
</p>
|
||||||
|
|
||||||
|
|
||||||
|
<br>
|
||||||
|
<br>
|
||||||
|
|
||||||
|
|
||||||
# Installation
|
# Installation
|
||||||
@ -101,6 +117,10 @@ npm install
|
|||||||
```
|
```
|
||||||
|
|
||||||
|
|
||||||
|
<br>
|
||||||
|
<br>
|
||||||
|
|
||||||
|
|
||||||
# Building the Project
|
# Building the Project
|
||||||
## React-webapp
|
## React-webapp
|
||||||
When flashing to the ESP32, the files in the `react-app/build/` folder are written to a SPIFFS partition.
|
When flashing to the ESP32, the files in the `react-app/build/` folder are written to a SPIFFS partition.
|
||||||
@ -148,16 +168,43 @@ idf.py monitor
|
|||||||
```
|
```
|
||||||
|
|
||||||
|
|
||||||
|
<br>
|
||||||
|
<br>
|
||||||
|
|
||||||
|
|
||||||
# Usage / User Interface
|
# Usage / User Interface
|
||||||
|
|
||||||
## Encoder Functions
|
## Quickstart
|
||||||
|
- **Browse / select any mode**
|
||||||
|
- `[long press]` opens menu for selecting the desired mode (*JOYSTICK* for driving)
|
||||||
|
- **Driving**
|
||||||
|
- `[3x click]` enters *JOYSTICK* mode
|
||||||
|
- **Rest position**
|
||||||
|
- `[rotate]` adjusts the leg rest position
|
||||||
|
- `[press + rotate]` at the same time: adjusts the back rest position
|
||||||
|
- alternatively enter *ADJUST* mode and control rests via joystick
|
||||||
|
|
||||||
**When not in MENU mode**, the button (encoder click) has the following functions:
|
<br>
|
||||||
|
|
||||||
|
## Encoder Functions
|
||||||
|
- *When not in MENU mode*, **rotating the encoder** has the following functions:
|
||||||
|
|
||||||
|
| Encoder Event | Action |
|
||||||
|
|---------------------|---------------------------|
|
||||||
|
| rotate left | Move leg rest up by 10% |
|
||||||
|
| rotate right | Move leg rest DOWN by 10% |
|
||||||
|
| press + rotate left | Move back rest down by 5% |
|
||||||
|
| press + rotate left | Move back rest up by 5% |
|
||||||
|
|
||||||
|
Note: first tick is ignored -> quickly rotate 2 ticks at first
|
||||||
|
|
||||||
|
<br>
|
||||||
|
|
||||||
|
- *When not in MENU mode*, **clicking the encoder** has the following functions:
|
||||||
|
|
||||||
| Count | Type | Action | Description |
|
| Count | Type | Action | Description |
|
||||||
|-------|---------------|----------------------|---------------------------------------------------------------------------------------------|
|
|-------|---------------|----------------------|---------------------------------------------------------------------------------------------|
|
||||||
| 1x long | switch mode | **MENU_MODE_SELECT** | Open menu for selecting the current control mode |
|
| 1x long | switch mode | **MENU_MODE_SELECT** | Open **menu for selecting the current control mode** |
|
||||||
| 1x | control | [MASSAGE] **freeze** input | When in massage mode: lock or unlock joystick input at current position. |
|
| 1x | control | [MASSAGE] **freeze** input | When in massage mode: lock or unlock joystick input at current position. |
|
||||||
| 1x short, 1x long | switch mode | **ADJUST-CHAIR** | Switch to mode where the armchair leg and backrest are controlled via joystick. |
|
| 1x short, 1x long | switch mode | **ADJUST-CHAIR** | Switch to mode where the armchair leg and backrest are controlled via joystick. |
|
||||||
| 2x | toggle mode | **IDLE** <=> previous| Enable/disable chair armchair (e.g., enable after startup or switch to previous mode after timeout). |
|
| 2x | toggle mode | **IDLE** <=> previous| Enable/disable chair armchair (e.g., enable after startup or switch to previous mode after timeout). |
|
||||||
@ -169,7 +216,10 @@ idf.py monitor
|
|||||||
| 8x | toggle option| **deceleration limit** | Disable/enable deceleration limit (default on) => more responsive. |
|
| 8x | toggle option| **deceleration limit** | Disable/enable deceleration limit (default on) => more responsive. |
|
||||||
| 12x | toggle option| **alt stick mapping** | Toggle between default and alternative stick mapping (reverse direction swapped). |
|
| 12x | toggle option| **alt stick mapping** | Toggle between default and alternative stick mapping (reverse direction swapped). |
|
||||||
|
|
||||||
**When in MENU_SETTINGS mode** (5x click), the encoder controls the settings menu: (similar in MENU_MODE_SELECT)
|
|
||||||
|
<br>
|
||||||
|
|
||||||
|
- When in **MENU_SETTINGS mode** (5x click), the encoder controls the settings menu: (similar in MENU_MODE_SELECT)
|
||||||
|
|
||||||
| Encoder Event | Current Menu | Action |
|
| Encoder Event | Current Menu | Action |
|
||||||
|---------------|--------------|--------------------------------------------------------------|
|
|---------------|--------------|--------------------------------------------------------------|
|
||||||
@ -180,6 +230,8 @@ idf.py monitor
|
|||||||
| rotate | main-menu | Scroll through menu items. |
|
| rotate | main-menu | Scroll through menu items. |
|
||||||
| rotate | value-select | Change value. |
|
| rotate | value-select | Change value. |
|
||||||
|
|
||||||
|
<br>
|
||||||
|
|
||||||
## HTTP Mode
|
## HTTP Mode
|
||||||
Control the armchair via a virtual joystick on the web interface.
|
Control the armchair via a virtual joystick on the web interface.
|
||||||
|
|
||||||
|
@ -23,7 +23,7 @@ void task_button(void *task_button_parameters)
|
|||||||
task_button_parameters_t *objects = (task_button_parameters_t *)task_button_parameters;
|
task_button_parameters_t *objects = (task_button_parameters_t *)task_button_parameters;
|
||||||
ESP_LOGI(TAG, "Initializing command-button and starting handle loop");
|
ESP_LOGI(TAG, "Initializing command-button and starting handle loop");
|
||||||
// create button instance
|
// create button instance
|
||||||
buttonCommands commandButton(objects->control, objects->joystick, objects->encoderQueue, objects->motorLeft, objects->motorRight, objects->buzzer);
|
buttonCommands commandButton(objects->control, objects->joystick, objects->encoderQueue, objects->motorLeft, objects->motorRight, objects->legRest, objects->backRest, objects->buzzer);
|
||||||
// start handle loop
|
// start handle loop
|
||||||
commandButton.startHandleLoop();
|
commandButton.startHandleLoop();
|
||||||
}
|
}
|
||||||
@ -35,8 +35,10 @@ buttonCommands::buttonCommands(
|
|||||||
controlledArmchair *control_f,
|
controlledArmchair *control_f,
|
||||||
evaluatedJoystick *joystick_f,
|
evaluatedJoystick *joystick_f,
|
||||||
QueueHandle_t encoderQueue_f,
|
QueueHandle_t encoderQueue_f,
|
||||||
controlledMotor *motorLeft_f,
|
controlledMotor * motorLeft_f,
|
||||||
controlledMotor *motorRight_f,
|
controlledMotor *motorRight_f,
|
||||||
|
cControlledRest *legRest_f,
|
||||||
|
cControlledRest *backRest_f,
|
||||||
buzzer_t *buzzer_f)
|
buzzer_t *buzzer_f)
|
||||||
{
|
{
|
||||||
// copy object pointers
|
// copy object pointers
|
||||||
@ -46,6 +48,8 @@ buttonCommands::buttonCommands(
|
|||||||
motorLeft = motorLeft_f;
|
motorLeft = motorLeft_f;
|
||||||
motorRight = motorRight_f;
|
motorRight = motorRight_f;
|
||||||
buzzer = buzzer_f;
|
buzzer = buzzer_f;
|
||||||
|
legRest = legRest_f;
|
||||||
|
backRest = backRest_f;
|
||||||
// TODO declare / configure evaluatedSwitch here instead of config (unnecessary that button object is globally available - only used here)?
|
// TODO declare / configure evaluatedSwitch here instead of config (unnecessary that button object is globally available - only used here)?
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -141,6 +145,12 @@ void buttonCommands::action (uint8_t count, bool lastPressLong){
|
|||||||
control->changeMode(controlMode_t::MASSAGE); //switch to MASSAGE mode
|
control->changeMode(controlMode_t::MASSAGE); //switch to MASSAGE mode
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case 7:
|
||||||
|
legRest->setTargetPercent(100);
|
||||||
|
backRest->setTargetPercent(0);
|
||||||
|
ESP_LOGW(TAG, "7x TESTING: set leg/back rest to 100/0");
|
||||||
|
break;
|
||||||
|
|
||||||
case 8:
|
case 8:
|
||||||
// ## toggle "sport-mode" ##
|
// ## toggle "sport-mode" ##
|
||||||
//toggle deceleration fading between on and off
|
//toggle deceleration fading between on and off
|
||||||
@ -172,13 +182,16 @@ void buttonCommands::action (uint8_t count, bool lastPressLong){
|
|||||||
// when not in MENU_SETTINGS mode, repeatedly receives events from encoder button
|
// when not in MENU_SETTINGS mode, repeatedly receives events from encoder button
|
||||||
// and takes the corresponding action
|
// and takes the corresponding action
|
||||||
// this function has to be started once in a separate task
|
// this function has to be started once in a separate task
|
||||||
#define INPUT_TIMEOUT 500 // duration of no button events, after which action is run (implicitly also is 'long-press' time)
|
#define INPUT_TIMEOUT 600 // duration of no button events, after which action is run (implicitly also is 'long-press' time)
|
||||||
|
#define IGNORE_BUTTON_TIME_SINCE_LAST_ROTATE 2600 // time that has to be passed since last encoder rotate click for button count command to be accepted (e.g. prevent long press action after PRESS+ROTATE was used)
|
||||||
|
#define IGNORE_ROTATE_COUNT 1 //amount of ignored clicks before action is actually taken (ignore accidental touches)
|
||||||
void buttonCommands::startHandleLoop()
|
void buttonCommands::startHandleLoop()
|
||||||
{
|
{
|
||||||
//-- variables --
|
//-- variables --
|
||||||
bool isPressed = false;
|
static bool isPressed = false;
|
||||||
static rotary_encoder_event_t event; // store event data
|
static rotary_encoder_event_t event; // store event data
|
||||||
int rotateCount = 0; // temporary count clicks encoder was rotated
|
int rotateCount = 0; // temporary count clicks encoder was rotated
|
||||||
|
uint32_t timestampLastAdjustChange = 0;
|
||||||
// int count = 0; (from class)
|
// int count = 0; (from class)
|
||||||
|
|
||||||
while (1)
|
while (1)
|
||||||
@ -211,19 +224,46 @@ void buttonCommands::startHandleLoop()
|
|||||||
ESP_LOGD(TAG, "Button released");
|
ESP_LOGD(TAG, "Button released");
|
||||||
isPressed = false; // rest stored state
|
isPressed = false; // rest stored state
|
||||||
break;
|
break;
|
||||||
case RE_ET_CHANGED: // scroll through status pages when simply rotating encoder
|
case RE_ET_CHANGED:
|
||||||
rotateCount++;
|
// ignore first clicks (dont ignore when changed position recently)
|
||||||
if (rotateCount >= 2) // at least two rotate-clicks necessary for one page switch
|
if ((rotateCount++ < IGNORE_ROTATE_COUNT) && ((esp_log_timestamp() - timestampLastAdjustChange) > IGNORE_BUTTON_TIME_SINCE_LAST_ROTATE))
|
||||||
{
|
{
|
||||||
|
buzzer->beep(1, 20, 0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
timestampLastAdjustChange = esp_log_timestamp();
|
||||||
|
}
|
||||||
|
if (isPressed){
|
||||||
|
/////### scroll through status pages when PRESSED + ROTATED ###
|
||||||
|
///if (event.diff > 0)
|
||||||
|
/// display_rotateStatusPage(true, true); // select NEXT status screen, stay at last element (dont rotate to first)
|
||||||
|
///else
|
||||||
|
/// display_rotateStatusPage(false, true); // select PREVIOUS status screen, stay at first element (dont rotate to last)
|
||||||
|
//### adjust back support when PRESSED + ROTATED ###
|
||||||
if (event.diff > 0)
|
if (event.diff > 0)
|
||||||
display_rotateStatusPage(true, true); // select NEXT status screen, stay at last element (dont rotate to first)
|
backRest->setTargetPercent(backRest->getTargetPercent() - 5);
|
||||||
else
|
else
|
||||||
display_rotateStatusPage(false, true); // select PREVIOUS status screen, stay at first element (dont rotate to last)
|
backRest->setTargetPercent(backRest->getTargetPercent() + 5);
|
||||||
rotateCount = 0;
|
// show temporary notification on display
|
||||||
buzzer->beep(1, 90, 0);
|
char buf[8];
|
||||||
|
snprintf(buf, 8, "%.0f%%", backRest->getTargetPercent());
|
||||||
|
display_showNotification(IGNORE_BUTTON_TIME_SINCE_LAST_ROTATE, "moving Rest:", "BACK", buf);
|
||||||
}
|
}
|
||||||
|
//### adjust leg support when ROTATED ###
|
||||||
else
|
else
|
||||||
buzzer->beep(1, 65, 0);
|
{
|
||||||
|
// increment target position each click
|
||||||
|
if (event.diff > 0)
|
||||||
|
legRest->setTargetPercent(legRest->getTargetPercent() - 10);
|
||||||
|
else
|
||||||
|
legRest->setTargetPercent(legRest->getTargetPercent() + 10);
|
||||||
|
// show temporary notification on display
|
||||||
|
char buf[8];
|
||||||
|
snprintf(buf, 8, "%.0f%%", legRest->getTargetPercent());
|
||||||
|
display_showNotification(2500, "moving Rest:", "LEG", buf);
|
||||||
|
}
|
||||||
|
buzzer->beep(1, 40, 0);
|
||||||
break;
|
break;
|
||||||
case RE_ET_BTN_LONG_PRESSED:
|
case RE_ET_BTN_LONG_PRESSED:
|
||||||
case RE_ET_BTN_CLICKED:
|
case RE_ET_BTN_CLICKED:
|
||||||
@ -233,17 +273,15 @@ void buttonCommands::startHandleLoop()
|
|||||||
}
|
}
|
||||||
else // timeout (no event received within TIMEOUT)
|
else // timeout (no event received within TIMEOUT)
|
||||||
{
|
{
|
||||||
// switch back to default status screen in case less than 2 rotate-clicks received
|
rotateCount = 0; // reset rotate count
|
||||||
if (rotateCount != 0)
|
// ignore button click events when "ROTATE+PRESSED" was just used
|
||||||
|
if (count > 0 && (esp_log_timestamp() - timestampLastAdjustChange < IGNORE_BUTTON_TIME_SINCE_LAST_ROTATE))
|
||||||
{
|
{
|
||||||
rotateCount = 0;
|
ESP_LOGW(TAG, "ignoring button count %d because encoder was rotated less than %d ms ago", count, IGNORE_BUTTON_TIME_SINCE_LAST_ROTATE);
|
||||||
display_selectStatusPage(STATUS_SCREEN_OVERVIEW);
|
count = 0;
|
||||||
//TODO only change/beep if not already at STATUS_SCREEN_OVERVIEW
|
|
||||||
//buzzer->beep(1, 100, 0);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// encoder was pressed
|
// encoder was pressed
|
||||||
if (count > 0)
|
else if (count > 0)
|
||||||
{
|
{
|
||||||
//-- run action with count of presses --
|
//-- run action with count of presses --
|
||||||
ESP_LOGI(TAG, "timeout: count=%d, lastPressLong=%d -> running action", count, isPressed);
|
ESP_LOGI(TAG, "timeout: count=%d, lastPressLong=%d -> running action", count, isPressed);
|
||||||
|
@ -6,6 +6,7 @@
|
|||||||
#include "motorctl.hpp"
|
#include "motorctl.hpp"
|
||||||
#include "auto.hpp"
|
#include "auto.hpp"
|
||||||
#include "joystick.hpp"
|
#include "joystick.hpp"
|
||||||
|
#include "chairAdjust.hpp"
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
@ -22,6 +23,8 @@ class buttonCommands {
|
|||||||
QueueHandle_t encoderQueue_f,
|
QueueHandle_t encoderQueue_f,
|
||||||
controlledMotor * motorLeft_f,
|
controlledMotor * motorLeft_f,
|
||||||
controlledMotor *motorRight_f,
|
controlledMotor *motorRight_f,
|
||||||
|
cControlledRest *legRest_f,
|
||||||
|
cControlledRest *backRest_f,
|
||||||
buzzer_t *buzzer_f);
|
buzzer_t *buzzer_f);
|
||||||
|
|
||||||
//--- functions ---
|
//--- functions ---
|
||||||
@ -40,6 +43,8 @@ class buttonCommands {
|
|||||||
controlledMotor * motorRight;
|
controlledMotor * motorRight;
|
||||||
buzzer_t* buzzer;
|
buzzer_t* buzzer;
|
||||||
QueueHandle_t encoderQueue;
|
QueueHandle_t encoderQueue;
|
||||||
|
cControlledRest *legRest;
|
||||||
|
cControlledRest *backRest;
|
||||||
|
|
||||||
//--- variables ---
|
//--- variables ---
|
||||||
uint8_t count = 0;
|
uint8_t count = 0;
|
||||||
@ -62,6 +67,8 @@ typedef struct task_button_parameters_t
|
|||||||
QueueHandle_t encoderQueue;
|
QueueHandle_t encoderQueue;
|
||||||
controlledMotor *motorLeft;
|
controlledMotor *motorLeft;
|
||||||
controlledMotor *motorRight;
|
controlledMotor *motorRight;
|
||||||
|
cControlledRest *legRest;
|
||||||
|
cControlledRest *backRest;
|
||||||
buzzer_t *buzzer;
|
buzzer_t *buzzer;
|
||||||
} task_button_parameters_t;
|
} task_button_parameters_t;
|
||||||
|
|
||||||
|
@ -39,7 +39,7 @@ void setLoglevels(void)
|
|||||||
esp_log_level_set("wifi", ESP_LOG_INFO);
|
esp_log_level_set("wifi", ESP_LOG_INFO);
|
||||||
esp_log_level_set("http", ESP_LOG_INFO);
|
esp_log_level_set("http", ESP_LOG_INFO);
|
||||||
// esp_log_level_set("automatedArmchair", ESP_LOG_DEBUG);
|
// esp_log_level_set("automatedArmchair", ESP_LOG_DEBUG);
|
||||||
esp_log_level_set("display", ESP_LOG_INFO);
|
esp_log_level_set("display", ESP_LOG_WARN);
|
||||||
// esp_log_level_set("current-sensors", ESP_LOG_INFO);
|
// esp_log_level_set("current-sensors", ESP_LOG_INFO);
|
||||||
esp_log_level_set("speedSensor", ESP_LOG_WARN);
|
esp_log_level_set("speedSensor", ESP_LOG_WARN);
|
||||||
esp_log_level_set("chair-adjustment", ESP_LOG_INFO);
|
esp_log_level_set("chair-adjustment", ESP_LOG_INFO);
|
||||||
|
@ -120,21 +120,55 @@ void controlledArmchair::startHandleLoop()
|
|||||||
{
|
{
|
||||||
while (1)
|
while (1)
|
||||||
{
|
{
|
||||||
|
// === handle current mode ===
|
||||||
// mutex to prevent race condition with actions beeing run at mode change and previous mode still beeing executed
|
// mutex to prevent race condition with actions beeing run at mode change and previous mode still beeing executed
|
||||||
|
ESP_LOGV(TAG, "handle(): requesting mutex...");
|
||||||
if (xSemaphoreTake(handleIteration_mutex, MUTEX_TIMEOUT / portTICK_PERIOD_MS) == pdTRUE)
|
if (xSemaphoreTake(handleIteration_mutex, MUTEX_TIMEOUT / portTICK_PERIOD_MS) == pdTRUE)
|
||||||
{
|
{
|
||||||
|
ESP_LOGV(TAG, "handle(): got mutex!");
|
||||||
//--- handle current mode ---
|
//--- handle current mode ---
|
||||||
ESP_LOGV(TAG, "control loop executing... mode='%s'", controlModeStr[(int)mode]);
|
ESP_LOGV(TAG, "control loop executing... mode='%s'", controlModeStr[(int)mode]);
|
||||||
handle();
|
handle();
|
||||||
|
|
||||||
|
ESP_LOGV(TAG, "handle(): releasing mutex");
|
||||||
xSemaphoreGive(handleIteration_mutex);
|
xSemaphoreGive(handleIteration_mutex);
|
||||||
} // end mutex
|
} // end mutex
|
||||||
else {
|
else
|
||||||
|
{
|
||||||
ESP_LOGE(TAG, "mutex timeout - stuck in changeMode? -> RESTART");
|
ESP_LOGE(TAG, "mutex timeout - stuck in changeMode? -> RESTART");
|
||||||
esp_restart();
|
esp_restart();
|
||||||
}
|
}
|
||||||
|
|
||||||
//--- slow loop ---
|
// ==== run mode specific delay ===
|
||||||
|
// outsourced here to not block the mutex by just waiting
|
||||||
|
switch (mode)
|
||||||
|
{
|
||||||
|
default:
|
||||||
|
case controlMode_t::IDLE:
|
||||||
|
vTaskDelay(500 / portTICK_PERIOD_MS);
|
||||||
|
break;
|
||||||
|
case controlMode_t::JOYSTICK:
|
||||||
|
vTaskDelay(50 / portTICK_PERIOD_MS);
|
||||||
|
break;
|
||||||
|
case controlMode_t::MASSAGE:
|
||||||
|
vTaskDelay(10 / portTICK_PERIOD_MS);
|
||||||
|
break;
|
||||||
|
case controlMode_t::HTTP:
|
||||||
|
// has 500ms timeout waiting for new events, thus blocks mutex...
|
||||||
|
break;
|
||||||
|
case controlMode_t::AUTO:
|
||||||
|
vTaskDelay(20 / portTICK_PERIOD_MS);
|
||||||
|
break;
|
||||||
|
case controlMode_t::ADJUST_CHAIR:
|
||||||
|
vTaskDelay(100 / portTICK_PERIOD_MS);
|
||||||
|
break;
|
||||||
|
case controlMode_t::MENU_SETTINGS:
|
||||||
|
case controlMode_t::MENU_MODE_SELECT:
|
||||||
|
vTaskDelay(500 / portTICK_PERIOD_MS);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
//=== slow loop, timeout ===
|
||||||
// this section is run approx every 5s (+500ms)
|
// this section is run approx every 5s (+500ms)
|
||||||
if (esp_log_timestamp() - timestamp_SlowLoopLastRun > 5000)
|
if (esp_log_timestamp() - timestamp_SlowLoopLastRun > 5000)
|
||||||
{
|
{
|
||||||
@ -150,12 +184,14 @@ void controlledArmchair::startHandleLoop()
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//-------------------------------------
|
//-------------------------------------
|
||||||
//---------- Handle control -----------
|
//---------- Handle control -----------
|
||||||
//-------------------------------------
|
//-------------------------------------
|
||||||
// function that repeatedly generates motor commands and runs actions depending on the current mode
|
// function that repeatedly generates motor commands and runs actions depending on the current mode
|
||||||
void controlledArmchair::handle()
|
void controlledArmchair::handle()
|
||||||
{
|
{
|
||||||
|
//note: mode specific delays are outsourced to startHandleLoop() to not block the mutex
|
||||||
|
|
||||||
switch (mode)
|
switch (mode)
|
||||||
{
|
{
|
||||||
@ -166,7 +202,6 @@ void controlledArmchair::handle()
|
|||||||
|
|
||||||
//------- handle IDLE -------
|
//------- handle IDLE -------
|
||||||
case controlMode_t::IDLE:
|
case controlMode_t::IDLE:
|
||||||
vTaskDelay(500 / portTICK_PERIOD_MS);
|
|
||||||
// TODO repeatedly set motors to idle, in case driver bugs? Currently 15s motorctl timeout would have to pass
|
// TODO repeatedly set motors to idle, in case driver bugs? Currently 15s motorctl timeout would have to pass
|
||||||
#ifdef JOYSTICK_LOG_IN_IDLE
|
#ifdef JOYSTICK_LOG_IN_IDLE
|
||||||
// get joystick data and log it
|
// get joystick data and log it
|
||||||
@ -180,7 +215,6 @@ void controlledArmchair::handle()
|
|||||||
|
|
||||||
//------- handle JOYSTICK mode -------
|
//------- handle JOYSTICK mode -------
|
||||||
case controlMode_t::JOYSTICK:
|
case controlMode_t::JOYSTICK:
|
||||||
vTaskDelay(50 / portTICK_PERIOD_MS);
|
|
||||||
// get current joystick data with getData method of evaluatedJoystick
|
// get current joystick data with getData method of evaluatedJoystick
|
||||||
stickDataLast = stickData;
|
stickDataLast = stickData;
|
||||||
stickData = joystick_l->getData();
|
stickData = joystick_l->getData();
|
||||||
@ -205,7 +239,6 @@ void controlledArmchair::handle()
|
|||||||
|
|
||||||
//------- handle MASSAGE mode -------
|
//------- handle MASSAGE mode -------
|
||||||
case controlMode_t::MASSAGE:
|
case controlMode_t::MASSAGE:
|
||||||
vTaskDelay(10 / portTICK_PERIOD_MS);
|
|
||||||
//--- read joystick ---
|
//--- read joystick ---
|
||||||
// only update joystick data when input not frozen
|
// only update joystick data when input not frozen
|
||||||
stickDataLast = stickData;
|
stickDataLast = stickData;
|
||||||
@ -250,7 +283,6 @@ void controlledArmchair::handle()
|
|||||||
|
|
||||||
//------- handle AUTO mode -------
|
//------- handle AUTO mode -------
|
||||||
case controlMode_t::AUTO:
|
case controlMode_t::AUTO:
|
||||||
vTaskDelay(20 / portTICK_PERIOD_MS);
|
|
||||||
// generate commands
|
// generate commands
|
||||||
commands = automatedArmchair->generateCommands(&instruction);
|
commands = automatedArmchair->generateCommands(&instruction);
|
||||||
//--- apply commands to motors ---
|
//--- apply commands to motors ---
|
||||||
@ -291,7 +323,6 @@ void controlledArmchair::handle()
|
|||||||
|
|
||||||
//------- handle ADJUST_CHAIR mode -------
|
//------- handle ADJUST_CHAIR mode -------
|
||||||
case controlMode_t::ADJUST_CHAIR:
|
case controlMode_t::ADJUST_CHAIR:
|
||||||
vTaskDelay(100 / portTICK_PERIOD_MS);
|
|
||||||
//--- read joystick ---
|
//--- read joystick ---
|
||||||
stickDataLast = stickData;
|
stickDataLast = stickData;
|
||||||
stickData = joystick_l->getData();
|
stickData = joystick_l->getData();
|
||||||
@ -308,7 +339,6 @@ void controlledArmchair::handle()
|
|||||||
case controlMode_t::MENU_SETTINGS:
|
case controlMode_t::MENU_SETTINGS:
|
||||||
case controlMode_t::MENU_MODE_SELECT:
|
case controlMode_t::MENU_MODE_SELECT:
|
||||||
// nothing to do here, display task handles the menu
|
// nothing to do here, display task handles the menu
|
||||||
vTaskDelay(500 / portTICK_PERIOD_MS);
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
// TODO: add other modes here
|
// TODO: add other modes here
|
||||||
@ -457,8 +487,10 @@ void controlledArmchair::changeMode(controlMode_t modeNew, bool noBeep)
|
|||||||
// mutex to wait for current handle iteration (control-task) to finish
|
// mutex to wait for current handle iteration (control-task) to finish
|
||||||
// prevents race conditions where operations when changing mode are run but old mode gets handled still
|
// prevents race conditions where operations when changing mode are run but old mode gets handled still
|
||||||
ESP_LOGI(TAG, "changeMode: waiting for current handle() iteration to finish...");
|
ESP_LOGI(TAG, "changeMode: waiting for current handle() iteration to finish...");
|
||||||
|
ESP_LOGV(TAG, "changemode(): requesting mutex...");
|
||||||
if (xSemaphoreTake(handleIteration_mutex, MUTEX_TIMEOUT / portTICK_PERIOD_MS) == pdTRUE)
|
if (xSemaphoreTake(handleIteration_mutex, MUTEX_TIMEOUT / portTICK_PERIOD_MS) == pdTRUE)
|
||||||
{
|
{
|
||||||
|
ESP_LOGV(TAG, "changemode(): got mutex!");
|
||||||
// copy previous mode
|
// copy previous mode
|
||||||
modePrevious = mode;
|
modePrevious = mode;
|
||||||
// store time changed (needed for timeout)
|
// store time changed (needed for timeout)
|
||||||
@ -514,8 +546,8 @@ void controlledArmchair::changeMode(controlMode_t modeNew, bool noBeep)
|
|||||||
case controlMode_t::ADJUST_CHAIR:
|
case controlMode_t::ADJUST_CHAIR:
|
||||||
ESP_LOGW(TAG, "switching from ADJUST_CHAIR mode => turning off adjustment motors...");
|
ESP_LOGW(TAG, "switching from ADJUST_CHAIR mode => turning off adjustment motors...");
|
||||||
// prevent motors from being always on in case of mode switch while joystick is not in center thus motors currently moving
|
// prevent motors from being always on in case of mode switch while joystick is not in center thus motors currently moving
|
||||||
legRest->setState(REST_OFF);
|
legRest->requestStateChange(REST_OFF);
|
||||||
backRest->setState(REST_OFF);
|
backRest->requestStateChange(REST_OFF);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -569,6 +601,7 @@ void controlledArmchair::changeMode(controlMode_t modeNew, bool noBeep)
|
|||||||
mode = modeNew;
|
mode = modeNew;
|
||||||
|
|
||||||
// unlock mutex for control task to continue handling modes
|
// unlock mutex for control task to continue handling modes
|
||||||
|
ESP_LOGV(TAG, "changemode(): releasing mutex");
|
||||||
xSemaphoreGive(handleIteration_mutex);
|
xSemaphoreGive(handleIteration_mutex);
|
||||||
} // end mutex
|
} // end mutex
|
||||||
else
|
else
|
||||||
|
@ -23,6 +23,11 @@ extern "C"{
|
|||||||
// every function can access the display configuration from config.cpp
|
// every function can access the display configuration from config.cpp
|
||||||
static display_config_t displayConfig;
|
static display_config_t displayConfig;
|
||||||
|
|
||||||
|
// communicate with display task to block+restore display writing, when a notification was triggered
|
||||||
|
uint32_t timestampNotificationStop = 0;
|
||||||
|
bool notificationIsActive = false;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//--------------------------
|
//--------------------------
|
||||||
//------- getVoltage -------
|
//------- getVoltage -------
|
||||||
@ -584,6 +589,29 @@ void handleStatusScreen(display_task_parameters_t *objects)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//==============================
|
||||||
|
//====== showNotification ======
|
||||||
|
//==============================
|
||||||
|
// trigger custom notification that is shown in any mode for set amount of time
|
||||||
|
void display_showNotification(uint32_t showDurationMs, const char *line1, const char *line2Large, const char *line3Large)
|
||||||
|
{
|
||||||
|
// clear display when notification initially shown
|
||||||
|
if (notificationIsActive == false)
|
||||||
|
ssd1306_clear_screen(&dev, false);
|
||||||
|
// update state and timestamp for auto exit
|
||||||
|
timestampNotificationStop = esp_log_timestamp() + showDurationMs;
|
||||||
|
notificationIsActive = true;
|
||||||
|
// void displayTextLineCentered(SSD1306_t *display, int line, bool isLarge, bool inverted, const char *format, ...);
|
||||||
|
displayTextLineCentered(&dev, 0, false, false, "%s", line1);
|
||||||
|
displayTextLineCentered(&dev, 1, true, false, "%s", line2Large);
|
||||||
|
displayTextLineCentered(&dev, 4, true, false, "%s", line3Large);
|
||||||
|
displayTextLine(&dev, 7, false, false, " ");
|
||||||
|
ESP_LOGI(TAG, "start showing notification '%s' '%s' for %d ms", line1, line2Large, showDurationMs);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//============================
|
//============================
|
||||||
//======= display task =======
|
//======= display task =======
|
||||||
//============================
|
//============================
|
||||||
@ -606,6 +634,15 @@ void display_task(void *pvParameters)
|
|||||||
// repeatedly update display with content depending on current mode
|
// repeatedly update display with content depending on current mode
|
||||||
while (1)
|
while (1)
|
||||||
{
|
{
|
||||||
|
// dont update anything when a notification is active + check timeout
|
||||||
|
if (notificationIsActive){
|
||||||
|
if (esp_log_timestamp() >= timestampNotificationStop)
|
||||||
|
notificationIsActive = false;
|
||||||
|
vTaskDelay(100 / portTICK_PERIOD_MS);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
//update display according to current control mode
|
||||||
switch (objects->control->getCurrentMode())
|
switch (objects->control->getCurrentMode())
|
||||||
{
|
{
|
||||||
case controlMode_t::MENU_SETTINGS:
|
case controlMode_t::MENU_SETTINGS:
|
||||||
|
@ -67,6 +67,9 @@ void display_selectStatusPage(displayStatusPage_t newStatusPage);
|
|||||||
// select next/previous status screen to be shown, when noRotate is set is stays at first/last screen
|
// select next/previous status screen to be shown, when noRotate is set is stays at first/last screen
|
||||||
void display_rotateStatusPage(bool reverseDirection = false, bool noRotate = false);
|
void display_rotateStatusPage(bool reverseDirection = false, bool noRotate = false);
|
||||||
|
|
||||||
|
// show content for certain time in any mode
|
||||||
|
void display_showNotification(uint32_t showDurationMs, const char *line1, const char * line2Large, const char * line3Large );
|
||||||
|
|
||||||
//task that inititialized the display, displays welcome message
|
//task that inititialized the display, displays welcome message
|
||||||
//and releatedly updates the display with certain content
|
//and releatedly updates the display with certain content
|
||||||
void display_task( void * pvParameters );
|
void display_task( void * pvParameters );
|
||||||
|
@ -161,9 +161,9 @@ void createObjects()
|
|||||||
buzzer = new buzzer_t(GPIO_NUM_12, 1);
|
buzzer = new buzzer_t(GPIO_NUM_12, 1);
|
||||||
|
|
||||||
// create objects for controlling the chair position
|
// create objects for controlling the chair position
|
||||||
// gpio_up, gpio_down, name
|
// gpio_up, gpio_down, travelDuration, name, defaultPosition
|
||||||
legRest = new cControlledRest(GPIO_NUM_2, GPIO_NUM_15, "legRest");
|
legRest = new cControlledRest(GPIO_NUM_2, GPIO_NUM_15, 11000, "legRest");
|
||||||
backRest = new cControlledRest(GPIO_NUM_16, GPIO_NUM_4, "backRest");
|
backRest = new cControlledRest(GPIO_NUM_16, GPIO_NUM_4, 12000, "backRest", 5); //default position "100% up"
|
||||||
|
|
||||||
// create control object (control.hpp)
|
// create control object (control.hpp)
|
||||||
// with configuration from config.cpp
|
// with configuration from config.cpp
|
||||||
@ -266,7 +266,7 @@ extern "C" void app_main(void) {
|
|||||||
//--- create task for button ---
|
//--- create task for button ---
|
||||||
//------------------------------
|
//------------------------------
|
||||||
//task that handles button/encoder events in any mode except 'MENU_SETTINGS' and 'MENU_MODE_SELECT' (e.g. switch modes by pressing certain count)
|
//task that handles button/encoder events in any mode except 'MENU_SETTINGS' and 'MENU_MODE_SELECT' (e.g. switch modes by pressing certain count)
|
||||||
task_button_parameters_t button_param = {control, joystick, encoderQueue, motorLeft, motorRight, buzzer};
|
task_button_parameters_t button_param = {control, joystick, encoderQueue, motorLeft, motorRight, legRest, backRest, buzzer};
|
||||||
xTaskCreate(&task_button, "task_button", 4096, &button_param, 3, NULL);
|
xTaskCreate(&task_button, "task_button", 4096, &button_param, 3, NULL);
|
||||||
|
|
||||||
//-----------------------------------
|
//-----------------------------------
|
||||||
@ -282,6 +282,13 @@ extern "C" void app_main(void) {
|
|||||||
//task that handles the display (show stats, handle menu in 'MENU_SETTINGS' and 'MENU_MODE_SELECT' mode)
|
//task that handles the display (show stats, handle menu in 'MENU_SETTINGS' and 'MENU_MODE_SELECT' mode)
|
||||||
display_task_parameters_t display_param = {display_config, control, joystick, encoderQueue, motorLeft, motorRight, speedLeft, speedRight, buzzer, &nvsHandle};
|
display_task_parameters_t display_param = {display_config, control, joystick, encoderQueue, motorLeft, motorRight, speedLeft, speedRight, buzzer, &nvsHandle};
|
||||||
xTaskCreate(&display_task, "display_task", 3*2048, &display_param, 3, NULL);
|
xTaskCreate(&display_task, "display_task", 3*2048, &display_param, 3, NULL);
|
||||||
|
|
||||||
|
//-------------------------------------
|
||||||
|
//-- create task for chairAdjustment --
|
||||||
|
//-------------------------------------
|
||||||
|
//tasks that stop chair-rest motors when they reach target (note: they sleep when motors not running)
|
||||||
|
xTaskCreate(&chairAdjust_task, "chairAdjustLeg_task", 2048, legRest, 1, NULL);
|
||||||
|
xTaskCreate(&chairAdjust_task, "chairAdjustBack_task", 2048, backRest, 1, NULL);
|
||||||
|
|
||||||
vTaskDelay(200 / portTICK_PERIOD_MS); //wait for all tasks to finish initializing
|
vTaskDelay(200 / portTICK_PERIOD_MS); //wait for all tasks to finish initializing
|
||||||
printf("\n");
|
printf("\n");
|
||||||
|
@ -1,8 +1,5 @@
|
|||||||
extern "C"
|
extern "C"
|
||||||
{
|
{
|
||||||
#include "freertos/FreeRTOS.h"
|
|
||||||
#include "freertos/task.h"
|
|
||||||
#include "driver/gpio.h"
|
|
||||||
#include "esp_log.h"
|
#include "esp_log.h"
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
}
|
}
|
||||||
@ -11,6 +8,15 @@ extern "C"
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//--- config ---
|
||||||
|
#define MUTEX_TIMEOUT (8000 / portTICK_PERIOD_MS)
|
||||||
|
// thresholds to protect relays from welding stuck
|
||||||
|
#define MIN_TIME_ON 200 // minimum time in ms motor has to be ON before being able to turn off again
|
||||||
|
#define MIN_TIME_OFF 400 // minimum time in ms motor has to be OFF before being able to turn on again (other or same direction)
|
||||||
|
#define TRAVEL_TIME_LIMIT_ADDITION_MS 1300 // traveling longer into limit compensates inaccuracies in time based position tracking
|
||||||
|
#define CHAIR_ADJUST_HANDLE_TASK_DELAY 100 // interval the stop-condition and state-switching is checked/handled
|
||||||
|
|
||||||
|
|
||||||
//--- gloabl variables ---
|
//--- gloabl variables ---
|
||||||
// strings for logging the rest state
|
// strings for logging the rest state
|
||||||
const char* restStateStr[] = {"REST_OFF", "REST_DOWN", "REST_UP"};
|
const char* restStateStr[] = {"REST_OFF", "REST_DOWN", "REST_UP"};
|
||||||
@ -24,10 +30,12 @@ static const char * TAG = "chair-adjustment";
|
|||||||
//=============================
|
//=============================
|
||||||
//======== constructor ========
|
//======== constructor ========
|
||||||
//=============================
|
//=============================
|
||||||
cControlledRest::cControlledRest(gpio_num_t gpio_up_f, gpio_num_t gpio_down_f, const char * name_f){
|
cControlledRest::cControlledRest(gpio_num_t gpio_up_f, gpio_num_t gpio_down_f, uint32_t travelDurationMs, const char * name_f, float defaultPosition): gpio_up(gpio_up_f), gpio_down(gpio_down_f), travelDuration(travelDurationMs){
|
||||||
strcpy(name, name_f);
|
strcpy(name, name_f);
|
||||||
gpio_up = gpio_up_f;
|
positionNow = defaultPosition;
|
||||||
gpio_down = gpio_down_f;
|
positionTarget = positionNow;
|
||||||
|
// recursive mutex necessary, because handle() method calls setState() which both have the same mutex
|
||||||
|
mutex = xSemaphoreCreateRecursiveMutex();
|
||||||
init();
|
init();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -53,22 +61,222 @@ void cControlledRest::init()
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
//============================
|
//==========================
|
||||||
//========= setState =========
|
//===== updatePosition =====
|
||||||
//============================
|
//==========================
|
||||||
void cControlledRest::setState(restState_t targetState)
|
// calculate and update position in percent based of time running in current direction
|
||||||
|
void cControlledRest::updatePosition()
|
||||||
{
|
{
|
||||||
//check if actually changed
|
// calculate time motor was on
|
||||||
if (targetState == state){
|
uint32_t now = esp_log_timestamp();
|
||||||
ESP_LOGD(TAG, "[%s] state already at '%s', nothing to do", name, restStateStr[state]);
|
uint32_t timeRan = now - timestamp_lastPosUpdate;
|
||||||
|
// note: timestamp_lastPosUpdate also gets updated when changing to active mode in changemode
|
||||||
|
|
||||||
|
timestamp_lastPosUpdate = now;
|
||||||
|
float positionOld = positionNow;
|
||||||
|
|
||||||
|
// calculate new percentage
|
||||||
|
switch (state)
|
||||||
|
{
|
||||||
|
case REST_UP:
|
||||||
|
positionNow += (float)timeRan / travelDuration * 100;
|
||||||
|
break;
|
||||||
|
case REST_DOWN:
|
||||||
|
positionNow -= (float)timeRan / travelDuration * 100;
|
||||||
|
break;
|
||||||
|
case REST_OFF:
|
||||||
|
// no change
|
||||||
|
ESP_LOGW(TAG, "updatePosition: unknown direction - cant update position when state is REST_OFF");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
//apply new state
|
// clip to 0-100 (because cant actually happen due to limit switches)
|
||||||
ESP_LOGI(TAG, "[%s] switching from state '%s' to '%s'", name, restStateStr[state], restStateStr[targetState]);
|
if (positionNow < 0)
|
||||||
state = targetState;
|
positionNow = 0;
|
||||||
timestamp_lastChange = esp_log_timestamp(); //TODO use this to estimate position
|
else if (positionNow > 100)
|
||||||
switch (state)
|
positionNow = 100;
|
||||||
|
|
||||||
|
ESP_LOGD(TAG, "[%s] updatePosition: update pos from %.2f%% to %.2f%% (time ran %dms, prev-state '%s')", name, positionOld, positionNow, timeRan, restStateStr[state] );
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//==========================
|
||||||
|
//==== setTargetPercent ====
|
||||||
|
//==========================
|
||||||
|
void cControlledRest::setTargetPercent(float targetPercent)
|
||||||
|
{
|
||||||
|
// lock the mutex before accessing shared variables
|
||||||
|
if (xSemaphoreTakeRecursive(mutex, MUTEX_TIMEOUT) == pdTRUE)
|
||||||
|
{
|
||||||
|
float positionTargetPrev = positionTarget;
|
||||||
|
positionTarget = targetPercent;
|
||||||
|
|
||||||
|
// limit to 0-100
|
||||||
|
if (positionTarget > 100)
|
||||||
|
positionTarget = 100;
|
||||||
|
else if (positionTarget < 0)
|
||||||
|
positionTarget = 0;
|
||||||
|
|
||||||
|
ESP_LOGI(TAG, "[%s] changed Target position from %.2f%% to %.2f%%", name, positionTargetPrev, positionTarget);
|
||||||
|
|
||||||
|
// update actual position positionNow first when already running
|
||||||
|
if (state != REST_OFF)
|
||||||
|
updatePosition();
|
||||||
|
|
||||||
|
// start rest in required direction
|
||||||
|
// TODO always run this check in handle()?
|
||||||
|
// note: when already at 0/100 start anyways (runs for certain threshold in case tracked position out of sync)
|
||||||
|
if (positionTarget > positionNow || positionTarget >= 100)
|
||||||
|
requestStateChange(REST_UP);
|
||||||
|
else if (positionTarget < positionNow || positionTarget <= 0)
|
||||||
|
requestStateChange(REST_DOWN);
|
||||||
|
else // already at exact position
|
||||||
|
requestStateChange(REST_OFF);
|
||||||
|
|
||||||
|
// Release the mutex
|
||||||
|
xSemaphoreGiveRecursive(mutex);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
ESP_LOGE(TAG, "mutex timeout while waiting in setTargetPercent -> RESTART");
|
||||||
|
esp_restart();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//============================
|
||||||
|
//==== requestStateChange ====
|
||||||
|
//============================
|
||||||
|
// queue state change that is executed when valid (respecting min thresholds)
|
||||||
|
void cControlledRest::requestStateChange(restState_t targetState)
|
||||||
|
{
|
||||||
|
// check if task is linked
|
||||||
|
if (taskHandle == NULL)
|
||||||
|
{
|
||||||
|
ESP_LOGE(TAG, "[%s] can not activate task! Task is not running", name);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// lock the mutex before accessing shared variables
|
||||||
|
if (xSemaphoreTakeRecursive(mutex, MUTEX_TIMEOUT) == pdTRUE)
|
||||||
|
{
|
||||||
|
ESP_LOGD(TAG, "[%s] requesting change to state '%s'", name, restStateStr[targetState]);
|
||||||
|
nextState = targetState;
|
||||||
|
|
||||||
|
// activate task to change, when on running already
|
||||||
|
if (taskIsRunning == false)
|
||||||
|
xTaskNotifyGive(taskHandle); // activate handle task that handles state change and stops the rest-motor again
|
||||||
|
// Release the mutex
|
||||||
|
xSemaphoreGiveRecursive(mutex);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
ESP_LOGE(TAG, "mutex timeout while waiting in requestStateChange -> RESTART");
|
||||||
|
esp_restart();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//===========================
|
||||||
|
//==== handleStateChange ====
|
||||||
|
//===========================
|
||||||
|
// ensure MIN_TIME_ON and MIN_TIME_OFF has passed between doing the requested state change
|
||||||
|
// repeatedly run by task if state is requested
|
||||||
|
void cControlledRest::handleStateChange()
|
||||||
|
{
|
||||||
|
// lock the mutex before accessing shared variables
|
||||||
|
if (xSemaphoreTakeRecursive(mutex, MUTEX_TIMEOUT) == pdTRUE)
|
||||||
|
{
|
||||||
|
uint32_t now = esp_log_timestamp();
|
||||||
|
|
||||||
|
// already at target state
|
||||||
|
if (state == nextState)
|
||||||
|
{
|
||||||
|
// exit, nothing todo
|
||||||
|
ESP_LOGV(TAG, "[%s] handleStateChange: already at target state, nothing to do", name);
|
||||||
|
xSemaphoreGiveRecursive(mutex);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// turn off requested
|
||||||
|
else if (nextState == REST_OFF)
|
||||||
|
{
|
||||||
|
// exit if not on long enough
|
||||||
|
if (now - timestamp_lastStateChange < MIN_TIME_ON)
|
||||||
|
{
|
||||||
|
ESP_LOGD(TAG, "[%s] handleStateChange: not on long enough, not turning off yet", name);
|
||||||
|
xSemaphoreGiveRecursive(mutex);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// turn on requested
|
||||||
|
else if (state == REST_OFF && nextState != REST_OFF)
|
||||||
|
{
|
||||||
|
// exit if not off long enough
|
||||||
|
if (now - timestamp_lastStateChange < MIN_TIME_OFF)
|
||||||
|
{
|
||||||
|
ESP_LOGV(TAG, "[%s] handleStateChange: not OFF long enough, not turning on yet", name);
|
||||||
|
xSemaphoreGiveRecursive(mutex);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// direction change requested
|
||||||
|
else if (state != REST_OFF && nextState != REST_OFF)
|
||||||
|
{
|
||||||
|
// exit if not on long enough
|
||||||
|
if (now - timestamp_lastStateChange < MIN_TIME_ON)
|
||||||
|
{
|
||||||
|
ESP_LOGD(TAG, "[%s] handleStateChange: dir change detected: not ON long enough, not turning off yet", name);
|
||||||
|
xSemaphoreGiveRecursive(mutex);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
// no immediate dir change, turn off first
|
||||||
|
else
|
||||||
|
{
|
||||||
|
ESP_LOGW(TAG, "[%s] handleStateChange: dir change detected: turning off first", name );
|
||||||
|
changeState(REST_OFF);
|
||||||
|
xSemaphoreGiveRecursive(mutex);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// not exited by now = no reason to prevent the state change -> update state!
|
||||||
|
ESP_LOGV(TAG, "[%s] handleStateChange: change is allowed now -> applying new state '%s'", name , restStateStr[nextState]);
|
||||||
|
changeState(nextState);
|
||||||
|
|
||||||
|
// Release the mutex
|
||||||
|
xSemaphoreGiveRecursive(mutex);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
ESP_LOGE(TAG, "mutex timeout while waiting in handleStateChange -> RESTART");
|
||||||
|
esp_restart();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//=========================
|
||||||
|
//====== changeState ======
|
||||||
|
//=========================
|
||||||
|
// change state (relays, timestamp) without any validation whether change is allowed
|
||||||
|
void cControlledRest::changeState(restState_t newState)
|
||||||
|
{
|
||||||
|
// check if actually changed
|
||||||
|
if (newState == state)
|
||||||
|
{
|
||||||
|
ESP_LOGV(TAG, "[%s] changeState: Relay state already at '%s', nothing to do", name, restStateStr[state]);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// apply new state to relays
|
||||||
|
ESP_LOGI(TAG, "[%s] changeState: switching Relays from state '%s' to '%s'", name, restStateStr[state], restStateStr[newState]);
|
||||||
|
switch (newState)
|
||||||
{
|
{
|
||||||
case REST_UP:
|
case REST_UP:
|
||||||
gpio_set_level(gpio_down, 0);
|
gpio_set_level(gpio_down, 0);
|
||||||
@ -83,6 +291,94 @@ void cControlledRest::setState(restState_t targetState)
|
|||||||
gpio_set_level(gpio_up, 0);
|
gpio_set_level(gpio_up, 0);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// apply new state to variables
|
||||||
|
uint32_t now = esp_log_timestamp();
|
||||||
|
if (state != REST_OFF && newState == REST_OFF) // previously on (turning off now)
|
||||||
|
{
|
||||||
|
updatePosition(); // movement finished -> update position
|
||||||
|
positionTarget = positionNow; // disable resuming - no unexpected pos when incrementing
|
||||||
|
}
|
||||||
|
else if (state == REST_OFF && newState != REST_OFF)// previously off (turning on now)
|
||||||
|
timestamp_lastPosUpdate = now; // pos did not change during off time - reset timestamp
|
||||||
|
|
||||||
|
state = newState;
|
||||||
|
timestamp_lastStateChange = now;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//===============================
|
||||||
|
//=== handle StopAtPosReached ===
|
||||||
|
//===============================
|
||||||
|
// handle automatic stop when target position is reached, should be run repeatedly in a task
|
||||||
|
void cControlledRest::handleStopAtPosReached()
|
||||||
|
{
|
||||||
|
// lock the mutex before accessing shared variables
|
||||||
|
if (xSemaphoreTakeRecursive(mutex, MUTEX_TIMEOUT) == pdTRUE)
|
||||||
|
{
|
||||||
|
// nothing to do when not running atm
|
||||||
|
if (state == REST_OFF)
|
||||||
|
{
|
||||||
|
xSemaphoreGiveRecursive(mutex);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// calculate time already running
|
||||||
|
uint32_t timeRan = esp_log_timestamp() - timestamp_lastPosUpdate;
|
||||||
|
// calculate needed time to reach target
|
||||||
|
uint32_t timeTarget = travelDuration * fabs(positionTarget - positionNow) / 100;
|
||||||
|
|
||||||
|
// intentionally travel longer into limit - compensates inaccuracies in time based position tracking
|
||||||
|
if (positionTarget == 0 || positionTarget == 100)
|
||||||
|
timeTarget += TRAVEL_TIME_LIMIT_ADDITION_MS;
|
||||||
|
|
||||||
|
// target reached
|
||||||
|
if (timeRan >= timeTarget)
|
||||||
|
{
|
||||||
|
ESP_LOGI(TAG, "[%s] TARGET REACHED! run-time (%dms/%dms) for target position %.1f%% -> requesting stop", name, timeRan, timeTarget, positionTarget);
|
||||||
|
requestStateChange(REST_OFF);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
ESP_LOGV(TAG, "[%s] target not reached yet, run-time (%dms/%dms) for target position %.1f%%", name, timeRan, timeTarget, positionTarget);
|
||||||
|
|
||||||
|
// Release the mutex
|
||||||
|
xSemaphoreGiveRecursive(mutex);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
ESP_LOGE(TAG, "mutex timeout while waiting in handleStopAtPosReached -> RESTART");
|
||||||
|
esp_restart();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//============================
|
||||||
|
//===== chairAdjust_task =====
|
||||||
|
//============================
|
||||||
|
void chairAdjust_task(void *pvParameter)
|
||||||
|
{
|
||||||
|
cControlledRest *rest = (cControlledRest *)pvParameter;
|
||||||
|
ESP_LOGW(TAG, "Starting task for controlling %s...", rest->getName());
|
||||||
|
// provide taskHandle to rest object for wakeup
|
||||||
|
rest->setTaskHandle(xTaskGetCurrentTaskHandle());
|
||||||
|
|
||||||
|
while (1)
|
||||||
|
{
|
||||||
|
ulTaskNotifyTake(pdTRUE, portMAX_DELAY); // wait for wakeup by changeState() (rest-motor turned on)
|
||||||
|
rest->setTaskIsRunning();
|
||||||
|
ESP_LOGD(TAG, "task %s: received notification -> activating task!", rest->getName());
|
||||||
|
// running while 1. motor running or 2. not in target state yet
|
||||||
|
while ((rest->getState() != REST_OFF) || (rest->getNextState() != rest->getState()))
|
||||||
|
{
|
||||||
|
rest->handleStateChange();
|
||||||
|
rest->handleStopAtPosReached();
|
||||||
|
vTaskDelay(CHAIR_ADJUST_HANDLE_TASK_DELAY / portTICK_PERIOD_MS);
|
||||||
|
}
|
||||||
|
rest->clearTaskIsRunning();
|
||||||
|
ESP_LOGD(TAG, "task %s: motor-off and at target state -> sleeping task", rest->getName());
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -91,25 +387,20 @@ void cControlledRest::setState(restState_t targetState)
|
|||||||
//====== controlChairAdjustment ======
|
//====== controlChairAdjustment ======
|
||||||
//====================================
|
//====================================
|
||||||
//function that controls the two rests according to joystick data (applies threshold, defines direction)
|
//function that controls the two rests according to joystick data (applies threshold, defines direction)
|
||||||
//TODO:
|
|
||||||
// - add separate task that controls chair adjustment
|
|
||||||
// - timeout
|
|
||||||
// - track position
|
|
||||||
// - auto-adjust: move to position while driving
|
|
||||||
// - control via app
|
|
||||||
// - add delay betweem direction change
|
|
||||||
void controlChairAdjustment(joystickData_t data, cControlledRest * legRest, cControlledRest * backRest){
|
void controlChairAdjustment(joystickData_t data, cControlledRest * legRest, cControlledRest * backRest){
|
||||||
//--- variables ---
|
//--- variables ---
|
||||||
float stickThreshold = 0.3; //min coordinate for motor to start
|
float stickThreshold = 0.3; //min coordinate for motor to start
|
||||||
|
|
||||||
//--- control rest motors ---
|
//--- control rest motors ---
|
||||||
//leg rest (x-axis)
|
//leg rest (x-axis)
|
||||||
if (data.x > stickThreshold) legRest->setState(REST_UP);
|
if (data.x > stickThreshold) legRest->setTargetPercent(100);
|
||||||
else if (data.x < -stickThreshold) legRest->setState(REST_DOWN);
|
else if (data.x < -stickThreshold) legRest->setTargetPercent(0);
|
||||||
else legRest->setState(REST_OFF);
|
else
|
||||||
|
legRest->requestStateChange(REST_OFF);
|
||||||
|
|
||||||
//back rest (y-axis)
|
//back rest (y-axis)
|
||||||
if (data.y > stickThreshold) backRest->setState(REST_UP);
|
if (data.y > stickThreshold) backRest->setTargetPercent(0);
|
||||||
else if (data.y < -stickThreshold) backRest->setState(REST_DOWN);
|
else if (data.y < -stickThreshold) backRest->setTargetPercent(100);
|
||||||
else backRest->setState(REST_OFF);
|
else
|
||||||
}
|
backRest->requestStateChange(REST_OFF);
|
||||||
|
}
|
@ -1,7 +1,15 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#include "freertos/FreeRTOS.h"
|
||||||
|
#include "freertos/task.h"
|
||||||
|
#include "freertos/semphr.h"
|
||||||
|
#include "driver/gpio.h"
|
||||||
|
}
|
||||||
|
|
||||||
#include "joystick.hpp"
|
#include "joystick.hpp"
|
||||||
|
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
REST_OFF = 0,
|
REST_OFF = 0,
|
||||||
REST_DOWN,
|
REST_DOWN,
|
||||||
@ -11,6 +19,7 @@ typedef enum {
|
|||||||
extern const char* restStateStr[];
|
extern const char* restStateStr[];
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//=====================================
|
//=====================================
|
||||||
//======= cControlledRest class =======
|
//======= cControlledRest class =======
|
||||||
//=====================================
|
//=====================================
|
||||||
@ -18,22 +27,61 @@ extern const char* restStateStr[];
|
|||||||
//2 instances will be created one for back and one for leg rest
|
//2 instances will be created one for back and one for leg rest
|
||||||
class cControlledRest {
|
class cControlledRest {
|
||||||
public:
|
public:
|
||||||
cControlledRest(gpio_num_t gpio_up, gpio_num_t gpio_down, const char *name);
|
cControlledRest(gpio_num_t gpio_up, gpio_num_t gpio_down, uint32_t travelDurationMs, const char *name, float defaultPosition = 0);
|
||||||
void setState(restState_t targetState);
|
|
||||||
void stop();
|
// control the rest:
|
||||||
|
void requestStateChange(restState_t targetState); //mutex
|
||||||
|
restState_t getState() const {return state;};
|
||||||
|
const char * getName() const {return name;};
|
||||||
|
void setTargetPercent(float targetPercent); //mutex
|
||||||
|
float getTargetPercent() const {return positionTarget;};
|
||||||
|
float getPercent(); //TODO update position first
|
||||||
|
|
||||||
|
// required for task controlling the rest:
|
||||||
|
void setTaskHandle(TaskHandle_t handle) {taskHandle = handle;};
|
||||||
|
void setTaskIsRunning() {taskIsRunning = true;};
|
||||||
|
void clearTaskIsRunning() {taskIsRunning = false;};
|
||||||
|
void handleStopAtPosReached(); //mutex
|
||||||
|
void handleStateChange(); //mutex
|
||||||
|
restState_t getNextState() const {return nextState;};
|
||||||
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
void init();
|
void init();
|
||||||
|
void updatePosition();
|
||||||
|
void changeState(restState_t newState);
|
||||||
|
|
||||||
|
// task related:
|
||||||
|
TaskHandle_t taskHandle = NULL; //task that repeatedly runs the handle() method, is assigned at task creation
|
||||||
|
bool taskIsRunning = false;
|
||||||
|
SemaphoreHandle_t mutex;
|
||||||
|
|
||||||
|
// config:
|
||||||
char name[32];
|
char name[32];
|
||||||
gpio_num_t gpio_up;
|
const gpio_num_t gpio_up;
|
||||||
gpio_num_t gpio_down;
|
const gpio_num_t gpio_down;
|
||||||
restState_t state;
|
const uint32_t travelDuration = 12000;
|
||||||
const uint32_t travelDuration = 5000;
|
|
||||||
uint32_t timestamp_lastChange;
|
// variables:
|
||||||
float currentPosition = 0;
|
restState_t state = REST_OFF;
|
||||||
|
restState_t nextState = REST_OFF;
|
||||||
|
uint32_t timestamp_lastStateChange = 0;
|
||||||
|
uint32_t timestamp_lastPosUpdate = 0;
|
||||||
|
float positionTarget = 0;
|
||||||
|
float positionNow = 0;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//===========================
|
||||||
|
//==== chairAdjust_task =====
|
||||||
|
//===========================
|
||||||
|
// repeatedly runs handle methods of specified ControlledRest object to turn of the rest, when activated by changeState() method
|
||||||
|
void chairAdjust_task( void * cControlledRest );
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//====================================
|
//====================================
|
||||||
//====== controlChairAdjustment ======
|
//====== controlChairAdjustment ======
|
||||||
//====================================
|
//====================================
|
||||||
|
19476
hardware/chairAdjust-relayBoard/chairAdjust-relayBoard.kicad_pcb
Normal file
@ -0,0 +1,82 @@
|
|||||||
|
{
|
||||||
|
"board": {
|
||||||
|
"active_layer": 31,
|
||||||
|
"active_layer_preset": "",
|
||||||
|
"auto_track_width": true,
|
||||||
|
"hidden_netclasses": [],
|
||||||
|
"hidden_nets": [],
|
||||||
|
"high_contrast_mode": 0,
|
||||||
|
"net_color_mode": 1,
|
||||||
|
"opacity": {
|
||||||
|
"images": 0.6,
|
||||||
|
"pads": 1.0,
|
||||||
|
"tracks": 1.0,
|
||||||
|
"vias": 1.0,
|
||||||
|
"zones": 0.2199999988079071
|
||||||
|
},
|
||||||
|
"selection_filter": {
|
||||||
|
"dimensions": true,
|
||||||
|
"footprints": true,
|
||||||
|
"graphics": true,
|
||||||
|
"keepouts": true,
|
||||||
|
"lockedItems": false,
|
||||||
|
"otherItems": true,
|
||||||
|
"pads": true,
|
||||||
|
"text": true,
|
||||||
|
"tracks": true,
|
||||||
|
"vias": true,
|
||||||
|
"zones": true
|
||||||
|
},
|
||||||
|
"visible_items": [
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
2,
|
||||||
|
3,
|
||||||
|
4,
|
||||||
|
5,
|
||||||
|
8,
|
||||||
|
9,
|
||||||
|
10,
|
||||||
|
11,
|
||||||
|
13,
|
||||||
|
15,
|
||||||
|
16,
|
||||||
|
17,
|
||||||
|
18,
|
||||||
|
19,
|
||||||
|
20,
|
||||||
|
21,
|
||||||
|
22,
|
||||||
|
23,
|
||||||
|
24,
|
||||||
|
25,
|
||||||
|
26,
|
||||||
|
27,
|
||||||
|
28,
|
||||||
|
29,
|
||||||
|
30,
|
||||||
|
32,
|
||||||
|
33,
|
||||||
|
34,
|
||||||
|
35,
|
||||||
|
36,
|
||||||
|
39,
|
||||||
|
40
|
||||||
|
],
|
||||||
|
"visible_layers": "fffffff_ffffffff",
|
||||||
|
"zone_display_mode": 0
|
||||||
|
},
|
||||||
|
"git": {
|
||||||
|
"repo_password": "",
|
||||||
|
"repo_type": "",
|
||||||
|
"repo_username": "",
|
||||||
|
"ssh_key": ""
|
||||||
|
},
|
||||||
|
"meta": {
|
||||||
|
"filename": "chairAdjust-relayBoard.kicad_prl",
|
||||||
|
"version": 3
|
||||||
|
},
|
||||||
|
"project": {
|
||||||
|
"files": []
|
||||||
|
}
|
||||||
|
}
|
605
hardware/chairAdjust-relayBoard/chairAdjust-relayBoard.kicad_pro
Normal file
@ -0,0 +1,605 @@
|
|||||||
|
{
|
||||||
|
"board": {
|
||||||
|
"3dviewports": [],
|
||||||
|
"design_settings": {
|
||||||
|
"defaults": {
|
||||||
|
"apply_defaults_to_fp_fields": false,
|
||||||
|
"apply_defaults_to_fp_shapes": false,
|
||||||
|
"apply_defaults_to_fp_text": false,
|
||||||
|
"board_outline_line_width": 0.05,
|
||||||
|
"copper_line_width": 0.2,
|
||||||
|
"copper_text_italic": false,
|
||||||
|
"copper_text_size_h": 1.5,
|
||||||
|
"copper_text_size_v": 1.5,
|
||||||
|
"copper_text_thickness": 0.3,
|
||||||
|
"copper_text_upright": false,
|
||||||
|
"courtyard_line_width": 0.05,
|
||||||
|
"dimension_precision": 4,
|
||||||
|
"dimension_units": 3,
|
||||||
|
"dimensions": {
|
||||||
|
"arrow_length": 1270000,
|
||||||
|
"extension_offset": 500000,
|
||||||
|
"keep_text_aligned": true,
|
||||||
|
"suppress_zeroes": false,
|
||||||
|
"text_position": 0,
|
||||||
|
"units_format": 1
|
||||||
|
},
|
||||||
|
"fab_line_width": 0.1,
|
||||||
|
"fab_text_italic": false,
|
||||||
|
"fab_text_size_h": 1.0,
|
||||||
|
"fab_text_size_v": 1.0,
|
||||||
|
"fab_text_thickness": 0.15,
|
||||||
|
"fab_text_upright": false,
|
||||||
|
"other_line_width": 0.1,
|
||||||
|
"other_text_italic": false,
|
||||||
|
"other_text_size_h": 1.0,
|
||||||
|
"other_text_size_v": 1.0,
|
||||||
|
"other_text_thickness": 0.15,
|
||||||
|
"other_text_upright": false,
|
||||||
|
"pads": {
|
||||||
|
"drill": 0.5,
|
||||||
|
"height": 1.5,
|
||||||
|
"width": 1.5
|
||||||
|
},
|
||||||
|
"silk_line_width": 0.1,
|
||||||
|
"silk_text_italic": false,
|
||||||
|
"silk_text_size_h": 1.0,
|
||||||
|
"silk_text_size_v": 1.0,
|
||||||
|
"silk_text_thickness": 0.1,
|
||||||
|
"silk_text_upright": false,
|
||||||
|
"zones": {
|
||||||
|
"min_clearance": 0.8
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"diff_pair_dimensions": [
|
||||||
|
{
|
||||||
|
"gap": 0.0,
|
||||||
|
"via_gap": 0.0,
|
||||||
|
"width": 0.0
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"drc_exclusions": [],
|
||||||
|
"meta": {
|
||||||
|
"version": 2
|
||||||
|
},
|
||||||
|
"rule_severities": {
|
||||||
|
"annular_width": "error",
|
||||||
|
"clearance": "error",
|
||||||
|
"connection_width": "warning",
|
||||||
|
"copper_edge_clearance": "error",
|
||||||
|
"copper_sliver": "warning",
|
||||||
|
"courtyards_overlap": "warning",
|
||||||
|
"diff_pair_gap_out_of_range": "error",
|
||||||
|
"diff_pair_uncoupled_length_too_long": "error",
|
||||||
|
"drill_out_of_range": "error",
|
||||||
|
"duplicate_footprints": "warning",
|
||||||
|
"extra_footprint": "warning",
|
||||||
|
"footprint": "error",
|
||||||
|
"footprint_symbol_mismatch": "warning",
|
||||||
|
"footprint_type_mismatch": "ignore",
|
||||||
|
"hole_clearance": "error",
|
||||||
|
"hole_near_hole": "error",
|
||||||
|
"holes_co_located": "warning",
|
||||||
|
"invalid_outline": "error",
|
||||||
|
"isolated_copper": "warning",
|
||||||
|
"item_on_disabled_layer": "error",
|
||||||
|
"items_not_allowed": "error",
|
||||||
|
"length_out_of_range": "error",
|
||||||
|
"lib_footprint_issues": "warning",
|
||||||
|
"lib_footprint_mismatch": "warning",
|
||||||
|
"malformed_courtyard": "error",
|
||||||
|
"microvia_drill_out_of_range": "error",
|
||||||
|
"missing_courtyard": "ignore",
|
||||||
|
"missing_footprint": "warning",
|
||||||
|
"net_conflict": "warning",
|
||||||
|
"npth_inside_courtyard": "ignore",
|
||||||
|
"padstack": "warning",
|
||||||
|
"pth_inside_courtyard": "ignore",
|
||||||
|
"shorting_items": "error",
|
||||||
|
"silk_edge_clearance": "ignore",
|
||||||
|
"silk_over_copper": "ignore",
|
||||||
|
"silk_overlap": "ignore",
|
||||||
|
"skew_out_of_range": "error",
|
||||||
|
"solder_mask_bridge": "error",
|
||||||
|
"starved_thermal": "error",
|
||||||
|
"text_height": "ignore",
|
||||||
|
"text_thickness": "ignore",
|
||||||
|
"through_hole_pad_without_hole": "error",
|
||||||
|
"too_many_vias": "error",
|
||||||
|
"track_dangling": "warning",
|
||||||
|
"track_width": "error",
|
||||||
|
"tracks_crossing": "error",
|
||||||
|
"unconnected_items": "error",
|
||||||
|
"unresolved_variable": "error",
|
||||||
|
"via_dangling": "warning",
|
||||||
|
"zones_intersect": "error"
|
||||||
|
},
|
||||||
|
"rules": {
|
||||||
|
"max_error": 0.005,
|
||||||
|
"min_clearance": 0.0,
|
||||||
|
"min_connection": 0.0,
|
||||||
|
"min_copper_edge_clearance": 0.5,
|
||||||
|
"min_hole_clearance": 0.25,
|
||||||
|
"min_hole_to_hole": 0.25,
|
||||||
|
"min_microvia_diameter": 0.2,
|
||||||
|
"min_microvia_drill": 0.1,
|
||||||
|
"min_resolved_spokes": 2,
|
||||||
|
"min_silk_clearance": 0.0,
|
||||||
|
"min_text_height": 0.8,
|
||||||
|
"min_text_thickness": 0.08,
|
||||||
|
"min_through_hole_diameter": 0.3,
|
||||||
|
"min_track_width": 0.0,
|
||||||
|
"min_via_annular_width": 0.1,
|
||||||
|
"min_via_diameter": 0.5,
|
||||||
|
"solder_mask_to_copper_clearance": 0.0,
|
||||||
|
"use_height_for_length_calcs": true
|
||||||
|
},
|
||||||
|
"teardrop_options": [
|
||||||
|
{
|
||||||
|
"td_onpadsmd": true,
|
||||||
|
"td_onroundshapesonly": false,
|
||||||
|
"td_ontrackend": false,
|
||||||
|
"td_onviapad": true
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"teardrop_parameters": [
|
||||||
|
{
|
||||||
|
"td_allow_use_two_tracks": true,
|
||||||
|
"td_curve_segcount": 0,
|
||||||
|
"td_height_ratio": 1.0,
|
||||||
|
"td_length_ratio": 0.5,
|
||||||
|
"td_maxheight": 2.0,
|
||||||
|
"td_maxlen": 1.0,
|
||||||
|
"td_on_pad_in_zone": false,
|
||||||
|
"td_target_name": "td_round_shape",
|
||||||
|
"td_width_to_size_filter_ratio": 0.9
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"td_allow_use_two_tracks": true,
|
||||||
|
"td_curve_segcount": 0,
|
||||||
|
"td_height_ratio": 1.0,
|
||||||
|
"td_length_ratio": 0.5,
|
||||||
|
"td_maxheight": 2.0,
|
||||||
|
"td_maxlen": 1.0,
|
||||||
|
"td_on_pad_in_zone": false,
|
||||||
|
"td_target_name": "td_rect_shape",
|
||||||
|
"td_width_to_size_filter_ratio": 0.9
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"td_allow_use_two_tracks": true,
|
||||||
|
"td_curve_segcount": 0,
|
||||||
|
"td_height_ratio": 1.0,
|
||||||
|
"td_length_ratio": 0.5,
|
||||||
|
"td_maxheight": 2.0,
|
||||||
|
"td_maxlen": 1.0,
|
||||||
|
"td_on_pad_in_zone": false,
|
||||||
|
"td_target_name": "td_track_end",
|
||||||
|
"td_width_to_size_filter_ratio": 0.9
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"track_widths": [
|
||||||
|
0.0,
|
||||||
|
0.8,
|
||||||
|
1.0,
|
||||||
|
2.5,
|
||||||
|
4.0
|
||||||
|
],
|
||||||
|
"tuning_pattern_settings": {
|
||||||
|
"diff_pair_defaults": {
|
||||||
|
"corner_radius_percentage": 80,
|
||||||
|
"corner_style": 1,
|
||||||
|
"max_amplitude": 1.0,
|
||||||
|
"min_amplitude": 0.2,
|
||||||
|
"single_sided": false,
|
||||||
|
"spacing": 1.0
|
||||||
|
},
|
||||||
|
"diff_pair_skew_defaults": {
|
||||||
|
"corner_radius_percentage": 80,
|
||||||
|
"corner_style": 1,
|
||||||
|
"max_amplitude": 1.0,
|
||||||
|
"min_amplitude": 0.2,
|
||||||
|
"single_sided": false,
|
||||||
|
"spacing": 0.6
|
||||||
|
},
|
||||||
|
"single_track_defaults": {
|
||||||
|
"corner_radius_percentage": 80,
|
||||||
|
"corner_style": 1,
|
||||||
|
"max_amplitude": 1.0,
|
||||||
|
"min_amplitude": 0.2,
|
||||||
|
"single_sided": false,
|
||||||
|
"spacing": 0.6
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"via_dimensions": [
|
||||||
|
{
|
||||||
|
"diameter": 0.0,
|
||||||
|
"drill": 0.0
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"diameter": 4.0,
|
||||||
|
"drill": 1.0
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"zones_allow_external_fillets": false
|
||||||
|
},
|
||||||
|
"ipc2581": {
|
||||||
|
"dist": "",
|
||||||
|
"distpn": "",
|
||||||
|
"internal_id": "",
|
||||||
|
"mfg": "",
|
||||||
|
"mpn": ""
|
||||||
|
},
|
||||||
|
"layer_presets": [],
|
||||||
|
"viewports": []
|
||||||
|
},
|
||||||
|
"boards": [],
|
||||||
|
"cvpcb": {
|
||||||
|
"equivalence_files": []
|
||||||
|
},
|
||||||
|
"erc": {
|
||||||
|
"erc_exclusions": [],
|
||||||
|
"meta": {
|
||||||
|
"version": 0
|
||||||
|
},
|
||||||
|
"pin_map": [
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
2,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
1,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2
|
||||||
|
]
|
||||||
|
],
|
||||||
|
"rule_severities": {
|
||||||
|
"bus_definition_conflict": "error",
|
||||||
|
"bus_entry_needed": "error",
|
||||||
|
"bus_to_bus_conflict": "error",
|
||||||
|
"bus_to_net_conflict": "error",
|
||||||
|
"conflicting_netclasses": "error",
|
||||||
|
"different_unit_footprint": "error",
|
||||||
|
"different_unit_net": "error",
|
||||||
|
"duplicate_reference": "error",
|
||||||
|
"duplicate_sheet_names": "error",
|
||||||
|
"endpoint_off_grid": "warning",
|
||||||
|
"extra_units": "error",
|
||||||
|
"global_label_dangling": "warning",
|
||||||
|
"hier_label_mismatch": "error",
|
||||||
|
"label_dangling": "error",
|
||||||
|
"lib_symbol_issues": "warning",
|
||||||
|
"missing_bidi_pin": "warning",
|
||||||
|
"missing_input_pin": "warning",
|
||||||
|
"missing_power_pin": "error",
|
||||||
|
"missing_unit": "warning",
|
||||||
|
"multiple_net_names": "warning",
|
||||||
|
"net_not_bus_member": "warning",
|
||||||
|
"no_connect_connected": "warning",
|
||||||
|
"no_connect_dangling": "warning",
|
||||||
|
"pin_not_connected": "error",
|
||||||
|
"pin_not_driven": "error",
|
||||||
|
"pin_to_pin": "warning",
|
||||||
|
"power_pin_not_driven": "error",
|
||||||
|
"similar_labels": "warning",
|
||||||
|
"simulation_model_issue": "ignore",
|
||||||
|
"unannotated": "error",
|
||||||
|
"unit_value_mismatch": "error",
|
||||||
|
"unresolved_variable": "error",
|
||||||
|
"wire_dangling": "error"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"libraries": {
|
||||||
|
"pinned_footprint_libs": [],
|
||||||
|
"pinned_symbol_libs": []
|
||||||
|
},
|
||||||
|
"meta": {
|
||||||
|
"filename": "chairAdjust-relayBoard.kicad_pro",
|
||||||
|
"version": 1
|
||||||
|
},
|
||||||
|
"net_settings": {
|
||||||
|
"classes": [
|
||||||
|
{
|
||||||
|
"bus_width": 12,
|
||||||
|
"clearance": 0.2,
|
||||||
|
"diff_pair_gap": 0.25,
|
||||||
|
"diff_pair_via_gap": 0.25,
|
||||||
|
"diff_pair_width": 0.2,
|
||||||
|
"line_style": 0,
|
||||||
|
"microvia_diameter": 0.3,
|
||||||
|
"microvia_drill": 0.1,
|
||||||
|
"name": "Default",
|
||||||
|
"pcb_color": "rgba(0, 0, 0, 0.000)",
|
||||||
|
"schematic_color": "rgba(0, 0, 0, 0.000)",
|
||||||
|
"track_width": 0.2,
|
||||||
|
"via_diameter": 0.6,
|
||||||
|
"via_drill": 0.3,
|
||||||
|
"wire_width": 6
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"meta": {
|
||||||
|
"version": 3
|
||||||
|
},
|
||||||
|
"net_colors": null,
|
||||||
|
"netclass_assignments": null,
|
||||||
|
"netclass_patterns": []
|
||||||
|
},
|
||||||
|
"pcbnew": {
|
||||||
|
"last_paths": {
|
||||||
|
"gencad": "",
|
||||||
|
"idf": "",
|
||||||
|
"netlist": "",
|
||||||
|
"plot": "export/",
|
||||||
|
"pos_files": "",
|
||||||
|
"specctra_dsn": "",
|
||||||
|
"step": "export/3d-model_low.step",
|
||||||
|
"svg": "export/",
|
||||||
|
"vrml": "export/3d-model.wrl"
|
||||||
|
},
|
||||||
|
"page_layout_descr_file": ""
|
||||||
|
},
|
||||||
|
"schematic": {
|
||||||
|
"annotate_start_num": 0,
|
||||||
|
"bom_export_filename": "",
|
||||||
|
"bom_fmt_presets": [],
|
||||||
|
"bom_fmt_settings": {
|
||||||
|
"field_delimiter": ",",
|
||||||
|
"keep_line_breaks": false,
|
||||||
|
"keep_tabs": false,
|
||||||
|
"name": "CSV",
|
||||||
|
"ref_delimiter": ",",
|
||||||
|
"ref_range_delimiter": "",
|
||||||
|
"string_delimiter": "\""
|
||||||
|
},
|
||||||
|
"bom_presets": [],
|
||||||
|
"bom_settings": {
|
||||||
|
"exclude_dnp": false,
|
||||||
|
"fields_ordered": [
|
||||||
|
{
|
||||||
|
"group_by": false,
|
||||||
|
"label": "Reference",
|
||||||
|
"name": "Reference",
|
||||||
|
"show": true
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"group_by": true,
|
||||||
|
"label": "Value",
|
||||||
|
"name": "Value",
|
||||||
|
"show": true
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"group_by": false,
|
||||||
|
"label": "Datasheet",
|
||||||
|
"name": "Datasheet",
|
||||||
|
"show": true
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"group_by": false,
|
||||||
|
"label": "Footprint",
|
||||||
|
"name": "Footprint",
|
||||||
|
"show": true
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"group_by": false,
|
||||||
|
"label": "Qty",
|
||||||
|
"name": "${QUANTITY}",
|
||||||
|
"show": true
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"group_by": true,
|
||||||
|
"label": "DNP",
|
||||||
|
"name": "${DNP}",
|
||||||
|
"show": true
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"filter_string": "",
|
||||||
|
"group_symbols": true,
|
||||||
|
"name": "Grouped By Value",
|
||||||
|
"sort_asc": true,
|
||||||
|
"sort_field": "Reference"
|
||||||
|
},
|
||||||
|
"connection_grid_size": 50.0,
|
||||||
|
"drawing": {
|
||||||
|
"dashed_lines_dash_length_ratio": 12.0,
|
||||||
|
"dashed_lines_gap_length_ratio": 3.0,
|
||||||
|
"default_line_thickness": 6.0,
|
||||||
|
"default_text_size": 50.0,
|
||||||
|
"field_names": [],
|
||||||
|
"intersheets_ref_own_page": false,
|
||||||
|
"intersheets_ref_prefix": "",
|
||||||
|
"intersheets_ref_short": false,
|
||||||
|
"intersheets_ref_show": false,
|
||||||
|
"intersheets_ref_suffix": "",
|
||||||
|
"junction_size_choice": 3,
|
||||||
|
"label_size_ratio": 0.375,
|
||||||
|
"operating_point_overlay_i_precision": 3,
|
||||||
|
"operating_point_overlay_i_range": "~A",
|
||||||
|
"operating_point_overlay_v_precision": 3,
|
||||||
|
"operating_point_overlay_v_range": "~V",
|
||||||
|
"overbar_offset_ratio": 1.23,
|
||||||
|
"pin_symbol_size": 25.0,
|
||||||
|
"text_offset_ratio": 0.15
|
||||||
|
},
|
||||||
|
"legacy_lib_dir": "",
|
||||||
|
"legacy_lib_list": [],
|
||||||
|
"meta": {
|
||||||
|
"version": 1
|
||||||
|
},
|
||||||
|
"net_format_name": "",
|
||||||
|
"page_layout_descr_file": "",
|
||||||
|
"plot_directory": "export/",
|
||||||
|
"spice_current_sheet_as_root": false,
|
||||||
|
"spice_external_command": "spice \"%I\"",
|
||||||
|
"spice_model_current_sheet_as_root": true,
|
||||||
|
"spice_save_all_currents": false,
|
||||||
|
"spice_save_all_dissipations": false,
|
||||||
|
"spice_save_all_voltages": false,
|
||||||
|
"subpart_first_id": 65,
|
||||||
|
"subpart_id_separator": 0
|
||||||
|
},
|
||||||
|
"sheets": [
|
||||||
|
[
|
||||||
|
"30898b44-6bb1-4dee-9c2d-8b9a1b5f01c8",
|
||||||
|
"Root"
|
||||||
|
]
|
||||||
|
],
|
||||||
|
"text_variables": {}
|
||||||
|
}
|
13397
hardware/chairAdjust-relayBoard/chairAdjust-relayBoard.kicad_sch
Normal file
98547
hardware/chairAdjust-relayBoard/export/3d-model.wrl
Normal file
@ -0,0 +1,23 @@
|
|||||||
|
%TF.GenerationSoftware,KiCad,Pcbnew,8.0.4*%
|
||||||
|
%TF.CreationDate,2024-09-07T09:02:32+02:00*%
|
||||||
|
%TF.ProjectId,chairAdjust-relayBoard,63686169-7241-4646-9a75-73742d72656c,rev?*%
|
||||||
|
%TF.SameCoordinates,Original*%
|
||||||
|
%TF.FileFunction,Profile,NP*%
|
||||||
|
%FSLAX46Y46*%
|
||||||
|
G04 Gerber Fmt 4.6, Leading zero omitted, Abs format (unit mm)*
|
||||||
|
G04 Created by KiCad (PCBNEW 8.0.4) date 2024-09-07 09:02:32*
|
||||||
|
%MOMM*%
|
||||||
|
%LPD*%
|
||||||
|
G01*
|
||||||
|
G04 APERTURE LIST*
|
||||||
|
%TA.AperFunction,Profile*%
|
||||||
|
%ADD10C,0.050000*%
|
||||||
|
%TD*%
|
||||||
|
G04 APERTURE END LIST*
|
||||||
|
D10*
|
||||||
|
X107315000Y-28575000D02*
|
||||||
|
X208280000Y-28575000D01*
|
||||||
|
X208280000Y-107315000D01*
|
||||||
|
X107315000Y-107315000D01*
|
||||||
|
X107315000Y-28575000D01*
|
||||||
|
M02*
|
@ -0,0 +1,559 @@
|
|||||||
|
%TF.GenerationSoftware,KiCad,Pcbnew,8.0.4*%
|
||||||
|
%TF.CreationDate,2024-09-07T09:02:32+02:00*%
|
||||||
|
%TF.ProjectId,chairAdjust-relayBoard,63686169-7241-4646-9a75-73742d72656c,rev?*%
|
||||||
|
%TF.SameCoordinates,Original*%
|
||||||
|
%TF.FileFunction,Copper,L1,Top*%
|
||||||
|
%TF.FilePolarity,Positive*%
|
||||||
|
%FSLAX46Y46*%
|
||||||
|
G04 Gerber Fmt 4.6, Leading zero omitted, Abs format (unit mm)*
|
||||||
|
G04 Created by KiCad (PCBNEW 8.0.4) date 2024-09-07 09:02:32*
|
||||||
|
%MOMM*%
|
||||||
|
%LPD*%
|
||||||
|
G01*
|
||||||
|
G04 APERTURE LIST*
|
||||||
|
%TA.AperFunction,ComponentPad*%
|
||||||
|
%ADD10R,3.000000X3.000000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,ComponentPad*%
|
||||||
|
%ADD11C,3.000000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,ComponentPad*%
|
||||||
|
%ADD12R,0.850000X0.850000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,ComponentPad*%
|
||||||
|
%ADD13R,2.800000X2.800000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,ComponentPad*%
|
||||||
|
%ADD14O,2.800000X2.800000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,ComponentPad*%
|
||||||
|
%ADD15R,2.400000X2.400000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,ComponentPad*%
|
||||||
|
%ADD16O,2.400000X2.400000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,ComponentPad*%
|
||||||
|
%ADD17C,1.600000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,ComponentPad*%
|
||||||
|
%ADD18O,1.600000X1.600000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,ComponentPad*%
|
||||||
|
%ADD19R,1.500000X1.500000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,ComponentPad*%
|
||||||
|
%ADD20C,1.500000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,ComponentPad*%
|
||||||
|
%ADD21O,2.000000X3.000000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,ComponentPad*%
|
||||||
|
%ADD22R,3.000000X2.000000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,ComponentPad*%
|
||||||
|
%ADD23O,3.000000X2.000000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,ComponentPad*%
|
||||||
|
%ADD24R,1.700000X1.700000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,ComponentPad*%
|
||||||
|
%ADD25O,1.700000X1.700000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,ComponentPad*%
|
||||||
|
%ADD26C,2.400000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,ViaPad*%
|
||||||
|
%ADD27C,4.000000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,Conductor*%
|
||||||
|
%ADD28C,4.000000*%
|
||||||
|
%TD*%
|
||||||
|
%TA.AperFunction,Conductor*%
|
||||||
|
%ADD29C,2.500000*%
|
||||||
|
%TD*%
|
||||||
|
G04 APERTURE END LIST*
|
||||||
|
D10*
|
||||||
|
%TO.P,J4,1,Pin_1*%
|
||||||
|
%TO.N,+24V*%
|
||||||
|
X176530000Y-35560000D03*
|
||||||
|
D11*
|
||||||
|
%TO.P,J4,2,Pin_2*%
|
||||||
|
X171450000Y-35560000D03*
|
||||||
|
%TD*%
|
||||||
|
D12*
|
||||||
|
%TO.P,TP7,1,1*%
|
||||||
|
%TO.N,Net-(D3-K)*%
|
||||||
|
X130556000Y-68326000D03*
|
||||||
|
%TD*%
|
||||||
|
D13*
|
||||||
|
%TO.P,D8,1,K*%
|
||||||
|
%TO.N,Net-(D8-K)*%
|
||||||
|
X139700000Y-86360000D03*
|
||||||
|
D14*
|
||||||
|
%TO.P,D8,2,A*%
|
||||||
|
%TO.N,GND*%
|
||||||
|
X139700000Y-73660000D03*
|
||||||
|
%TD*%
|
||||||
|
D15*
|
||||||
|
%TO.P,D11,1,K*%
|
||||||
|
%TO.N,Net-(D10-A)*%
|
||||||
|
X196850000Y-92075000D03*
|
||||||
|
D16*
|
||||||
|
%TO.P,D11,2,A*%
|
||||||
|
%TO.N,GNDPWR*%
|
||||||
|
X196850000Y-71755000D03*
|
||||||
|
%TD*%
|
||||||
|
D17*
|
||||||
|
%TO.P,R7,1*%
|
||||||
|
%TO.N,/Relay_M2.2*%
|
||||||
|
X120015000Y-92075000D03*
|
||||||
|
D18*
|
||||||
|
%TO.P,R7,2*%
|
||||||
|
%TO.N,+12V*%
|
||||||
|
X130175000Y-92075000D03*
|
||||||
|
%TD*%
|
||||||
|
D15*
|
||||||
|
%TO.P,D7,1,K*%
|
||||||
|
%TO.N,Net-(D4-A)*%
|
||||||
|
X196850000Y-66675000D03*
|
||||||
|
D16*
|
||||||
|
%TO.P,D7,2,A*%
|
||||||
|
%TO.N,GNDPWR*%
|
||||||
|
X196850000Y-46355000D03*
|
||||||
|
%TD*%
|
||||||
|
D12*
|
||||||
|
%TO.P,TP9,1,1*%
|
||||||
|
%TO.N,Net-(D8-K)*%
|
||||||
|
X130429000Y-85090000D03*
|
||||||
|
%TD*%
|
||||||
|
D19*
|
||||||
|
%TO.P,Q2,1,C*%
|
||||||
|
%TO.N,Net-(D8-K)*%
|
||||||
|
X134980000Y-81915000D03*
|
||||||
|
D20*
|
||||||
|
%TO.P,Q2,2,B*%
|
||||||
|
%TO.N,Net-(Q2-B)*%
|
||||||
|
X134980000Y-79375000D03*
|
||||||
|
%TO.P,Q2,3,E*%
|
||||||
|
%TO.N,+12V*%
|
||||||
|
X134980000Y-76835000D03*
|
||||||
|
%TD*%
|
||||||
|
D15*
|
||||||
|
%TO.P,D6,1,K*%
|
||||||
|
%TO.N,Net-(D5-A)*%
|
||||||
|
X191135000Y-61595000D03*
|
||||||
|
D16*
|
||||||
|
%TO.P,D6,2,A*%
|
||||||
|
%TO.N,GNDPWR*%
|
||||||
|
X191135000Y-41275000D03*
|
||||||
|
%TD*%
|
||||||
|
D15*
|
||||||
|
%TO.P,D12,1,K*%
|
||||||
|
%TO.N,+24V*%
|
||||||
|
X179705000Y-76835000D03*
|
||||||
|
D16*
|
||||||
|
%TO.P,D12,2,A*%
|
||||||
|
%TO.N,Net-(D12-A)*%
|
||||||
|
X179705000Y-97155000D03*
|
||||||
|
%TD*%
|
||||||
|
D19*
|
||||||
|
%TO.P,Q3,1,C*%
|
||||||
|
%TO.N,Net-(D3-K)*%
|
||||||
|
X134980000Y-65405000D03*
|
||||||
|
D20*
|
||||||
|
%TO.P,Q3,2,B*%
|
||||||
|
%TO.N,Net-(Q3-B)*%
|
||||||
|
X134980000Y-62865000D03*
|
||||||
|
%TO.P,Q3,3,E*%
|
||||||
|
%TO.N,+12V*%
|
||||||
|
X134980000Y-60325000D03*
|
||||||
|
%TD*%
|
||||||
|
D12*
|
||||||
|
%TO.P,TP8,1,1*%
|
||||||
|
%TO.N,Net-(D1-K)*%
|
||||||
|
X130429000Y-51689000D03*
|
||||||
|
%TD*%
|
||||||
|
D21*
|
||||||
|
%TO.P,K1,11*%
|
||||||
|
%TO.N,Net-(D5-A)*%
|
||||||
|
X166350000Y-43300000D03*
|
||||||
|
X166350000Y-50800000D03*
|
||||||
|
%TO.P,K1,12*%
|
||||||
|
%TO.N,GNDPWR*%
|
||||||
|
X161310000Y-43300000D03*
|
||||||
|
X161310000Y-50800000D03*
|
||||||
|
%TO.P,K1,14*%
|
||||||
|
%TO.N,+24V*%
|
||||||
|
X171390000Y-43300000D03*
|
||||||
|
X171390000Y-50800000D03*
|
||||||
|
D22*
|
||||||
|
%TO.P,K1,A1*%
|
||||||
|
%TO.N,Net-(D1-K)*%
|
||||||
|
X146050000Y-50800000D03*
|
||||||
|
D23*
|
||||||
|
%TO.P,K1,A2*%
|
||||||
|
%TO.N,GND*%
|
||||||
|
X146050000Y-43300000D03*
|
||||||
|
%TD*%
|
||||||
|
D12*
|
||||||
|
%TO.P,TP6,1,1*%
|
||||||
|
%TO.N,+12V*%
|
||||||
|
X124079000Y-35306000D03*
|
||||||
|
%TD*%
|
||||||
|
D10*
|
||||||
|
%TO.P,J7,1,Pin_1*%
|
||||||
|
%TO.N,Net-(D12-A)*%
|
||||||
|
X203835000Y-88265000D03*
|
||||||
|
D11*
|
||||||
|
%TO.P,J7,2,Pin_2*%
|
||||||
|
%TO.N,Net-(D10-A)*%
|
||||||
|
X203835000Y-83185000D03*
|
||||||
|
%TD*%
|
||||||
|
D12*
|
||||||
|
%TO.P,TP10,1,1*%
|
||||||
|
%TO.N,Net-(D9-K)*%
|
||||||
|
X129794000Y-101473000D03*
|
||||||
|
%TD*%
|
||||||
|
D24*
|
||||||
|
%TO.P,J3,1,Pin_1*%
|
||||||
|
%TO.N,/Relay_M2.2*%
|
||||||
|
X117475000Y-73025000D03*
|
||||||
|
D25*
|
||||||
|
%TO.P,J3,2,Pin_2*%
|
||||||
|
%TO.N,/Relay_M2.1*%
|
||||||
|
X117475000Y-70485000D03*
|
||||||
|
%TO.P,J3,3,Pin_3*%
|
||||||
|
%TO.N,/Relay_M1.2*%
|
||||||
|
X117475000Y-67945000D03*
|
||||||
|
%TO.P,J3,4,Pin_4*%
|
||||||
|
%TO.N,/Relay_M1.1*%
|
||||||
|
X117475000Y-65405000D03*
|
||||||
|
%TD*%
|
||||||
|
D21*
|
||||||
|
%TO.P,K4,11*%
|
||||||
|
%TO.N,Net-(D12-A)*%
|
||||||
|
X166348000Y-92830000D03*
|
||||||
|
X166348000Y-100330000D03*
|
||||||
|
%TO.P,K4,12*%
|
||||||
|
%TO.N,GNDPWR*%
|
||||||
|
X161308000Y-92830000D03*
|
||||||
|
X161308000Y-100330000D03*
|
||||||
|
%TO.P,K4,14*%
|
||||||
|
%TO.N,+24V*%
|
||||||
|
X171388000Y-92830000D03*
|
||||||
|
X171388000Y-100330000D03*
|
||||||
|
D22*
|
||||||
|
%TO.P,K4,A1*%
|
||||||
|
%TO.N,Net-(D9-K)*%
|
||||||
|
X146048000Y-100330000D03*
|
||||||
|
D23*
|
||||||
|
%TO.P,K4,A2*%
|
||||||
|
%TO.N,GND*%
|
||||||
|
X146048000Y-92830000D03*
|
||||||
|
%TD*%
|
||||||
|
D13*
|
||||||
|
%TO.P,D1,1,K*%
|
||||||
|
%TO.N,Net-(D1-K)*%
|
||||||
|
X139700000Y-53340000D03*
|
||||||
|
D14*
|
||||||
|
%TO.P,D1,2,A*%
|
||||||
|
%TO.N,GND*%
|
||||||
|
X139700000Y-40640000D03*
|
||||||
|
%TD*%
|
||||||
|
D10*
|
||||||
|
%TO.P,J1,1,Pin_1*%
|
||||||
|
%TO.N,Net-(D4-A)*%
|
||||||
|
X203835000Y-62230000D03*
|
||||||
|
D11*
|
||||||
|
%TO.P,J1,2,Pin_2*%
|
||||||
|
%TO.N,Net-(D5-A)*%
|
||||||
|
X203835000Y-57150000D03*
|
||||||
|
%TD*%
|
||||||
|
D17*
|
||||||
|
%TO.P,R2,1*%
|
||||||
|
%TO.N,/Relay_M1.1*%
|
||||||
|
X119655000Y-46355000D03*
|
||||||
|
D18*
|
||||||
|
%TO.P,R2,2*%
|
||||||
|
%TO.N,Net-(Q1-B)*%
|
||||||
|
X129815000Y-46355000D03*
|
||||||
|
%TD*%
|
||||||
|
D19*
|
||||||
|
%TO.P,TP4,1,1*%
|
||||||
|
%TO.N,GNDPWR*%
|
||||||
|
X150622000Y-35560000D03*
|
||||||
|
%TD*%
|
||||||
|
%TO.P,Q1,1,C*%
|
||||||
|
%TO.N,Net-(D1-K)*%
|
||||||
|
X134980000Y-48895000D03*
|
||||||
|
D20*
|
||||||
|
%TO.P,Q1,2,B*%
|
||||||
|
%TO.N,Net-(Q1-B)*%
|
||||||
|
X134980000Y-46355000D03*
|
||||||
|
%TO.P,Q1,3,E*%
|
||||||
|
%TO.N,+12V*%
|
||||||
|
X134980000Y-43815000D03*
|
||||||
|
%TD*%
|
||||||
|
D15*
|
||||||
|
%TO.P,D5,1,K*%
|
||||||
|
%TO.N,+24V*%
|
||||||
|
X179705000Y-41275000D03*
|
||||||
|
D16*
|
||||||
|
%TO.P,D5,2,A*%
|
||||||
|
%TO.N,Net-(D5-A)*%
|
||||||
|
X179705000Y-61595000D03*
|
||||||
|
%TD*%
|
||||||
|
D12*
|
||||||
|
%TO.P,TP11,1,1*%
|
||||||
|
%TO.N,Net-(D10-A)*%
|
||||||
|
X204216000Y-77470000D03*
|
||||||
|
%TD*%
|
||||||
|
D15*
|
||||||
|
%TO.P,J2,1,Pin_1*%
|
||||||
|
%TO.N,/Relay_M1.1*%
|
||||||
|
X111225000Y-63965000D03*
|
||||||
|
D26*
|
||||||
|
%TO.P,J2,2,Pin_2*%
|
||||||
|
%TO.N,/Relay_M1.2*%
|
||||||
|
X111225000Y-67465000D03*
|
||||||
|
%TO.P,J2,3,Pin_3*%
|
||||||
|
%TO.N,/Relay_M2.1*%
|
||||||
|
X111225000Y-70965000D03*
|
||||||
|
%TO.P,J2,4,Pin_4*%
|
||||||
|
%TO.N,/Relay_M2.2*%
|
||||||
|
X111225000Y-74465000D03*
|
||||||
|
%TD*%
|
||||||
|
D13*
|
||||||
|
%TO.P,D3,1,K*%
|
||||||
|
%TO.N,Net-(D3-K)*%
|
||||||
|
X139700000Y-69850000D03*
|
||||||
|
D14*
|
||||||
|
%TO.P,D3,2,A*%
|
||||||
|
%TO.N,GND*%
|
||||||
|
X139700000Y-57150000D03*
|
||||||
|
%TD*%
|
||||||
|
D19*
|
||||||
|
%TO.P,Q4,1,C*%
|
||||||
|
%TO.N,Net-(D9-K)*%
|
||||||
|
X134980000Y-98425000D03*
|
||||||
|
D20*
|
||||||
|
%TO.P,Q4,2,B*%
|
||||||
|
%TO.N,Net-(Q4-B)*%
|
||||||
|
X134980000Y-95885000D03*
|
||||||
|
%TO.P,Q4,3,E*%
|
||||||
|
%TO.N,+12V*%
|
||||||
|
X134980000Y-93345000D03*
|
||||||
|
%TD*%
|
||||||
|
D21*
|
||||||
|
%TO.P,K2,11*%
|
||||||
|
%TO.N,Net-(D4-A)*%
|
||||||
|
X166348000Y-59810000D03*
|
||||||
|
X166348000Y-67310000D03*
|
||||||
|
%TO.P,K2,12*%
|
||||||
|
%TO.N,GNDPWR*%
|
||||||
|
X161308000Y-59810000D03*
|
||||||
|
X161308000Y-67310000D03*
|
||||||
|
%TO.P,K2,14*%
|
||||||
|
%TO.N,+24V*%
|
||||||
|
X171388000Y-59810000D03*
|
||||||
|
X171388000Y-67310000D03*
|
||||||
|
D22*
|
||||||
|
%TO.P,K2,A1*%
|
||||||
|
%TO.N,Net-(D3-K)*%
|
||||||
|
X146048000Y-67310000D03*
|
||||||
|
D23*
|
||||||
|
%TO.P,K2,A2*%
|
||||||
|
%TO.N,GND*%
|
||||||
|
X146048000Y-59810000D03*
|
||||||
|
%TD*%
|
||||||
|
D15*
|
||||||
|
%TO.P,D13,1,K*%
|
||||||
|
%TO.N,Net-(D12-A)*%
|
||||||
|
X191135000Y-97155000D03*
|
||||||
|
D16*
|
||||||
|
%TO.P,D13,2,A*%
|
||||||
|
%TO.N,GNDPWR*%
|
||||||
|
X191135000Y-76835000D03*
|
||||||
|
%TD*%
|
||||||
|
D13*
|
||||||
|
%TO.P,D9,1,K*%
|
||||||
|
%TO.N,Net-(D9-K)*%
|
||||||
|
X139700000Y-102870000D03*
|
||||||
|
D14*
|
||||||
|
%TO.P,D9,2,A*%
|
||||||
|
%TO.N,GND*%
|
||||||
|
X139700000Y-90170000D03*
|
||||||
|
%TD*%
|
||||||
|
D21*
|
||||||
|
%TO.P,K3,11*%
|
||||||
|
%TO.N,Net-(D10-A)*%
|
||||||
|
X166350000Y-76320000D03*
|
||||||
|
X166350000Y-83820000D03*
|
||||||
|
%TO.P,K3,12*%
|
||||||
|
%TO.N,GNDPWR*%
|
||||||
|
X161310000Y-76320000D03*
|
||||||
|
X161310000Y-83820000D03*
|
||||||
|
%TO.P,K3,14*%
|
||||||
|
%TO.N,+24V*%
|
||||||
|
X171390000Y-76320000D03*
|
||||||
|
X171390000Y-83820000D03*
|
||||||
|
D22*
|
||||||
|
%TO.P,K3,A1*%
|
||||||
|
%TO.N,Net-(D8-K)*%
|
||||||
|
X146050000Y-83820000D03*
|
||||||
|
D23*
|
||||||
|
%TO.P,K3,A2*%
|
||||||
|
%TO.N,GND*%
|
||||||
|
X146050000Y-76320000D03*
|
||||||
|
%TD*%
|
||||||
|
D17*
|
||||||
|
%TO.P,R5,1*%
|
||||||
|
%TO.N,/Relay_M1.2*%
|
||||||
|
X120015000Y-59309000D03*
|
||||||
|
D18*
|
||||||
|
%TO.P,R5,2*%
|
||||||
|
%TO.N,+12V*%
|
||||||
|
X130175000Y-59309000D03*
|
||||||
|
%TD*%
|
||||||
|
D15*
|
||||||
|
%TO.P,D4,1,K*%
|
||||||
|
%TO.N,+24V*%
|
||||||
|
X185420000Y-46355000D03*
|
||||||
|
D16*
|
||||||
|
%TO.P,D4,2,A*%
|
||||||
|
%TO.N,Net-(D4-A)*%
|
||||||
|
X185420000Y-66675000D03*
|
||||||
|
%TD*%
|
||||||
|
D17*
|
||||||
|
%TO.P,R4,1*%
|
||||||
|
%TO.N,/Relay_M1.2*%
|
||||||
|
X120015000Y-62865000D03*
|
||||||
|
D18*
|
||||||
|
%TO.P,R4,2*%
|
||||||
|
%TO.N,Net-(Q3-B)*%
|
||||||
|
X130175000Y-62865000D03*
|
||||||
|
%TD*%
|
||||||
|
D10*
|
||||||
|
%TO.P,J6,1,Pin_1*%
|
||||||
|
%TO.N,GND*%
|
||||||
|
X134874000Y-35560000D03*
|
||||||
|
D11*
|
||||||
|
%TO.P,J6,2,Pin_2*%
|
||||||
|
%TO.N,+12V*%
|
||||||
|
X129794000Y-35560000D03*
|
||||||
|
%TD*%
|
||||||
|
D12*
|
||||||
|
%TO.P,TP1,1,1*%
|
||||||
|
%TO.N,Net-(D5-A)*%
|
||||||
|
X204089000Y-50927000D03*
|
||||||
|
%TD*%
|
||||||
|
%TO.P,TP3,1,1*%
|
||||||
|
%TO.N,+24V*%
|
||||||
|
X182245000Y-35560000D03*
|
||||||
|
%TD*%
|
||||||
|
D17*
|
||||||
|
%TO.P,R3,1*%
|
||||||
|
%TO.N,/Relay_M1.1*%
|
||||||
|
X119655000Y-42545000D03*
|
||||||
|
D18*
|
||||||
|
%TO.P,R3,2*%
|
||||||
|
%TO.N,+12V*%
|
||||||
|
X129815000Y-42545000D03*
|
||||||
|
%TD*%
|
||||||
|
D12*
|
||||||
|
%TO.P,TP12,1,1*%
|
||||||
|
%TO.N,Net-(D12-A)*%
|
||||||
|
X204216000Y-94234000D03*
|
||||||
|
%TD*%
|
||||||
|
D15*
|
||||||
|
%TO.P,D10,1,K*%
|
||||||
|
%TO.N,+24V*%
|
||||||
|
X185420000Y-71755000D03*
|
||||||
|
D16*
|
||||||
|
%TO.P,D10,2,A*%
|
||||||
|
%TO.N,Net-(D10-A)*%
|
||||||
|
X185420000Y-92075000D03*
|
||||||
|
%TD*%
|
||||||
|
D17*
|
||||||
|
%TO.P,R6,1*%
|
||||||
|
%TO.N,/Relay_M2.1*%
|
||||||
|
X120015000Y-75565000D03*
|
||||||
|
D18*
|
||||||
|
%TO.P,R6,2*%
|
||||||
|
%TO.N,+12V*%
|
||||||
|
X130175000Y-75565000D03*
|
||||||
|
%TD*%
|
||||||
|
D10*
|
||||||
|
%TO.P,J5,1,Pin_1*%
|
||||||
|
%TO.N,GNDPWR*%
|
||||||
|
X161290000Y-35560000D03*
|
||||||
|
D11*
|
||||||
|
%TO.P,J5,2,Pin_2*%
|
||||||
|
X156210000Y-35560000D03*
|
||||||
|
%TD*%
|
||||||
|
D17*
|
||||||
|
%TO.P,R9,1*%
|
||||||
|
%TO.N,/Relay_M2.2*%
|
||||||
|
X120015000Y-95885000D03*
|
||||||
|
D18*
|
||||||
|
%TO.P,R9,2*%
|
||||||
|
%TO.N,Net-(Q4-B)*%
|
||||||
|
X130175000Y-95885000D03*
|
||||||
|
%TD*%
|
||||||
|
D17*
|
||||||
|
%TO.P,R8,1*%
|
||||||
|
%TO.N,/Relay_M2.1*%
|
||||||
|
X120015000Y-79375000D03*
|
||||||
|
D18*
|
||||||
|
%TO.P,R8,2*%
|
||||||
|
%TO.N,Net-(Q2-B)*%
|
||||||
|
X130175000Y-79375000D03*
|
||||||
|
%TD*%
|
||||||
|
D12*
|
||||||
|
%TO.P,TP2,1,1*%
|
||||||
|
%TO.N,Net-(D4-A)*%
|
||||||
|
X204089000Y-68199000D03*
|
||||||
|
%TD*%
|
||||||
|
D19*
|
||||||
|
%TO.P,TP5,1,1*%
|
||||||
|
%TO.N,GND*%
|
||||||
|
X140208000Y-35560000D03*
|
||||||
|
%TD*%
|
||||||
|
D27*
|
||||||
|
%TO.N,Net-(D4-A)*%
|
||||||
|
X166370000Y-71755000D03*
|
||||||
|
X175590000Y-71755000D03*
|
||||||
|
%TO.N,Net-(D5-A)*%
|
||||||
|
X166370000Y-55245000D03*
|
||||||
|
X175590000Y-55245000D03*
|
||||||
|
%TO.N,Net-(D10-A)*%
|
||||||
|
X166370000Y-88265000D03*
|
||||||
|
X175590000Y-88265000D03*
|
||||||
|
%TD*%
|
||||||
|
D28*
|
||||||
|
%TO.N,Net-(D4-A)*%
|
||||||
|
X166370000Y-71755000D02*
|
||||||
|
X175590000Y-71755000D01*
|
||||||
|
%TO.N,Net-(D5-A)*%
|
||||||
|
X166370000Y-55245000D02*
|
||||||
|
X175590000Y-55245000D01*
|
||||||
|
D29*
|
||||||
|
%TO.N,GNDPWR*%
|
||||||
|
X186828327Y-63275000D02*
|
||||||
|
X191135000Y-67581673D01*
|
||||||
|
X186828327Y-59101673D02*
|
||||||
|
X186828327Y-63275000D01*
|
||||||
|
X191135000Y-54795000D02*
|
||||||
|
X186828327Y-59101673D01*
|
||||||
|
X191135000Y-41275000D02*
|
||||||
|
X191135000Y-54795000D01*
|
||||||
|
D28*
|
||||||
|
%TO.N,Net-(D10-A)*%
|
||||||
|
X166370000Y-88265000D02*
|
||||||
|
X175590000Y-88265000D01*
|
||||||
|
D29*
|
||||||
|
%TO.N,GNDPWR*%
|
||||||
|
X191135000Y-67581673D02*
|
||||||
|
X191135000Y-76835000D01*
|
||||||
|
%TD*%
|
||||||
|
M02*
|
@ -0,0 +1,19 @@
|
|||||||
|
M48
|
||||||
|
; DRILL file {KiCad 8.0.4} date 2024-09-07T08:33:15+0200
|
||||||
|
; FORMAT={-:-/ absolute / metric / decimal}
|
||||||
|
; #@! TF.CreationDate,2024-09-07T08:33:15+02:00
|
||||||
|
; #@! TF.GenerationSoftware,Kicad,Pcbnew,8.0.4
|
||||||
|
; #@! TF.FileFunction,NonPlated,1,2,NPTH
|
||||||
|
FMAT,2
|
||||||
|
METRIC
|
||||||
|
; #@! TA.AperFunction,NonPlated,NPTH,ComponentDrill
|
||||||
|
T1C5.300
|
||||||
|
%
|
||||||
|
G90
|
||||||
|
G05
|
||||||
|
T1
|
||||||
|
X113.03Y-34.29
|
||||||
|
X113.03Y-101.6
|
||||||
|
X202.565Y-34.29
|
||||||
|
X202.565Y-101.6
|
||||||
|
M30
|
@ -0,0 +1,159 @@
|
|||||||
|
M48
|
||||||
|
; DRILL file {KiCad 8.0.4} date 2024-09-07T08:33:15+0200
|
||||||
|
; FORMAT={-:-/ absolute / metric / decimal}
|
||||||
|
; #@! TF.CreationDate,2024-09-07T08:33:15+02:00
|
||||||
|
; #@! TF.GenerationSoftware,Kicad,Pcbnew,8.0.4
|
||||||
|
; #@! TF.FileFunction,Plated,1,2,PTH
|
||||||
|
FMAT,2
|
||||||
|
METRIC
|
||||||
|
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
|
||||||
|
T1C0.500
|
||||||
|
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
|
||||||
|
T2C0.800
|
||||||
|
; #@! TA.AperFunction,Plated,PTH,ViaDrill
|
||||||
|
T3C1.000
|
||||||
|
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
|
||||||
|
T4C1.000
|
||||||
|
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
|
||||||
|
T5C1.200
|
||||||
|
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
|
||||||
|
T6C1.300
|
||||||
|
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
|
||||||
|
T7C1.400
|
||||||
|
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
|
||||||
|
T8C1.500
|
||||||
|
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
|
||||||
|
T9C1.520
|
||||||
|
%
|
||||||
|
G90
|
||||||
|
G05
|
||||||
|
T1
|
||||||
|
X124.079Y-35.306
|
||||||
|
X129.794Y-101.473
|
||||||
|
X130.429Y-51.689
|
||||||
|
X130.429Y-85.09
|
||||||
|
X130.556Y-68.326
|
||||||
|
X140.208Y-35.56
|
||||||
|
X150.622Y-35.56
|
||||||
|
X182.245Y-35.56
|
||||||
|
X204.089Y-50.927
|
||||||
|
X204.089Y-68.199
|
||||||
|
X204.216Y-77.47
|
||||||
|
X204.216Y-94.234
|
||||||
|
T2
|
||||||
|
X119.655Y-42.545
|
||||||
|
X119.655Y-46.355
|
||||||
|
X120.015Y-59.309
|
||||||
|
X120.015Y-62.865
|
||||||
|
X120.015Y-75.565
|
||||||
|
X120.015Y-79.375
|
||||||
|
X120.015Y-92.075
|
||||||
|
X120.015Y-95.885
|
||||||
|
X129.815Y-42.545
|
||||||
|
X129.815Y-46.355
|
||||||
|
X130.175Y-59.309
|
||||||
|
X130.175Y-62.865
|
||||||
|
X130.175Y-75.565
|
||||||
|
X130.175Y-79.375
|
||||||
|
X130.175Y-92.075
|
||||||
|
X130.175Y-95.885
|
||||||
|
X134.98Y-43.815
|
||||||
|
X134.98Y-46.355
|
||||||
|
X134.98Y-48.895
|
||||||
|
X134.98Y-60.325
|
||||||
|
X134.98Y-62.865
|
||||||
|
X134.98Y-65.405
|
||||||
|
X134.98Y-76.835
|
||||||
|
X134.98Y-79.375
|
||||||
|
X134.98Y-81.915
|
||||||
|
X134.98Y-93.345
|
||||||
|
X134.98Y-95.885
|
||||||
|
X134.98Y-98.425
|
||||||
|
T3
|
||||||
|
X166.37Y-55.245
|
||||||
|
X166.37Y-71.755
|
||||||
|
X166.37Y-88.265
|
||||||
|
X175.59Y-55.245
|
||||||
|
X175.59Y-71.755
|
||||||
|
X175.59Y-88.265
|
||||||
|
T4
|
||||||
|
X117.475Y-65.405
|
||||||
|
X117.475Y-67.945
|
||||||
|
X117.475Y-70.485
|
||||||
|
X117.475Y-73.025
|
||||||
|
T5
|
||||||
|
X111.225Y-63.965
|
||||||
|
X111.225Y-67.465
|
||||||
|
X111.225Y-70.965
|
||||||
|
X111.225Y-74.465
|
||||||
|
T6
|
||||||
|
X146.048Y-59.81
|
||||||
|
X146.048Y-67.31
|
||||||
|
X146.048Y-92.83
|
||||||
|
X146.048Y-100.33
|
||||||
|
X146.05Y-43.3
|
||||||
|
X146.05Y-50.8
|
||||||
|
X146.05Y-76.32
|
||||||
|
X146.05Y-83.82
|
||||||
|
X161.308Y-59.81
|
||||||
|
X161.308Y-67.31
|
||||||
|
X161.308Y-92.83
|
||||||
|
X161.308Y-100.33
|
||||||
|
X161.31Y-43.3
|
||||||
|
X161.31Y-50.8
|
||||||
|
X161.31Y-76.32
|
||||||
|
X161.31Y-83.82
|
||||||
|
X166.348Y-59.81
|
||||||
|
X166.348Y-67.31
|
||||||
|
X166.348Y-92.83
|
||||||
|
X166.348Y-100.33
|
||||||
|
X166.35Y-43.3
|
||||||
|
X166.35Y-50.8
|
||||||
|
X166.35Y-76.32
|
||||||
|
X166.35Y-83.82
|
||||||
|
X171.388Y-59.81
|
||||||
|
X171.388Y-67.31
|
||||||
|
X171.388Y-92.83
|
||||||
|
X171.388Y-100.33
|
||||||
|
X171.39Y-43.3
|
||||||
|
X171.39Y-50.8
|
||||||
|
X171.39Y-76.32
|
||||||
|
X171.39Y-83.82
|
||||||
|
T7
|
||||||
|
X139.7Y-40.64
|
||||||
|
X139.7Y-53.34
|
||||||
|
X139.7Y-57.15
|
||||||
|
X139.7Y-69.85
|
||||||
|
X139.7Y-73.66
|
||||||
|
X139.7Y-86.36
|
||||||
|
X139.7Y-90.17
|
||||||
|
X139.7Y-102.87
|
||||||
|
T8
|
||||||
|
X179.705Y-41.275
|
||||||
|
X179.705Y-61.595
|
||||||
|
X179.705Y-76.835
|
||||||
|
X179.705Y-97.155
|
||||||
|
X185.42Y-46.355
|
||||||
|
X185.42Y-66.675
|
||||||
|
X185.42Y-71.755
|
||||||
|
X185.42Y-92.075
|
||||||
|
X191.135Y-41.275
|
||||||
|
X191.135Y-61.595
|
||||||
|
X191.135Y-76.835
|
||||||
|
X191.135Y-97.155
|
||||||
|
X196.85Y-46.355
|
||||||
|
X196.85Y-66.675
|
||||||
|
X196.85Y-71.755
|
||||||
|
X196.85Y-92.075
|
||||||
|
T9
|
||||||
|
X129.794Y-35.56
|
||||||
|
X134.874Y-35.56
|
||||||
|
X156.21Y-35.56
|
||||||
|
X161.29Y-35.56
|
||||||
|
X171.45Y-35.56
|
||||||
|
X176.53Y-35.56
|
||||||
|
X203.835Y-57.15
|
||||||
|
X203.835Y-62.23
|
||||||
|
X203.835Y-83.185
|
||||||
|
X203.835Y-88.265
|
||||||
|
M30
|
@ -0,0 +1,97 @@
|
|||||||
|
{
|
||||||
|
"Header": {
|
||||||
|
"GenerationSoftware": {
|
||||||
|
"Vendor": "KiCad",
|
||||||
|
"Application": "Pcbnew",
|
||||||
|
"Version": "8.0.4"
|
||||||
|
},
|
||||||
|
"CreationDate": "2024-09-07T09:02:32+02:00"
|
||||||
|
},
|
||||||
|
"GeneralSpecs": {
|
||||||
|
"ProjectId": {
|
||||||
|
"Name": "chairAdjust-relayBoard",
|
||||||
|
"GUID": "63686169-7241-4646-9a75-73742d72656c",
|
||||||
|
"Revision": "rev?"
|
||||||
|
},
|
||||||
|
"Size": {
|
||||||
|
"X": 101.015,
|
||||||
|
"Y": 78.79
|
||||||
|
},
|
||||||
|
"LayerNumber": 2,
|
||||||
|
"BoardThickness": 1.6,
|
||||||
|
"Finish": "None"
|
||||||
|
},
|
||||||
|
"DesignRules": [
|
||||||
|
{
|
||||||
|
"Layers": "Outer",
|
||||||
|
"PadToPad": 0.2,
|
||||||
|
"PadToTrack": 0.2,
|
||||||
|
"TrackToTrack": 0.2,
|
||||||
|
"MinLineWidth": 1.0,
|
||||||
|
"TrackToRegion": 0.8,
|
||||||
|
"RegionToRegion": 0.8
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"FilesAttributes": [
|
||||||
|
{
|
||||||
|
"Path": "chairAdjust-relayBoard-F_Cu.gbr",
|
||||||
|
"FileFunction": "Copper,L1,Top",
|
||||||
|
"FilePolarity": "Positive"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"Path": "chairAdjust-relayBoard-B_Cu.gbr",
|
||||||
|
"FileFunction": "Copper,L2,Bot",
|
||||||
|
"FilePolarity": "Positive"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"Path": "chairAdjust-relayBoard-Edge_Cuts.gbr",
|
||||||
|
"FileFunction": "Profile",
|
||||||
|
"FilePolarity": "Positive"
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"MaterialStackup": [
|
||||||
|
{
|
||||||
|
"Type": "Legend",
|
||||||
|
"Name": "Top Silk Screen"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"Type": "SolderPaste",
|
||||||
|
"Name": "Top Solder Paste"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"Type": "SolderMask",
|
||||||
|
"Thickness": 0.01,
|
||||||
|
"Name": "Top Solder Mask"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"Type": "Copper",
|
||||||
|
"Thickness": 0.035,
|
||||||
|
"Name": "F.Cu"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"Type": "Dielectric",
|
||||||
|
"Thickness": 1.51,
|
||||||
|
"Material": "FR4",
|
||||||
|
"Name": "F.Cu/B.Cu",
|
||||||
|
"Notes": "Type: dielectric layer 1 (from F.Cu to B.Cu)"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"Type": "Copper",
|
||||||
|
"Thickness": 0.035,
|
||||||
|
"Name": "B.Cu"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"Type": "SolderMask",
|
||||||
|
"Thickness": 0.01,
|
||||||
|
"Name": "Bottom Solder Mask"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"Type": "SolderPaste",
|
||||||
|
"Name": "Bottom Solder Paste"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"Type": "Legend",
|
||||||
|
"Name": "Bottom Silk Screen"
|
||||||
|
}
|
||||||
|
]
|
||||||
|
}
|
27989
hardware/chairAdjust-relayBoard/export/layout-no-zones.svg
Normal file
After Width: | Height: | Size: 662 KiB |
BIN
hardware/chairAdjust-relayBoard/export/layout.jpg
Normal file
After Width: | Height: | Size: 328 KiB |
33693
hardware/chairAdjust-relayBoard/export/layout.svg
Normal file
After Width: | Height: | Size: 750 KiB |
BIN
hardware/chairAdjust-relayBoard/export/schematic.pdf
Normal file
41451
hardware/chairAdjust-relayBoard/export/schematic.svg
Normal file
After Width: | Height: | Size: 930 KiB |
173881
hardware/chairAdjust-relayBoard/fp-info-cache
Normal file
82
hardware/chairAdjust-relayBoard/pcb2gcode/162x102_planfraesen.din
Executable file
@ -0,0 +1,82 @@
|
|||||||
|
%
|
||||||
|
(Projekt 162x102_planfraesen)
|
||||||
|
(Erstellt mit Estlcam 2.5D Version 7 Build 7,622)
|
||||||
|
(Fraesrichtung: Gegenlauf)
|
||||||
|
(Nullpunkt: Auf Teileoberseite)
|
||||||
|
(Maximale Fraestiefe: 0,70mm)
|
||||||
|
(Verwendete Werkzeuge:)
|
||||||
|
(Fraeser 6mm)
|
||||||
|
|
||||||
|
G90
|
||||||
|
T10 M06 S20000
|
||||||
|
M03
|
||||||
|
|
||||||
|
G00 Z-5.0000
|
||||||
|
|
||||||
|
(Nr. 1 Ausschnitt 2)
|
||||||
|
G00 X3.6000 Y3.7500
|
||||||
|
G00 Z-0.5000
|
||||||
|
G01 Z0.7000 F5.000 S20000
|
||||||
|
G01 X158.4000 F9.000
|
||||||
|
G01 Y8.2500
|
||||||
|
G01 X3.6000
|
||||||
|
G01 Y12.7500
|
||||||
|
G01 X158.4000
|
||||||
|
G01 Y17.2500
|
||||||
|
G01 X3.6000
|
||||||
|
G01 Y21.7500
|
||||||
|
G01 X158.4000
|
||||||
|
G01 Y26.2500
|
||||||
|
G01 X3.6000
|
||||||
|
G01 Y30.7500
|
||||||
|
G01 X158.4000
|
||||||
|
G01 Y35.2500
|
||||||
|
G01 X3.6000
|
||||||
|
G01 Y39.7500
|
||||||
|
G01 X158.4000
|
||||||
|
G01 Y44.2500
|
||||||
|
G01 X3.6000
|
||||||
|
G01 Y48.7500
|
||||||
|
G01 X158.4000
|
||||||
|
G01 Y53.2500
|
||||||
|
G01 X3.6000
|
||||||
|
G01 Y57.7500
|
||||||
|
G01 X158.4000
|
||||||
|
G01 Y62.2500
|
||||||
|
G01 X3.6000
|
||||||
|
G01 Y66.7500
|
||||||
|
G01 X158.4000
|
||||||
|
G01 Y71.2500
|
||||||
|
G01 X3.6000
|
||||||
|
G01 Y75.7500
|
||||||
|
G01 X158.4000
|
||||||
|
G01 Y80.2500
|
||||||
|
G01 X3.6000
|
||||||
|
G01 Y84.7500
|
||||||
|
G01 X158.4000
|
||||||
|
G01 Y89.2500
|
||||||
|
G01 X3.6000
|
||||||
|
G01 Y93.7500
|
||||||
|
G01 X158.4000
|
||||||
|
G01 Y98.2500
|
||||||
|
G01 X3.6000
|
||||||
|
G00 Z-5.0000
|
||||||
|
G00 X2.1213 Y2.1213
|
||||||
|
G00 Z-0.5000
|
||||||
|
G01 Z0.7000 F5.000
|
||||||
|
G01 X3.0000 Y3.0000 F9.000
|
||||||
|
G01 Y99.0000
|
||||||
|
G01 X2.1213 Y99.8787
|
||||||
|
G01 X3.0000 Y99.0000
|
||||||
|
G01 X159.0000
|
||||||
|
G01 X159.8787 Y99.8787
|
||||||
|
G01 X159.0000 Y99.0000
|
||||||
|
G01 Y3.0000
|
||||||
|
G01 X159.8787 Y2.1213
|
||||||
|
G01 X159.0000 Y3.0000
|
||||||
|
G01 X3.0000
|
||||||
|
G01 X2.1213 Y2.1213
|
||||||
|
G00 Z-5.0000
|
||||||
|
|
||||||
|
M05
|
||||||
|
M30
|
83
hardware/chairAdjust-relayBoard/pcb2gcode/millproject
Normal file
@ -0,0 +1,83 @@
|
|||||||
|
# === USAGE ===
|
||||||
|
# simply run pcb2gcode in terminal while being in this folder.
|
||||||
|
# pcb2gcode will use "millproject" in current folder for parameters by default
|
||||||
|
#
|
||||||
|
# === Notes ===
|
||||||
|
# web based gcode viewer:
|
||||||
|
# https://ncviewer.com/
|
||||||
|
|
||||||
|
|
||||||
|
# === CONFIG ===
|
||||||
|
# Configuration file generated by pcb2gcodeGUI version 0.1 on Wed Apr 6 15:40:16 2022
|
||||||
|
# stopped using gui and customized parameters manually since then...
|
||||||
|
back=../export/chairAdjust-relayBoard-B_Cu.gbr
|
||||||
|
front=../export/chairAdjust-relayBoard-F_Cu.gbr
|
||||||
|
outline=../export/chairAdjust-relayBoard-Edge_Cuts.gbr
|
||||||
|
#note: running for each drill file separately and merging the gcode manually (4 mounting holes are in a separate gerber file)
|
||||||
|
drill=../export/chairAdjust-relayBoard-PTH.drl
|
||||||
|
#drill=../export/chairAdjust-relayBoard-NPTH.drl
|
||||||
|
|
||||||
|
output-dir=./out
|
||||||
|
|
||||||
|
# Common options
|
||||||
|
metric=true
|
||||||
|
metricoutput=true
|
||||||
|
mirror-axis=0.0000
|
||||||
|
mirror-yaxis=false
|
||||||
|
nog64=false
|
||||||
|
|
||||||
|
#set optimized to default value, because when it was set to 0 (disable) it caused crash (runs till ram full) for some reason, since adding text to center of pcb ==> set to default
|
||||||
|
optimise=0.00000254 #default
|
||||||
|
backtrack=0 #if default/undefined caused unwanted moves in copper without retracting, especially at letters (seen in gcode viewer) - thus disabled this feature
|
||||||
|
tile-x=1
|
||||||
|
tile-y=1
|
||||||
|
tolerance=0.0500
|
||||||
|
zchange=30.0000
|
||||||
|
zchange-absolute=false
|
||||||
|
zero-start=true
|
||||||
|
zsafe=3.5000 #3mm to be able to cross mounting screws
|
||||||
|
|
||||||
|
# Mill options
|
||||||
|
extra-passes=0
|
||||||
|
mill-feed=400 #default 600mm/min
|
||||||
|
mill-speed=20000
|
||||||
|
offset=0.400 #intentional bigger offset than necessary, using 0.4 there were almost no small strips beeing left over between insolation lines.
|
||||||
|
voronoi=false
|
||||||
|
zwork=-0.2000 #usin 60degree cutter resulted in ~0.42mm line
|
||||||
|
|
||||||
|
# Drill options
|
||||||
|
drill-feed=200
|
||||||
|
drill-side=back
|
||||||
|
drill-speed=20000
|
||||||
|
milldrill=false
|
||||||
|
#@#milldrill-diameter=3.0000
|
||||||
|
nog81=false
|
||||||
|
nog91-1=true
|
||||||
|
onedrill=false
|
||||||
|
zdrill=-1.7500
|
||||||
|
drills-available=0.8,1,1.5
|
||||||
|
|
||||||
|
# Outline options
|
||||||
|
bridges=1.0000
|
||||||
|
bridgesnum=2
|
||||||
|
cut-feed=200
|
||||||
|
cut-infeed=0.5000
|
||||||
|
cut-side=back
|
||||||
|
cut-speed=10000
|
||||||
|
cut-vertfeed=60
|
||||||
|
cutter-diameter=0.0000 #not really cutting, just using line as reference for zeroing
|
||||||
|
fill-outline=true
|
||||||
|
zbridges=-0.6000
|
||||||
|
zcut=-2.7000
|
||||||
|
|
||||||
|
# Autoleveller options
|
||||||
|
al-back=false
|
||||||
|
al-front=false
|
||||||
|
al-probecode=G31
|
||||||
|
al-probefeed=100
|
||||||
|
al-probevar=2002
|
||||||
|
al-setzzero=G92 Z0
|
||||||
|
al-x=15.0000
|
||||||
|
al-y=15.0000
|
||||||
|
software=custom
|
||||||
|
|
86
hardware/chairAdjust-relayBoard/pcb2gcode/millproject_text
Normal file
@ -0,0 +1,86 @@
|
|||||||
|
# === USAGE ===
|
||||||
|
# simply run pcb2gcode in terminal while being in this folder.
|
||||||
|
# pcb2gcode will use "millproject" in current folder for parameters by default
|
||||||
|
#
|
||||||
|
# === Notes ===
|
||||||
|
# web based gcode viewer:
|
||||||
|
# https://ncviewer.com/
|
||||||
|
|
||||||
|
|
||||||
|
# === CONFIG ===
|
||||||
|
# Configuration file generated by pcb2gcodeGUI version 0.1 on Wed Apr 6 15:40:16 2022
|
||||||
|
# stopped using gui and customized parameters manually since then...
|
||||||
|
|
||||||
|
#text layer
|
||||||
|
back=./in/pcb-ihc_kicad-User_1.gbr
|
||||||
|
#add other layers (ignore output) otherwise alignment/origin wont match
|
||||||
|
front=./in/pcb-ihc_kicad-F_Cu.gbr
|
||||||
|
outline=./in/pcb-ihc_kicad-Edge_Cuts.gbr
|
||||||
|
drill=./in/pcb-ihc_kicad-PTH.drl
|
||||||
|
|
||||||
|
|
||||||
|
output-dir=./out/text
|
||||||
|
|
||||||
|
# Common options
|
||||||
|
metric=true
|
||||||
|
metricoutput=true
|
||||||
|
mirror-axis=0.0000
|
||||||
|
mirror-yaxis=false
|
||||||
|
nog64=false
|
||||||
|
|
||||||
|
#set optimized to default value, because when it was set to 0 (disable) it caused crash (runs till ram full) for some reason, since adding text to center of pcb ==> set to default
|
||||||
|
optimise=0.00000254 #default
|
||||||
|
backtrack=0 #if default/undefined caused unwanted moves in copper without retracting, especially at letters (seen in gcode viewer) - thus disabled this feature
|
||||||
|
tile-x=1
|
||||||
|
tile-y=1
|
||||||
|
tolerance=0.0500
|
||||||
|
zchange=30.0000
|
||||||
|
zchange-absolute=false
|
||||||
|
zero-start=true
|
||||||
|
zsafe=2.0000
|
||||||
|
|
||||||
|
# Mill options
|
||||||
|
extra-passes=0
|
||||||
|
mill-feed=500 #default 600mm/min
|
||||||
|
mill-speed=20000
|
||||||
|
#####################
|
||||||
|
offset=-0.140 #text line width is 0.3 so offset -0.14 is minimun otherwise crash
|
||||||
|
zwork=-0.2000
|
||||||
|
#####################
|
||||||
|
voronoi=false
|
||||||
|
|
||||||
|
# Drill options
|
||||||
|
drill-feed=200
|
||||||
|
drill-side=back
|
||||||
|
drill-speed=20000
|
||||||
|
milldrill=false
|
||||||
|
#@#milldrill-diameter=3.0000
|
||||||
|
nog81=false
|
||||||
|
nog91-1=true
|
||||||
|
onedrill=false
|
||||||
|
zdrill=-1.7500
|
||||||
|
|
||||||
|
# Outline options
|
||||||
|
bridges=1.0000
|
||||||
|
bridgesnum=2
|
||||||
|
cut-feed=200
|
||||||
|
cut-infeed=0.5000
|
||||||
|
cut-side=back
|
||||||
|
cut-speed=10000
|
||||||
|
cut-vertfeed=60
|
||||||
|
cutter-diameter=0.0000
|
||||||
|
fill-outline=true
|
||||||
|
zbridges=-0.6000
|
||||||
|
zcut=-2.7000
|
||||||
|
|
||||||
|
# Autoleveller options
|
||||||
|
al-back=false
|
||||||
|
al-front=false
|
||||||
|
al-probecode=G31
|
||||||
|
al-probefeed=100
|
||||||
|
al-probevar=2002
|
||||||
|
al-setzzero=G92 Z0
|
||||||
|
al-x=15.0000
|
||||||
|
al-y=15.0000
|
||||||
|
software=custom
|
||||||
|
|
9657
hardware/chairAdjust-relayBoard/pcb2gcode/out/back.ngc
Normal file
177
hardware/chairAdjust-relayBoard/pcb2gcode/out/drill.ngc
Normal file
@ -0,0 +1,177 @@
|
|||||||
|
( pcb2gcode 2.5.0 )
|
||||||
|
( Software-independent Gcode )
|
||||||
|
|
||||||
|
( This file uses 3 drill bit sizes. )
|
||||||
|
( Bit sizes: [0.8mm] [1mm] [1.5mm] )
|
||||||
|
|
||||||
|
G94 (Millimeters per minute feed rate.)
|
||||||
|
G21 (Units == Millimeters.)
|
||||||
|
G90 (Absolute coordinates.)
|
||||||
|
G00 S20000 (RPM spindle speed.)
|
||||||
|
|
||||||
|
G00 Z30.00000 (Retract)
|
||||||
|
T1
|
||||||
|
M5 (Spindle stop.)
|
||||||
|
G04 P1.00000
|
||||||
|
(MSG, Change tool bit to drill size 0.8mm)
|
||||||
|
M6 (Tool change.)
|
||||||
|
M0 (Temporary machine stop.)
|
||||||
|
M3 (Spindle on clockwise.)
|
||||||
|
G0 Z3.50000
|
||||||
|
G04 P1.00000
|
||||||
|
|
||||||
|
G81 R3.50000 Z-1.75000 F200.00000 X-96.92600 Y29.87000
|
||||||
|
X-96.79900 Y39.14100
|
||||||
|
X-96.79900 Y56.41300
|
||||||
|
X-74.95500 Y71.78000
|
||||||
|
X-43.33200 Y71.78000
|
||||||
|
X-32.91800 Y71.78000
|
||||||
|
X-27.69000 Y63.52500
|
||||||
|
X-27.69000 Y60.98500
|
||||||
|
X-27.69000 Y58.44500
|
||||||
|
X-23.13900 Y55.65100
|
||||||
|
X-22.52500 Y60.98500
|
||||||
|
X-22.52500 Y64.79500
|
||||||
|
X-16.78900 Y72.03400
|
||||||
|
X-12.36500 Y64.79500
|
||||||
|
X-12.36500 Y60.98500
|
||||||
|
X-12.72500 Y48.03100
|
||||||
|
X-12.72500 Y44.47500
|
||||||
|
X-12.72500 Y31.77500
|
||||||
|
X-12.72500 Y27.96500
|
||||||
|
X-12.72500 Y15.26500
|
||||||
|
X-12.72500 Y11.45500
|
||||||
|
X-22.50400 Y5.86700
|
||||||
|
X-27.69000 Y8.91500
|
||||||
|
X-27.69000 Y11.45500
|
||||||
|
X-27.69000 Y13.99500
|
||||||
|
X-22.88500 Y11.45500
|
||||||
|
X-22.88500 Y15.26500
|
||||||
|
X-23.13900 Y22.25000
|
||||||
|
X-27.69000 Y25.42500
|
||||||
|
X-27.69000 Y27.96500
|
||||||
|
X-27.69000 Y30.50500
|
||||||
|
X-22.88500 Y27.96500
|
||||||
|
X-22.88500 Y31.77500
|
||||||
|
X-23.26600 Y39.01400
|
||||||
|
X-22.88500 Y44.47500
|
||||||
|
X-22.88500 Y48.03100
|
||||||
|
X-27.69000 Y47.01500
|
||||||
|
X-27.69000 Y44.47500
|
||||||
|
X-27.69000 Y41.93500
|
||||||
|
X-96.92600 Y13.10600
|
||||||
|
G80
|
||||||
|
|
||||||
|
G00 Z30.00000 (Retract)
|
||||||
|
T3
|
||||||
|
M5 (Spindle stop.)
|
||||||
|
G04 P1.00000
|
||||||
|
(MSG, Change tool bit to drill size 1mm)
|
||||||
|
M6 (Tool change.)
|
||||||
|
M0 (Temporary machine stop.)
|
||||||
|
M3 (Spindle on clockwise.)
|
||||||
|
G0 Z3.50000
|
||||||
|
G04 P1.00000
|
||||||
|
|
||||||
|
G81 R3.50000 Z-1.75000 F200.00000 X-68.30000 Y52.09500
|
||||||
|
X-59.08000 Y52.09500
|
||||||
|
X-59.08000 Y35.58500
|
||||||
|
X-68.30000 Y35.58500
|
||||||
|
X-68.30000 Y19.07500
|
||||||
|
X-59.08000 Y19.07500
|
||||||
|
X-10.18500 Y41.93500
|
||||||
|
X-10.18500 Y39.39500
|
||||||
|
X-10.18500 Y36.85500
|
||||||
|
X-10.18500 Y34.31500
|
||||||
|
X-3.93500 Y32.87500
|
||||||
|
X-3.93500 Y36.37500
|
||||||
|
X-3.93500 Y39.87500
|
||||||
|
X-3.93500 Y43.37500
|
||||||
|
G80
|
||||||
|
|
||||||
|
G00 Z30.00000 (Retract)
|
||||||
|
T6
|
||||||
|
M5 (Spindle stop.)
|
||||||
|
G04 P1.00000
|
||||||
|
(MSG, Change tool bit to drill size 1.5mm)
|
||||||
|
M6 (Tool change.)
|
||||||
|
M0 (Temporary machine stop.)
|
||||||
|
M3 (Spindle on clockwise.)
|
||||||
|
G0 Z3.50000
|
||||||
|
G04 P1.00000
|
||||||
|
|
||||||
|
G81 R3.50000 Z-1.75000 F200.00000 X-89.56000 Y60.98500
|
||||||
|
X-83.84500 Y66.06500
|
||||||
|
X-96.54500 Y50.19000
|
||||||
|
X-96.54500 Y45.11000
|
||||||
|
X-89.56000 Y40.66500
|
||||||
|
X-89.56000 Y35.58500
|
||||||
|
X-96.54500 Y24.15500
|
||||||
|
X-96.54500 Y19.07500
|
||||||
|
X-89.56000 Y15.26500
|
||||||
|
X-83.84500 Y10.18500
|
||||||
|
X-78.13000 Y15.26500
|
||||||
|
X-83.84500 Y30.50500
|
||||||
|
X-78.13000 Y35.58500
|
||||||
|
X-72.41500 Y30.50500
|
||||||
|
X-64.10000 Y31.02000
|
||||||
|
X-64.10000 Y23.52000
|
||||||
|
X-59.06000 Y23.52000
|
||||||
|
X-54.02000 Y23.52000
|
||||||
|
X-54.02000 Y31.02000
|
||||||
|
X-59.06000 Y31.02000
|
||||||
|
X-64.09800 Y40.03000
|
||||||
|
X-59.05800 Y40.03000
|
||||||
|
X-54.01800 Y40.03000
|
||||||
|
X-54.01800 Y47.53000
|
||||||
|
X-59.05800 Y47.53000
|
||||||
|
X-64.09800 Y47.53000
|
||||||
|
X-72.41500 Y45.74500
|
||||||
|
X-78.13000 Y40.66500
|
||||||
|
X-83.84500 Y45.74500
|
||||||
|
X-78.13000 Y60.98500
|
||||||
|
X-72.41500 Y66.06500
|
||||||
|
X-69.24000 Y71.78000
|
||||||
|
X-64.16000 Y71.78000
|
||||||
|
X-64.10000 Y64.04000
|
||||||
|
X-64.10000 Y56.54000
|
||||||
|
X-59.06000 Y56.54000
|
||||||
|
X-54.02000 Y56.54000
|
||||||
|
X-54.02000 Y64.04000
|
||||||
|
X-59.06000 Y64.04000
|
||||||
|
X-54.00000 Y71.78000
|
||||||
|
X-48.92000 Y71.78000
|
||||||
|
X-38.76000 Y64.04000
|
||||||
|
X-32.41000 Y66.70000
|
||||||
|
X-27.58400 Y71.78000
|
||||||
|
X-22.50400 Y71.78000
|
||||||
|
X-38.76000 Y56.54000
|
||||||
|
X-32.41000 Y54.00000
|
||||||
|
X-32.41000 Y50.19000
|
||||||
|
X-38.75800 Y47.53000
|
||||||
|
X-38.75800 Y40.03000
|
||||||
|
X-32.41000 Y37.49000
|
||||||
|
X-32.41000 Y33.68000
|
||||||
|
X-38.76000 Y31.02000
|
||||||
|
X-38.76000 Y23.52000
|
||||||
|
X-32.41000 Y20.98000
|
||||||
|
X-32.41000 Y17.17000
|
||||||
|
X-38.75800 Y14.51000
|
||||||
|
X-32.41000 Y4.47000
|
||||||
|
X-38.75800 Y7.01000
|
||||||
|
X-54.01800 Y14.51000
|
||||||
|
X-59.05800 Y14.51000
|
||||||
|
X-64.09800 Y14.51000
|
||||||
|
X-72.41500 Y10.18500
|
||||||
|
X-64.09800 Y7.01000
|
||||||
|
X-59.05800 Y7.01000
|
||||||
|
X-54.01800 Y7.01000
|
||||||
|
G80
|
||||||
|
|
||||||
|
G00 Z30.000 ( All done -- retract )
|
||||||
|
|
||||||
|
M5 (Spindle off.)
|
||||||
|
G04 P1.000000
|
||||||
|
M9 (Coolant off.)
|
||||||
|
M2 (Program end.)
|
||||||
|
|
7725
hardware/chairAdjust-relayBoard/pcb2gcode/out/front.ngc
Normal file
127
hardware/chairAdjust-relayBoard/pcb2gcode/out/original_drill.svg
Normal file
@ -0,0 +1,127 @@
|
|||||||
|
<?xml version="1.0" standalone="no"?>
|
||||||
|
<!DOCTYPE svg PUBLIC "-//W3C//DTD SVG 1.1//EN"
|
||||||
|
"http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd">
|
||||||
|
<svg width="381.789" height="297.789" viewBox="0 0 7953.94 6203.94" version="1.1"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:xlink="http://www.w3.org/1999/xlink">
|
||||||
|
<circle cx="7631.97" cy="3851.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="7621.97" cy="3121.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="7621.97" cy="1761.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="5901.97" cy="551.969" r="31.4961" style=""/>
|
||||||
|
<circle cx="3411.97" cy="551.969" r="31.4961" style=""/>
|
||||||
|
<circle cx="2591.97" cy="551.969" r="31.4961" style=""/>
|
||||||
|
<circle cx="2180.31" cy="1201.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="2180.31" cy="1401.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="2180.31" cy="1601.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1821.97" cy="1821.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1773.62" cy="1401.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1773.62" cy="1101.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1321.97" cy="531.969" r="31.4961" style=""/>
|
||||||
|
<circle cx="973.622" cy="1101.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="973.622" cy="1401.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1001.97" cy="2421.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1001.97" cy="2701.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1001.97" cy="3701.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1001.97" cy="4001.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1001.97" cy="5001.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1001.97" cy="5301.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1771.97" cy="5741.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="2180.31" cy="5501.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="2180.31" cy="5301.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="2180.31" cy="5101.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1801.97" cy="5301.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1801.97" cy="5001.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1821.97" cy="4451.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="2180.31" cy="4201.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="2180.31" cy="4001.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="2180.31" cy="3801.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1801.97" cy="4001.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1801.97" cy="3701.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1831.97" cy="3131.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1801.97" cy="2701.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="1801.97" cy="2421.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="2180.31" cy="2501.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="2180.31" cy="2701.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="2180.31" cy="2901.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="7631.97" cy="5171.97" r="31.4961" style=""/>
|
||||||
|
<circle cx="5377.95" cy="2101.97" r="39.3701" style=""/>
|
||||||
|
<circle cx="4651.97" cy="2101.97" r="39.3701" style=""/>
|
||||||
|
<circle cx="4651.97" cy="3401.97" r="39.3701" style=""/>
|
||||||
|
<circle cx="5377.95" cy="3401.97" r="39.3701" style=""/>
|
||||||
|
<circle cx="5377.95" cy="4701.97" r="39.3701" style=""/>
|
||||||
|
<circle cx="4651.97" cy="4701.97" r="39.3701" style=""/>
|
||||||
|
<circle cx="801.969" cy="2901.97" r="39.3701" style=""/>
|
||||||
|
<circle cx="801.969" cy="3101.97" r="39.3701" style=""/>
|
||||||
|
<circle cx="801.969" cy="3301.97" r="39.3701" style=""/>
|
||||||
|
<circle cx="801.969" cy="3501.97" r="39.3701" style=""/>
|
||||||
|
<circle cx="309.843" cy="3615.35" r="39.3701" style=""/>
|
||||||
|
<circle cx="309.843" cy="3339.76" r="39.3701" style=""/>
|
||||||
|
<circle cx="309.843" cy="3064.17" r="39.3701" style=""/>
|
||||||
|
<circle cx="309.843" cy="2788.58" r="39.3701" style=""/>
|
||||||
|
<circle cx="7051.97" cy="1401.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="6601.97" cy="1001.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="7601.97" cy="2251.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="7601.97" cy="2651.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="7051.97" cy="3001.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="7051.97" cy="3401.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="7601.97" cy="4301.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="7601.97" cy="4701.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="7051.97" cy="5001.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="6601.97" cy="5401.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="6151.97" cy="5001.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="6601.97" cy="3801.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="6151.97" cy="3401.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="5701.97" cy="3801.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="5047.24" cy="3761.42" r="59.0551" style=""/>
|
||||||
|
<circle cx="5047.24" cy="4351.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="4650.39" cy="4351.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="4253.54" cy="4351.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="4253.54" cy="3761.42" r="59.0551" style=""/>
|
||||||
|
<circle cx="4650.39" cy="3761.42" r="59.0551" style=""/>
|
||||||
|
<circle cx="5047.09" cy="3051.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="4650.24" cy="3051.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="4253.39" cy="3051.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="4253.39" cy="2461.42" r="59.0551" style=""/>
|
||||||
|
<circle cx="4650.24" cy="2461.42" r="59.0551" style=""/>
|
||||||
|
<circle cx="5047.09" cy="2461.42" r="59.0551" style=""/>
|
||||||
|
<circle cx="5701.97" cy="2601.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="6151.97" cy="3001.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="6601.97" cy="2601.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="6151.97" cy="1401.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="5701.97" cy="1001.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="5451.97" cy="551.969" r="59.0551" style=""/>
|
||||||
|
<circle cx="5051.97" cy="551.969" r="59.0551" style=""/>
|
||||||
|
<circle cx="5047.24" cy="1161.42" r="59.0551" style=""/>
|
||||||
|
<circle cx="5047.24" cy="1751.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="4650.39" cy="1751.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="4253.54" cy="1751.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="4253.54" cy="1161.42" r="59.0551" style=""/>
|
||||||
|
<circle cx="4650.39" cy="1161.42" r="59.0551" style=""/>
|
||||||
|
<circle cx="4251.97" cy="551.969" r="59.0551" style=""/>
|
||||||
|
<circle cx="3851.97" cy="551.969" r="59.0551" style=""/>
|
||||||
|
<circle cx="3051.97" cy="1161.42" r="59.0551" style=""/>
|
||||||
|
<circle cx="2551.97" cy="951.969" r="59.0551" style=""/>
|
||||||
|
<circle cx="2171.97" cy="551.969" r="59.0551" style=""/>
|
||||||
|
<circle cx="1771.97" cy="551.969" r="59.0551" style=""/>
|
||||||
|
<circle cx="3051.97" cy="1751.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="2551.97" cy="1951.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="2551.97" cy="2251.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="3051.81" cy="2461.42" r="59.0551" style=""/>
|
||||||
|
<circle cx="3051.81" cy="3051.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="2551.97" cy="3251.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="2551.97" cy="3551.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="3051.97" cy="3761.42" r="59.0551" style=""/>
|
||||||
|
<circle cx="3051.97" cy="4351.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="2551.97" cy="4551.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="2551.97" cy="4851.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="3051.81" cy="5061.42" r="59.0551" style=""/>
|
||||||
|
<circle cx="2551.97" cy="5851.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="3051.81" cy="5651.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="4253.39" cy="5061.42" r="59.0551" style=""/>
|
||||||
|
<circle cx="4650.24" cy="5061.42" r="59.0551" style=""/>
|
||||||
|
<circle cx="5047.09" cy="5061.42" r="59.0551" style=""/>
|
||||||
|
<circle cx="5701.97" cy="5401.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="5047.09" cy="5651.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="4650.24" cy="5651.97" r="59.0551" style=""/>
|
||||||
|
<circle cx="4253.39" cy="5651.97" r="59.0551" style=""/>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 7.0 KiB |
130
hardware/chairAdjust-relayBoard/pcb2gcode/out/outline.ngc
Normal file
@ -0,0 +1,130 @@
|
|||||||
|
( pcb2gcode 2.5.0 )
|
||||||
|
( Software-independent Gcode )
|
||||||
|
|
||||||
|
G94 ( Millimeters per minute feed rate. )
|
||||||
|
G21 ( Units == Millimeters. )
|
||||||
|
|
||||||
|
G90 ( Absolute coordinates. )
|
||||||
|
G00 S10000 ( RPM spindle speed. )
|
||||||
|
G64 P0.05000 ( set maximum deviation from commanded toolpath )
|
||||||
|
G01 F200.00000 ( Feedrate. )
|
||||||
|
|
||||||
|
|
||||||
|
G00 Z30.00000 (Retract to tool change height)
|
||||||
|
T1
|
||||||
|
M5 (Spindle stop.)
|
||||||
|
G04 P1.00000 (Wait for spindle to stop)
|
||||||
|
(MSG, Change tool bit to cutter diameter 0.00000mm)
|
||||||
|
M6 (Tool change.)
|
||||||
|
M0 (Temporary machine stop.)
|
||||||
|
M3 ( Spindle on clockwise. )
|
||||||
|
G04 P1.00000 (Wait for spindle to get up to speed)
|
||||||
|
G04 P0 ( dwell for no time -- G64 should not smooth over this point )
|
||||||
|
G00 Z3.50000 ( retract )
|
||||||
|
|
||||||
|
G00 X-0.02500 Y0.02500 ( rapid move to begin. )
|
||||||
|
G01 Z-0.45000 F60.00000 ( plunge. )
|
||||||
|
G04 P0 ( dwell for no time -- G64 should not smooth over this point )
|
||||||
|
G01 F200.00000
|
||||||
|
G01 X-0.02500 Y38.89500
|
||||||
|
G01 X-0.02500 Y39.89500
|
||||||
|
G01 X-0.02500 Y78.76500
|
||||||
|
G01 X-100.98997 Y78.76500
|
||||||
|
G01 X-100.98997 Y39.89500
|
||||||
|
G01 X-100.98997 Y38.89500
|
||||||
|
G01 X-100.98997 Y0.02500
|
||||||
|
G01 X-0.02500 Y0.02500
|
||||||
|
G01 Z-0.90000 F60.00000 ( plunge. )
|
||||||
|
G04 P0 ( dwell for no time -- G64 should not smooth over this point )
|
||||||
|
G01 F200.00000
|
||||||
|
G01 X-0.02500 Y38.89500
|
||||||
|
G00 Z-0.60000
|
||||||
|
G01 X-0.02500 Y39.89500
|
||||||
|
G01 Z-0.90000 F60.00000
|
||||||
|
G01 F200.00000
|
||||||
|
G01 X-0.02500 Y78.76500
|
||||||
|
G01 X-100.98997 Y78.76500
|
||||||
|
G01 X-100.98997 Y39.89500
|
||||||
|
G00 Z-0.60000
|
||||||
|
G01 X-100.98997 Y38.89500
|
||||||
|
G01 Z-0.90000 F60.00000
|
||||||
|
G01 F200.00000
|
||||||
|
G01 X-100.98997 Y0.02500
|
||||||
|
G01 X-0.02500 Y0.02500
|
||||||
|
G01 Z-1.35000 F60.00000 ( plunge. )
|
||||||
|
G04 P0 ( dwell for no time -- G64 should not smooth over this point )
|
||||||
|
G01 F200.00000
|
||||||
|
G01 X-0.02500 Y38.89500
|
||||||
|
G00 Z-0.60000
|
||||||
|
G01 X-0.02500 Y39.89500
|
||||||
|
G01 Z-1.35000 F60.00000
|
||||||
|
G01 F200.00000
|
||||||
|
G01 X-0.02500 Y78.76500
|
||||||
|
G01 X-100.98997 Y78.76500
|
||||||
|
G01 X-100.98997 Y39.89500
|
||||||
|
G00 Z-0.60000
|
||||||
|
G01 X-100.98997 Y38.89500
|
||||||
|
G01 Z-1.35000 F60.00000
|
||||||
|
G01 F200.00000
|
||||||
|
G01 X-100.98997 Y0.02500
|
||||||
|
G01 X-0.02500 Y0.02500
|
||||||
|
G01 Z-1.80000 F60.00000 ( plunge. )
|
||||||
|
G04 P0 ( dwell for no time -- G64 should not smooth over this point )
|
||||||
|
G01 F200.00000
|
||||||
|
G01 X-0.02500 Y38.89500
|
||||||
|
G00 Z-0.60000
|
||||||
|
G01 X-0.02500 Y39.89500
|
||||||
|
G01 Z-1.80000 F60.00000
|
||||||
|
G01 F200.00000
|
||||||
|
G01 X-0.02500 Y78.76500
|
||||||
|
G01 X-100.98997 Y78.76500
|
||||||
|
G01 X-100.98997 Y39.89500
|
||||||
|
G00 Z-0.60000
|
||||||
|
G01 X-100.98997 Y38.89500
|
||||||
|
G01 Z-1.80000 F60.00000
|
||||||
|
G01 F200.00000
|
||||||
|
G01 X-100.98997 Y0.02500
|
||||||
|
G01 X-0.02500 Y0.02500
|
||||||
|
G01 Z-2.25000 F60.00000 ( plunge. )
|
||||||
|
G04 P0 ( dwell for no time -- G64 should not smooth over this point )
|
||||||
|
G01 F200.00000
|
||||||
|
G01 X-0.02500 Y38.89500
|
||||||
|
G00 Z-0.60000
|
||||||
|
G01 X-0.02500 Y39.89500
|
||||||
|
G01 Z-2.25000 F60.00000
|
||||||
|
G01 F200.00000
|
||||||
|
G01 X-0.02500 Y78.76500
|
||||||
|
G01 X-100.98997 Y78.76500
|
||||||
|
G01 X-100.98997 Y39.89500
|
||||||
|
G00 Z-0.60000
|
||||||
|
G01 X-100.98997 Y38.89500
|
||||||
|
G01 Z-2.25000 F60.00000
|
||||||
|
G01 F200.00000
|
||||||
|
G01 X-100.98997 Y0.02500
|
||||||
|
G01 X-0.02500 Y0.02500
|
||||||
|
G01 Z-2.70000 F60.00000 ( plunge. )
|
||||||
|
G04 P0 ( dwell for no time -- G64 should not smooth over this point )
|
||||||
|
G01 F200.00000
|
||||||
|
G01 X-0.02500 Y38.89500
|
||||||
|
G00 Z-0.60000
|
||||||
|
G01 X-0.02500 Y39.89500
|
||||||
|
G01 Z-2.70000 F60.00000
|
||||||
|
G01 F200.00000
|
||||||
|
G01 X-0.02500 Y78.76500
|
||||||
|
G01 X-100.98997 Y78.76500
|
||||||
|
G01 X-100.98997 Y39.89500
|
||||||
|
G00 Z-0.60000
|
||||||
|
G01 X-100.98997 Y38.89500
|
||||||
|
G01 Z-2.70000 F60.00000
|
||||||
|
G01 F200.00000
|
||||||
|
G01 X-100.98997 Y0.02500
|
||||||
|
G01 X-0.02500 Y0.02500
|
||||||
|
|
||||||
|
G04 P0 ( dwell for no time -- G64 should not smooth over this point )
|
||||||
|
G00 Z30.000000 ( retract )
|
||||||
|
|
||||||
|
M5 ( Spindle off. )
|
||||||
|
G04 P1.000000
|
||||||
|
M9 ( Coolant off. )
|
||||||
|
M2 ( Program end. )
|
||||||
|
|
After Width: | Height: | Size: 603 KiB |
After Width: | Height: | Size: 484 KiB |