Initial commit
BIN
abc_measurements.xlsx
Normal file
122
firmware_smartstepper_trikarus/stepper_nano_zero/.cproject
Normal file
@ -0,0 +1,122 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<?fileVersion 4.0.0?><cproject storage_type_id="org.eclipse.cdt.core.XmlProjectDescriptionStorage">
|
||||||
|
<storageModule moduleId="org.eclipse.cdt.core.settings">
|
||||||
|
<cconfiguration id="cdt.managedbuild.toolchain.gnu.cross.base.1504376676">
|
||||||
|
<storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.toolchain.gnu.cross.base.1504376676" moduleId="org.eclipse.cdt.core.settings" name="Default">
|
||||||
|
<externalSettings>
|
||||||
|
<externalSetting>
|
||||||
|
<entry flags="RESOLVED" kind="includePath" name="C:\Users\tstern\AppData\Local\Arduino15\packages\misfittech\hardware\samd\1.0.0\variants\nano_zero"/>
|
||||||
|
<entry flags="RESOLVED" kind="includePath" name="C:\Users\tstern\AppData\Local\Arduino15\packages\misfittech\hardware\samd\1.0.0\cores\arduino"/>
|
||||||
|
</externalSetting>
|
||||||
|
</externalSettings>
|
||||||
|
<extensions>
|
||||||
|
<extension id="org.eclipse.cdt.core.ELF" point="org.eclipse.cdt.core.BinaryParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.GASErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.GmakeErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.GLDErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.CWDLocator" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.GCCErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
</extensions>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
|
||||||
|
<configuration artifactName="${ProjName}" buildProperties="" description="" id="cdt.managedbuild.toolchain.gnu.cross.base.1504376676" name="Default" parent="org.eclipse.cdt.build.core.emptycfg">
|
||||||
|
<folderInfo id="cdt.managedbuild.toolchain.gnu.cross.base.1504376676.350447049" name="/" resourcePath="">
|
||||||
|
<toolChain id="cdt.managedbuild.toolchain.gnu.cross.base.515513271" name="Cross GCC" superClass="cdt.managedbuild.toolchain.gnu.cross.base">
|
||||||
|
<option id="cdt.managedbuild.option.gnu.cross.prefix.582370251" name="Prefix" superClass="cdt.managedbuild.option.gnu.cross.prefix"/>
|
||||||
|
<option id="cdt.managedbuild.option.gnu.cross.path.231717393" name="Path" superClass="cdt.managedbuild.option.gnu.cross.path"/>
|
||||||
|
<targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="cdt.managedbuild.targetPlatform.gnu.cross.1339435354" isAbstract="false" osList="all" superClass="cdt.managedbuild.targetPlatform.gnu.cross"/>
|
||||||
|
<builder id="cdt.managedbuild.builder.gnu.cross.241627781" keepEnvironmentInBuildfile="false" managedBuildOn="false" name="Gnu Make Builder" superClass="cdt.managedbuild.builder.gnu.cross">
|
||||||
|
<outputEntries/>
|
||||||
|
</builder>
|
||||||
|
<tool id="cdt.managedbuild.tool.gnu.cross.c.compiler.1805317535" name="Cross GCC Compiler" superClass="cdt.managedbuild.tool.gnu.cross.c.compiler">
|
||||||
|
<option id="gnu.c.compiler.option.include.paths.1641555759" name="Include paths (-I)" superClass="gnu.c.compiler.option.include.paths" useByScannerDiscovery="false" valueType="includePath">
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\misfittech\hardware\samd\1.0.0\variants\nano_zero""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\Documents\Arduino\libraries\Adafruit_SSD1306-master""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\Documents\Arduino\libraries\Adafruit-GFX-Library-master""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\Device\ATMEL\samd21\include""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\Device\ATMEL\samd21\include\pio""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\Device\ATMEL\samd21\include\instance""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\Device\ATMEL\samd21\include\component""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\misfittech\hardware\samd\1.0.0\cores\arduino""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\Device\ATMEL""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\TSTERN\AppData\Local\Arduino15\packages\arduino\hardware\samd\1.6.6\libraries\SPI""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\CMSIS\include""/>
|
||||||
|
</option>
|
||||||
|
<option id="gnu.c.compiler.option.preprocessor.def.symbols.77778103" name="Defined symbols (-D)" superClass="gnu.c.compiler.option.preprocessor.def.symbols" useByScannerDiscovery="false" valueType="definedSymbols">
|
||||||
|
<listOptionValue builtIn="false" value="ARDUINO_SAMD_ZERO"/>
|
||||||
|
<listOptionValue builtIn="false" value="__SAMD21G18A__"/>
|
||||||
|
</option>
|
||||||
|
<inputType id="cdt.managedbuild.tool.gnu.c.compiler.input.1328245026" superClass="cdt.managedbuild.tool.gnu.c.compiler.input"/>
|
||||||
|
</tool>
|
||||||
|
<tool id="cdt.managedbuild.tool.gnu.cross.cpp.compiler.1543385682" name="Cross G++ Compiler" superClass="cdt.managedbuild.tool.gnu.cross.cpp.compiler">
|
||||||
|
<option id="gnu.cpp.compiler.option.include.paths.784350866" name="Include paths (-I)" superClass="gnu.cpp.compiler.option.include.paths" useByScannerDiscovery="false" valueType="includePath">
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\misfittech\hardware\samd\1.0.0\cores\arduino""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\misfittech\hardware\samd\1.0.0\variants\nano_zero""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\Documents\Arduino\libraries\Adafruit_SSD1306-master""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\Documents\Arduino\libraries\Adafruit-GFX-Library-master""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\Device\ATMEL\samd21\include""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\Device\ATMEL\samd21\include\pio""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\Device\ATMEL\samd21\include\instance""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\Device\ATMEL\samd21\include\component""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\Device\ATMEL""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\TSTERN\AppData\Local\Arduino15\packages\arduino\hardware\samd\1.6.6\libraries\SPI""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\CMSIS\include""/>
|
||||||
|
</option>
|
||||||
|
<option id="gnu.cpp.compiler.option.preprocessor.def.215333140" name="Defined symbols (-D)" superClass="gnu.cpp.compiler.option.preprocessor.def" useByScannerDiscovery="false" valueType="definedSymbols">
|
||||||
|
<listOptionValue builtIn="false" value="__SAMD21G18A__"/>
|
||||||
|
<listOptionValue builtIn="false" value="ARDUINO_SAMD_ZERO"/>
|
||||||
|
</option>
|
||||||
|
<inputType id="cdt.managedbuild.tool.gnu.cpp.compiler.input.1198492994" superClass="cdt.managedbuild.tool.gnu.cpp.compiler.input"/>
|
||||||
|
</tool>
|
||||||
|
<tool id="cdt.managedbuild.tool.gnu.cross.c.linker.1644022969" name="Cross GCC Linker" superClass="cdt.managedbuild.tool.gnu.cross.c.linker"/>
|
||||||
|
<tool id="cdt.managedbuild.tool.gnu.cross.cpp.linker.1373326859" name="Cross G++ Linker" superClass="cdt.managedbuild.tool.gnu.cross.cpp.linker">
|
||||||
|
<option id="gnu.cpp.link.option.paths.1624146493" name="Library search path (-L)" superClass="gnu.cpp.link.option.paths"/>
|
||||||
|
<inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.1257879712" superClass="cdt.managedbuild.tool.gnu.cpp.linker.input">
|
||||||
|
<additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
|
||||||
|
<additionalInput kind="additionalinput" paths="$(LIBS)"/>
|
||||||
|
</inputType>
|
||||||
|
</tool>
|
||||||
|
<tool id="cdt.managedbuild.tool.gnu.cross.archiver.722380566" name="Cross GCC Archiver" superClass="cdt.managedbuild.tool.gnu.cross.archiver"/>
|
||||||
|
<tool id="cdt.managedbuild.tool.gnu.cross.assembler.7579640" name="Cross GCC Assembler" superClass="cdt.managedbuild.tool.gnu.cross.assembler">
|
||||||
|
<option id="gnu.both.asm.option.include.paths.2128933212" name="Include paths (-I)" superClass="gnu.both.asm.option.include.paths" valueType="includePath">
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\misfittech\hardware\samd\1.0.0\variants\nano_zero""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\Documents\Arduino\libraries\Adafruit_SSD1306-master""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\Documents\Arduino\libraries\Adafruit-GFX-Library-master""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\Device\ATMEL\samd21\include""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\Device\ATMEL\samd21\include\pio""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\Device\ATMEL\samd21\include\instance""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\Device\ATMEL\samd21\include\component""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\misfittech\hardware\samd\1.0.0\cores\arduino""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\Device\ATMEL""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\TSTERN\AppData\Local\Arduino15\packages\arduino\hardware\samd\1.6.6\libraries\SPI""/>
|
||||||
|
<listOptionValue builtIn="false" value=""C:\Users\tstern\AppData\Local\Arduino15\packages\arduino\tools\CMSIS\4.0.0-atmel\CMSIS\Include""/>
|
||||||
|
</option>
|
||||||
|
<inputType id="cdt.managedbuild.tool.gnu.assembler.input.474088881" superClass="cdt.managedbuild.tool.gnu.assembler.input"/>
|
||||||
|
</tool>
|
||||||
|
</toolChain>
|
||||||
|
</folderInfo>
|
||||||
|
<sourceEntries>
|
||||||
|
<entry excluding="Adafruit-GFX-Library-master|Adafruit_SSD1306-master" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
|
||||||
|
</sourceEntries>
|
||||||
|
</configuration>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
|
||||||
|
<storageModule moduleId="ilg.gnuarmeclipse.managedbuild.packs"/>
|
||||||
|
</cconfiguration>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
|
||||||
|
<project id="NZS.null.440051529" name="NZS"/>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="org.eclipse.cdt.core.LanguageSettingsProviders"/>
|
||||||
|
<storageModule moduleId="scannerConfiguration">
|
||||||
|
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
|
||||||
|
<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.cross.base.1504376676;cdt.managedbuild.toolchain.gnu.cross.base.1504376676.350447049;cdt.managedbuild.tool.gnu.cross.c.compiler.1805317535;cdt.managedbuild.tool.gnu.c.compiler.input.1328245026">
|
||||||
|
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
|
||||||
|
</scannerConfigBuildInfo>
|
||||||
|
<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.cross.base.1504376676;cdt.managedbuild.toolchain.gnu.cross.base.1504376676.350447049;cdt.managedbuild.tool.gnu.cross.cpp.compiler.1543385682;cdt.managedbuild.tool.gnu.cpp.compiler.input.1198492994">
|
||||||
|
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
|
||||||
|
</scannerConfigBuildInfo>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="refreshScope"/>
|
||||||
|
<storageModule moduleId="org.eclipse.cdt.make.core.buildtargets"/>
|
||||||
|
</cproject>
|
34
firmware_smartstepper_trikarus/stepper_nano_zero/.project
Normal file
@ -0,0 +1,34 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<projectDescription>
|
||||||
|
<name>NZS</name>
|
||||||
|
<comment></comment>
|
||||||
|
<projects>
|
||||||
|
</projects>
|
||||||
|
<buildSpec>
|
||||||
|
<buildCommand>
|
||||||
|
<name>org.eclipse.cdt.managedbuilder.core.genmakebuilder</name>
|
||||||
|
<triggers>clean,full,incremental,</triggers>
|
||||||
|
<arguments>
|
||||||
|
</arguments>
|
||||||
|
</buildCommand>
|
||||||
|
<buildCommand>
|
||||||
|
<name>org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder</name>
|
||||||
|
<triggers>full,incremental,</triggers>
|
||||||
|
<arguments>
|
||||||
|
</arguments>
|
||||||
|
</buildCommand>
|
||||||
|
</buildSpec>
|
||||||
|
<natures>
|
||||||
|
<nature>org.eclipse.cdt.core.cnature</nature>
|
||||||
|
<nature>org.eclipse.cdt.core.ccnature</nature>
|
||||||
|
<nature>org.eclipse.cdt.managedbuilder.core.managedBuildNature</nature>
|
||||||
|
<nature>org.eclipse.cdt.managedbuilder.core.ScannerConfigNature</nature>
|
||||||
|
</natures>
|
||||||
|
<linkedResources>
|
||||||
|
<link>
|
||||||
|
<name>arduino</name>
|
||||||
|
<type>2</type>
|
||||||
|
<location>C:/Users/tramp_000/AppData/Local/Arduino15/packages/arduino/hardware/samd/1.6.8/cores/arduino</location>
|
||||||
|
</link>
|
||||||
|
</linkedResources>
|
||||||
|
</projectDescription>
|
152
firmware_smartstepper_trikarus/stepper_nano_zero/A1333.cpp
Normal file
@ -0,0 +1,152 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2019 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "syslog.h"
|
||||||
|
#include "A1333.h"
|
||||||
|
#include "SPI.h"
|
||||||
|
#include <stdio.h>
|
||||||
|
#include "board.h"
|
||||||
|
|
||||||
|
|
||||||
|
#define A1333_CMD_NOP (0x0000)
|
||||||
|
#define A1333_ANG15 (0x3200)
|
||||||
|
|
||||||
|
SPISettings settingsA(500000, MSBFIRST, SPI_MODE3); ///400000, MSBFIRST, SPI_MODE1);
|
||||||
|
|
||||||
|
boolean A1333::begin(int csPin)
|
||||||
|
{
|
||||||
|
|
||||||
|
digitalWrite(PIN_AS5047D_CS,LOW); //pull CS LOW by default (chip powered off)
|
||||||
|
digitalWrite(PIN_MOSI,LOW);
|
||||||
|
digitalWrite(PIN_SCK,LOW);
|
||||||
|
digitalWrite(PIN_MISO,LOW);
|
||||||
|
pinMode(PIN_MISO,OUTPUT);
|
||||||
|
delay(1000);
|
||||||
|
|
||||||
|
|
||||||
|
digitalWrite(PIN_AS5047D_CS,HIGH); //pull CS high
|
||||||
|
|
||||||
|
pinMode(PIN_MISO,INPUT);
|
||||||
|
|
||||||
|
|
||||||
|
chipSelectPin=csPin;
|
||||||
|
|
||||||
|
LOG("csPin is %d",csPin);
|
||||||
|
pinMode(chipSelectPin,OUTPUT);
|
||||||
|
digitalWrite(chipSelectPin,HIGH); //pull CS high by default
|
||||||
|
delay(1);
|
||||||
|
|
||||||
|
SPI.begin(); //AS5047D SPI uses mode=1 (CPOL=0, CPHA=1)
|
||||||
|
|
||||||
|
LOG("Begin A1333...");
|
||||||
|
|
||||||
|
LOG("Address is 0x%04X",readAddress(A1333_ANG15));
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
//read the encoders
|
||||||
|
int16_t A1333::readAddress(uint16_t addr)
|
||||||
|
{
|
||||||
|
uint16_t data;
|
||||||
|
//make sure it is a write by setting bit 14
|
||||||
|
//addr=addr | 0x4000;
|
||||||
|
|
||||||
|
SPI.beginTransaction(settingsA);
|
||||||
|
digitalWrite(chipSelectPin, LOW);
|
||||||
|
delayMicroseconds(1);
|
||||||
|
//clock out the address to read
|
||||||
|
//LOG("address 0x%04X",addr);
|
||||||
|
SPI.transfer16(addr);
|
||||||
|
digitalWrite(chipSelectPin, HIGH);
|
||||||
|
delayMicroseconds(1);
|
||||||
|
digitalWrite(chipSelectPin, LOW);
|
||||||
|
//clock out zeros to read in the data from address
|
||||||
|
data=SPI.transfer16(0x00);
|
||||||
|
|
||||||
|
digitalWrite(chipSelectPin, HIGH);
|
||||||
|
SPI.endTransaction();
|
||||||
|
|
||||||
|
return data;
|
||||||
|
}
|
||||||
|
|
||||||
|
//read the encoders
|
||||||
|
int16_t A1333::readEncoderAngle(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
return readAddress(A1333_ANG15)>>1;
|
||||||
|
}
|
||||||
|
|
||||||
|
int16_t A1333::readEncoderAnglePipeLineRead(void)
|
||||||
|
{
|
||||||
|
static bool first=true;
|
||||||
|
uint16_t addr = A1333_ANG15;
|
||||||
|
uint16_t addr2;
|
||||||
|
uint16_t data;
|
||||||
|
|
||||||
|
if (first)
|
||||||
|
{
|
||||||
|
//make sure it is a write by setting bit 14
|
||||||
|
//addr2=addr | 0x4000;
|
||||||
|
SPI.beginTransaction(settingsA);
|
||||||
|
digitalWrite(chipSelectPin, LOW);
|
||||||
|
delayMicroseconds(1);
|
||||||
|
//clock out the address to read
|
||||||
|
SPI.transfer16(addr);
|
||||||
|
digitalWrite(chipSelectPin, HIGH);
|
||||||
|
delayMicroseconds(1);
|
||||||
|
digitalWrite(chipSelectPin, LOW);
|
||||||
|
delayMicroseconds(1);
|
||||||
|
//clock out zeros to read in the data from address
|
||||||
|
data=SPI.transfer16(addr);
|
||||||
|
|
||||||
|
digitalWrite(chipSelectPin, HIGH);
|
||||||
|
SPI.endTransaction();
|
||||||
|
first=false;
|
||||||
|
return data>>1;
|
||||||
|
}
|
||||||
|
|
||||||
|
SPI.beginTransaction(settingsA);
|
||||||
|
digitalWrite(chipSelectPin, LOW);
|
||||||
|
delayMicroseconds(1);
|
||||||
|
//clock out zeros to read in the data from address
|
||||||
|
data=SPI.transfer16(addr);
|
||||||
|
|
||||||
|
digitalWrite(chipSelectPin, HIGH);
|
||||||
|
SPI.endTransaction();
|
||||||
|
return data>>1;
|
||||||
|
}
|
59
firmware_smartstepper_trikarus/stepper_nano_zero/A1333.h
Normal file
@ -0,0 +1,59 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2019 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#ifndef A1333_H_
|
||||||
|
#define A1333_H_
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
|
||||||
|
#define A1333_DEGREES_PER_BIT (360.0/(float)(0x7FFF))
|
||||||
|
|
||||||
|
class A1333 {
|
||||||
|
private:
|
||||||
|
int chipSelectPin;
|
||||||
|
public:
|
||||||
|
boolean begin(int csPin);
|
||||||
|
int16_t readEncoderAngle(void);
|
||||||
|
int16_t readAddress(uint16_t addr);
|
||||||
|
int16_t readEncoderAnglePipeLineRead(void);
|
||||||
|
void diagnostics(char *ptrStr) {return;};
|
||||||
|
bool getError(void) {return false;};
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* A1333_H_ */
|
412
firmware_smartstepper_trikarus/stepper_nano_zero/A4954.cpp
Normal file
@ -0,0 +1,412 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#include "A4954.h"
|
||||||
|
#include "wiring_private.h"
|
||||||
|
#include "syslog.h"
|
||||||
|
#include "angle.h"
|
||||||
|
#include "Arduino.h"
|
||||||
|
#include "sine.h"
|
||||||
|
|
||||||
|
static uint8_t pinState=0;
|
||||||
|
|
||||||
|
#pragma GCC push_options
|
||||||
|
#pragma GCC optimize ("-Ofast")
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#define DAC_MAX (0x01FFL)
|
||||||
|
// Wait for synchronization of registers between the clock domains
|
||||||
|
static __inline__ void syncTCC(Tcc* TCCx) __attribute__((always_inline, unused));
|
||||||
|
static void syncTCC(Tcc* TCCx) {
|
||||||
|
//int32_t t0=1000;
|
||||||
|
while (TCCx->SYNCBUSY.reg & TCC_SYNCBUSY_MASK)
|
||||||
|
{
|
||||||
|
// t0--;
|
||||||
|
// if (t0==0)
|
||||||
|
// {
|
||||||
|
// break;
|
||||||
|
// }
|
||||||
|
// delay(1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
static inline void bridge1(int state)
|
||||||
|
{
|
||||||
|
if (state==0)
|
||||||
|
{
|
||||||
|
PORT->Group[g_APinDescription[PIN_A4954_IN1].ulPort].PINCFG[g_APinDescription[PIN_A4954_IN1].ulPin].bit.PMUXEN = 0;
|
||||||
|
GPIO_OUTPUT(PIN_A4954_IN1);//pinMode(PIN_A4954_IN1,OUTPUT);
|
||||||
|
GPIO_OUTPUT(PIN_A4954_IN2);//pinMode(PIN_A4954_IN2,OUTPUT);
|
||||||
|
GPIO_HIGH(PIN_A4954_IN1);// digitalWrite(PIN_A4954_IN1, HIGH);
|
||||||
|
GPIO_LOW(PIN_A4954_IN2);//digitalWrite(PIN_A4954_IN2, LOW);
|
||||||
|
//pinPeripheral(PIN_A4954_IN2, PIO_TIMER_ALT);
|
||||||
|
pinState=(pinState & 0x0C) | 0x1;
|
||||||
|
}
|
||||||
|
if (state==1)
|
||||||
|
{
|
||||||
|
PORT->Group[g_APinDescription[PIN_A4954_IN2].ulPort].PINCFG[g_APinDescription[PIN_A4954_IN2].ulPin].bit.PMUXEN = 0;
|
||||||
|
GPIO_OUTPUT(PIN_A4954_IN2);//pinMode(PIN_A4954_IN2,OUTPUT);
|
||||||
|
GPIO_OUTPUT(PIN_A4954_IN1);pinMode(PIN_A4954_IN1,OUTPUT);
|
||||||
|
GPIO_LOW(PIN_A4954_IN1);//digitalWrite(PIN_A4954_IN1, LOW);
|
||||||
|
GPIO_HIGH(PIN_A4954_IN2);//digitalWrite(PIN_A4954_IN2, HIGH);
|
||||||
|
//pinPeripheral(PIN_A4954_IN1, PIO_TIMER);
|
||||||
|
pinState=(pinState & 0x0C) | 0x2;
|
||||||
|
}
|
||||||
|
if (state==3)
|
||||||
|
{
|
||||||
|
GPIO_LOW(PIN_A4954_IN1);
|
||||||
|
GPIO_LOW(PIN_A4954_IN2);
|
||||||
|
//digitalWrite(PIN_A4954_IN1, LOW);
|
||||||
|
//digitalWrite(PIN_A4954_IN2, LOW);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline void bridge2(int state)
|
||||||
|
{
|
||||||
|
if (state==0)
|
||||||
|
{
|
||||||
|
PORT->Group[g_APinDescription[PIN_A4954_IN3].ulPort].PINCFG[g_APinDescription[PIN_A4954_IN3].ulPin].bit.PMUXEN = 0;
|
||||||
|
GPIO_OUTPUT(PIN_A4954_IN3); //pinMode(PIN_A4954_IN3,OUTPUT);
|
||||||
|
GPIO_OUTPUT(PIN_A4954_IN4);//pinMode(PIN_A4954_IN4,OUTPUT);
|
||||||
|
GPIO_HIGH(PIN_A4954_IN3);//digitalWrite(PIN_A4954_IN3, HIGH);
|
||||||
|
GPIO_LOW(PIN_A4954_IN4);//digitalWrite(PIN_A4954_IN4, LOW);
|
||||||
|
//pinPeripheral(PIN_A4954_IN4, PIO_TIMER_ALT);
|
||||||
|
pinState=(pinState & 0x03) | 0x4;
|
||||||
|
}
|
||||||
|
if (state==1)
|
||||||
|
{
|
||||||
|
PORT->Group[g_APinDescription[PIN_A4954_IN4].ulPort].PINCFG[g_APinDescription[PIN_A4954_IN4].ulPin].bit.PMUXEN = 0;
|
||||||
|
GPIO_OUTPUT(PIN_A4954_IN4);//pinMode(PIN_A4954_IN4,OUTPUT);
|
||||||
|
GPIO_OUTPUT(PIN_A4954_IN3);//pinMode(PIN_A4954_IN3,OUTPUT);
|
||||||
|
GPIO_LOW(PIN_A4954_IN3);//digitalWrite(PIN_A4954_IN3, LOW);
|
||||||
|
GPIO_HIGH(PIN_A4954_IN4);//digitalWrite(PIN_A4954_IN4, HIGH);
|
||||||
|
//pinPeripheral(PIN_A4954_IN3, PIO_TIMER_ALT);
|
||||||
|
pinState=(pinState & 0x03) | 0x8;
|
||||||
|
}
|
||||||
|
if (state==3)
|
||||||
|
{
|
||||||
|
GPIO_LOW(PIN_A4954_IN3);
|
||||||
|
GPIO_LOW(PIN_A4954_IN4);
|
||||||
|
//digitalWrite(PIN_A4954_IN3, LOW);
|
||||||
|
//digitalWrite(PIN_A4954_IN4, LOW);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void enableTCC0(uint8_t percent)
|
||||||
|
{
|
||||||
|
#ifdef MECHADUINO_HARDWARE
|
||||||
|
return;
|
||||||
|
#else
|
||||||
|
Tcc* TCCx = TCC0 ;
|
||||||
|
|
||||||
|
|
||||||
|
uint32_t ulValue=((uint32_t)(100-percent)*480)/100;
|
||||||
|
//ERROR("Enable TCC0");
|
||||||
|
|
||||||
|
GCLK->CLKCTRL.reg = (uint16_t) (GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID( GCM_TCC0_TCC1 )) ;
|
||||||
|
|
||||||
|
while ( GCLK->STATUS.bit.SYNCBUSY == 1 ) ;
|
||||||
|
|
||||||
|
//ERROR("Setting TCC %d %d",ulValue,ulPin);
|
||||||
|
TCCx->CTRLA.reg &= ~TCC_CTRLA_ENABLE;
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
// Set TCx as normal PWM
|
||||||
|
TCCx->WAVE.reg |= TCC_WAVE_WAVEGEN_NPWM;
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
// Set TCx in waveform mode Normal PWM
|
||||||
|
TCCx->CC[1].reg = (uint32_t)ulValue; //ch5 //IN3
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
TCCx->CC[2].reg = (uint32_t)ulValue; //ch6 //IN4
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
TCCx->CC[3].reg = (uint32_t)ulValue; //ch7 //IN2
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
TCCx->CC[1].reg = (uint32_t)ulValue; //ch1 == ch5 //IN1
|
||||||
|
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
// Set PER to maximum counter value (resolution : 0xFF)
|
||||||
|
TCCx->PER.reg = DAC_MAX;
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
// Enable TCCx
|
||||||
|
TCCx->CTRLA.reg |= TCC_CTRLA_ENABLE ;
|
||||||
|
syncTCC(TCCx);
|
||||||
|
//ERROR("Enable TCC0 DONE");
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
static void setDAC(uint32_t DAC1, uint32_t DAC2)
|
||||||
|
{
|
||||||
|
TCC1->CC[1].reg = (uint32_t)DAC1; //D9 PA07 - VREF12
|
||||||
|
syncTCC(TCC1);
|
||||||
|
TCC1->CC[0].reg = (uint32_t)DAC2; //D4 - VREF34
|
||||||
|
syncTCC(TCC1);
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
static void setupDAC(void)
|
||||||
|
{
|
||||||
|
Tcc* TCCx = TCC1 ;
|
||||||
|
|
||||||
|
|
||||||
|
pinPeripheral(PIN_A4954_VREF34, PIO_TIMER_ALT);
|
||||||
|
pinPeripheral(PIN_A4954_VREF12, PIO_TIMER);
|
||||||
|
|
||||||
|
GCLK->CLKCTRL.reg = (uint16_t) (GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID( GCM_TCC0_TCC1 )) ;
|
||||||
|
|
||||||
|
while ( GCLK->STATUS.bit.SYNCBUSY == 1 ) ;
|
||||||
|
|
||||||
|
//ERROR("Setting TCC %d %d",ulValue,ulPin);
|
||||||
|
TCCx->CTRLA.reg &= ~TCC_CTRLA_ENABLE;
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
// Set TCx as normal PWM
|
||||||
|
TCCx->WAVE.reg |= TCC_WAVE_WAVEGEN_NPWM;
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
// Set TCx in waveform mode Normal PWM
|
||||||
|
TCCx->CC[1].reg = (uint32_t)0;
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
TCCx->CC[0].reg = (uint32_t)0;
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
// Set PER to maximum counter value (resolution : 0xFFF = 12 bits)
|
||||||
|
// =48e6/2^12=11kHz frequency
|
||||||
|
TCCx->PER.reg = DAC_MAX;
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
// Enable TCCx
|
||||||
|
TCCx->CTRLA.reg |= TCC_CTRLA_ENABLE ;
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void A4954::begin()
|
||||||
|
{
|
||||||
|
//setup the A4954 pins
|
||||||
|
digitalWrite(PIN_A4954_IN3,LOW);
|
||||||
|
pinMode(PIN_A4954_IN3,OUTPUT);
|
||||||
|
digitalWrite(PIN_A4954_IN4,LOW);
|
||||||
|
pinMode(PIN_A4954_IN4,OUTPUT);
|
||||||
|
digitalWrite(PIN_A4954_IN2,LOW);
|
||||||
|
pinMode(PIN_A4954_IN2,OUTPUT);
|
||||||
|
digitalWrite(PIN_A4954_IN1,LOW);
|
||||||
|
pinMode(PIN_A4954_IN1,OUTPUT);
|
||||||
|
|
||||||
|
//setup the PWM for current on the A4954, set for low current
|
||||||
|
digitalWrite(PIN_A4954_VREF12,LOW);
|
||||||
|
digitalWrite(PIN_A4954_VREF34,LOW);
|
||||||
|
pinMode(PIN_A4954_VREF34, OUTPUT);
|
||||||
|
pinMode(PIN_A4954_VREF12, OUTPUT);
|
||||||
|
|
||||||
|
enabled=true;
|
||||||
|
lastStepMicros=0;
|
||||||
|
forwardRotation=true;
|
||||||
|
|
||||||
|
enableTCC0(90);
|
||||||
|
setupDAC();
|
||||||
|
//
|
||||||
|
// int i=0;
|
||||||
|
// bridge1(0);
|
||||||
|
// bridge2(0);
|
||||||
|
//while (1)
|
||||||
|
// {
|
||||||
|
// int32_t x;
|
||||||
|
// WARNING("MA %d",i);
|
||||||
|
// x=(int32_t)((int64_t)i*(DAC_MAX))/3300;
|
||||||
|
// setDAC(x,x);
|
||||||
|
// delay(1000);
|
||||||
|
// i=i+10;
|
||||||
|
// if (i>1000)
|
||||||
|
// {
|
||||||
|
// i=0;
|
||||||
|
// }
|
||||||
|
//
|
||||||
|
// }
|
||||||
|
|
||||||
|
//
|
||||||
|
// WARNING("Setting DAC for 500mA output");
|
||||||
|
// setDAC((int32_t)((int64_t)1000*(DAC_MAX))/3300,(int32_t)((int64_t)1000*(DAC_MAX))/3300);
|
||||||
|
// bridge1(0);
|
||||||
|
// bridge2(0);
|
||||||
|
// while(1)
|
||||||
|
// {
|
||||||
|
//
|
||||||
|
// }
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
void A4954::limitCurrent(uint8_t percent)
|
||||||
|
{
|
||||||
|
#ifdef MECHADUINO_HARDWARE
|
||||||
|
return;
|
||||||
|
#else
|
||||||
|
//WARNING("current limit %d",percent);
|
||||||
|
enableTCC0(percent);
|
||||||
|
if (pinState & 0x01)
|
||||||
|
{
|
||||||
|
pinPeripheral(PIN_A4954_IN2, PIO_TIMER_ALT); //TCC0 WO[7]
|
||||||
|
}
|
||||||
|
if (pinState & 0x02)
|
||||||
|
{
|
||||||
|
pinPeripheral(PIN_A4954_IN1, PIO_TIMER); //TCC0 WO[1]
|
||||||
|
}
|
||||||
|
if (pinState & 0x04)
|
||||||
|
{
|
||||||
|
pinPeripheral(PIN_A4954_IN4, PIO_TIMER_ALT);
|
||||||
|
}
|
||||||
|
if (pinState & 0x08)
|
||||||
|
{
|
||||||
|
pinPeripheral(PIN_A4954_IN3, PIO_TIMER_ALT);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void A4954::enable(bool enable)
|
||||||
|
{
|
||||||
|
enabled=enable;
|
||||||
|
if (enabled == false)
|
||||||
|
{
|
||||||
|
WARNING("A4954 disabled");
|
||||||
|
setDAC(0,0); //turn current off
|
||||||
|
bridge1(3); //tri state bridge outputs
|
||||||
|
bridge2(3); //tri state bridge outputs
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//this is precise move and modulo of A4954_NUM_MICROSTEPS is a full step.
|
||||||
|
// stepAngle is in A4954_NUM_MICROSTEPS units..
|
||||||
|
// The A4954 has no idea where the motor is, so the calling function has to
|
||||||
|
// to tell the A4954 what phase to drive motor coils.
|
||||||
|
// A4954_NUM_MICROSTEPS is 256 by default so stepAngle of 1024 is 360 degrees
|
||||||
|
// Note you can only move up to +/-A4954_NUM_MICROSTEPS from where you
|
||||||
|
// currently are.
|
||||||
|
int32_t A4954::move(int32_t stepAngle, uint32_t mA)
|
||||||
|
{
|
||||||
|
uint16_t angle;
|
||||||
|
int32_t cos,sin;
|
||||||
|
int32_t dacSin,dacCos;
|
||||||
|
//static int i=0;
|
||||||
|
|
||||||
|
if (enabled == false)
|
||||||
|
{
|
||||||
|
//WARNING("A4954 disabled");
|
||||||
|
setDAC(0,0); //turn current off
|
||||||
|
bridge1(3); //tri state bridge outputs
|
||||||
|
bridge2(3); //tri state bridge outputs
|
||||||
|
return stepAngle;
|
||||||
|
}
|
||||||
|
|
||||||
|
//WARNING("move %d %d",stepAngle,mA);
|
||||||
|
//handle roll overs, could do with modulo operator
|
||||||
|
stepAngle=stepAngle%SINE_STEPS;
|
||||||
|
|
||||||
|
//figure out our sine Angle
|
||||||
|
// note our SINE_STEPS is 4x of microsteps for a reason
|
||||||
|
//angle=(stepAngle+(SINE_STEPS/8)) % SINE_STEPS;
|
||||||
|
angle=(stepAngle);
|
||||||
|
|
||||||
|
//calculate the sine and cosine of our angle
|
||||||
|
sin=sine(angle);
|
||||||
|
cos=cosine(angle);
|
||||||
|
|
||||||
|
//if we are reverse swap the sign of one of the angels
|
||||||
|
if (false == forwardRotation)
|
||||||
|
{
|
||||||
|
cos=-cos;
|
||||||
|
}
|
||||||
|
|
||||||
|
//scale sine result by current(mA)
|
||||||
|
dacSin=((int32_t)mA*(int64_t)abs(sin))/SINE_MAX;
|
||||||
|
|
||||||
|
//scale cosine result by current(mA)
|
||||||
|
dacCos=((int32_t)mA*(int64_t)abs(cos))/SINE_MAX;
|
||||||
|
|
||||||
|
// if (i==0)
|
||||||
|
// {
|
||||||
|
// WARNING("dacs are %d %d",dacSin,dacCos);
|
||||||
|
// }
|
||||||
|
|
||||||
|
//convert value into DAC scaled to 3300mA max
|
||||||
|
dacCos=(int32_t)((int64_t)dacCos*(DAC_MAX))/3300;
|
||||||
|
//convert value into DAC scaled to 3300mA max
|
||||||
|
dacSin=(int32_t)((int64_t)dacSin*(DAC_MAX))/3300;
|
||||||
|
|
||||||
|
//WARNING("dacs are %d %d ",dacSin,dacCos);
|
||||||
|
|
||||||
|
setDAC(dacSin,dacCos);
|
||||||
|
|
||||||
|
if (sin>0)
|
||||||
|
{
|
||||||
|
bridge1(1);
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
bridge1(0);
|
||||||
|
}
|
||||||
|
if (cos>0)
|
||||||
|
{
|
||||||
|
bridge2(1);
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
bridge2(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// if (i++>3000)
|
||||||
|
// {
|
||||||
|
// i=0;
|
||||||
|
// }
|
||||||
|
// YELLOW_LED(led);
|
||||||
|
// led=(led+1) & 0x01;
|
||||||
|
lastStepMicros=micros();
|
||||||
|
return stepAngle;
|
||||||
|
}
|
||||||
|
#pragma GCC pop_options
|
||||||
|
|
90
firmware_smartstepper_trikarus/stepper_nano_zero/A4954.h
Normal file
@ -0,0 +1,90 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2019 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#ifndef __A4954__H__
|
||||||
|
#define __A4954__H__
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "board.h"
|
||||||
|
#include "angle.h"
|
||||||
|
#include "sine.h"
|
||||||
|
|
||||||
|
#define A4954_NUM_MICROSTEPS (256)
|
||||||
|
#define A4954_MIN_TIME_BETWEEN_STEPS_MICROS (1000)
|
||||||
|
|
||||||
|
//prevent someone for making a mistake with the code
|
||||||
|
#if ((A4954_NUM_MICROSTEPS*4) != SINE_STEPS)
|
||||||
|
#error "SINE_STEPS must be 4x of Micro steps for the move function"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
* When it comes to the stepper driver if we use angles
|
||||||
|
* we will always have a rounding error. For example
|
||||||
|
* a 0-65536(360) angle for 1.8 degree step is 327.68 so
|
||||||
|
* if you increment 200 of these as 327 you have a 13.6 error
|
||||||
|
* after one rotation.
|
||||||
|
* If you use floating point the effect is the same but takes longer.
|
||||||
|
*
|
||||||
|
* The only error-less accumulation system is to use native units, ie full
|
||||||
|
* steps and microsteps.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
class A4954
|
||||||
|
{
|
||||||
|
private:
|
||||||
|
uint32_t lastStepMicros; // time in microseconds that last step happened
|
||||||
|
bool forwardRotation=true;
|
||||||
|
volatile bool enabled=true;
|
||||||
|
|
||||||
|
public:
|
||||||
|
void begin(void);
|
||||||
|
|
||||||
|
//moves motor where the modulo of A4954_NUM_MICROSTEPS is a full step.
|
||||||
|
int32_t move(int32_t stepAngle, uint32_t mA);
|
||||||
|
|
||||||
|
uint32_t microsSinceStep(void) {return micros()-lastStepMicros;};
|
||||||
|
void setRotationDirection(bool forward) {forwardRotation=forward;};
|
||||||
|
|
||||||
|
void enable(bool enable);
|
||||||
|
void limitCurrent(uint8_t percent); //higher more current
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#endif //__A4954__H__
|
337
firmware_smartstepper_trikarus/stepper_nano_zero/A5995.cpp
Normal file
@ -0,0 +1,337 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
|
||||||
|
#include "A5995.h"
|
||||||
|
#include "wiring_private.h"
|
||||||
|
#include "syslog.h"
|
||||||
|
#include "angle.h"
|
||||||
|
#include "Arduino.h"
|
||||||
|
#include "sine.h"
|
||||||
|
|
||||||
|
static uint8_t pinState=0;
|
||||||
|
|
||||||
|
#pragma GCC push_options
|
||||||
|
#pragma GCC optimize ("-Ofast")
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#define DAC_MAX (0x01FFL)
|
||||||
|
// Wait for synchronization of registers between the clock domains
|
||||||
|
static __inline__ void syncTCC(Tcc* TCCx) __attribute__((always_inline, unused));
|
||||||
|
static void syncTCC(Tcc* TCCx) {
|
||||||
|
//int32_t t0=1000;
|
||||||
|
while (TCCx->SYNCBUSY.reg & TCC_SYNCBUSY_MASK)
|
||||||
|
{
|
||||||
|
// t0--;
|
||||||
|
// if (t0==0)
|
||||||
|
// {
|
||||||
|
// break;
|
||||||
|
// }
|
||||||
|
// delay(1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
static void setDAC(uint32_t DAC1, uint32_t DAC2)
|
||||||
|
{
|
||||||
|
TCC1->CC[1].reg = (uint32_t)DAC1; //D9 PA07 - VREF2
|
||||||
|
syncTCC(TCC1);
|
||||||
|
TCC1->CC[0].reg = (uint32_t)DAC2; //D4 - VREF1
|
||||||
|
syncTCC(TCC1);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
static void setupDAC(void)
|
||||||
|
{
|
||||||
|
Tcc* TCCx = TCC1 ;
|
||||||
|
|
||||||
|
|
||||||
|
pinPeripheral(PIN_A5995_VREF1, PIO_TIMER_ALT);
|
||||||
|
pinPeripheral(PIN_A5995_VREF2, PIO_TIMER);
|
||||||
|
|
||||||
|
GCLK->CLKCTRL.reg = (uint16_t) (GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID( GCM_TCC0_TCC1 )) ;
|
||||||
|
|
||||||
|
while ( GCLK->STATUS.bit.SYNCBUSY == 1 ) ;
|
||||||
|
|
||||||
|
//ERROR("Setting TCC %d %d",ulValue,ulPin);
|
||||||
|
TCCx->CTRLA.reg &= ~TCC_CTRLA_ENABLE;
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
// Set TCx as normal PWM
|
||||||
|
TCCx->WAVE.reg |= TCC_WAVE_WAVEGEN_NPWM;
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
// Set TCx in waveform mode Normal PWM
|
||||||
|
TCCx->CC[1].reg = (uint32_t)0;
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
TCCx->CC[0].reg = (uint32_t)0;
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
// Set PER to maximum counter value (resolution : 0xFFF = 12 bits)
|
||||||
|
// =48e6/2^12=11kHz frequency
|
||||||
|
TCCx->PER.reg = DAC_MAX;
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
// Enable TCCx
|
||||||
|
TCCx->CTRLA.reg |= TCC_CTRLA_ENABLE ;
|
||||||
|
syncTCC(TCCx);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void A5995::begin()
|
||||||
|
{
|
||||||
|
//setup the A5995 pins
|
||||||
|
digitalWrite(PIN_A5995_ENABLE1,LOW);
|
||||||
|
pinMode(PIN_A5995_ENABLE1,OUTPUT);
|
||||||
|
digitalWrite(PIN_A5995_ENABLE2,LOW);
|
||||||
|
pinMode(PIN_A5995_ENABLE2,OUTPUT);
|
||||||
|
digitalWrite(PIN_A5995_MODE1,LOW);
|
||||||
|
pinMode(PIN_A5995_MODE1,OUTPUT);
|
||||||
|
digitalWrite(PIN_A5995_MODE2,LOW);
|
||||||
|
pinMode(PIN_A5995_MODE2,OUTPUT);
|
||||||
|
digitalWrite(PIN_A5995_PHASE1,LOW);
|
||||||
|
pinMode(PIN_A5995_PHASE1,OUTPUT);
|
||||||
|
digitalWrite(PIN_A5995_PHASE2,LOW);
|
||||||
|
pinMode(PIN_A5995_PHASE2,OUTPUT);
|
||||||
|
|
||||||
|
digitalWrite(PIN_A5995_SLEEPn,HIGH);
|
||||||
|
pinMode(PIN_A5995_SLEEPn,OUTPUT);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//setup the PWM for current on the A4954, set for low current
|
||||||
|
digitalWrite(PIN_A5995_VREF1,LOW);
|
||||||
|
digitalWrite(PIN_A5995_VREF2,LOW);
|
||||||
|
pinMode(PIN_A5995_VREF1, OUTPUT);
|
||||||
|
pinMode(PIN_A5995_VREF2, OUTPUT);
|
||||||
|
|
||||||
|
enabled=true;
|
||||||
|
lastStepMicros=0;
|
||||||
|
forwardRotation=true;
|
||||||
|
|
||||||
|
setupDAC();
|
||||||
|
|
||||||
|
|
||||||
|
//
|
||||||
|
// GPIO_HIGH(PIN_A5995_ENABLE1);
|
||||||
|
// GPIO_HIGH(PIN_A5995_ENABLE2);
|
||||||
|
// GPIO_LOW(PIN_A5995_MODE1);
|
||||||
|
// GPIO_LOW(PIN_A5995_MODE2);
|
||||||
|
// GPIO_HIGH(PIN_A5995_PHASE1);
|
||||||
|
// GPIO_HIGH(PIN_A5995_PHASE2);
|
||||||
|
// int i=0;;
|
||||||
|
// while (1)
|
||||||
|
// {
|
||||||
|
// int32_t x;
|
||||||
|
// WARNING("MA %d",i);
|
||||||
|
// x=(int32_t)((int64_t)i*(DAC_MAX))/3300;
|
||||||
|
// setDAC(x,x);
|
||||||
|
// delay(1000);
|
||||||
|
// i=i+10;
|
||||||
|
// if (i>1000)
|
||||||
|
// {
|
||||||
|
// i=0;
|
||||||
|
// }
|
||||||
|
//
|
||||||
|
// }
|
||||||
|
|
||||||
|
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void A5995::enable(bool enable)
|
||||||
|
{
|
||||||
|
enabled=enable;
|
||||||
|
if (enabled == false)
|
||||||
|
{
|
||||||
|
WARNING("A4954 disabled");
|
||||||
|
setDAC(0,0); //turn current off
|
||||||
|
GPIO_LOW(PIN_A5995_ENABLE1);
|
||||||
|
GPIO_LOW(PIN_A5995_ENABLE2);
|
||||||
|
GPIO_LOW(PIN_A5995_MODE1);
|
||||||
|
GPIO_LOW(PIN_A5995_MODE2);
|
||||||
|
GPIO_LOW(PIN_A5995_PHASE1);
|
||||||
|
GPIO_LOW(PIN_A5995_PHASE2);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//this is precise move and modulo of A4954_NUM_MICROSTEPS is a full step.
|
||||||
|
// stepAngle is in A4954_NUM_MICROSTEPS units..
|
||||||
|
// The A4954 has no idea where the motor is, so the calling function has to
|
||||||
|
// to tell the A4954 what phase to drive motor coils.
|
||||||
|
// A4954_NUM_MICROSTEPS is 256 by default so stepAngle of 1024 is 360 degrees
|
||||||
|
// Note you can only move up to +/-A4954_NUM_MICROSTEPS from where you
|
||||||
|
// currently are.
|
||||||
|
int32_t A5995::move(int32_t stepAngle, uint32_t mA)
|
||||||
|
{
|
||||||
|
uint16_t angle;
|
||||||
|
int32_t cos,sin;
|
||||||
|
int32_t dacSin,dacCos;
|
||||||
|
static int32_t lastSin=0,lastCos=0;
|
||||||
|
static int i=1;
|
||||||
|
|
||||||
|
if (enabled == false)
|
||||||
|
{
|
||||||
|
WARNING("A4954 disabled");
|
||||||
|
setDAC(0,0); //turn current off
|
||||||
|
GPIO_LOW(PIN_A5995_ENABLE1);
|
||||||
|
GPIO_LOW(PIN_A5995_ENABLE2);
|
||||||
|
GPIO_LOW(PIN_A5995_MODE1);
|
||||||
|
GPIO_LOW(PIN_A5995_MODE2);
|
||||||
|
GPIO_LOW(PIN_A5995_PHASE1);
|
||||||
|
GPIO_LOW(PIN_A5995_PHASE2);
|
||||||
|
return stepAngle;
|
||||||
|
}
|
||||||
|
|
||||||
|
//WARNING("move %d %d",stepAngle,mA);
|
||||||
|
|
||||||
|
stepAngle=(stepAngle) % SINE_STEPS;
|
||||||
|
//figure out our sine Angle
|
||||||
|
// note our SINE_STEPS is 4x of microsteps for a reason
|
||||||
|
//angle=(stepAngle+(SINE_STEPS/8)) % SINE_STEPS;
|
||||||
|
angle=stepAngle;
|
||||||
|
|
||||||
|
if (i==0)
|
||||||
|
{
|
||||||
|
WARNING("angle %d ",angle);
|
||||||
|
}
|
||||||
|
//calculate the sine and cosine of our angle
|
||||||
|
sin=sine(angle);
|
||||||
|
cos=cosine(angle);
|
||||||
|
|
||||||
|
//if we are reverse swap the sign of one of the angels
|
||||||
|
if (false == forwardRotation)
|
||||||
|
{
|
||||||
|
cos=-cos;
|
||||||
|
}
|
||||||
|
|
||||||
|
//scale sine result by current(mA)
|
||||||
|
dacSin=((int32_t)mA*(int64_t)(sin))/SINE_MAX;
|
||||||
|
|
||||||
|
if (i==0)
|
||||||
|
{
|
||||||
|
WARNING("dacsine %d ",dacSin);
|
||||||
|
}
|
||||||
|
// if ((lastSin-dacSin)>100) //decreasing current
|
||||||
|
// {
|
||||||
|
// GPIO_LOW(PIN_A5995_MODE2); //fast decay
|
||||||
|
// } else
|
||||||
|
// {
|
||||||
|
// GPIO_HIGH(PIN_A5995_MODE2); //slow decay
|
||||||
|
// }
|
||||||
|
lastSin=dacSin;
|
||||||
|
|
||||||
|
//convert value into DAC scaled to 3300mA max
|
||||||
|
dacSin=(int32_t)((int64_t)abs(dacSin)*(DAC_MAX))/3300;
|
||||||
|
|
||||||
|
|
||||||
|
//scale cosine result by current(mA)
|
||||||
|
dacCos=((int32_t)mA*(int64_t)(cos))/SINE_MAX;
|
||||||
|
|
||||||
|
if (i==0)
|
||||||
|
{
|
||||||
|
WARNING("daccos %d ",dacCos);
|
||||||
|
}
|
||||||
|
// if ((lastCos-dacCos)>100) //decreasing current
|
||||||
|
// {
|
||||||
|
// GPIO_LOW(PIN_A5995_MODE1); //fast decay
|
||||||
|
// } else
|
||||||
|
// {
|
||||||
|
// GPIO_HIGH(PIN_A5995_MODE1); //slow decay
|
||||||
|
// }
|
||||||
|
lastCos=dacCos;
|
||||||
|
|
||||||
|
//convert value into DAC scaled to 3300mA max
|
||||||
|
dacCos=(int32_t)((int64_t)abs(dacCos)*(DAC_MAX))/3300;
|
||||||
|
|
||||||
|
|
||||||
|
if (i==0)
|
||||||
|
{
|
||||||
|
WARNING("dacs are %d %d",dacSin,dacCos);
|
||||||
|
}
|
||||||
|
setDAC(dacSin,dacCos);
|
||||||
|
|
||||||
|
GPIO_HIGH(PIN_A5995_ENABLE1);
|
||||||
|
GPIO_HIGH(PIN_A5995_ENABLE2);
|
||||||
|
GPIO_LOW(PIN_A5995_MODE1);
|
||||||
|
GPIO_LOW(PIN_A5995_MODE2);
|
||||||
|
|
||||||
|
|
||||||
|
if (i==0)
|
||||||
|
{
|
||||||
|
WARNING("sins are %d %d",sin,cos);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (sin>0)
|
||||||
|
{
|
||||||
|
GPIO_HIGH(PIN_A5995_PHASE2);
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
GPIO_LOW(PIN_A5995_PHASE2);
|
||||||
|
|
||||||
|
}
|
||||||
|
if (cos>0)
|
||||||
|
{
|
||||||
|
GPIO_HIGH(PIN_A5995_PHASE1);
|
||||||
|
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
GPIO_LOW(PIN_A5995_PHASE1);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// i++;
|
||||||
|
// if (i>3000) i=0;
|
||||||
|
// YELLOW_LED(led);
|
||||||
|
// led=(led+1) & 0x01;
|
||||||
|
lastStepMicros=micros();
|
||||||
|
return stepAngle;
|
||||||
|
}
|
||||||
|
#pragma GCC pop_options
|
||||||
|
|
||||||
|
|
||||||
|
|
92
firmware_smartstepper_trikarus/stepper_nano_zero/A5995.h
Normal file
@ -0,0 +1,92 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
#ifndef A5995_H_
|
||||||
|
#define A5995_H_
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "board.h"
|
||||||
|
#include "angle.h"
|
||||||
|
#include "sine.h"
|
||||||
|
|
||||||
|
#define A5995_NUM_MICROSTEPS (256)
|
||||||
|
|
||||||
|
|
||||||
|
//prevent someone for making a mistake with the code
|
||||||
|
#if ((A5995_NUM_MICROSTEPS*4) != SINE_STEPS)
|
||||||
|
#error "SINE_STEPS must be 4x of Micro steps for the move function"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
* When it comes to the stepper driver if we use angles
|
||||||
|
* we will always have a rounding error. For example
|
||||||
|
* a 0-65536(360) angle for 1.8 degree step is 327.68 so
|
||||||
|
* if you increment 200 of these as 327 you have a 13.6 error
|
||||||
|
* after one rotation.
|
||||||
|
* If you use floating point the effect is the same but takes longer.
|
||||||
|
*
|
||||||
|
* The only error-less accumulation system is to use native units, ie full
|
||||||
|
* steps and microsteps.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
class A5995
|
||||||
|
{
|
||||||
|
private:
|
||||||
|
uint32_t lastStepMicros; // time in microseconds that last step happened
|
||||||
|
bool forwardRotation=true;
|
||||||
|
volatile bool enabled=true;
|
||||||
|
|
||||||
|
public:
|
||||||
|
void begin(void);
|
||||||
|
|
||||||
|
//moves motor where the modulo of A4954_NUM_MICROSTEPS is a full step.
|
||||||
|
int32_t move(int32_t stepAngle, uint32_t mA);
|
||||||
|
|
||||||
|
uint32_t microsSinceStep(void) {return micros()-lastStepMicros;};
|
||||||
|
void setRotationDirection(bool forward) {forwardRotation=forward;};
|
||||||
|
|
||||||
|
void enable(bool enable);
|
||||||
|
void limitCurrent(uint8_t percent) {return;}; //Not used
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* A5995_H_ */
|
1071
firmware_smartstepper_trikarus/stepper_nano_zero/Adafruit_GFX.cpp
Normal file
155
firmware_smartstepper_trikarus/stepper_nano_zero/Adafruit_GFX.h
Normal file
@ -0,0 +1,155 @@
|
|||||||
|
#ifndef _ADAFRUIT_GFX_H
|
||||||
|
#define _ADAFRUIT_GFX_H
|
||||||
|
|
||||||
|
#if ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#include "Print.h"
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "gfxfont.h"
|
||||||
|
|
||||||
|
class Adafruit_GFX : public Print {
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
Adafruit_GFX(int16_t w, int16_t h); // Constructor
|
||||||
|
|
||||||
|
// This MUST be defined by the subclass:
|
||||||
|
virtual void drawPixel(int16_t x, int16_t y, uint16_t color) = 0;
|
||||||
|
|
||||||
|
// These MAY be overridden by the subclass to provide device-specific
|
||||||
|
// optimized code. Otherwise 'generic' versions are used.
|
||||||
|
virtual void
|
||||||
|
drawLine(int16_t x0, int16_t y0, int16_t x1, int16_t y1, uint16_t color),
|
||||||
|
drawFastVLine(int16_t x, int16_t y, int16_t h, uint16_t color),
|
||||||
|
drawFastHLine(int16_t x, int16_t y, int16_t w, uint16_t color),
|
||||||
|
drawRect(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color),
|
||||||
|
fillRect(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color),
|
||||||
|
fillScreen(uint16_t color),
|
||||||
|
invertDisplay(boolean i);
|
||||||
|
|
||||||
|
// These exist only with Adafruit_GFX (no subclass overrides)
|
||||||
|
void
|
||||||
|
drawCircle(int16_t x0, int16_t y0, int16_t r, uint16_t color),
|
||||||
|
drawCircleHelper(int16_t x0, int16_t y0, int16_t r, uint8_t cornername,
|
||||||
|
uint16_t color),
|
||||||
|
fillCircle(int16_t x0, int16_t y0, int16_t r, uint16_t color),
|
||||||
|
fillCircleHelper(int16_t x0, int16_t y0, int16_t r, uint8_t cornername,
|
||||||
|
int16_t delta, uint16_t color),
|
||||||
|
drawTriangle(int16_t x0, int16_t y0, int16_t x1, int16_t y1,
|
||||||
|
int16_t x2, int16_t y2, uint16_t color),
|
||||||
|
fillTriangle(int16_t x0, int16_t y0, int16_t x1, int16_t y1,
|
||||||
|
int16_t x2, int16_t y2, uint16_t color),
|
||||||
|
drawRoundRect(int16_t x0, int16_t y0, int16_t w, int16_t h,
|
||||||
|
int16_t radius, uint16_t color),
|
||||||
|
fillRoundRect(int16_t x0, int16_t y0, int16_t w, int16_t h,
|
||||||
|
int16_t radius, uint16_t color),
|
||||||
|
drawBitmap(int16_t x, int16_t y, const uint8_t *bitmap,
|
||||||
|
int16_t w, int16_t h, uint16_t color),
|
||||||
|
drawBitmap(int16_t x, int16_t y, const uint8_t *bitmap,
|
||||||
|
int16_t w, int16_t h, uint16_t color, uint16_t bg),
|
||||||
|
drawBitmap(int16_t x, int16_t y, uint8_t *bitmap,
|
||||||
|
int16_t w, int16_t h, uint16_t color),
|
||||||
|
drawBitmap(int16_t x, int16_t y, uint8_t *bitmap,
|
||||||
|
int16_t w, int16_t h, uint16_t color, uint16_t bg),
|
||||||
|
drawXBitmap(int16_t x, int16_t y, const uint8_t *bitmap,
|
||||||
|
int16_t w, int16_t h, uint16_t color),
|
||||||
|
drawChar(int16_t x, int16_t y, unsigned char c, uint16_t color,
|
||||||
|
uint16_t bg, uint8_t size),
|
||||||
|
setCursor(int16_t x, int16_t y),
|
||||||
|
setTextColor(uint16_t c),
|
||||||
|
setTextColor(uint16_t c, uint16_t bg),
|
||||||
|
setTextSize(uint8_t s),
|
||||||
|
setTextWrap(boolean w),
|
||||||
|
setRotation(uint8_t r),
|
||||||
|
cp437(boolean x=true),
|
||||||
|
setFont(const GFXfont *f = NULL),
|
||||||
|
getTextBounds(char *string, int16_t x, int16_t y,
|
||||||
|
int16_t *x1, int16_t *y1, uint16_t *w, uint16_t *h),
|
||||||
|
getTextBounds(const __FlashStringHelper *s, int16_t x, int16_t y,
|
||||||
|
int16_t *x1, int16_t *y1, uint16_t *w, uint16_t *h);
|
||||||
|
|
||||||
|
#if ARDUINO >= 100
|
||||||
|
virtual size_t write(uint8_t);
|
||||||
|
#else
|
||||||
|
virtual void write(uint8_t);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
int16_t height(void) const;
|
||||||
|
int16_t width(void) const;
|
||||||
|
|
||||||
|
uint8_t getRotation(void) const;
|
||||||
|
|
||||||
|
// get current cursor position (get rotation safe maximum values, using: width() for x, height() for y)
|
||||||
|
int16_t getCursorX(void) const;
|
||||||
|
int16_t getCursorY(void) const;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
const int16_t
|
||||||
|
WIDTH, HEIGHT; // This is the 'raw' display w/h - never changes
|
||||||
|
int16_t
|
||||||
|
_width, _height, // Display w/h as modified by current rotation
|
||||||
|
cursor_x, cursor_y;
|
||||||
|
uint16_t
|
||||||
|
textcolor, textbgcolor;
|
||||||
|
uint8_t
|
||||||
|
textsize,
|
||||||
|
rotation;
|
||||||
|
boolean
|
||||||
|
wrap, // If set, 'wrap' text at right edge of display
|
||||||
|
_cp437; // If set, use correct CP437 charset (default is off)
|
||||||
|
GFXfont
|
||||||
|
*gfxFont;
|
||||||
|
};
|
||||||
|
|
||||||
|
class Adafruit_GFX_Button {
|
||||||
|
|
||||||
|
public:
|
||||||
|
Adafruit_GFX_Button(void);
|
||||||
|
void initButton(Adafruit_GFX *gfx, int16_t x, int16_t y,
|
||||||
|
uint8_t w, uint8_t h, uint16_t outline, uint16_t fill,
|
||||||
|
uint16_t textcolor, char *label, uint8_t textsize);
|
||||||
|
void drawButton(boolean inverted = false);
|
||||||
|
boolean contains(int16_t x, int16_t y);
|
||||||
|
|
||||||
|
void press(boolean p);
|
||||||
|
boolean isPressed();
|
||||||
|
boolean justPressed();
|
||||||
|
boolean justReleased();
|
||||||
|
|
||||||
|
private:
|
||||||
|
Adafruit_GFX *_gfx;
|
||||||
|
int16_t _x, _y;
|
||||||
|
uint16_t _w, _h;
|
||||||
|
uint8_t _textsize;
|
||||||
|
uint16_t _outlinecolor, _fillcolor, _textcolor;
|
||||||
|
char _label[10];
|
||||||
|
|
||||||
|
boolean currstate, laststate;
|
||||||
|
};
|
||||||
|
|
||||||
|
class GFXcanvas1 : public Adafruit_GFX {
|
||||||
|
|
||||||
|
public:
|
||||||
|
GFXcanvas1(uint16_t w, uint16_t h);
|
||||||
|
~GFXcanvas1(void);
|
||||||
|
void drawPixel(int16_t x, int16_t y, uint16_t color),
|
||||||
|
fillScreen(uint16_t color);
|
||||||
|
uint8_t *getBuffer(void);
|
||||||
|
private:
|
||||||
|
uint8_t *buffer;
|
||||||
|
};
|
||||||
|
|
||||||
|
class GFXcanvas16 : public Adafruit_GFX {
|
||||||
|
GFXcanvas16(uint16_t w, uint16_t h);
|
||||||
|
~GFXcanvas16(void);
|
||||||
|
void drawPixel(int16_t x, int16_t y, uint16_t color),
|
||||||
|
fillScreen(uint16_t color);
|
||||||
|
uint16_t *getBuffer(void);
|
||||||
|
private:
|
||||||
|
uint16_t *buffer;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // _ADAFRUIT_GFX_H
|
@ -0,0 +1,750 @@
|
|||||||
|
/*********************************************************************
|
||||||
|
This is a library for our Monochrome OLEDs based on SSD1306 drivers
|
||||||
|
|
||||||
|
Pick one up today in the adafruit shop!
|
||||||
|
------> http://www.adafruit.com/category/63_98
|
||||||
|
|
||||||
|
These displays use SPI to communicate, 4 or 5 pins are required to
|
||||||
|
interface
|
||||||
|
|
||||||
|
Adafruit invests time and resources providing this open source code,
|
||||||
|
please support Adafruit and open-source hardware by purchasing
|
||||||
|
products from Adafruit!
|
||||||
|
|
||||||
|
Written by Limor Fried/Ladyada for Adafruit Industries.
|
||||||
|
BSD license, check license.txt for more information
|
||||||
|
All text above, and the splash screen below must be included in any redistribution
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
#ifdef __AVR__
|
||||||
|
#include <avr/pgmspace.h>
|
||||||
|
#elif defined(ESP8266)
|
||||||
|
#include <pgmspace.h>
|
||||||
|
#else
|
||||||
|
#define pgm_read_byte(addr) (*(const unsigned char *)(addr))
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if !defined(__ARM_ARCH) && !defined(ENERGIA) && !defined(ESP8266)
|
||||||
|
#include <util/delay.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <stdlib.h>
|
||||||
|
|
||||||
|
#include <Wire.h>
|
||||||
|
#include <SPI.h>
|
||||||
|
#include "Adafruit_GFX.h"
|
||||||
|
#include "Adafruit_SSD1306.h"
|
||||||
|
#include "syslog.h"
|
||||||
|
|
||||||
|
// the memory buffer for the LCD
|
||||||
|
|
||||||
|
static uint8_t buffer[SSD1306_LCDHEIGHT * SSD1306_LCDWIDTH / 8] = {
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80,
|
||||||
|
0x80, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x80, 0x80, 0xC0, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x80, 0xC0, 0xE0, 0xF0, 0xF8, 0xFC, 0xF8, 0xE0, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x80, 0x80,
|
||||||
|
0x80, 0x80, 0x00, 0x80, 0x80, 0x00, 0x00, 0x00, 0x00, 0x80, 0x80, 0x80, 0x80, 0x80, 0x00, 0xFF,
|
||||||
|
#if (SSD1306_LCDHEIGHT * SSD1306_LCDWIDTH > 96*16)
|
||||||
|
0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x80, 0x80, 0x80, 0x80, 0x00, 0x00, 0x80, 0x80, 0x00, 0x00,
|
||||||
|
0x80, 0xFF, 0xFF, 0x80, 0x80, 0x00, 0x80, 0x80, 0x00, 0x80, 0x80, 0x80, 0x80, 0x00, 0x80, 0x80,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x80, 0x00, 0x00, 0x8C, 0x8E, 0x84, 0x00, 0x00, 0x80, 0xF8,
|
||||||
|
0xF8, 0xF8, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xE0, 0xE0, 0xC0, 0x80,
|
||||||
|
0x00, 0xE0, 0xFC, 0xFE, 0xFF, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFE, 0xFF, 0xC7, 0x01, 0x01,
|
||||||
|
0x01, 0x01, 0x83, 0xFF, 0xFF, 0x00, 0x00, 0x7C, 0xFE, 0xC7, 0x01, 0x01, 0x01, 0x01, 0x83, 0xFF,
|
||||||
|
0xFF, 0xFF, 0x00, 0x38, 0xFE, 0xC7, 0x83, 0x01, 0x01, 0x01, 0x83, 0xC7, 0xFF, 0xFF, 0x00, 0x00,
|
||||||
|
0x01, 0xFF, 0xFF, 0x01, 0x01, 0x00, 0xFF, 0xFF, 0x07, 0x01, 0x01, 0x01, 0x00, 0x00, 0x7F, 0xFF,
|
||||||
|
0x80, 0x00, 0x00, 0x00, 0xFF, 0xFF, 0x7F, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x01, 0xFF,
|
||||||
|
0xFF, 0xFF, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x03, 0x0F, 0x3F, 0x7F, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE7, 0xC7, 0xC7, 0x8F,
|
||||||
|
0x8F, 0x9F, 0xBF, 0xFF, 0xFF, 0xC3, 0xC0, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xFC, 0xFC,
|
||||||
|
0xFC, 0xFC, 0xFC, 0xFC, 0xFC, 0xF8, 0xF8, 0xF0, 0xF0, 0xE0, 0xC0, 0x00, 0x01, 0x03, 0x03, 0x03,
|
||||||
|
0x03, 0x03, 0x01, 0x03, 0x03, 0x00, 0x00, 0x00, 0x00, 0x01, 0x03, 0x03, 0x03, 0x03, 0x01, 0x01,
|
||||||
|
0x03, 0x01, 0x00, 0x00, 0x00, 0x01, 0x03, 0x03, 0x03, 0x03, 0x01, 0x01, 0x03, 0x03, 0x00, 0x00,
|
||||||
|
0x00, 0x03, 0x03, 0x00, 0x00, 0x00, 0x03, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01,
|
||||||
|
0x03, 0x03, 0x03, 0x03, 0x03, 0x01, 0x00, 0x00, 0x00, 0x01, 0x03, 0x01, 0x00, 0x00, 0x00, 0x03,
|
||||||
|
0x03, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
#if (SSD1306_LCDHEIGHT == 64)
|
||||||
|
0x00, 0x00, 0x00, 0x80, 0xC0, 0xE0, 0xF0, 0xF9, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x3F, 0x1F, 0x0F,
|
||||||
|
0x87, 0xC7, 0xF7, 0xFF, 0xFF, 0x1F, 0x1F, 0x3D, 0xFC, 0xF8, 0xF8, 0xF8, 0xF8, 0x7C, 0x7D, 0xFF,
|
||||||
|
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0x3F, 0x0F, 0x07, 0x00, 0x30, 0x30, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0xFE, 0xFE, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xE0, 0xC0, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x30, 0x30, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0xC0, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0x7F, 0x3F, 0x1F,
|
||||||
|
0x0F, 0x07, 0x1F, 0x7F, 0xFF, 0xFF, 0xF8, 0xF8, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xF8, 0xE0,
|
||||||
|
0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFE, 0xFE, 0x00, 0x00,
|
||||||
|
0x00, 0xFC, 0xFE, 0xFC, 0x0C, 0x06, 0x06, 0x0E, 0xFC, 0xF8, 0x00, 0x00, 0xF0, 0xF8, 0x1C, 0x0E,
|
||||||
|
0x06, 0x06, 0x06, 0x0C, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0xFE, 0xFE, 0x00, 0x00, 0x00, 0x00, 0xFC,
|
||||||
|
0xFE, 0xFC, 0x00, 0x18, 0x3C, 0x7E, 0x66, 0xE6, 0xCE, 0x84, 0x00, 0x00, 0x06, 0xFF, 0xFF, 0x06,
|
||||||
|
0x06, 0xFC, 0xFE, 0xFC, 0x0C, 0x06, 0x06, 0x06, 0x00, 0x00, 0xFE, 0xFE, 0x00, 0x00, 0xC0, 0xF8,
|
||||||
|
0xFC, 0x4E, 0x46, 0x46, 0x46, 0x4E, 0x7C, 0x78, 0x40, 0x18, 0x3C, 0x76, 0xE6, 0xCE, 0xCC, 0x80,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x01, 0x07, 0x0F, 0x1F, 0x1F, 0x3F, 0x3F, 0x3F, 0x3F, 0x1F, 0x0F, 0x03,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00, 0x00,
|
||||||
|
0x00, 0x0F, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x03, 0x07, 0x0E, 0x0C,
|
||||||
|
0x18, 0x18, 0x0C, 0x06, 0x0F, 0x0F, 0x0F, 0x00, 0x00, 0x01, 0x0F, 0x0E, 0x0C, 0x18, 0x0C, 0x0F,
|
||||||
|
0x07, 0x01, 0x00, 0x04, 0x0E, 0x0C, 0x18, 0x0C, 0x0F, 0x07, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00,
|
||||||
|
0x00, 0x0F, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x07,
|
||||||
|
0x07, 0x0C, 0x0C, 0x18, 0x1C, 0x0C, 0x06, 0x06, 0x00, 0x04, 0x0E, 0x0C, 0x18, 0x0C, 0x0F, 0x07,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
};
|
||||||
|
|
||||||
|
#define ssd1306_swap(a, b) { int16_t t = a; a = b; b = t; }
|
||||||
|
|
||||||
|
// the most basic function, set a single pixel
|
||||||
|
void Adafruit_SSD1306::drawPixel(int16_t x, int16_t y, uint16_t color) {
|
||||||
|
if ((x < 0) || (x >= width()) || (y < 0) || (y >= height()))
|
||||||
|
return;
|
||||||
|
|
||||||
|
// check rotation, move pixel around if necessary
|
||||||
|
switch (getRotation()) {
|
||||||
|
case 1:
|
||||||
|
ssd1306_swap(x, y);
|
||||||
|
x = WIDTH - x - 1;
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
x = WIDTH - x - 1;
|
||||||
|
y = HEIGHT - y - 1;
|
||||||
|
break;
|
||||||
|
case 3:
|
||||||
|
ssd1306_swap(x, y);
|
||||||
|
y = HEIGHT - y - 1;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
// x is which column
|
||||||
|
switch (color)
|
||||||
|
{
|
||||||
|
case WHITE: buffer[x+ (y/8)*SSD1306_LCDWIDTH] |= (1 << (y&7)); break;
|
||||||
|
case BLACK: buffer[x+ (y/8)*SSD1306_LCDWIDTH] &= ~(1 << (y&7)); break;
|
||||||
|
case INVERSE: buffer[x+ (y/8)*SSD1306_LCDWIDTH] ^= (1 << (y&7)); break;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
Adafruit_SSD1306::Adafruit_SSD1306(int8_t SID, int8_t SCLK, int8_t DC, int8_t RST, int8_t CS) : Adafruit_GFX(SSD1306_LCDWIDTH, SSD1306_LCDHEIGHT) {
|
||||||
|
cs = CS;
|
||||||
|
rst = RST;
|
||||||
|
dc = DC;
|
||||||
|
sclk = SCLK;
|
||||||
|
sid = SID;
|
||||||
|
hwSPI = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// constructor for hardware SPI - we indicate DataCommand, ChipSelect, Reset
|
||||||
|
Adafruit_SSD1306::Adafruit_SSD1306(int8_t DC, int8_t RST, int8_t CS) : Adafruit_GFX(SSD1306_LCDWIDTH, SSD1306_LCDHEIGHT) {
|
||||||
|
dc = DC;
|
||||||
|
rst = RST;
|
||||||
|
cs = CS;
|
||||||
|
hwSPI = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// initializer for I2C - we only indicate the reset pin!
|
||||||
|
Adafruit_SSD1306::Adafruit_SSD1306(int8_t reset) :
|
||||||
|
Adafruit_GFX(SSD1306_LCDWIDTH, SSD1306_LCDHEIGHT) {
|
||||||
|
sclk = dc = cs = sid = -1;
|
||||||
|
rst = reset;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
bool Adafruit_SSD1306::begin(uint8_t vccstate, uint8_t i2caddr, bool reset) {
|
||||||
|
_vccstate = vccstate;
|
||||||
|
_i2caddr = i2caddr;
|
||||||
|
|
||||||
|
// set pin directions
|
||||||
|
if (sid != -1){
|
||||||
|
pinMode(dc, OUTPUT);
|
||||||
|
pinMode(cs, OUTPUT);
|
||||||
|
#ifdef HAVE_PORTREG
|
||||||
|
csport = portOutputRegister(digitalPinToPort(cs));
|
||||||
|
cspinmask = digitalPinToBitMask(cs);
|
||||||
|
dcport = portOutputRegister(digitalPinToPort(dc));
|
||||||
|
dcpinmask = digitalPinToBitMask(dc);
|
||||||
|
#endif
|
||||||
|
if (!hwSPI){
|
||||||
|
// set pins for software-SPI
|
||||||
|
pinMode(sid, OUTPUT);
|
||||||
|
pinMode(sclk, OUTPUT);
|
||||||
|
#ifdef HAVE_PORTREG
|
||||||
|
clkport = portOutputRegister(digitalPinToPort(sclk));
|
||||||
|
clkpinmask = digitalPinToBitMask(sclk);
|
||||||
|
mosiport = portOutputRegister(digitalPinToPort(sid));
|
||||||
|
mosipinmask = digitalPinToBitMask(sid);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
if (hwSPI){
|
||||||
|
SPI.begin();
|
||||||
|
#ifdef SPI_HAS_TRANSACTION
|
||||||
|
SPI.beginTransaction(SPISettings(8000000, MSBFIRST, SPI_MODE0));
|
||||||
|
#else
|
||||||
|
SPI.setClockDivider (4);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
// I2C Init
|
||||||
|
Wire.begin();
|
||||||
|
#ifdef __SAM3X8E__
|
||||||
|
// Force 400 KHz I2C, rawr! (Uses pins 20, 21 for SDA, SCL)
|
||||||
|
TWI1->TWI_CWGR = 0;
|
||||||
|
TWI1->TWI_CWGR = ((VARIANT_MCK / (2 * 400000)) - 4) * 0x101;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
if ((reset) && (rst >= 0)) {
|
||||||
|
// Setup reset pin direction (used by both SPI and I2C)
|
||||||
|
pinMode(rst, OUTPUT);
|
||||||
|
digitalWrite(rst, HIGH);
|
||||||
|
// VDD (3.3V) goes high at start, lets just chill for a ms
|
||||||
|
delay(1);
|
||||||
|
// bring reset low
|
||||||
|
digitalWrite(rst, LOW);
|
||||||
|
// wait 10ms
|
||||||
|
delay(10);
|
||||||
|
// bring out of reset
|
||||||
|
digitalWrite(rst, HIGH);
|
||||||
|
// turn on VCC (9V?)
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t ret;
|
||||||
|
// Init sequence
|
||||||
|
LOG("Sending LCD display off");
|
||||||
|
ret=ssd1306_command(SSD1306_DISPLAYOFF); // 0xAE
|
||||||
|
LOG("Display off returned %d",ret);
|
||||||
|
if (ret != 0)
|
||||||
|
{
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
ssd1306_command(SSD1306_SETDISPLAYCLOCKDIV); // 0xD5
|
||||||
|
ssd1306_command(0x80); // the suggested ratio 0x80
|
||||||
|
|
||||||
|
ssd1306_command(SSD1306_SETMULTIPLEX); // 0xA8
|
||||||
|
ssd1306_command(SSD1306_LCDHEIGHT - 1);
|
||||||
|
|
||||||
|
ssd1306_command(SSD1306_SETDISPLAYOFFSET); // 0xD3
|
||||||
|
ssd1306_command(0x0); // no offset
|
||||||
|
ssd1306_command(SSD1306_SETSTARTLINE | 0x0); // line #0
|
||||||
|
ssd1306_command(SSD1306_CHARGEPUMP); // 0x8D
|
||||||
|
if (vccstate == SSD1306_EXTERNALVCC)
|
||||||
|
{ ssd1306_command(0x10); }
|
||||||
|
else
|
||||||
|
{ ssd1306_command(0x14); }
|
||||||
|
ssd1306_command(SSD1306_MEMORYMODE); // 0x20
|
||||||
|
ssd1306_command(0x00); // 0x0 act like ks0108
|
||||||
|
ssd1306_command(SSD1306_SEGREMAP | 0x1);
|
||||||
|
ssd1306_command(SSD1306_COMSCANDEC);
|
||||||
|
|
||||||
|
#if defined SSD1306_128_32
|
||||||
|
ssd1306_command(SSD1306_SETCOMPINS); // 0xDA
|
||||||
|
ssd1306_command(0x02);
|
||||||
|
ssd1306_command(SSD1306_SETCONTRAST); // 0x81
|
||||||
|
ssd1306_command(0x8F);
|
||||||
|
|
||||||
|
#elif defined SSD1306_128_64
|
||||||
|
ssd1306_command(SSD1306_SETCOMPINS); // 0xDA
|
||||||
|
ssd1306_command(0x12);
|
||||||
|
ssd1306_command(SSD1306_SETCONTRAST); // 0x81
|
||||||
|
if (vccstate == SSD1306_EXTERNALVCC)
|
||||||
|
{ ssd1306_command(0x9F); }
|
||||||
|
else
|
||||||
|
{ ssd1306_command(0xCF); }
|
||||||
|
|
||||||
|
#elif defined SSD1306_96_16
|
||||||
|
ssd1306_command(SSD1306_SETCOMPINS); // 0xDA
|
||||||
|
ssd1306_command(0x2); //ada x12
|
||||||
|
ssd1306_command(SSD1306_SETCONTRAST); // 0x81
|
||||||
|
if (vccstate == SSD1306_EXTERNALVCC)
|
||||||
|
{ ssd1306_command(0x10); }
|
||||||
|
else
|
||||||
|
{ ssd1306_command(0xAF); }
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
ssd1306_command(SSD1306_SETPRECHARGE); // 0xd9
|
||||||
|
if (vccstate == SSD1306_EXTERNALVCC)
|
||||||
|
{ ssd1306_command(0x22); }
|
||||||
|
else
|
||||||
|
{ ssd1306_command(0xF1); }
|
||||||
|
ssd1306_command(SSD1306_SETVCOMDETECT); // 0xDB
|
||||||
|
ssd1306_command(0x40);
|
||||||
|
ssd1306_command(SSD1306_DISPLAYALLON_RESUME); // 0xA4
|
||||||
|
ssd1306_command(SSD1306_NORMALDISPLAY); // 0xA6
|
||||||
|
|
||||||
|
ssd1306_command(SSD1306_DEACTIVATE_SCROLL);
|
||||||
|
|
||||||
|
ssd1306_command(SSD1306_DISPLAYON);//--turn on oled panel
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void Adafruit_SSD1306::invertDisplay(uint8_t i) {
|
||||||
|
if (i) {
|
||||||
|
ssd1306_command(SSD1306_INVERTDISPLAY);
|
||||||
|
} else {
|
||||||
|
ssd1306_command(SSD1306_NORMALDISPLAY);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Errors:
|
||||||
|
// 0 : Success
|
||||||
|
// 1 : Data too long
|
||||||
|
// 2 : NACK on transmit of address
|
||||||
|
// 3 : NACK on transmit of data
|
||||||
|
// 4 : Other error
|
||||||
|
uint8_t Adafruit_SSD1306::ssd1306_command(uint8_t c) {
|
||||||
|
if (sid != -1)
|
||||||
|
{
|
||||||
|
// SPI
|
||||||
|
#ifdef HAVE_PORTREG
|
||||||
|
*csport |= cspinmask;
|
||||||
|
*dcport &= ~dcpinmask;
|
||||||
|
*csport &= ~cspinmask;
|
||||||
|
#else
|
||||||
|
digitalWrite(cs, HIGH);
|
||||||
|
digitalWrite(dc, LOW);
|
||||||
|
digitalWrite(cs, LOW);
|
||||||
|
#endif
|
||||||
|
fastSPIwrite(c);
|
||||||
|
#ifdef HAVE_PORTREG
|
||||||
|
*csport |= cspinmask;
|
||||||
|
#else
|
||||||
|
digitalWrite(cs, HIGH);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
// I2C
|
||||||
|
uint8_t control = 0x00; // Co = 0, D/C = 0
|
||||||
|
//LOG("wire begin");
|
||||||
|
Wire.beginTransmission(_i2caddr);
|
||||||
|
//LOG("wire write");
|
||||||
|
Wire.write(control);
|
||||||
|
//LOG("wire write c");
|
||||||
|
Wire.write(c);
|
||||||
|
//LOG("wire end");
|
||||||
|
Wire.endTransmission();
|
||||||
|
//LOG("wire done");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// startscrollright
|
||||||
|
// Activate a right handed scroll for rows start through stop
|
||||||
|
// Hint, the display is 16 rows tall. To scroll the whole display, run:
|
||||||
|
// display.scrollright(0x00, 0x0F)
|
||||||
|
void Adafruit_SSD1306::startscrollright(uint8_t start, uint8_t stop){
|
||||||
|
ssd1306_command(SSD1306_RIGHT_HORIZONTAL_SCROLL);
|
||||||
|
ssd1306_command(0X00);
|
||||||
|
ssd1306_command(start);
|
||||||
|
ssd1306_command(0X00);
|
||||||
|
ssd1306_command(stop);
|
||||||
|
ssd1306_command(0X00);
|
||||||
|
ssd1306_command(0XFF);
|
||||||
|
ssd1306_command(SSD1306_ACTIVATE_SCROLL);
|
||||||
|
}
|
||||||
|
|
||||||
|
// startscrollleft
|
||||||
|
// Activate a right handed scroll for rows start through stop
|
||||||
|
// Hint, the display is 16 rows tall. To scroll the whole display, run:
|
||||||
|
// display.scrollright(0x00, 0x0F)
|
||||||
|
void Adafruit_SSD1306::startscrollleft(uint8_t start, uint8_t stop){
|
||||||
|
ssd1306_command(SSD1306_LEFT_HORIZONTAL_SCROLL);
|
||||||
|
ssd1306_command(0X00);
|
||||||
|
ssd1306_command(start);
|
||||||
|
ssd1306_command(0X00);
|
||||||
|
ssd1306_command(stop);
|
||||||
|
ssd1306_command(0X00);
|
||||||
|
ssd1306_command(0XFF);
|
||||||
|
ssd1306_command(SSD1306_ACTIVATE_SCROLL);
|
||||||
|
}
|
||||||
|
|
||||||
|
// startscrolldiagright
|
||||||
|
// Activate a diagonal scroll for rows start through stop
|
||||||
|
// Hint, the display is 16 rows tall. To scroll the whole display, run:
|
||||||
|
// display.scrollright(0x00, 0x0F)
|
||||||
|
void Adafruit_SSD1306::startscrolldiagright(uint8_t start, uint8_t stop){
|
||||||
|
ssd1306_command(SSD1306_SET_VERTICAL_SCROLL_AREA);
|
||||||
|
ssd1306_command(0X00);
|
||||||
|
ssd1306_command(SSD1306_LCDHEIGHT);
|
||||||
|
ssd1306_command(SSD1306_VERTICAL_AND_RIGHT_HORIZONTAL_SCROLL);
|
||||||
|
ssd1306_command(0X00);
|
||||||
|
ssd1306_command(start);
|
||||||
|
ssd1306_command(0X00);
|
||||||
|
ssd1306_command(stop);
|
||||||
|
ssd1306_command(0X01);
|
||||||
|
ssd1306_command(SSD1306_ACTIVATE_SCROLL);
|
||||||
|
}
|
||||||
|
|
||||||
|
// startscrolldiagleft
|
||||||
|
// Activate a diagonal scroll for rows start through stop
|
||||||
|
// Hint, the display is 16 rows tall. To scroll the whole display, run:
|
||||||
|
// display.scrollright(0x00, 0x0F)
|
||||||
|
void Adafruit_SSD1306::startscrolldiagleft(uint8_t start, uint8_t stop){
|
||||||
|
ssd1306_command(SSD1306_SET_VERTICAL_SCROLL_AREA);
|
||||||
|
ssd1306_command(0X00);
|
||||||
|
ssd1306_command(SSD1306_LCDHEIGHT);
|
||||||
|
ssd1306_command(SSD1306_VERTICAL_AND_LEFT_HORIZONTAL_SCROLL);
|
||||||
|
ssd1306_command(0X00);
|
||||||
|
ssd1306_command(start);
|
||||||
|
ssd1306_command(0X00);
|
||||||
|
ssd1306_command(stop);
|
||||||
|
ssd1306_command(0X01);
|
||||||
|
ssd1306_command(SSD1306_ACTIVATE_SCROLL);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Adafruit_SSD1306::stopscroll(void){
|
||||||
|
ssd1306_command(SSD1306_DEACTIVATE_SCROLL);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Dim the display
|
||||||
|
// dim = true: display is dimmed
|
||||||
|
// dim = false: display is normal
|
||||||
|
void Adafruit_SSD1306::dim(boolean dim) {
|
||||||
|
uint8_t contrast;
|
||||||
|
|
||||||
|
if (dim) {
|
||||||
|
contrast = 0; // Dimmed display
|
||||||
|
} else {
|
||||||
|
if (_vccstate == SSD1306_EXTERNALVCC) {
|
||||||
|
contrast = 0x9F;
|
||||||
|
} else {
|
||||||
|
contrast = 0xCF;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// the range of contrast to too small to be really useful
|
||||||
|
// it is useful to dim the display
|
||||||
|
ssd1306_command(SSD1306_SETCONTRAST);
|
||||||
|
ssd1306_command(contrast);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Adafruit_SSD1306::display(void) {
|
||||||
|
ssd1306_command(SSD1306_COLUMNADDR);
|
||||||
|
ssd1306_command(0); // Column start address (0 = reset)
|
||||||
|
ssd1306_command(SSD1306_LCDWIDTH-1); // Column end address (127 = reset)
|
||||||
|
|
||||||
|
ssd1306_command(SSD1306_PAGEADDR);
|
||||||
|
ssd1306_command(0); // Page start address (0 = reset)
|
||||||
|
#if SSD1306_LCDHEIGHT == 64
|
||||||
|
ssd1306_command(7); // Page end address
|
||||||
|
#endif
|
||||||
|
#if SSD1306_LCDHEIGHT == 32
|
||||||
|
ssd1306_command(3); // Page end address
|
||||||
|
#endif
|
||||||
|
#if SSD1306_LCDHEIGHT == 16
|
||||||
|
ssd1306_command(1); // Page end address
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (sid != -1)
|
||||||
|
{
|
||||||
|
// SPI
|
||||||
|
#ifdef HAVE_PORTREG
|
||||||
|
*csport |= cspinmask;
|
||||||
|
*dcport |= dcpinmask;
|
||||||
|
*csport &= ~cspinmask;
|
||||||
|
#else
|
||||||
|
digitalWrite(cs, HIGH);
|
||||||
|
digitalWrite(dc, HIGH);
|
||||||
|
digitalWrite(cs, LOW);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
for (uint16_t i=0; i<(SSD1306_LCDWIDTH*SSD1306_LCDHEIGHT/8); i++) {
|
||||||
|
fastSPIwrite(buffer[i]);
|
||||||
|
}
|
||||||
|
#ifdef HAVE_PORTREG
|
||||||
|
*csport |= cspinmask;
|
||||||
|
#else
|
||||||
|
digitalWrite(cs, HIGH);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
// save I2C bitrate
|
||||||
|
#ifdef TWBR
|
||||||
|
uint8_t twbrbackup = TWBR;
|
||||||
|
TWBR = 12; // upgrade to 400KHz!
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//Serial.println(TWBR, DEC);
|
||||||
|
//Serial.println(TWSR & 0x3, DEC);
|
||||||
|
|
||||||
|
// I2C
|
||||||
|
for (uint16_t i=0; i<(SSD1306_LCDWIDTH*SSD1306_LCDHEIGHT/8); i++) {
|
||||||
|
// send a bunch of data in one xmission
|
||||||
|
Wire.beginTransmission(_i2caddr);
|
||||||
|
WIRE_WRITE(0x40);
|
||||||
|
for (uint8_t x=0; x<16; x++) {
|
||||||
|
WIRE_WRITE(buffer[i]);
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
i--;
|
||||||
|
Wire.endTransmission();
|
||||||
|
}
|
||||||
|
#ifdef TWBR
|
||||||
|
TWBR = twbrbackup;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// clear everything
|
||||||
|
void Adafruit_SSD1306::clearDisplay(void) {
|
||||||
|
memset(buffer, 0, (SSD1306_LCDWIDTH*SSD1306_LCDHEIGHT/8));
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
inline void Adafruit_SSD1306::fastSPIwrite(uint8_t d) {
|
||||||
|
|
||||||
|
if(hwSPI) {
|
||||||
|
(void)SPI.transfer(d);
|
||||||
|
} else {
|
||||||
|
for(uint8_t bit = 0x80; bit; bit >>= 1) {
|
||||||
|
#ifdef HAVE_PORTREG
|
||||||
|
*clkport &= ~clkpinmask;
|
||||||
|
if(d & bit) *mosiport |= mosipinmask;
|
||||||
|
else *mosiport &= ~mosipinmask;
|
||||||
|
*clkport |= clkpinmask;
|
||||||
|
#else
|
||||||
|
digitalWrite(sclk, LOW);
|
||||||
|
if(d & bit) digitalWrite(sid, HIGH);
|
||||||
|
else digitalWrite(sid, LOW);
|
||||||
|
digitalWrite(sclk, HIGH);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void Adafruit_SSD1306::drawFastHLine(int16_t x, int16_t y, int16_t w, uint16_t color) {
|
||||||
|
boolean bSwap = false;
|
||||||
|
switch(rotation) {
|
||||||
|
case 0:
|
||||||
|
// 0 degree rotation, do nothing
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
// 90 degree rotation, swap x & y for rotation, then invert x
|
||||||
|
bSwap = true;
|
||||||
|
ssd1306_swap(x, y);
|
||||||
|
x = WIDTH - x - 1;
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
// 180 degree rotation, invert x and y - then shift y around for height.
|
||||||
|
x = WIDTH - x - 1;
|
||||||
|
y = HEIGHT - y - 1;
|
||||||
|
x -= (w-1);
|
||||||
|
break;
|
||||||
|
case 3:
|
||||||
|
// 270 degree rotation, swap x & y for rotation, then invert y and adjust y for w (not to become h)
|
||||||
|
bSwap = true;
|
||||||
|
ssd1306_swap(x, y);
|
||||||
|
y = HEIGHT - y - 1;
|
||||||
|
y -= (w-1);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
if(bSwap) {
|
||||||
|
drawFastVLineInternal(x, y, w, color);
|
||||||
|
} else {
|
||||||
|
drawFastHLineInternal(x, y, w, color);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void Adafruit_SSD1306::drawFastHLineInternal(int16_t x, int16_t y, int16_t w, uint16_t color) {
|
||||||
|
// Do bounds/limit checks
|
||||||
|
if(y < 0 || y >= HEIGHT) { return; }
|
||||||
|
|
||||||
|
// make sure we don't try to draw below 0
|
||||||
|
if(x < 0) {
|
||||||
|
w += x;
|
||||||
|
x = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// make sure we don't go off the edge of the display
|
||||||
|
if( (x + w) > WIDTH) {
|
||||||
|
w = (WIDTH - x);
|
||||||
|
}
|
||||||
|
|
||||||
|
// if our width is now negative, punt
|
||||||
|
if(w <= 0) { return; }
|
||||||
|
|
||||||
|
// set up the pointer for movement through the buffer
|
||||||
|
register uint8_t *pBuf = buffer;
|
||||||
|
// adjust the buffer pointer for the current row
|
||||||
|
pBuf += ((y/8) * SSD1306_LCDWIDTH);
|
||||||
|
// and offset x columns in
|
||||||
|
pBuf += x;
|
||||||
|
|
||||||
|
register uint8_t mask = 1 << (y&7);
|
||||||
|
|
||||||
|
switch (color)
|
||||||
|
{
|
||||||
|
case WHITE: while(w--) { *pBuf++ |= mask; }; break;
|
||||||
|
case BLACK: mask = ~mask; while(w--) { *pBuf++ &= mask; }; break;
|
||||||
|
case INVERSE: while(w--) { *pBuf++ ^= mask; }; break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void Adafruit_SSD1306::drawFastVLine(int16_t x, int16_t y, int16_t h, uint16_t color) {
|
||||||
|
bool bSwap = false;
|
||||||
|
switch(rotation) {
|
||||||
|
case 0:
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
// 90 degree rotation, swap x & y for rotation, then invert x and adjust x for h (now to become w)
|
||||||
|
bSwap = true;
|
||||||
|
ssd1306_swap(x, y);
|
||||||
|
x = WIDTH - x - 1;
|
||||||
|
x -= (h-1);
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
// 180 degree rotation, invert x and y - then shift y around for height.
|
||||||
|
x = WIDTH - x - 1;
|
||||||
|
y = HEIGHT - y - 1;
|
||||||
|
y -= (h-1);
|
||||||
|
break;
|
||||||
|
case 3:
|
||||||
|
// 270 degree rotation, swap x & y for rotation, then invert y
|
||||||
|
bSwap = true;
|
||||||
|
ssd1306_swap(x, y);
|
||||||
|
y = HEIGHT - y - 1;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
if(bSwap) {
|
||||||
|
drawFastHLineInternal(x, y, h, color);
|
||||||
|
} else {
|
||||||
|
drawFastVLineInternal(x, y, h, color);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void Adafruit_SSD1306::drawFastVLineInternal(int16_t x, int16_t __y, int16_t __h, uint16_t color) {
|
||||||
|
|
||||||
|
// do nothing if we're off the left or right side of the screen
|
||||||
|
if(x < 0 || x >= WIDTH) { return; }
|
||||||
|
|
||||||
|
// make sure we don't try to draw below 0
|
||||||
|
if(__y < 0) {
|
||||||
|
// __y is negative, this will subtract enough from __h to account for __y being 0
|
||||||
|
__h += __y;
|
||||||
|
__y = 0;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// make sure we don't go past the height of the display
|
||||||
|
if( (__y + __h) > HEIGHT) {
|
||||||
|
__h = (HEIGHT - __y);
|
||||||
|
}
|
||||||
|
|
||||||
|
// if our height is now negative, punt
|
||||||
|
if(__h <= 0) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// this display doesn't need ints for coordinates, use local byte registers for faster juggling
|
||||||
|
register uint8_t y = __y;
|
||||||
|
register uint8_t h = __h;
|
||||||
|
|
||||||
|
|
||||||
|
// set up the pointer for fast movement through the buffer
|
||||||
|
register uint8_t *pBuf = buffer;
|
||||||
|
// adjust the buffer pointer for the current row
|
||||||
|
pBuf += ((y/8) * SSD1306_LCDWIDTH);
|
||||||
|
// and offset x columns in
|
||||||
|
pBuf += x;
|
||||||
|
|
||||||
|
// do the first partial byte, if necessary - this requires some masking
|
||||||
|
register uint8_t mod = (y&7);
|
||||||
|
if(mod) {
|
||||||
|
// mask off the high n bits we want to set
|
||||||
|
mod = 8-mod;
|
||||||
|
|
||||||
|
// note - lookup table results in a nearly 10% performance improvement in fill* functions
|
||||||
|
// register uint8_t mask = ~(0xFF >> (mod));
|
||||||
|
static uint8_t premask[8] = {0x00, 0x80, 0xC0, 0xE0, 0xF0, 0xF8, 0xFC, 0xFE };
|
||||||
|
register uint8_t mask = premask[mod];
|
||||||
|
|
||||||
|
// adjust the mask if we're not going to reach the end of this byte
|
||||||
|
if( h < mod) {
|
||||||
|
mask &= (0XFF >> (mod-h));
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (color)
|
||||||
|
{
|
||||||
|
case WHITE: *pBuf |= mask; break;
|
||||||
|
case BLACK: *pBuf &= ~mask; break;
|
||||||
|
case INVERSE: *pBuf ^= mask; break;
|
||||||
|
}
|
||||||
|
|
||||||
|
// fast exit if we're done here!
|
||||||
|
if(h<mod) { return; }
|
||||||
|
|
||||||
|
h -= mod;
|
||||||
|
|
||||||
|
pBuf += SSD1306_LCDWIDTH;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// write solid bytes while we can - effectively doing 8 rows at a time
|
||||||
|
if(h >= 8) {
|
||||||
|
if (color == INVERSE) { // separate copy of the code so we don't impact performance of the black/white write version with an extra comparison per loop
|
||||||
|
do {
|
||||||
|
*pBuf=~(*pBuf);
|
||||||
|
|
||||||
|
// adjust the buffer forward 8 rows worth of data
|
||||||
|
pBuf += SSD1306_LCDWIDTH;
|
||||||
|
|
||||||
|
// adjust h & y (there's got to be a faster way for me to do this, but this should still help a fair bit for now)
|
||||||
|
h -= 8;
|
||||||
|
} while(h >= 8);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
// store a local value to work with
|
||||||
|
register uint8_t val = (color == WHITE) ? 255 : 0;
|
||||||
|
|
||||||
|
do {
|
||||||
|
// write our value in
|
||||||
|
*pBuf = val;
|
||||||
|
|
||||||
|
// adjust the buffer forward 8 rows worth of data
|
||||||
|
pBuf += SSD1306_LCDWIDTH;
|
||||||
|
|
||||||
|
// adjust h & y (there's got to be a faster way for me to do this, but this should still help a fair bit for now)
|
||||||
|
h -= 8;
|
||||||
|
} while(h >= 8);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// now do the final partial byte, if necessary
|
||||||
|
if(h) {
|
||||||
|
mod = h & 7;
|
||||||
|
// this time we want to mask the low bits of the byte, vs the high bits we did above
|
||||||
|
// register uint8_t mask = (1 << mod) - 1;
|
||||||
|
// note - lookup table results in a nearly 10% performance improvement in fill* functions
|
||||||
|
static uint8_t postmask[8] = {0x00, 0x01, 0x03, 0x07, 0x0F, 0x1F, 0x3F, 0x7F };
|
||||||
|
register uint8_t mask = postmask[mod];
|
||||||
|
switch (color)
|
||||||
|
{
|
||||||
|
case WHITE: *pBuf |= mask; break;
|
||||||
|
case BLACK: *pBuf &= ~mask; break;
|
||||||
|
case INVERSE: *pBuf ^= mask; break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
@ -0,0 +1,182 @@
|
|||||||
|
/*********************************************************************
|
||||||
|
This is a library for our Monochrome OLEDs based on SSD1306 drivers
|
||||||
|
|
||||||
|
Pick one up today in the adafruit shop!
|
||||||
|
------> http://www.adafruit.com/category/63_98
|
||||||
|
|
||||||
|
These displays use SPI to communicate, 4 or 5 pins are required to
|
||||||
|
interface
|
||||||
|
|
||||||
|
Adafruit invests time and resources providing this open source code,
|
||||||
|
please support Adafruit and open-source hardware by purchasing
|
||||||
|
products from Adafruit!
|
||||||
|
|
||||||
|
Written by Limor Fried/Ladyada for Adafruit Industries.
|
||||||
|
BSD license, check license.txt for more information
|
||||||
|
All text above, and the splash screen must be included in any redistribution
|
||||||
|
*********************************************************************/
|
||||||
|
#ifndef _Adafruit_SSD1306_H_
|
||||||
|
#define _Adafruit_SSD1306_H_
|
||||||
|
|
||||||
|
#if ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#define WIRE_WRITE Wire.write
|
||||||
|
#else
|
||||||
|
#include "WProgram.h"
|
||||||
|
#define WIRE_WRITE Wire.send
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(__SAM3X8E__)
|
||||||
|
typedef volatile RwReg PortReg;
|
||||||
|
typedef uint32_t PortMask;
|
||||||
|
#define HAVE_PORTREG
|
||||||
|
#elif defined(ARDUINO_ARCH_SAMD)
|
||||||
|
// not supported
|
||||||
|
#elif defined(ESP8266) || defined(ARDUINO_STM32_FEATHER)
|
||||||
|
typedef volatile uint32_t PortReg;
|
||||||
|
typedef uint32_t PortMask;
|
||||||
|
#else
|
||||||
|
typedef volatile uint8_t PortReg;
|
||||||
|
typedef uint8_t PortMask;
|
||||||
|
#define HAVE_PORTREG
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <SPI.h>
|
||||||
|
#include "Adafruit_GFX.h"
|
||||||
|
|
||||||
|
#define BLACK 0
|
||||||
|
#define WHITE 1
|
||||||
|
#define INVERSE 2
|
||||||
|
|
||||||
|
#define SSD1306_I2C_ADDRESS 0x3C // 011110+SA0+RW - 0x3C or 0x3D
|
||||||
|
// Address for 128x32 is 0x3C
|
||||||
|
// Address for 128x64 is 0x3D (default) or 0x3C (if SA0 is grounded)
|
||||||
|
|
||||||
|
/*=========================================================================
|
||||||
|
SSD1306 Displays
|
||||||
|
-----------------------------------------------------------------------
|
||||||
|
The driver is used in multiple displays (128x64, 128x32, etc.).
|
||||||
|
Select the appropriate display below to create an appropriately
|
||||||
|
sized framebuffer, etc.
|
||||||
|
|
||||||
|
SSD1306_128_64 128x64 pixel display
|
||||||
|
|
||||||
|
SSD1306_128_32 128x32 pixel display
|
||||||
|
|
||||||
|
SSD1306_96_16
|
||||||
|
|
||||||
|
-----------------------------------------------------------------------*/
|
||||||
|
#define SSD1306_128_64
|
||||||
|
// #define SSD1306_128_32
|
||||||
|
// #define SSD1306_96_16
|
||||||
|
/*=========================================================================*/
|
||||||
|
|
||||||
|
#if defined SSD1306_128_64 && defined SSD1306_128_32
|
||||||
|
#error "Only one SSD1306 display can be specified at once in SSD1306.h"
|
||||||
|
#endif
|
||||||
|
#if !defined SSD1306_128_64 && !defined SSD1306_128_32 && !defined SSD1306_96_16
|
||||||
|
#error "At least one SSD1306 display must be specified in SSD1306.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined SSD1306_128_64
|
||||||
|
#define SSD1306_LCDWIDTH 128
|
||||||
|
#define SSD1306_LCDHEIGHT 64
|
||||||
|
#endif
|
||||||
|
#if defined SSD1306_128_32
|
||||||
|
#define SSD1306_LCDWIDTH 128
|
||||||
|
#define SSD1306_LCDHEIGHT 32
|
||||||
|
#endif
|
||||||
|
#if defined SSD1306_96_16
|
||||||
|
#define SSD1306_LCDWIDTH 96
|
||||||
|
#define SSD1306_LCDHEIGHT 16
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define SSD1306_SETCONTRAST 0x81
|
||||||
|
#define SSD1306_DISPLAYALLON_RESUME 0xA4
|
||||||
|
#define SSD1306_DISPLAYALLON 0xA5
|
||||||
|
#define SSD1306_NORMALDISPLAY 0xA6
|
||||||
|
#define SSD1306_INVERTDISPLAY 0xA7
|
||||||
|
#define SSD1306_DISPLAYOFF 0xAE
|
||||||
|
#define SSD1306_DISPLAYON 0xAF
|
||||||
|
|
||||||
|
#define SSD1306_SETDISPLAYOFFSET 0xD3
|
||||||
|
#define SSD1306_SETCOMPINS 0xDA
|
||||||
|
|
||||||
|
#define SSD1306_SETVCOMDETECT 0xDB
|
||||||
|
|
||||||
|
#define SSD1306_SETDISPLAYCLOCKDIV 0xD5
|
||||||
|
#define SSD1306_SETPRECHARGE 0xD9
|
||||||
|
|
||||||
|
#define SSD1306_SETMULTIPLEX 0xA8
|
||||||
|
|
||||||
|
#define SSD1306_SETLOWCOLUMN 0x00
|
||||||
|
#define SSD1306_SETHIGHCOLUMN 0x10
|
||||||
|
|
||||||
|
#define SSD1306_SETSTARTLINE 0x40
|
||||||
|
|
||||||
|
#define SSD1306_MEMORYMODE 0x20
|
||||||
|
#define SSD1306_COLUMNADDR 0x21
|
||||||
|
#define SSD1306_PAGEADDR 0x22
|
||||||
|
|
||||||
|
#define SSD1306_COMSCANINC 0xC0
|
||||||
|
#define SSD1306_COMSCANDEC 0xC8
|
||||||
|
|
||||||
|
#define SSD1306_SEGREMAP 0xA0
|
||||||
|
|
||||||
|
#define SSD1306_CHARGEPUMP 0x8D
|
||||||
|
|
||||||
|
#define SSD1306_EXTERNALVCC 0x1
|
||||||
|
#define SSD1306_SWITCHCAPVCC 0x2
|
||||||
|
|
||||||
|
// Scrolling #defines
|
||||||
|
#define SSD1306_ACTIVATE_SCROLL 0x2F
|
||||||
|
#define SSD1306_DEACTIVATE_SCROLL 0x2E
|
||||||
|
#define SSD1306_SET_VERTICAL_SCROLL_AREA 0xA3
|
||||||
|
#define SSD1306_RIGHT_HORIZONTAL_SCROLL 0x26
|
||||||
|
#define SSD1306_LEFT_HORIZONTAL_SCROLL 0x27
|
||||||
|
#define SSD1306_VERTICAL_AND_RIGHT_HORIZONTAL_SCROLL 0x29
|
||||||
|
#define SSD1306_VERTICAL_AND_LEFT_HORIZONTAL_SCROLL 0x2A
|
||||||
|
|
||||||
|
class Adafruit_SSD1306 : public Adafruit_GFX {
|
||||||
|
public:
|
||||||
|
Adafruit_SSD1306(int8_t SID, int8_t SCLK, int8_t DC, int8_t RST, int8_t CS);
|
||||||
|
Adafruit_SSD1306(int8_t DC, int8_t RST, int8_t CS);
|
||||||
|
Adafruit_SSD1306(int8_t RST = -1);
|
||||||
|
|
||||||
|
bool begin(uint8_t switchvcc = SSD1306_SWITCHCAPVCC, uint8_t i2caddr = SSD1306_I2C_ADDRESS, bool reset=true);
|
||||||
|
uint8_t ssd1306_command(uint8_t c);
|
||||||
|
|
||||||
|
void clearDisplay(void);
|
||||||
|
void invertDisplay(uint8_t i);
|
||||||
|
void display();
|
||||||
|
|
||||||
|
void startscrollright(uint8_t start, uint8_t stop);
|
||||||
|
void startscrollleft(uint8_t start, uint8_t stop);
|
||||||
|
|
||||||
|
void startscrolldiagright(uint8_t start, uint8_t stop);
|
||||||
|
void startscrolldiagleft(uint8_t start, uint8_t stop);
|
||||||
|
void stopscroll(void);
|
||||||
|
|
||||||
|
void dim(boolean dim);
|
||||||
|
|
||||||
|
void drawPixel(int16_t x, int16_t y, uint16_t color);
|
||||||
|
|
||||||
|
virtual void drawFastVLine(int16_t x, int16_t y, int16_t h, uint16_t color);
|
||||||
|
virtual void drawFastHLine(int16_t x, int16_t y, int16_t w, uint16_t color);
|
||||||
|
|
||||||
|
private:
|
||||||
|
int8_t _i2caddr, _vccstate, sid, sclk, dc, rst, cs;
|
||||||
|
void fastSPIwrite(uint8_t c);
|
||||||
|
|
||||||
|
boolean hwSPI;
|
||||||
|
#ifdef HAVE_PORTREG
|
||||||
|
PortReg *mosiport, *clkport, *csport, *dcport;
|
||||||
|
PortMask mosipinmask, clkpinmask, cspinmask, dcpinmask;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
inline void drawFastVLineInternal(int16_t x, int16_t y, int16_t h, uint16_t color) __attribute__((always_inline));
|
||||||
|
inline void drawFastHLineInternal(int16_t x, int16_t y, int16_t w, uint16_t color) __attribute__((always_inline));
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* _Adafruit_SSD1306_H_ */
|
192
firmware_smartstepper_trikarus/stepper_nano_zero/Flash.cpp
Normal file
@ -0,0 +1,192 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#include "Flash.h"
|
||||||
|
#include "syslog.h"
|
||||||
|
|
||||||
|
bool flashInit(void){
|
||||||
|
if (NVMCTRL->PARAM.bit.PSZ != 3)
|
||||||
|
{
|
||||||
|
ERROR("FLASH PAGE SIZE is not 64 bytes");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
static void erase(const volatile void *flash_ptr)
|
||||||
|
{
|
||||||
|
NVMCTRL->ADDR.reg = ((uint32_t)flash_ptr) / 2;
|
||||||
|
NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_ER;
|
||||||
|
while (!NVMCTRL->INTFLAG.bit.READY) { }
|
||||||
|
}
|
||||||
|
|
||||||
|
bool flashErase(const volatile void *flash_ptr, uint32_t size)
|
||||||
|
{
|
||||||
|
const uint8_t *ptr = (const uint8_t *)flash_ptr;
|
||||||
|
while (size > FLASH_ROW_SIZE) {
|
||||||
|
erase(ptr);
|
||||||
|
ptr += FLASH_ROW_SIZE;
|
||||||
|
size -= FLASH_ROW_SIZE;
|
||||||
|
}
|
||||||
|
if (size>0)
|
||||||
|
{
|
||||||
|
erase(ptr);
|
||||||
|
}
|
||||||
|
return true; //TODO should verify the erase
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline uint32_t read_unaligned_uint32(const void *data)
|
||||||
|
{
|
||||||
|
union {
|
||||||
|
uint32_t u32;
|
||||||
|
uint8_t u8[4];
|
||||||
|
} res;
|
||||||
|
const uint8_t *d = (const uint8_t *)data;
|
||||||
|
res.u8[0] = d[0];
|
||||||
|
res.u8[1] = d[1];
|
||||||
|
res.u8[2] = d[2];
|
||||||
|
res.u8[3] = d[3];
|
||||||
|
return res.u32;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void flashWrite(const volatile void *flash_ptr,const void *data, uint32_t size)
|
||||||
|
{
|
||||||
|
uint32_t *ptrPage;
|
||||||
|
uint8_t *destPtr;
|
||||||
|
uint8_t *srcPtr;
|
||||||
|
uint32_t bytesInBlock;
|
||||||
|
__attribute__((__aligned__(4))) uint8_t buffer[FLASH_ROW_SIZE];
|
||||||
|
uint32_t offset;
|
||||||
|
|
||||||
|
destPtr=(uint8_t *)flash_ptr;
|
||||||
|
srcPtr=(uint8_t *)data;
|
||||||
|
|
||||||
|
//LOG("flash write called");
|
||||||
|
while(size>0)
|
||||||
|
{
|
||||||
|
uint32_t i,j;
|
||||||
|
|
||||||
|
//calculate the maximum number of bytes we can write in page
|
||||||
|
offset=((uint32_t)destPtr)%(FLASH_ROW_SIZE); //offset into page
|
||||||
|
bytesInBlock=FLASH_ROW_SIZE-offset; //this is how many bytes we need to overwrite in this page
|
||||||
|
|
||||||
|
//LOG("offset %d, bytesInBlock %d size %d", offset, bytesInBlock,size);
|
||||||
|
//get pointer to start of page
|
||||||
|
ptrPage=(uint32_t *) ((((uint32_t)destPtr)/(FLASH_ROW_SIZE)) * FLASH_ROW_SIZE);
|
||||||
|
|
||||||
|
//LOG("pointer to page %d(0x%08x) %d",(uint32_t)ptrPage,(uint32_t)ptrPage,destPtr);
|
||||||
|
|
||||||
|
//fill page buffer with data from flash
|
||||||
|
memcpy(buffer,ptrPage,FLASH_ROW_SIZE);
|
||||||
|
|
||||||
|
//now fill buffer with new data that needs changing
|
||||||
|
i=bytesInBlock;
|
||||||
|
if (size<i)
|
||||||
|
{
|
||||||
|
i=size;
|
||||||
|
}
|
||||||
|
//LOG("changing %d bytes",i);
|
||||||
|
memcpy(&buffer[offset],srcPtr,i);
|
||||||
|
|
||||||
|
//erase page
|
||||||
|
flashErase(ptrPage,FLASH_ROW_SIZE);
|
||||||
|
//write new data to flash
|
||||||
|
flashWritePage(ptrPage,buffer,FLASH_ROW_SIZE);
|
||||||
|
|
||||||
|
uint32_t *ptr=(uint32_t *)buffer;
|
||||||
|
for (j=0; j<FLASH_ROW_SIZE/4; j++)
|
||||||
|
{
|
||||||
|
if (*ptrPage != *ptr)
|
||||||
|
{
|
||||||
|
ERROR("write failed on byte %d %x %x",j,*ptrPage, *ptr);
|
||||||
|
}
|
||||||
|
ptrPage++;
|
||||||
|
ptr++;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
size=size-i; //decrease number of bytes to write
|
||||||
|
srcPtr+=i; //increase pointer to next bytes to read
|
||||||
|
destPtr+=i; //increment destination pointer
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void flashWritePage(const volatile void *flash_ptr, const void *data, uint32_t size)
|
||||||
|
{
|
||||||
|
// Calculate data boundaries
|
||||||
|
size = (size + 3) / 4; //convert bytes to words with rounding
|
||||||
|
|
||||||
|
volatile uint32_t *dst_addr = (volatile uint32_t *)flash_ptr;
|
||||||
|
const uint8_t *src_addr = (uint8_t *)data;
|
||||||
|
|
||||||
|
if (0 != ((uint32_t)flash_ptr)%(FLASH_PAGE_SIZE))
|
||||||
|
{
|
||||||
|
ERROR("Flash page write must be on boundry");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Disable automatic page write
|
||||||
|
NVMCTRL->CTRLB.bit.MANW = 1;
|
||||||
|
|
||||||
|
// Do writes in pages
|
||||||
|
while (size)
|
||||||
|
{
|
||||||
|
// Execute "PBC" Page Buffer Clear
|
||||||
|
NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_PBC;
|
||||||
|
while (NVMCTRL->INTFLAG.bit.READY == 0) { }
|
||||||
|
|
||||||
|
// Fill page buffer
|
||||||
|
uint32_t i;
|
||||||
|
for (i=0; i<(FLASH_PAGE_SIZE/4) && size; i++) //we write 4 bytes at a time
|
||||||
|
{
|
||||||
|
*dst_addr = read_unaligned_uint32(src_addr);
|
||||||
|
src_addr += 4;
|
||||||
|
dst_addr++;
|
||||||
|
size--; //size is set to number of 32bit words in first line above
|
||||||
|
}
|
||||||
|
|
||||||
|
// Execute "WP" Write Page
|
||||||
|
NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_WP;
|
||||||
|
while (NVMCTRL->INTFLAG.bit.READY == 0) { }
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
68
firmware_smartstepper_trikarus/stepper_nano_zero/Flash.h
Normal file
@ -0,0 +1,68 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#ifndef __FLASH__H__
|
||||||
|
#define __FLASH__H__
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "syslog.h"
|
||||||
|
|
||||||
|
|
||||||
|
#define FLASH_PAGE_SIZE_NZS (64) //bytes
|
||||||
|
#define FLASH_ROW_SIZE (FLASH_PAGE_SIZE_NZS*4) //defined in the datasheet as 4x page size
|
||||||
|
#define FLASH_ERASE_VALUE (0xFF) //value of flash after an erase
|
||||||
|
|
||||||
|
#define FLASH_ALLOCATE(name, size) \
|
||||||
|
__attribute__((__aligned__(FLASH_ROW_SIZE))) \
|
||||||
|
const uint8_t name[(size+(FLASH_ROW_SIZE-1))/FLASH_ROW_SIZE*FLASH_ROW_SIZE] = { };
|
||||||
|
|
||||||
|
bool flashInit(void); //this checks that our assumptions are true
|
||||||
|
|
||||||
|
bool flashErase(const volatile void *flash_ptr, uint32_t size);
|
||||||
|
void flashWrite(const volatile void *flash_ptr,const void *data,uint32_t size);
|
||||||
|
void flashWritePage(const volatile void *flash_ptr, const void *data, uint32_t size);
|
||||||
|
|
||||||
|
//you can read by dereferencing pointer but we will add a read
|
||||||
|
static inline int32_t flashRead(const volatile void *flash_ptr, void *data, uint32_t size)
|
||||||
|
{
|
||||||
|
memcpy(data, (const void *)flash_ptr, size);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#endif //__FLASH__H__
|
147
firmware_smartstepper_trikarus/stepper_nano_zero/angle.h
Normal file
@ -0,0 +1,147 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
#ifndef ANGLE_H_
|
||||||
|
#define ANGLE_H_
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <math.h>
|
||||||
|
|
||||||
|
#define ANGLE_STEPS (0x010000UL)
|
||||||
|
#define ANGLE_MAX ((uint16_t)0x0FFFF)
|
||||||
|
|
||||||
|
#define ANGLE_FROM_DEGREES(x) ((int32_t) ( ((float)ANGLE_STEPS*(float)(x)+180.0)/360.0 ) )
|
||||||
|
#define ANGLE_T0_DEGREES(x) ( (float) ((float(x)*360.0)/((float)ANGLE_STEPS) ))
|
||||||
|
class Angle
|
||||||
|
{
|
||||||
|
private:
|
||||||
|
uint16_t angle;
|
||||||
|
public:
|
||||||
|
Angle(void) {angle=0;}
|
||||||
|
Angle(int32_t x) {angle=(uint16_t)x;}
|
||||||
|
Angle(const Angle &x) {angle=x.angle;}
|
||||||
|
|
||||||
|
int16_t operator-( const Angle &a2)
|
||||||
|
{
|
||||||
|
int32_t x,y,dx;
|
||||||
|
x=(int32_t)angle;
|
||||||
|
y=(int32_t)a2.angle;
|
||||||
|
dx=x-y;
|
||||||
|
if (abs(x-y)>ANGLE_STEPS/2)
|
||||||
|
{
|
||||||
|
//we have a wrap condition
|
||||||
|
if (x>y)
|
||||||
|
{
|
||||||
|
dx=x-(y+ANGLE_STEPS);
|
||||||
|
}else if (x<y)
|
||||||
|
{
|
||||||
|
dx=(ANGLE_STEPS+x)-y;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return (int16_t)dx;
|
||||||
|
}
|
||||||
|
//
|
||||||
|
// int16_t operator-( const int32_t y)
|
||||||
|
// {
|
||||||
|
// int32_t x,y,dx;
|
||||||
|
// x=(int32_t)angle;
|
||||||
|
// while(y>ANGLE_MAX)
|
||||||
|
// {
|
||||||
|
// y=y-ANGLE_STEPS;
|
||||||
|
// }
|
||||||
|
// while(y<-ANGLE_MAX)
|
||||||
|
// {
|
||||||
|
// y=y+ANGLE_STEPS;
|
||||||
|
// }
|
||||||
|
//
|
||||||
|
// dx=x-y;
|
||||||
|
// if (abs(x-y)>ANGLE_STEPS/2)
|
||||||
|
// {
|
||||||
|
// //we have a wrap condition
|
||||||
|
// if (x>y)
|
||||||
|
// {
|
||||||
|
// dx=x-(y+ANGLE_STEPS);
|
||||||
|
// }else if (x<y)
|
||||||
|
// {
|
||||||
|
// dx=(ANGLE_STEPS+x)-y;
|
||||||
|
// }
|
||||||
|
// }
|
||||||
|
// return (int16_t)dx;
|
||||||
|
// }
|
||||||
|
|
||||||
|
Angle operator+(const Angle &y)
|
||||||
|
{
|
||||||
|
uint16_t a;
|
||||||
|
a=angle+ (uint16_t)y.angle;
|
||||||
|
return Angle(a);
|
||||||
|
}
|
||||||
|
Angle operator+(const long int x)
|
||||||
|
{
|
||||||
|
int32_t a;
|
||||||
|
a=(int32_t)angle+ x;
|
||||||
|
while (a>=ANGLE_STEPS)
|
||||||
|
{
|
||||||
|
a=a-ANGLE_STEPS;
|
||||||
|
}
|
||||||
|
while (a<0)
|
||||||
|
{
|
||||||
|
a=a+ANGLE_STEPS;
|
||||||
|
}
|
||||||
|
return Angle((uint16_t)a);
|
||||||
|
}
|
||||||
|
Angle operator+(const unsigned long int x)
|
||||||
|
{
|
||||||
|
uint32_t a;
|
||||||
|
a=(uint32_t)angle+ x;
|
||||||
|
while (a>=ANGLE_STEPS)
|
||||||
|
{
|
||||||
|
a=a-ANGLE_STEPS;
|
||||||
|
}
|
||||||
|
return Angle((uint16_t)a);
|
||||||
|
}
|
||||||
|
|
||||||
|
operator uint16_t() const {return angle;}
|
||||||
|
operator uint32_t() const {return (uint32_t)angle;}
|
||||||
|
operator int32_t() const {return (int32_t)angle;}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* ANGLE_H_ */
|
322
firmware_smartstepper_trikarus/stepper_nano_zero/as5047d.cpp
Normal file
@ -0,0 +1,322 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "syslog.h"
|
||||||
|
#include "as5047d.h"
|
||||||
|
#include "SPI.h"
|
||||||
|
#include <stdio.h>
|
||||||
|
#include "board.h"
|
||||||
|
|
||||||
|
#define AS5047D_CMD_NOP (0x0000)
|
||||||
|
#define AS5047D_CMD_ERRFL (0x0001)
|
||||||
|
#define AS5047D_CMD_PROG (0x0003)
|
||||||
|
#define AS5047D_CMD_DIAAGC (0x3FFC)
|
||||||
|
#define AS5047D_CMD_MAG (0x3FFD)
|
||||||
|
#define AS5047D_CMD_ANGLEUNC (0x3FFE)
|
||||||
|
#define AS5047D_CMD_ANGLECOM (0x3FFF)
|
||||||
|
|
||||||
|
|
||||||
|
#define AS5048A_CMD_NOP (0x0000)
|
||||||
|
#define AS5048A_CMD_ERRFL (0x0001)
|
||||||
|
#define AS5048A_CMD_PROG (0x0003)
|
||||||
|
#define AS5048A_CMD_DIAAGC (0x3FFD)
|
||||||
|
#define AS5048A_CMD_MAG (0x3FFE)
|
||||||
|
#define AS5048A_CMD_ANGLE (0x3FFF)
|
||||||
|
|
||||||
|
#pragma GCC push_options
|
||||||
|
#pragma GCC optimize ("-Ofast")
|
||||||
|
|
||||||
|
static int getBit(int16_t data, int bit)
|
||||||
|
{
|
||||||
|
return (data>>bit) & 0x01;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int getParity(uint16_t data)
|
||||||
|
{
|
||||||
|
int i,bits;
|
||||||
|
data=data & 0x7FFF; //mask out upper bit
|
||||||
|
|
||||||
|
//count number of bits, brute force
|
||||||
|
bits=0;
|
||||||
|
for(i=0; i<16; i++)
|
||||||
|
{
|
||||||
|
if (0 != (data & ((0x0001)<<i)))
|
||||||
|
{
|
||||||
|
bits++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return (bits & 0x01); //return 1 if odd
|
||||||
|
}
|
||||||
|
|
||||||
|
boolean AS5047D::begin(int csPin)
|
||||||
|
{
|
||||||
|
#ifdef PIN_AS5047D_PWR
|
||||||
|
digitalWrite(PIN_AS5047D_PWR,HIGH);
|
||||||
|
#endif
|
||||||
|
digitalWrite(PIN_AS5047D_CS,LOW); //pull CS LOW by default (chip powered off)
|
||||||
|
digitalWrite(PIN_MOSI,LOW);
|
||||||
|
digitalWrite(PIN_SCK,LOW);
|
||||||
|
digitalWrite(PIN_MISO,LOW);
|
||||||
|
pinMode(PIN_MISO,OUTPUT);
|
||||||
|
delay(1000);
|
||||||
|
|
||||||
|
|
||||||
|
digitalWrite(PIN_AS5047D_CS,HIGH); //pull CS high
|
||||||
|
#ifdef PIN_AS5047D_PWR
|
||||||
|
digitalWrite(PIN_AS5047D_PWR,LOW);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
pinMode(PIN_MISO,INPUT);
|
||||||
|
|
||||||
|
error=false;
|
||||||
|
SPISettings settingsA(5000000, MSBFIRST, SPI_MODE1); ///400000, MSBFIRST, SPI_MODE1);
|
||||||
|
chipSelectPin=csPin;
|
||||||
|
|
||||||
|
LOG("csPin is %d",csPin);
|
||||||
|
pinMode(chipSelectPin,OUTPUT);
|
||||||
|
digitalWrite(chipSelectPin,HIGH); //pull CS high by default
|
||||||
|
delay(1);
|
||||||
|
SPI.begin(); //AS5047D SPI uses mode=1 (CPOL=0, CPHA=1)
|
||||||
|
LOG("Begin AS5047D...");
|
||||||
|
|
||||||
|
SPI.beginTransaction(settingsA);
|
||||||
|
SPI.transfer16(AS5047D_CMD_NOP);
|
||||||
|
delay(10);
|
||||||
|
|
||||||
|
//wait for the LF bit to be set
|
||||||
|
uint16_t data=0,t0=100;
|
||||||
|
while (getBit(data,8)==0 && t0>0)
|
||||||
|
{
|
||||||
|
delay(1);
|
||||||
|
t0--;
|
||||||
|
if (t0==0)
|
||||||
|
{
|
||||||
|
ERROR("LF bit not set");
|
||||||
|
error=true;
|
||||||
|
break;
|
||||||
|
//return false;
|
||||||
|
}
|
||||||
|
LOG("AS5047D diag data is 0x%04X",data);
|
||||||
|
data=readAddress(AS5047D_CMD_DIAAGC);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (error)
|
||||||
|
{
|
||||||
|
error=false;
|
||||||
|
uint16_t data=0,t0=100;
|
||||||
|
while (getBit(data,8)==0 && t0>0)
|
||||||
|
{
|
||||||
|
delay(1);
|
||||||
|
t0--;
|
||||||
|
if (t0==0)
|
||||||
|
{
|
||||||
|
ERROR("AS5048A OCF bit not set");
|
||||||
|
error=true;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
data=readAddress(AS5048A_CMD_DIAAGC);
|
||||||
|
LOG("AS5048A diag data is 0x%04X",data);
|
||||||
|
}
|
||||||
|
as5047d=false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef NZS_AS5047_PIPELINE
|
||||||
|
//read encoder a few times to flush the pipeline
|
||||||
|
readEncoderAnglePipeLineRead();
|
||||||
|
readEncoderAnglePipeLineRead();
|
||||||
|
#endif
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
//read the encoders
|
||||||
|
int16_t AS5047D::readAddress(uint16_t addr)
|
||||||
|
{
|
||||||
|
uint16_t data;
|
||||||
|
error=false;
|
||||||
|
//make sure it is a read by setting bit 14
|
||||||
|
addr=addr | 0x4000;
|
||||||
|
|
||||||
|
//add the parity to the command
|
||||||
|
if (1 == getParity(addr))
|
||||||
|
{
|
||||||
|
addr=(addr & 0x7FFF) | 0x8000; //add parity bit to make command even number of bits
|
||||||
|
}
|
||||||
|
|
||||||
|
digitalWrite(chipSelectPin, LOW);
|
||||||
|
delayMicroseconds(1);
|
||||||
|
//clock out the address to read
|
||||||
|
SPI.transfer16(addr);
|
||||||
|
digitalWrite(chipSelectPin, HIGH);
|
||||||
|
delayMicroseconds(1);
|
||||||
|
digitalWrite(chipSelectPin, LOW);
|
||||||
|
//clock out zeros to read in the data from address
|
||||||
|
data=SPI.transfer16(0x00);
|
||||||
|
|
||||||
|
digitalWrite(chipSelectPin, HIGH);
|
||||||
|
|
||||||
|
if (data & (1<<14))
|
||||||
|
{
|
||||||
|
//if bit 14 is set then we have an error
|
||||||
|
ERROR("read command 0x%04X failed",addr);
|
||||||
|
error=true;
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (data>>15 != getParity(data))
|
||||||
|
{
|
||||||
|
//parity did not match
|
||||||
|
ERROR("read command parity error 0x%04X ",addr);
|
||||||
|
error=true;
|
||||||
|
return -2;
|
||||||
|
}
|
||||||
|
|
||||||
|
data=data & 0x3FFF; //mask off the error and parity bits
|
||||||
|
|
||||||
|
return data;
|
||||||
|
}
|
||||||
|
|
||||||
|
//read the encoders
|
||||||
|
int16_t AS5047D::readEncoderAngle(void)
|
||||||
|
{
|
||||||
|
if (as5047d)
|
||||||
|
{
|
||||||
|
return readAddress(AS5047D_CMD_ANGLECOM);
|
||||||
|
}
|
||||||
|
return readAddress(AS5048A_CMD_ANGLE);
|
||||||
|
}
|
||||||
|
|
||||||
|
//pipelined read of the encoder angle used for high speed reads, but value is always one read behind
|
||||||
|
int16_t AS5047D::readEncoderAnglePipeLineRead(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
int16_t data;
|
||||||
|
int error, t0=10;
|
||||||
|
GPIO_LOW(chipSelectPin);//(chipSelectPin, LOW);
|
||||||
|
//delayMicroseconds(1);
|
||||||
|
do {
|
||||||
|
|
||||||
|
// doing two 8 bit transfers is faster than one 16 bit
|
||||||
|
data =(uint16_t)SPI.transfer(0xFF)<<8 | ((uint16_t)SPI.transfer(0xFF) & 0x0FF);
|
||||||
|
t0--;
|
||||||
|
if (t0<=0)
|
||||||
|
{
|
||||||
|
ERROR("AS5047D problem");
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
//data=SPI.transfer16(0xFFFF); //to speed things up we know the parity and address for the read
|
||||||
|
}while(data & (1<<14)); //while error bit is set
|
||||||
|
|
||||||
|
data=data & 0x3FFF; //mask off the error and parity bits
|
||||||
|
GPIO_HIGH(chipSelectPin);
|
||||||
|
//digitalWrite(chipSelectPin, HIGH);
|
||||||
|
//TODO we really should check for errors and return a negative result or something
|
||||||
|
return data;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void AS5047D::diagnostics(char *ptrStr)
|
||||||
|
{
|
||||||
|
int16_t data;
|
||||||
|
int m,d;
|
||||||
|
|
||||||
|
if (as5047d)
|
||||||
|
{
|
||||||
|
|
||||||
|
data=readAddress(AS5047D_CMD_DIAAGC);
|
||||||
|
|
||||||
|
if (NULL == ptrStr)
|
||||||
|
{
|
||||||
|
LOG("DIAAGC: 0x%04X", data);
|
||||||
|
LOG("MAGL: %d", getBit(data,11));
|
||||||
|
LOG("MAGH: %d", getBit(data,10));
|
||||||
|
LOG("COF: %d", getBit(data,9));
|
||||||
|
LOG("LFGL: %d", getBit(data,8));
|
||||||
|
LOG("AGC: %d", data & 0x0FF);
|
||||||
|
|
||||||
|
data=readAddress(AS5047D_CMD_MAG);
|
||||||
|
LOG("CMAG: 0x%04X(%d)",data,data);
|
||||||
|
|
||||||
|
data=readAddress(AS5047D_CMD_ANGLEUNC);
|
||||||
|
m=(int)((float)data*AS5047D_DEGREES_PER_BIT);
|
||||||
|
d=(int)((float)data*AS5047D_DEGREES_PER_BIT*100 -m*100);
|
||||||
|
LOG("CORDICANG: 0x%04X(%d) %d.%02d deg(est)",data,data,m,d);
|
||||||
|
|
||||||
|
data=readAddress(AS5047D_CMD_ANGLECOM);
|
||||||
|
m=(int)((float)data*AS5047D_DEGREES_PER_BIT);
|
||||||
|
d=(int)((float)data*AS5047D_DEGREES_PER_BIT*100 -m*100);
|
||||||
|
LOG("DAECANG: 0x%04X(%d) %d.%02d deg(est)",data,data,m,d);
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
sprintf(ptrStr,"DIAAGC: 0x%04X\n\r", data);
|
||||||
|
sprintf(ptrStr,"%sMAGL: %d\n\r", ptrStr,getBit(data,11));
|
||||||
|
sprintf(ptrStr,"%sMAGH: %d\n\r", ptrStr,getBit(data,10));
|
||||||
|
sprintf(ptrStr,"%sCOF: %d\n\r", ptrStr, getBit(data,9));
|
||||||
|
sprintf(ptrStr,"%sLFGL: %d\n\r", ptrStr, getBit(data,8));
|
||||||
|
sprintf(ptrStr,"%sAGC: %d\n\r", ptrStr,data & 0x0FF);
|
||||||
|
|
||||||
|
data=readAddress(AS5047D_CMD_MAG);
|
||||||
|
sprintf(ptrStr,"%sCMAG: 0x%04X(%d)\n\r", ptrStr,data,data);
|
||||||
|
|
||||||
|
data=readAddress(AS5047D_CMD_ANGLEUNC);
|
||||||
|
m=(int)((float)data*AS5047D_DEGREES_PER_BIT);
|
||||||
|
d=(int)((float)data*AS5047D_DEGREES_PER_BIT*100 -m*100);
|
||||||
|
sprintf(ptrStr,"%sCORDICANG: 0x%04X(%d) %d.%02d deg(est)\n\r", ptrStr,data,data,m,d);
|
||||||
|
|
||||||
|
data=readAddress(AS5047D_CMD_ANGLECOM);
|
||||||
|
m=(int)((float)data*AS5047D_DEGREES_PER_BIT);
|
||||||
|
d=(int)((float)data*AS5047D_DEGREES_PER_BIT*100 -m*100);
|
||||||
|
sprintf(ptrStr,"%sDAECANG: 0x%04X(%d) %d.%02d deg(est)\n\r", ptrStr,data,data,m,d);
|
||||||
|
|
||||||
|
}
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
data=readAddress(AS5048A_CMD_DIAAGC);
|
||||||
|
sprintf(ptrStr,"AS5048A DIAAGC: 0x%04X\n\r", data);
|
||||||
|
data=readAddress(AS5048A_CMD_MAG);
|
||||||
|
sprintf(ptrStr,"%sMagnitude: %d\n\r", ptrStr,data);
|
||||||
|
data=readAddress(AS5048A_CMD_ANGLE);
|
||||||
|
sprintf(ptrStr,"%sAngle: %d\n\r", ptrStr,data);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#pragma GCC pop_options
|
||||||
|
|
58
firmware_smartstepper_trikarus/stepper_nano_zero/as5047d.h
Normal file
@ -0,0 +1,58 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2019 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#ifndef __AS5047D_H__
|
||||||
|
#define __AS5047D_H__
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#define AS5047D_DEGREES_PER_BIT (360.0/(float)(0x3FFF))
|
||||||
|
|
||||||
|
class AS5047D {
|
||||||
|
private:
|
||||||
|
int chipSelectPin;
|
||||||
|
int16_t readAddress(uint16_t addr);
|
||||||
|
bool error=false;
|
||||||
|
bool as5047d=true;
|
||||||
|
public:
|
||||||
|
boolean begin(int csPin);
|
||||||
|
int16_t readEncoderAngle(void);
|
||||||
|
void diagnostics(char *ptrStr);
|
||||||
|
int16_t readEncoderAnglePipeLineRead(void);
|
||||||
|
bool getError(void) {return error;};
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif //__AS5047D_H__
|
564
firmware_smartstepper_trikarus/stepper_nano_zero/board.h
Normal file
@ -0,0 +1,564 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#ifndef __BOARD_H__
|
||||||
|
#define __BOARD_H__
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
|
||||||
|
|
||||||
|
//uncomment this if you are using the Mechaduino hardware
|
||||||
|
//#define MECHADUINO_HARDWARE
|
||||||
|
|
||||||
|
|
||||||
|
//uncomment the follow lines if using the NEMA 23 10A hardware
|
||||||
|
//#define NEMA_23_10A_HW
|
||||||
|
|
||||||
|
//uncomment the following if the board uses the A5995 driver (NEMA 23 3.2A boards)
|
||||||
|
//#define A5995_DRIVER
|
||||||
|
|
||||||
|
//The March 21 2017 NEMA 17 Smart Stepper has changed some pin outs
|
||||||
|
// A1 was changed to read motor voltage, hence SW4 is now using D4
|
||||||
|
// comment out this next line if using the older hardware
|
||||||
|
#define NEMA17_SMART_STEPPER_3_21_2017
|
||||||
|
|
||||||
|
#if defined(MECHADUINO_HARDWARE) && defined(NEMA17_SMART_STEPPER_3_21_2017)
|
||||||
|
#error "Cannot have both MECHADUINO_HARDWARE and NEMA17_SMART_STEPPER_3_21_2017 defined in board.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//The MKS Servo42 uses the A1333_Encoder
|
||||||
|
// Please uncomment this line and make sure the NEMA17_SMART_STEPPER_3_21_2017 is
|
||||||
|
// uncommented for the Servo42
|
||||||
|
//#define A1333_ENCODER
|
||||||
|
|
||||||
|
#ifdef A5995_DRIVER
|
||||||
|
#ifdef NEMA17_SMART_STEPPER_3_21_2017
|
||||||
|
#error "Only NEMA17_SMART_STEPPER_3_21_2017 or A5595_DRIVER may be defined"
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define NZS_FAST_CAL // define this to use 32k of flash for fast calibration table
|
||||||
|
#define NZS_FAST_SINE //uses 2048 extra bytes to implement faster sine tables
|
||||||
|
|
||||||
|
|
||||||
|
#define NZS_AS5047_PIPELINE //does a pipeline read of encoder, which is slightly faster
|
||||||
|
|
||||||
|
#define NZS_CONTROL_LOOP_HZ (6000) //update rate of control loop
|
||||||
|
|
||||||
|
|
||||||
|
#define NZS_LCD_ABSOULTE_ANGLE //define this to show angle from zero in positive and negative direction
|
||||||
|
// for example 2 rotations from start will be angle of 720 degrees
|
||||||
|
|
||||||
|
//#define ENABLE_PHASE_PREDICTION //this enables prediction of phase at high velocity to increase motor speed
|
||||||
|
//as of FW0.11 it is considered development only
|
||||||
|
|
||||||
|
#define VERSION "FW: 0.40" //this is what prints on LCD during splash screen
|
||||||
|
|
||||||
|
//Define this to allow command out serial port, else hardware serial is debug log
|
||||||
|
//#define CMD_SERIAL_PORT
|
||||||
|
|
||||||
|
#define SERIAL_BAUD (115200) //baud rate for the serial ports
|
||||||
|
|
||||||
|
//This section is for using the step and dir pins as serial port
|
||||||
|
// when the enable pin is inactive.
|
||||||
|
#ifndef MECHADUINO_HARDWARE
|
||||||
|
#define USE_STEP_DIR_SERIAL
|
||||||
|
#define STEP_DIR_BAUD (19200) //this is the baud rate we will use
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
// These are used as an attempt to use TC4 to count steps
|
||||||
|
// currently this is not working.
|
||||||
|
//#define USE_NEW_STEP //define this to use new step method
|
||||||
|
#define USE_TC_STEP //use timer counter for step pin
|
||||||
|
|
||||||
|
#ifndef F_CPU
|
||||||
|
#define F_CPU (48000000UL)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* TODO are flaged with TODO
|
||||||
|
* TODO - add detection of magnet to make sure PCB is on motor
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* change log
|
||||||
|
* 0.02 added fixes for 0.9 degree motor
|
||||||
|
* 0.03 added code for using error pin as an enable pin, enable feedback by default
|
||||||
|
* 0.04
|
||||||
|
* 0.05 added different modes added support for mechaduino
|
||||||
|
* 0.06 added time out pipeline read, add some error logging on encoder failure for mechaduino
|
||||||
|
* 0.07 many changes including
|
||||||
|
* - fixed error on display when doing a move 99999
|
||||||
|
* - added velocity and position PID modes
|
||||||
|
* - fixed LCD menu and put LCD code in own file
|
||||||
|
* - include LCD source files from adafruit as that ssd1306 need lcd resoultion fix
|
||||||
|
* - added motor parameters to NVM such step size and rotation are only check on first boot
|
||||||
|
* - added test on power up to see if motor power is applied.
|
||||||
|
* - added factory reset command
|
||||||
|
* - pPID is not stable in my testing.
|
||||||
|
* 0.08
|
||||||
|
* - moved enable pin processing out of interrupt context
|
||||||
|
* - added mode for inverted logic on the enable pin
|
||||||
|
* - added pin definitions for NEMA23 10A hardware
|
||||||
|
* - Changed enable such that it does not move motor but just sets current posistion
|
||||||
|
* 0.09
|
||||||
|
* - enabled auto detection of LCD
|
||||||
|
* - cleaned up the commands, made motorparams and systemparams individual commands
|
||||||
|
* - added the option to the move command to move at a constant RPM
|
||||||
|
* - Added the setzero command to zero the relative location of motor
|
||||||
|
* - Added the stop command to stop the planner based moves.
|
||||||
|
* 0.10
|
||||||
|
* -Fixed bug in switching control mode to 3
|
||||||
|
* 0.11
|
||||||
|
* - Fixed bug where output current was half of what it should have been (sine.h)
|
||||||
|
* - Added #define for phase predictive advancement
|
||||||
|
* - Changed calibration to be done with one coil/phase on
|
||||||
|
* - Added smoothing for calibration
|
||||||
|
* - Continue to work on the Fet Driver code.
|
||||||
|
* 0.12
|
||||||
|
* - Continue to work on the FET driver code
|
||||||
|
* - fixed a constant issue with the DAC for the A4954 driver
|
||||||
|
* - added command for setting the operational mode of the enable pin
|
||||||
|
* - added the start of the A5995 driver.
|
||||||
|
* 0.13
|
||||||
|
* - Added delay in for the 0.9 degree motor calibration and testing
|
||||||
|
* - changed calibration to move 1/2 step at time as it was causing problems on A5995 due to current ramp down
|
||||||
|
* 0.14 - Added in data logging
|
||||||
|
* - Averaged the encoder when the motor is stationary to reduce noise/vibrations
|
||||||
|
* 0.15 - Fixed some fet driver code
|
||||||
|
* - Added support for the NEMA17 smart stepper
|
||||||
|
* - Fixed RPM display bug on the LCD
|
||||||
|
* 0.16 - Added support for enable and error pins on the 3-21-2017 hardware
|
||||||
|
*
|
||||||
|
* 0.17 - Added the ability for the command line to go over the hardwired serial port
|
||||||
|
* - Fixed a bug where step and direction pin were setup as pulled down pins
|
||||||
|
* which could cause false stepping in nosiey environments
|
||||||
|
* 0.18 - Added support for EEPROM writting of last location during brown out - currently brown out is too fast to write
|
||||||
|
* - Added commands to support reading and restoring location from eeprom
|
||||||
|
* - Check for pull up on SDA/SCL before doing a I2C read as that SERCOM driver has not time outs and locks.
|
||||||
|
* - Added faster detection of USB not being plugged in, reduces power up time with no USB
|
||||||
|
* 0.19 - removed debug information in the ssd1306 driver which caused LCD not always to be found
|
||||||
|
* 0.20 - Fixed bug in calibration, thanks to Oliver E.
|
||||||
|
* 0.21 - Fixed issues compiling for mechaduino, including disabling LCD for MEchaduino
|
||||||
|
* 0.22 - Added home command;
|
||||||
|
* 0.23 -- added motor voltage sense to remove stepping on power up
|
||||||
|
* 0.24 - Disabled the home command which used the enable pin if you do not have enable pin
|
||||||
|
* 0.25 - Added pin read command
|
||||||
|
* 0.26 - changed the step/dir pins to be input_pullups
|
||||||
|
* 0.27 - added the option to make the step/dir uart when enable is low.
|
||||||
|
* - fixed enable to line to disable the A4954 driver
|
||||||
|
* 0.28 - Enabled some homing options (still under development)
|
||||||
|
* 0.29 - fixed rounding bug in ANGLE_T0_DEGREES
|
||||||
|
* 0.30 - Added support for the AS5048A encoder
|
||||||
|
* 0.31 - Added reading enable pin on during main loop
|
||||||
|
* 0.32 - Fixed issue where steps were not being counted correctly
|
||||||
|
* 0.33 - changed sPID parameters back to 0.9 0.0001 0.01
|
||||||
|
* 0.34 - Added board type to the splash screen
|
||||||
|
* 0.35 - fixed usign TC4 (USE_TC_STEP) for counting steps. We can measure steps
|
||||||
|
* - at over 125khz, however the dir pin has ~8us setup time due to interrupt latency.
|
||||||
|
* - Added debug command to allow debug messages out the USB serial port
|
||||||
|
* 0.36 - eeprom set location math was wrong.
|
||||||
|
* 0.37 - fixed bug where the motor would pause periodically do the the TC4 counter.
|
||||||
|
* 0.38 - fixed bug in the velocity feedback mode.
|
||||||
|
* 0.39 - changed step count to TCC2, improved the dir pin setup/hold times
|
||||||
|
* - added support for the MKS Servo42 (A1333 encoder)
|
||||||
|
* 0.40 - fixed compiling errors for Mechaduino. Added sanity checks for different hardware boards (AK)
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Typedefs that are used across multiple files/modules
|
||||||
|
*/
|
||||||
|
typedef enum {
|
||||||
|
CW_ROTATION=0,
|
||||||
|
CCW_ROTATION=1,
|
||||||
|
} RotationDir_t;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
ERROR_PIN_MODE_ENABLE=0, //error pin works like enable on step sticks
|
||||||
|
ERROR_PIN_MODE_ACTIVE_LOW_ENABLE=1, //error pin works like enable on step sticks
|
||||||
|
ERROR_PIN_MODE_ERROR=2, //error pin is low when there is angle error
|
||||||
|
ERROR_PIN_MODE_BIDIR=3, //error pin is bidirection open collector
|
||||||
|
|
||||||
|
} ErrorPinMode_t;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
CTRL_OFF =0, //controller is disabled
|
||||||
|
CTRL_OPEN=1, //controller is in open loop mode
|
||||||
|
CTRL_SIMPLE = 2, //simple error controller
|
||||||
|
CTRL_POS_PID =3, //PID Position controller
|
||||||
|
CTRL_POS_VELOCITY_PID =4, //PID Velocity controller
|
||||||
|
CTRL_TORQUE =5
|
||||||
|
} feedbackCtrl_t;
|
||||||
|
|
||||||
|
// ******** EVENT SYS USAGAE ************
|
||||||
|
// Channel 0 - Step pin event
|
||||||
|
|
||||||
|
// ******** TIMER USAGE A4954 versions ************
|
||||||
|
//TCC1 is used for DAC PWM to the A4954
|
||||||
|
//TCC0 can be used as PWM for the input pins on the A4954
|
||||||
|
//TCC2 is used for the step count
|
||||||
|
//D0 step input could use TCC1 or TCC0 if not used
|
||||||
|
//TC3 is used for planner tick
|
||||||
|
//TC5 is use for timing the control loop
|
||||||
|
|
||||||
|
// ******** TIMER USAGE NEMA23 10A versions ************
|
||||||
|
//TCC0 PWM for the FET IN pins
|
||||||
|
//D10 step input could use TC3 or TCC0 if not used
|
||||||
|
//TC3 is used for planner tick
|
||||||
|
//TC4 is used for step count
|
||||||
|
//TC5 is use for timing the control loop
|
||||||
|
|
||||||
|
|
||||||
|
//mechaduio and Arduino Zero has defined serial ports differently than NZS
|
||||||
|
#ifdef MECHADUINO_HARDWARE
|
||||||
|
#warning "Compiling source for Mechaduino NOT NZS"
|
||||||
|
#define DISABLE_LCD
|
||||||
|
#undef Serial5
|
||||||
|
#define Serial5 Serial
|
||||||
|
#else
|
||||||
|
#define SerialUSB Serial
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define PIN_TXD (30)
|
||||||
|
#define PIN_RXD (31)
|
||||||
|
|
||||||
|
#define PIN_STEP_INPUT (0)
|
||||||
|
#define PIN_DIR_INPUT (1)
|
||||||
|
|
||||||
|
#define PIN_MOSI (23)
|
||||||
|
#define PIN_SCK (24)
|
||||||
|
#define PIN_MISO (22)
|
||||||
|
|
||||||
|
#ifdef MECHADUINO_HARDWARE
|
||||||
|
#ifdef USE_STEP_DIR_SERIAL
|
||||||
|
#error "Step/Dir UART not supported on Mechaduino yet"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define PIN_ERROR (19) //analogInputToDigitalPin(PIN_A5))
|
||||||
|
#else //not Mechaduino hardware
|
||||||
|
#ifdef NEMA17_SMART_STEPPER_3_21_2017
|
||||||
|
#define PIN_SW1 (19)//analogInputToDigitalPin(PIN_A5))
|
||||||
|
#define PIN_SW3 (14)//analogInputToDigitalPin(PIN_A0))
|
||||||
|
|
||||||
|
#ifdef A1333_ENCODER //the MKS Servo42 uses A1 for this switch
|
||||||
|
#define PIN_SW4 (15)//analogInputToDigitalPin(PIN_A1))
|
||||||
|
#else
|
||||||
|
#define PIN_SW4 (2)//D2
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define PIN_ENABLE (10)
|
||||||
|
#define PIN_ERROR (3)
|
||||||
|
|
||||||
|
#define PIN_VMOTOR (A1) //analog pin for the motor
|
||||||
|
|
||||||
|
#else
|
||||||
|
#define PIN_SW1 (19)//analogInputToDigitalPin(PIN_A5))
|
||||||
|
#define PIN_SW3 (14)//analogInputToDigitalPin(PIN_A0))
|
||||||
|
#define PIN_SW4 (15)//analogInputToDigitalPin(PIN_A1))
|
||||||
|
#define PIN_ERROR (10)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef A5995_DRIVER
|
||||||
|
#define PIN_ENABLE (3)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define PIN_SCL (21)
|
||||||
|
#define PIN_SDA (20)
|
||||||
|
#define PIN_USB_PWR (38) // this pin is high when usb is connected
|
||||||
|
|
||||||
|
#define PIN_AS5047D_CS (16)//analogInputToDigitalPin(PIN_A2))
|
||||||
|
#ifndef MECHADUINO_HARDWARE
|
||||||
|
#define PIN_AS5047D_PWR (11) //pull low to power on AS5047D
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//these pins use the TIMER in the A4954 driver
|
||||||
|
// changing the pin definitions here may require changes in the A4954.cpp file
|
||||||
|
|
||||||
|
#define PIN_FET_IN1 (5) //PA15 TC3/WO[1] TCC0/WO[5]1
|
||||||
|
#define PIN_FET_IN2 (6) //PA20 TC7/W0[0] TCC0/WO[6]2
|
||||||
|
#define PIN_FET_IN3 (7) //PA21 TC7/WO[1] TCC0/WO[7]3
|
||||||
|
#define PIN_FET_IN4 (2) //PA14 TC3/W0[0] TCC0/WO[4] 0
|
||||||
|
#define PIN_FET_VREF1 (4)
|
||||||
|
#define PIN_FET_VREF2 (3)
|
||||||
|
#define PIN_FET_ENABLE (12)
|
||||||
|
//current sense pin from each H-bridge
|
||||||
|
#define ISENSE_FET_A (17) //analogInputToDigitalPin(PIN_A3)
|
||||||
|
#define ISENSE_FET_B (8)
|
||||||
|
//Comparators analog inputs
|
||||||
|
//#define COMP_FET_A (18)//analogInputToDigitalPin(PIN_A4))
|
||||||
|
//#define COMP_FET_B (9)
|
||||||
|
|
||||||
|
|
||||||
|
//these are the pins used on the A5995 driver
|
||||||
|
#define PIN_A5995_ENABLE1 (2) //PA14
|
||||||
|
#define PIN_A5995_ENABLE2 (18) //PA05 analogInputToDigitalPin(PIN_A4))
|
||||||
|
#define PIN_A5995_MODE1 (8) //PA06 TCC1 WO[0]
|
||||||
|
#define PIN_A5995_MODE2 (7) //PA21 TCC0 WO[4] //3
|
||||||
|
#define PIN_A5995_PHASE1 (6) //PA20 TCC0 WO[6] //2
|
||||||
|
#define PIN_A5995_PHASE2 (5) //PA15 TCC0 W0[5] //1
|
||||||
|
#define PIN_A5995_VREF1 (4) //PA08
|
||||||
|
#define PIN_A5995_VREF2 (9) //PA07
|
||||||
|
#define PIN_A5995_SLEEPn (25) //RXLED
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef MECHADUINO_HARDWARE
|
||||||
|
#define PIN_YELLOW_LED (8)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef NEMA_23_10A_HW
|
||||||
|
#undef PIN_YELLOW_LED
|
||||||
|
#define PIN_YELLOW_LED (26) //TXLED (PA27)
|
||||||
|
#endif //NEMA_23_10A_HW
|
||||||
|
|
||||||
|
|
||||||
|
#define PIN_RED_LED (13)
|
||||||
|
#define PIN_A4954_IN3 (5)
|
||||||
|
#define PIN_A4954_IN4 (6)
|
||||||
|
#define PIN_A4954_IN2 (7)
|
||||||
|
#ifdef MECHADUINO_HARDWARE
|
||||||
|
#define PIN_A4954_IN1 (8)
|
||||||
|
#else
|
||||||
|
#define PIN_A4954_IN1 (18) //analogInputToDigitalPin(PIN_A4))
|
||||||
|
#endif
|
||||||
|
#define PIN_A4954_VREF34 (4)
|
||||||
|
#define PIN_A4954_VREF12 (9)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//Here are some useful macros
|
||||||
|
#define DIVIDE_WITH_ROUND(x,y) (((x)+(y)/2)/(y))
|
||||||
|
|
||||||
|
|
||||||
|
#define GPIO_LOW(pin) {PORT->Group[g_APinDescription[(pin)].ulPort].OUTCLR.reg = (1ul << g_APinDescription[(pin)].ulPin);}
|
||||||
|
#define GPIO_HIGH(pin) {PORT->Group[g_APinDescription[(pin)].ulPort].OUTSET.reg = (1ul << g_APinDescription[(pin)].ulPin);}
|
||||||
|
#define GPIO_OUTPUT(pin) {PORT->Group[g_APinDescription[(pin)].ulPort].PINCFG[g_APinDescription[(pin)].ulPin].reg &=~(uint8_t)(PORT_PINCFG_INEN) ; PORT->Group[g_APinDescription[(pin)].ulPort].DIRSET.reg = (uint32_t)(1<<g_APinDescription[(pin)].ulPin) ;}
|
||||||
|
|
||||||
|
#define PIN_GPIO_OUTPUT(pin) {PORT->Group[g_APinDescription[(pin)].ulPort].PINCFG[g_APinDescription[(pin)].ulPin].reg &=~(uint8_t)(PORT_PINCFG_INEN | PORT_PINCFG_PMUXEN) ; PORT->Group[g_APinDescription[(pin)].ulPort].DIRSET.reg = (uint32_t)(1<<g_APinDescription[(pin)].ulPin) ;}
|
||||||
|
|
||||||
|
#define PIN_GPIO(pin) {PORT->Group[g_APinDescription[(pin)].ulPort].PINCFG[g_APinDescription[(pin)].ulPin].reg &=~(uint8_t)(PORT_PINCFG_INEN | PORT_PINCFG_PMUXEN);}
|
||||||
|
#define GPIO_READ(ulPin) {(PORT->Group[g_APinDescription[ulPin].ulPort].IN.reg & (1ul << g_APinDescription[ulPin].ulPin)) != 0}
|
||||||
|
#define PIN_PERIPH(pin) {PORT->Group[g_APinDescription[(pin)].ulPort].PINCFG[g_APinDescription[(pin)].ulPin].reg |= PORT_PINCFG_PMUXEN;}
|
||||||
|
//sets up the pins for the board
|
||||||
|
static void boardSetupPins(void)
|
||||||
|
{
|
||||||
|
//setup switch pins
|
||||||
|
#ifdef PIN_SW1
|
||||||
|
pinMode(PIN_SW1, INPUT_PULLUP);
|
||||||
|
pinMode(PIN_SW3, INPUT_PULLUP);
|
||||||
|
pinMode(PIN_SW4, INPUT_PULLUP);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
pinMode(PIN_STEP_INPUT, INPUT_PULLUP);
|
||||||
|
pinMode(PIN_DIR_INPUT, INPUT_PULLUP);
|
||||||
|
|
||||||
|
#ifdef PIN_ENABLE
|
||||||
|
pinMode(PIN_ENABLE, INPUT_PULLUP); //default error pin as enable pin with pull up
|
||||||
|
#endif
|
||||||
|
pinMode(PIN_ERROR, INPUT_PULLUP); //default error pin as enable pin with pull up
|
||||||
|
|
||||||
|
pinMode(PIN_AS5047D_CS,OUTPUT);
|
||||||
|
digitalWrite(PIN_AS5047D_CS,LOW); //pull CS LOW by default (chip powered off)
|
||||||
|
|
||||||
|
//turn the AS5047D off by default
|
||||||
|
#ifdef PIN_AS5047D_PWR
|
||||||
|
pinMode(PIN_AS5047D_PWR,OUTPUT);
|
||||||
|
digitalWrite(PIN_AS5047D_PWR,HIGH);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
pinMode(PIN_MOSI,OUTPUT);
|
||||||
|
digitalWrite(PIN_MOSI,LOW);
|
||||||
|
pinMode(PIN_SCK,OUTPUT);
|
||||||
|
digitalWrite(PIN_SCK,LOW);
|
||||||
|
pinMode(PIN_MISO,INPUT);
|
||||||
|
|
||||||
|
//setup the A4954 pins
|
||||||
|
digitalWrite(PIN_A4954_IN3,LOW);
|
||||||
|
pinMode(PIN_A4954_IN3,OUTPUT);
|
||||||
|
digitalWrite(PIN_A4954_IN4,LOW);
|
||||||
|
pinMode(PIN_A4954_IN4,OUTPUT);
|
||||||
|
digitalWrite(PIN_A4954_IN2,LOW);
|
||||||
|
pinMode(PIN_A4954_IN2,OUTPUT);
|
||||||
|
digitalWrite(PIN_A4954_IN1,LOW);
|
||||||
|
pinMode(PIN_A4954_IN1,OUTPUT);
|
||||||
|
|
||||||
|
//setup the PWM for current on the A4954, set for low current
|
||||||
|
digitalWrite(PIN_A4954_VREF12,LOW);
|
||||||
|
digitalWrite(PIN_A4954_VREF34,LOW);
|
||||||
|
pinMode(PIN_A4954_VREF34, OUTPUT);
|
||||||
|
pinMode(PIN_A4954_VREF12, OUTPUT);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
pinMode(PIN_RED_LED,OUTPUT);
|
||||||
|
#ifdef PIN_YELLOW_LED
|
||||||
|
pinMode(PIN_YELLOW_LED,OUTPUT);
|
||||||
|
digitalWrite(PIN_YELLOW_LED,HIGH);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef NEMA17_SMART_STEPPER_3_21_2017
|
||||||
|
static float GetMotorVoltage(void)
|
||||||
|
{
|
||||||
|
uint32_t x;
|
||||||
|
float f;
|
||||||
|
//the motor voltage is 1/101 of the adc
|
||||||
|
x=analogRead(PIN_VMOTOR); //this should be a 10bit value mapped to 3.3V
|
||||||
|
f=(float)x*3.3/1024.0*101.0;
|
||||||
|
return f;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
static void inline YELLOW_LED(bool state)
|
||||||
|
{
|
||||||
|
#ifdef PIN_YELLOW_LED
|
||||||
|
digitalWrite(PIN_YELLOW_LED,!state);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
static void inline RED_LED(bool state)
|
||||||
|
{
|
||||||
|
digitalWrite(PIN_RED_LED,state);
|
||||||
|
}
|
||||||
|
|
||||||
|
#define MIN(a,b) (((a)<(b))?(a):(b))
|
||||||
|
#define MAX(a,b) (((a)>(b))?(a):(b))
|
||||||
|
#define ABS(a) (((a)>(0))?(a):(-(a)))
|
||||||
|
#define DIV(x,y) (((y)>(0))?((x)/(y)):(4294967295))
|
||||||
|
#define SIGN(x) (((x) > 0) - ((x) < 0))
|
||||||
|
|
||||||
|
#define NVIC_IS_IRQ_ENABLED(x) (NVIC->ISER[0] & (1 << ((uint32_t)(x) & 0x1F)))!=0
|
||||||
|
|
||||||
|
static inline uint8_t getPinMux(uint16_t ulPin)
|
||||||
|
{
|
||||||
|
uint8_t temp;
|
||||||
|
if ((ulPin & 0x01)==0)
|
||||||
|
{
|
||||||
|
temp = (PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg) & PORT_PMUX_PMUXE( 0xF ) ;
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
temp = (PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg)>>4 & 0xF;
|
||||||
|
}
|
||||||
|
return temp;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
static inline uint8_t getPinCfg(uint16_t ulPin)
|
||||||
|
{
|
||||||
|
uint8_t temp;
|
||||||
|
|
||||||
|
temp = PORT->Group[g_APinDescription[ulPin].ulPort].PINCFG[g_APinDescription[ulPin].ulPin].reg;
|
||||||
|
return temp;
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline void setPinCfg(uint16_t ulPin, uint8_t val)
|
||||||
|
{
|
||||||
|
PORT->Group[g_APinDescription[ulPin].ulPort].PINCFG[g_APinDescription[ulPin].ulPin].reg=val;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
static inline void setPinMux(uint16_t ulPin, uint8_t val)
|
||||||
|
{
|
||||||
|
uint8_t temp;
|
||||||
|
temp = (PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg);
|
||||||
|
if ((ulPin & 0x01)==0)
|
||||||
|
{
|
||||||
|
//if an even pin
|
||||||
|
temp = (temp & 0xF0) | (val & 0x0F);
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
temp = (temp & 0x0F) | ((val<<4) & 0x0F);
|
||||||
|
}
|
||||||
|
PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg=temp;
|
||||||
|
PORT->Group[g_APinDescription[ulPin].ulPort].PINCFG[g_APinDescription[ulPin].ulPin].reg |= PORT_PINCFG_PMUXEN ; // Enable port mux
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline void SET_PIN_PERHERIAL(uint16_t ulPin,EPioType ulPeripheral)
|
||||||
|
{
|
||||||
|
if ( g_APinDescription[ulPin].ulPin & 1 ) // is pin odd?
|
||||||
|
{
|
||||||
|
uint32_t temp ;
|
||||||
|
|
||||||
|
// Get whole current setup for both odd and even pins and remove odd one
|
||||||
|
temp = (PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg) & PORT_PMUX_PMUXE( 0xF ) ;
|
||||||
|
// Set new muxing
|
||||||
|
PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg = temp|PORT_PMUX_PMUXO( ulPeripheral ) ;
|
||||||
|
// Enable port mux
|
||||||
|
PORT->Group[g_APinDescription[ulPin].ulPort].PINCFG[g_APinDescription[ulPin].ulPin].reg |= PORT_PINCFG_PMUXEN ;
|
||||||
|
}
|
||||||
|
else // even pin
|
||||||
|
{
|
||||||
|
uint32_t temp ;
|
||||||
|
|
||||||
|
temp = (PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg) & PORT_PMUX_PMUXO( 0xF ) ;
|
||||||
|
PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg = temp|PORT_PMUX_PMUXE( ulPeripheral ) ;
|
||||||
|
PORT->Group[g_APinDescription[ulPin].ulPort].PINCFG[g_APinDescription[ulPin].ulPin].reg |= PORT_PINCFG_PMUXEN ; // Enable port mux
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
//the Arduino delay function requires interrupts to work.
|
||||||
|
// if interrupts are disabled use the delayMicroseconds which is a spin loop
|
||||||
|
static inline void DelayMs(uint32_t ms)
|
||||||
|
{
|
||||||
|
uint32_t prim;
|
||||||
|
/* Read PRIMASK register, check interrupt status before you disable them */
|
||||||
|
/* Returns 0 if they are enabled, or non-zero if disabled */
|
||||||
|
prim = __get_PRIMASK();
|
||||||
|
|
||||||
|
if (prim==0)
|
||||||
|
{
|
||||||
|
delay(ms);
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
while(ms)
|
||||||
|
{
|
||||||
|
delayMicroseconds(1000);
|
||||||
|
ms--;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif//__BOARD_H__
|
599
firmware_smartstepper_trikarus/stepper_nano_zero/calibration.cpp
Normal file
@ -0,0 +1,599 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#include "calibration.h"
|
||||||
|
#include "Flash.h"
|
||||||
|
#include "nonvolatile.h"
|
||||||
|
#include "board.h" //for divide with rounding macro
|
||||||
|
#include "utils.h"
|
||||||
|
|
||||||
|
|
||||||
|
static uint16_t getTableIndex(uint16_t value)
|
||||||
|
{
|
||||||
|
int32_t x;
|
||||||
|
|
||||||
|
x=((int32_t)value*CALIBRATION_TABLE_SIZE)/CALIBRATION_STEPS; //the divide is a floor not a round which is what we want
|
||||||
|
return (uint16_t)x;
|
||||||
|
|
||||||
|
}
|
||||||
|
static uint16_t interp(Angle x1, Angle y1, Angle x2, Angle y2, Angle x)
|
||||||
|
{
|
||||||
|
int32_t dx,dy,dx2,y;
|
||||||
|
dx=x2-x1;
|
||||||
|
dy=y2-y1;
|
||||||
|
dx2=x-x1;
|
||||||
|
y=(int32_t)y1+DIVIDE_WITH_ROUND((dx2*dy),dx);
|
||||||
|
if (y<0)
|
||||||
|
{
|
||||||
|
y=y+CALIBRATION_STEPS;
|
||||||
|
}
|
||||||
|
return (uint16_t)y;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void printData(int32_t *data, int32_t n)
|
||||||
|
{
|
||||||
|
int32_t i;
|
||||||
|
Serial.print("\n\r");
|
||||||
|
for (i=0; i<n; i++)
|
||||||
|
{
|
||||||
|
Serial.print(data[i]);
|
||||||
|
if (i!=(n-1))
|
||||||
|
{
|
||||||
|
Serial.print(",");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
Serial.print("\n\r");
|
||||||
|
}
|
||||||
|
bool CalibrationTable::updateTableValue(int32_t index, int32_t value)
|
||||||
|
{
|
||||||
|
|
||||||
|
table[index].value=value;
|
||||||
|
table[index].error=CALIBRATION_STEPS/CALIBRATION_TABLE_SIZE; //or error is roughly like variance, so set it to span to next calibration value.
|
||||||
|
return true;
|
||||||
|
|
||||||
|
}
|
||||||
|
void CalibrationTable::printCalTable(void)
|
||||||
|
{
|
||||||
|
int i;
|
||||||
|
Serial.print("\n\r");
|
||||||
|
for (i=0; i<CALIBRATION_TABLE_SIZE; i++)
|
||||||
|
{
|
||||||
|
Serial.print((uint16_t)table[i].value);
|
||||||
|
Serial.print(",");
|
||||||
|
}
|
||||||
|
Serial.print("\n\r");
|
||||||
|
}
|
||||||
|
|
||||||
|
Angle CalibrationTable::fastReverseLookup(Angle encoderAngle)
|
||||||
|
{
|
||||||
|
#ifdef NZS_FAST_CAL
|
||||||
|
//assume calibration is good
|
||||||
|
if (fastCalVaild)
|
||||||
|
{
|
||||||
|
uint16_t x;
|
||||||
|
x=((uint16_t)encoderAngle)/4; //we only have 16384 values in table
|
||||||
|
|
||||||
|
return (Angle)NVM->FastCal.angle[x];
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
return reverseLookup(encoderAngle);
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
return reverseLookup(encoderAngle)
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
Angle CalibrationTable::reverseLookup(Angle encoderAngle)
|
||||||
|
{
|
||||||
|
|
||||||
|
int32_t i=0;
|
||||||
|
int32_t a1,a2;
|
||||||
|
int32_t x;
|
||||||
|
int16_t y;
|
||||||
|
int32_t min,max;
|
||||||
|
min=(uint16_t)table[0].value;
|
||||||
|
max=min;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
for (i=0; i<CALIBRATION_TABLE_SIZE; i++)
|
||||||
|
{
|
||||||
|
x=(uint16_t)table[i].value;
|
||||||
|
if (x<min)
|
||||||
|
{
|
||||||
|
min=x;
|
||||||
|
}
|
||||||
|
if (x>max)
|
||||||
|
{
|
||||||
|
max=x;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
x=(uint16_t)encoderAngle;
|
||||||
|
if (x<min)
|
||||||
|
{
|
||||||
|
x=x+CALIBRATION_STEPS;
|
||||||
|
}
|
||||||
|
|
||||||
|
i=0;
|
||||||
|
|
||||||
|
while (i<CALIBRATION_TABLE_SIZE)
|
||||||
|
{
|
||||||
|
a1=(uint16_t)table[i].value;
|
||||||
|
|
||||||
|
//handle index wrap around
|
||||||
|
if (i==(CALIBRATION_TABLE_SIZE-1))
|
||||||
|
{
|
||||||
|
a2=(uint16_t)table[0].value;
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
a2=(uint16_t)table[i+1].value;
|
||||||
|
}
|
||||||
|
|
||||||
|
//wrap
|
||||||
|
if (abs(a1-a2)>CALIBRATION_STEPS/2)
|
||||||
|
{
|
||||||
|
if (a1<a2)
|
||||||
|
{
|
||||||
|
a1=a1+CALIBRATION_STEPS;
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
a2=a2+CALIBRATION_STEPS;
|
||||||
|
}
|
||||||
|
|
||||||
|
//LOG("xxxx %d %d %d",a1,a2,x);
|
||||||
|
}
|
||||||
|
|
||||||
|
//finding matching location
|
||||||
|
if ( (x>=a1 && x<=a2) ||
|
||||||
|
(x>=a2 && x<=a1) )
|
||||||
|
{
|
||||||
|
//LOG("%d", i);
|
||||||
|
// inerpolate results and return
|
||||||
|
//LOG("%d %d %d",a1,a2,x);
|
||||||
|
//LOG("%d,%d",(i*CALIBRATION_MAX)/CALIBRATION_TABLE_SIZE,((i+2)*CALIBRATION_MAX)/CALIBRATION_TABLE_SIZE);
|
||||||
|
|
||||||
|
y=interp(a1, DIVIDE_WITH_ROUND((i*CALIBRATION_STEPS),CALIBRATION_TABLE_SIZE), a2, DIVIDE_WITH_ROUND( ((i+1)*CALIBRATION_STEPS),CALIBRATION_TABLE_SIZE), x);
|
||||||
|
|
||||||
|
return y;
|
||||||
|
}
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
ERROR("WE did some thing wrong");
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void CalibrationTable::smoothTable(void)
|
||||||
|
{
|
||||||
|
uint16_t b[]={1,2,4,5,4,2,1};
|
||||||
|
uint16_t sum_b=19; //sum of b filter
|
||||||
|
|
||||||
|
int32_t data[CALIBRATION_TABLE_SIZE];
|
||||||
|
int32_t table2[CALIBRATION_TABLE_SIZE];
|
||||||
|
|
||||||
|
int32_t i;
|
||||||
|
int32_t offset=0;
|
||||||
|
int32_t startNum;
|
||||||
|
|
||||||
|
//first lets handle the wrap around in the table
|
||||||
|
for (i=0; i<CALIBRATION_TABLE_SIZE; i++)
|
||||||
|
{
|
||||||
|
if (i>0 && offset==0)
|
||||||
|
{
|
||||||
|
if(((uint16_t)table[i-1].value-(uint16_t)table[i].value) <-32768)
|
||||||
|
{
|
||||||
|
offset=-65536;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (((uint16_t)table[i-1].value-(uint16_t)table[i].value) > 32768)
|
||||||
|
{
|
||||||
|
offset=65536;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
table2[i]=(int32_t)((uint16_t)table[i].value)+offset;
|
||||||
|
}
|
||||||
|
|
||||||
|
//Serial.print("after wrap\n\r");
|
||||||
|
//printData(table2,CALIBRATION_TABLE_SIZE);
|
||||||
|
|
||||||
|
//remove the starting offset and compensate table for index
|
||||||
|
startNum=table2[0];
|
||||||
|
for (i=0; i<CALIBRATION_TABLE_SIZE; i++)
|
||||||
|
{
|
||||||
|
table2[i]=table2[i]-startNum - (i*65536)/CALIBRATION_TABLE_SIZE;
|
||||||
|
}
|
||||||
|
|
||||||
|
//Serial.print("after phase comp\n\r");
|
||||||
|
//printData(table2,CALIBRATION_TABLE_SIZE);
|
||||||
|
|
||||||
|
//filter the data
|
||||||
|
for (i=0; i<CALIBRATION_TABLE_SIZE; i++)
|
||||||
|
{
|
||||||
|
int j,ix,ib;;
|
||||||
|
int32_t sum=0;
|
||||||
|
|
||||||
|
ib=0;
|
||||||
|
for (j=i-3; j<i+4; j++)
|
||||||
|
{
|
||||||
|
ix=j;
|
||||||
|
if (ix<0)
|
||||||
|
{
|
||||||
|
ix=ix+CALIBRATION_TABLE_SIZE;
|
||||||
|
}
|
||||||
|
if (ix>=CALIBRATION_TABLE_SIZE)
|
||||||
|
{
|
||||||
|
ix=ix-CALIBRATION_TABLE_SIZE;
|
||||||
|
}
|
||||||
|
if (i==0)
|
||||||
|
{
|
||||||
|
LOG("index %d",ix);
|
||||||
|
}
|
||||||
|
sum=sum+table2[ix]*b[ib];
|
||||||
|
ib++;
|
||||||
|
}
|
||||||
|
sum=DIVIDE_WITH_ROUND(sum,sum_b);
|
||||||
|
data[i]=sum;
|
||||||
|
}
|
||||||
|
|
||||||
|
//Serial.print("after filter\n\r");
|
||||||
|
//printData(data,CALIBRATION_TABLE_SIZE);
|
||||||
|
|
||||||
|
//add in offset and the phase compenstation
|
||||||
|
for (i=0; i<CALIBRATION_TABLE_SIZE; i++)
|
||||||
|
{
|
||||||
|
data[i]=data[i]+startNum + (i*65536)/CALIBRATION_TABLE_SIZE;
|
||||||
|
}
|
||||||
|
|
||||||
|
//Serial.print("after phase comp added\n\r");
|
||||||
|
//printData(data,CALIBRATION_TABLE_SIZE);
|
||||||
|
|
||||||
|
//remove the uint16_t wrap
|
||||||
|
for (i=0; i<CALIBRATION_TABLE_SIZE; i++)
|
||||||
|
{
|
||||||
|
if (data[i]>=65536)
|
||||||
|
{
|
||||||
|
data[i]=data[i]-65536;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
//Serial.print("after wrap added\n\r");
|
||||||
|
//printData(data,CALIBRATION_TABLE_SIZE);
|
||||||
|
|
||||||
|
//save new table
|
||||||
|
for (i=0; i<CALIBRATION_TABLE_SIZE; i++)
|
||||||
|
{
|
||||||
|
table[i].value=data[i];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void CalibrationTable::saveToFlash(void)
|
||||||
|
{
|
||||||
|
FlashCalData_t data;
|
||||||
|
int i;
|
||||||
|
for (i=0; i<CALIBRATION_TABLE_SIZE; i++ )
|
||||||
|
{
|
||||||
|
data.table[i]=(uint16_t)table[i].value;
|
||||||
|
}
|
||||||
|
data.status=true;
|
||||||
|
|
||||||
|
LOG("Writting Calbiration to Flash");
|
||||||
|
nvmWriteCalTable(&data,sizeof(data));
|
||||||
|
|
||||||
|
memset(&data,0,sizeof(data));
|
||||||
|
memcpy(&data, &NVM->CalibrationTable,sizeof(data));
|
||||||
|
createFastCal();
|
||||||
|
|
||||||
|
LOG("after writting status is %d",data.status);
|
||||||
|
loadFromFlash();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void CalibrationTable::loadFromFlash(void)
|
||||||
|
{
|
||||||
|
FlashCalData_t data;
|
||||||
|
int i;
|
||||||
|
LOG("Reading Calbiration to Flash");
|
||||||
|
memcpy(&data, &NVM->CalibrationTable,sizeof(data));
|
||||||
|
for (i=0; i<CALIBRATION_TABLE_SIZE; i++ )
|
||||||
|
{
|
||||||
|
table[i].value=Angle(data.table[i]);
|
||||||
|
table[i].error=CALIBRATION_MIN_ERROR;
|
||||||
|
}
|
||||||
|
data.status=true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool CalibrationTable::flashGood(void)
|
||||||
|
{
|
||||||
|
LOG("calibration table status is: %d",NVM->CalibrationTable.status);
|
||||||
|
return NVM->CalibrationTable.status;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void CalibrationTable::createFastCal(void)
|
||||||
|
{
|
||||||
|
#ifdef NZS_FAST_CAL
|
||||||
|
int32_t i;
|
||||||
|
uint16_t cs=0;
|
||||||
|
uint16_t data[256];
|
||||||
|
int32_t j;
|
||||||
|
j=0;
|
||||||
|
cs=0;
|
||||||
|
LOG("setting fast calibration");
|
||||||
|
for (i=0; i<16384; i++)
|
||||||
|
{
|
||||||
|
|
||||||
|
uint16_t x;
|
||||||
|
x=reverseLookup(i*4);
|
||||||
|
data[j]=x;
|
||||||
|
j++;
|
||||||
|
if (j>=256)
|
||||||
|
{
|
||||||
|
flashWrite(&NVM->FastCal.angle[i-255],data,256*sizeof(uint16_t));
|
||||||
|
//LOG("Wrote fastcal at index %d-%d", i-255, i);
|
||||||
|
j=0;
|
||||||
|
}
|
||||||
|
cs+=x;
|
||||||
|
}
|
||||||
|
//update the checksum
|
||||||
|
flashWrite(&NVM->FastCal.checkSum,&cs,sizeof(uint16_t));
|
||||||
|
fastCalVaild=true;
|
||||||
|
|
||||||
|
//this is a quick test
|
||||||
|
/*
|
||||||
|
for (i=0; i<16384; i++)
|
||||||
|
{
|
||||||
|
LOG("fast Cal %d,%d,%d",i,NVM->FastCal.angle[i],(uint32_t)reverseLookup(i*4));
|
||||||
|
}
|
||||||
|
*/
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
void CalibrationTable::updateFastCal(void)
|
||||||
|
{
|
||||||
|
#ifdef NZS_FAST_CAL
|
||||||
|
int32_t i;
|
||||||
|
uint16_t cs=0;
|
||||||
|
uint16_t data[256];
|
||||||
|
int32_t j;
|
||||||
|
bool NonZero=false;
|
||||||
|
for (i=0; i<16384; i++)
|
||||||
|
{
|
||||||
|
cs+=NVM->FastCal.angle[i];
|
||||||
|
if (cs != 0)
|
||||||
|
{
|
||||||
|
NonZero=true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (cs!=NVM->FastCal.checkSum || NonZero==false)
|
||||||
|
{
|
||||||
|
createFastCal();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
LOG("fast cal is valid");
|
||||||
|
fastCalVaild=true;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void CalibrationTable::init(void)
|
||||||
|
{
|
||||||
|
int i;
|
||||||
|
|
||||||
|
if (true == flashGood())
|
||||||
|
{
|
||||||
|
loadFromFlash();
|
||||||
|
updateFastCal();
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
for (i=0; i<CALIBRATION_TABLE_SIZE; i++)
|
||||||
|
{
|
||||||
|
table[i].value=0;
|
||||||
|
table[i].error=CALIBRATION_ERROR_NOT_SET;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
#if 0
|
||||||
|
//This code was removed because with micro stepping we can not assume
|
||||||
|
// our actualAngle is correct.
|
||||||
|
void CalibrationTable::updateTable(Angle actualAngle, Angle encoderValue);
|
||||||
|
{
|
||||||
|
static int32_t lastAngle=-1;
|
||||||
|
static uint16_t lastEncoderValue=0;
|
||||||
|
|
||||||
|
if (last != -1)
|
||||||
|
{
|
||||||
|
int32_t dist;
|
||||||
|
|
||||||
|
//hopefull we can use the current point and last point to interpolate and set a value or two in table.
|
||||||
|
dist=abs((int32_t)actualAngle-(int32_t)lastAngle); //distance between the two angles
|
||||||
|
|
||||||
|
//since our angles wrap the shortest distance will be one less than 32768
|
||||||
|
if (dist>CALIBRATION_STEPS/2)
|
||||||
|
{
|
||||||
|
dist=dist-CALIBRATION_STEPS;
|
||||||
|
}
|
||||||
|
|
||||||
|
//if our distance is larger than size between calibration points in table we will ignore this sample
|
||||||
|
if (dist>CALIBRATION_STEPS/CALIBRATION_TABLE_SIZE)
|
||||||
|
{
|
||||||
|
//spans two or more table calibration points for this implementation we will not use
|
||||||
|
lastIndex=(int32_t)index;
|
||||||
|
lastValue=value;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
//now lets see if the values are above and below a table calibration point
|
||||||
|
dist= abs(getTableIndex(lastAngle)-getTableIndex(actualAngle));
|
||||||
|
if (dist != 0) //if the two indexs into table are not the same it spans a calibration point in table.
|
||||||
|
{
|
||||||
|
//the two span a set calibation table point.
|
||||||
|
uint16_t newValue;
|
||||||
|
newValue=interp(lastAngle, lastEncoderValue, actualAngle, encoderValue, getTableIndex(actualAngle)*(CALIBRATION_STEPS/CALIBRATION_TABLE_SIZE))
|
||||||
|
//this new value is our best guess as to the correct calibration value.
|
||||||
|
updateTableValue(getTableIndex(actualAngle),newValue);
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
//we should calibate the table value for the point the closest
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
lastAngle=(int32_t)actualAngle;
|
||||||
|
lastEncoderValue=encoderValue;
|
||||||
|
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//when we are microstepping and are in between steps the probability the stepper motor did not move
|
||||||
|
// is high. That is the actualAngle will be correct but the encoderValue will be behind due to not having enough torque to move motor.
|
||||||
|
// Therefore we only want to update the calibration on whole steps where we have highest probability of things being correct.
|
||||||
|
void CalibrationTable::updateTable(Angle actualAngle, Angle encoderValue)
|
||||||
|
{
|
||||||
|
int32_t dist, index;
|
||||||
|
Angle tableAngle;
|
||||||
|
|
||||||
|
index = getTableIndex((uint32_t)actualAngle+CALIBRATION_STEPS/CALIBRATION_TABLE_SIZE/2); //add half of distance to next entry to round to closest table index
|
||||||
|
|
||||||
|
tableAngle=(index*CALIBRATION_STEPS)/CALIBRATION_TABLE_SIZE; //calculate the angle for this index
|
||||||
|
|
||||||
|
dist=tableAngle-actualAngle; //distance to calibration table angle
|
||||||
|
|
||||||
|
//LOG("Dist is %d",dist);
|
||||||
|
if (abs(dist)<CALIBRATION_MIN_ERROR) //if we are with in our minimal error we can calibrate
|
||||||
|
{
|
||||||
|
updateTableValue(index,(int32_t)encoderValue);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool CalibrationTable::calValid(void)
|
||||||
|
{
|
||||||
|
uint32_t i;
|
||||||
|
for (i=0; i<CALIBRATION_TABLE_SIZE; i++)
|
||||||
|
{
|
||||||
|
if (table[i].error == CALIBRATION_ERROR_NOT_SET)
|
||||||
|
{
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (false == flashGood())
|
||||||
|
{
|
||||||
|
saveToFlash();
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
//We want to linearly interpolate between calibration table angle
|
||||||
|
int CalibrationTable::getValue(Angle actualAngle, CalData_t *ptrData)
|
||||||
|
{
|
||||||
|
int32_t indexLow,indexHigh;
|
||||||
|
int32_t angleLow,angleHigh;
|
||||||
|
uint16_t value;
|
||||||
|
int32_t y1,y2;
|
||||||
|
int16_t err;
|
||||||
|
|
||||||
|
indexLow=getTableIndex((uint16_t)actualAngle);
|
||||||
|
// LOG("index %d, actual %u",indexLow, (uint16_t)actualAngle);
|
||||||
|
indexHigh=indexLow+1;
|
||||||
|
|
||||||
|
angleLow=(indexLow*CALIBRATION_STEPS)/CALIBRATION_TABLE_SIZE;
|
||||||
|
angleHigh=(indexHigh*CALIBRATION_STEPS)/CALIBRATION_TABLE_SIZE;
|
||||||
|
|
||||||
|
if (indexHigh>=CALIBRATION_TABLE_SIZE)
|
||||||
|
{
|
||||||
|
indexHigh -= CALIBRATION_TABLE_SIZE;
|
||||||
|
}
|
||||||
|
|
||||||
|
//LOG("AngleLow %d, AngleHigh %d",angleLow,angleHigh);
|
||||||
|
//LOG("TableLow %u, TableHigh %d",(uint16_t)table[indexLow].value,(uint16_t)table[indexHigh].value);
|
||||||
|
y1=table[indexLow].value;
|
||||||
|
y2=table[indexHigh].value;
|
||||||
|
|
||||||
|
//handle the wrap condition
|
||||||
|
if (abs(y2-y1)>CALIBRATION_STEPS/2)
|
||||||
|
{
|
||||||
|
if (y2<y1)
|
||||||
|
{
|
||||||
|
y2=y2+CALIBRATION_STEPS;
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
y1=y1+CALIBRATION_STEPS;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
value=interp(angleLow, y1, angleHigh, y2,actualAngle);
|
||||||
|
|
||||||
|
//handle the wrap condition
|
||||||
|
if (value>=CALIBRATION_STEPS)
|
||||||
|
{
|
||||||
|
value=value-CALIBRATION_STEPS;
|
||||||
|
}
|
||||||
|
|
||||||
|
err=table[indexLow].error;
|
||||||
|
if (table[indexHigh].error > err)
|
||||||
|
{
|
||||||
|
err=table[indexHigh].error;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (table[indexLow].error == CALIBRATION_ERROR_NOT_SET ||
|
||||||
|
table[indexHigh].error == CALIBRATION_ERROR_NOT_SET)
|
||||||
|
{
|
||||||
|
err=CALIBRATION_ERROR_NOT_SET;
|
||||||
|
}
|
||||||
|
ptrData->value=value;
|
||||||
|
ptrData->error=err;
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
Angle CalibrationTable::getCal(Angle actualAngle)
|
||||||
|
{
|
||||||
|
CalData_t data;
|
||||||
|
getValue(actualAngle, &data);
|
||||||
|
return data.value;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
104
firmware_smartstepper_trikarus/stepper_nano_zero/calibration.h
Normal file
@ -0,0 +1,104 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#ifndef __CALIBRAITON_H__
|
||||||
|
#define __CALIBRAITON_H__
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "syslog.h"
|
||||||
|
#include "angle.h"
|
||||||
|
|
||||||
|
|
||||||
|
//this file implements a table that is linearly interpolated circular calibration table
|
||||||
|
// it is assumed the data wraps around, ie you interpolated 65536==0
|
||||||
|
//we want this to be "whole" steps, for 1.8 degree motors this should be 200.
|
||||||
|
// 200 will work for 0.9 degree too, but could be 400. However 400 is not good for 1.8 degree motors
|
||||||
|
#define CALIBRATION_TABLE_SIZE (200)
|
||||||
|
|
||||||
|
#define CALIBRATION_STEPS ((uint32_t)ANGLE_STEPS) // this is one rotation ie 0-65535 aka 65536 steps is 0-360 degrees
|
||||||
|
|
||||||
|
#define CALIBRATION_ERROR_NOT_SET (-1) //indicated that the calibration value is not set.
|
||||||
|
|
||||||
|
#define CALIBRATION_UPDATE_RATE (32) //number of samples to keep 1 pole running average
|
||||||
|
#define CALIBRATION_MIN_ERROR (4) //the minimal expected error on our calibration 4 ~=+/0.2 degrees
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
uint16_t table[CALIBRATION_TABLE_SIZE];
|
||||||
|
bool status;
|
||||||
|
} FlashCalData_t;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
Angle value; //cal value
|
||||||
|
int16_t error; //error assuming it is constantly updated
|
||||||
|
} CalData_t;
|
||||||
|
|
||||||
|
class CalibrationTable
|
||||||
|
{
|
||||||
|
private:
|
||||||
|
CalData_t table[CALIBRATION_TABLE_SIZE];
|
||||||
|
|
||||||
|
bool fastCalVaild=false;
|
||||||
|
void loadFromFlash(void);
|
||||||
|
bool flashGood(void); //returns true if the flash copy of calibration is valid
|
||||||
|
|
||||||
|
void updateFastCal(void);
|
||||||
|
void createFastCal(void);
|
||||||
|
|
||||||
|
public:
|
||||||
|
void init(void);
|
||||||
|
void saveToFlash(void); //saves the calibration to flash
|
||||||
|
bool updateTableValue(int32_t index, int32_t value);
|
||||||
|
void updateTable(Angle actualAngle, Angle encoderValue);
|
||||||
|
int getValue(Angle actualAngle, CalData_t *ptrData);
|
||||||
|
Angle getCal(Angle actualAngle);
|
||||||
|
bool calValid(void);
|
||||||
|
Angle reverseLookup(Angle encoderAngle); //this turns encoder angle into real angle
|
||||||
|
void printCalTable(void);
|
||||||
|
void smoothTable(void);
|
||||||
|
|
||||||
|
Angle fastReverseLookup(Angle encoderAngle);
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#endif //__CALIBRAITON_H__
|
381
firmware_smartstepper_trikarus/stepper_nano_zero/command.cpp
Normal file
@ -0,0 +1,381 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
#include "command.h"
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
|
|
||||||
|
#define ASCII_BACKSPACE 0x08
|
||||||
|
#define ASCII_ESC 0x1B
|
||||||
|
#define ASCII_UP_ARROW 0x9b
|
||||||
|
//const char CMD_ANSI_UP[]= {ASCII_ESC,'[','A',0};
|
||||||
|
|
||||||
|
int strcicmp(char const *a, char const *b)
|
||||||
|
{
|
||||||
|
for (;; a++, b++) {
|
||||||
|
int d = tolower(*a) - tolower(*b);
|
||||||
|
if (d != 0 || !*a)
|
||||||
|
return d;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int CommandInit(sCmdUart *ptrUart, uint8_t (*kbhit)(void), uint8_t (*getch)(void),uint8_t (*putch)(char data),uint8_t (*puts)(uint8_t *buffer, uint8_t size) )
|
||||||
|
{
|
||||||
|
ptrUart->kbhit=kbhit;
|
||||||
|
ptrUart->getch=getch;
|
||||||
|
ptrUart->putch=putch;
|
||||||
|
ptrUart->puts=puts;
|
||||||
|
ptrUart->histIndex=0;
|
||||||
|
ptrUart->buffIndex=0;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef PGM_P //check and see if the PGM_P is defined for the AVR
|
||||||
|
|
||||||
|
int CommandPrintf(sCmdUart *ptrUart, const char *fmt, ...)
|
||||||
|
{
|
||||||
|
int ret=0;
|
||||||
|
char vastr[MAX_STRING]={0};
|
||||||
|
//char str[MAX_STRING]={0};
|
||||||
|
char *ptr;
|
||||||
|
va_list ap;
|
||||||
|
|
||||||
|
//LOG("Command printf");
|
||||||
|
memset(vastr,0,MAX_STRING);
|
||||||
|
va_start(ap,fmt);
|
||||||
|
ret=vsprintf(vastr,(const char *)fmt,ap);
|
||||||
|
//ret=sprintf(vastr,"%s\r\n",str);
|
||||||
|
//LOG("%s",vastr);
|
||||||
|
if (ptrUart->puts!=NULL)
|
||||||
|
{
|
||||||
|
return ptrUart->puts((uint8_t *)vastr, (uint8_t)ret);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ptrUart->putch!=NULL)
|
||||||
|
{
|
||||||
|
ptr=vastr;
|
||||||
|
while(*ptr)
|
||||||
|
{
|
||||||
|
ptrUart->putch(*ptr++);
|
||||||
|
}
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#else
|
||||||
|
int CommandPrintf(sCmdUart *ptrUart, char *fmt, ...)
|
||||||
|
{
|
||||||
|
int ret=0;
|
||||||
|
char vastr[MAX_STRING]={0};
|
||||||
|
char *ptr;
|
||||||
|
va_list ap;
|
||||||
|
|
||||||
|
|
||||||
|
memset(vastr,0,MAX_STRING);
|
||||||
|
va_start(ap,fmt);
|
||||||
|
ret=vsprintf(vastr,(char *)fmt,ap);
|
||||||
|
if (ptrUart->puts!=NULL)
|
||||||
|
{
|
||||||
|
return ptrUart->puts((uint8_t *)vastr, (uint8_t)ret);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ptrUart->putch!=NULL)
|
||||||
|
{
|
||||||
|
ptr=vastr;
|
||||||
|
while(*ptr)
|
||||||
|
{
|
||||||
|
ptrUart->putch(*ptr++);
|
||||||
|
}
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
// the delimiter is command/parameter delimiter
|
||||||
|
// by default a ' '0x20 is used but for the TDR with GUI a ':' was preferred, not sure why
|
||||||
|
// set to ' '/0x20 if you want normal command parsing, like DOS
|
||||||
|
unsigned int CommandParse(sCmdUart *ptrUart,sCommand *ptrCmds, char *str, char delimitor )
|
||||||
|
{
|
||||||
|
char *ptr;
|
||||||
|
char *ptr2;
|
||||||
|
unsigned int i;
|
||||||
|
//char cmd[MAX_STRING];
|
||||||
|
char buff[MAX_CMD_LENGTH];
|
||||||
|
char argv[MAX_ARGS][MAX_ARG_LENGTH];
|
||||||
|
char *ptrArgv[MAX_ARGS];
|
||||||
|
unsigned int numArgs;
|
||||||
|
int emptyArg=0;
|
||||||
|
|
||||||
|
sCommand cmd_list;
|
||||||
|
|
||||||
|
|
||||||
|
while (*str==0x20 || *str=='\n' || *str=='\r' || *str=='\t') str++;
|
||||||
|
//first we need find command and arguments
|
||||||
|
ptr=strchr(str,delimitor); //find first char
|
||||||
|
|
||||||
|
//LOG("2parsing %s",str);
|
||||||
|
|
||||||
|
|
||||||
|
if (ptr==0)
|
||||||
|
{
|
||||||
|
//we have two options, frist whole thing is command
|
||||||
|
//second bad command
|
||||||
|
if(strlen(str)>0)
|
||||||
|
ptr=str+strlen(str);
|
||||||
|
else
|
||||||
|
return 0; //bad command
|
||||||
|
}
|
||||||
|
|
||||||
|
//copy string to command buffer.
|
||||||
|
i=0;
|
||||||
|
ptr2=str;
|
||||||
|
while(ptr!=0 && ptr!=ptr2 && i<(MAX_CMD_LENGTH-1))
|
||||||
|
{
|
||||||
|
//if (*ptr2!='\n' && *ptr2!='\r') //do not include newlines
|
||||||
|
{
|
||||||
|
buff[i++]=*ptr2;
|
||||||
|
}
|
||||||
|
ptr2++;
|
||||||
|
}
|
||||||
|
buff[i]=0;
|
||||||
|
|
||||||
|
//now buff contains the command let's get the args
|
||||||
|
numArgs=0;
|
||||||
|
while(*ptr!=0 && (*ptr==' ' || *ptr==delimitor))
|
||||||
|
ptr++; //increment pointer past ' '
|
||||||
|
if (*ptr!=0)
|
||||||
|
{
|
||||||
|
if (*ptr==34) // " char
|
||||||
|
{
|
||||||
|
ptr++;
|
||||||
|
ptr2=strchr(ptr,34); //find match
|
||||||
|
} else if (*ptr==39) // 'char
|
||||||
|
{
|
||||||
|
ptr++;
|
||||||
|
ptr2=strchr(ptr,39); //find match
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
ptr2=strchr(ptr,delimitor);
|
||||||
|
}
|
||||||
|
if (ptr2==0)
|
||||||
|
{
|
||||||
|
//we have two options, frist whole thing is command
|
||||||
|
//second bad command
|
||||||
|
//LOG("strlen ptr is %d",strlen(ptr));
|
||||||
|
if(strlen(ptr)>0)
|
||||||
|
ptr2=ptr+strlen(ptr);
|
||||||
|
}
|
||||||
|
emptyArg=0;
|
||||||
|
while((ptr2!=0 && numArgs<MAX_ARGS) || emptyArg==1)
|
||||||
|
{
|
||||||
|
int j;
|
||||||
|
emptyArg=0;
|
||||||
|
j=0;
|
||||||
|
//LOG("arg %s",ptr);
|
||||||
|
while (ptr2!=ptr && j<(MAX_ARG_LENGTH-1) && ptr2!=0)
|
||||||
|
{
|
||||||
|
argv[numArgs][j++]=*ptr++;
|
||||||
|
}
|
||||||
|
argv[numArgs][j++]=0;
|
||||||
|
numArgs++;
|
||||||
|
ptr2=0;
|
||||||
|
if (*ptr!=0)
|
||||||
|
{
|
||||||
|
if (*ptr==34 || *ptr==39) ptr++;
|
||||||
|
if (*ptr==delimitor && strlen(ptr)==1)
|
||||||
|
{
|
||||||
|
//LOG("Empty arg");
|
||||||
|
emptyArg=1;
|
||||||
|
}
|
||||||
|
while(*ptr!=0 && (*ptr==' ' || *ptr==delimitor))//p || *ptr==34 || *ptr==39))
|
||||||
|
ptr++; //increment pointer past ' '
|
||||||
|
if (*ptr==34) // " char
|
||||||
|
{
|
||||||
|
ptr++;
|
||||||
|
ptr2=strchr(ptr,34); //find match
|
||||||
|
} else if (*ptr==39) // 'char
|
||||||
|
{
|
||||||
|
ptr++;
|
||||||
|
ptr2=strchr(ptr,39); //find match
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
ptr2=strchr(ptr,delimitor);
|
||||||
|
}
|
||||||
|
if (ptr2==0)
|
||||||
|
{
|
||||||
|
//we have two options, frist whole thing is command
|
||||||
|
//second bad command
|
||||||
|
if(strlen(ptr)>0)
|
||||||
|
ptr2=ptr+strlen(ptr);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
for(i=0; i<MAX_ARGS; i++)
|
||||||
|
{
|
||||||
|
ptrArgv[i]=argv[i];
|
||||||
|
}
|
||||||
|
|
||||||
|
//now let's parse the command
|
||||||
|
i=0;
|
||||||
|
memcpy(&cmd_list, &ptrCmds[i], sizeof(sCommand));
|
||||||
|
|
||||||
|
|
||||||
|
//LOG("command is %s %d",buff,numArgs);
|
||||||
|
|
||||||
|
while(cmd_list.function!=0)
|
||||||
|
{
|
||||||
|
/*char str[20];
|
||||||
|
strcpy_P(str,cmd_list.name);
|
||||||
|
LOG("checkign '%s' to '%s'",buff,str);
|
||||||
|
LOG("comapre is %d",strcmp_P(buff,cmd_list.name));
|
||||||
|
*/
|
||||||
|
|
||||||
|
//memcpy_P(&p, cmd_list.name, sizeof(PGM_P));
|
||||||
|
#ifdef PGM_P //check and see if the PGM_P is defined for the AVR
|
||||||
|
if (strlen(buff)==strlen_P(cmd_list.name))
|
||||||
|
{
|
||||||
|
if (strcicmp(buff,cmd_list.name)==0) //ignore device ID
|
||||||
|
#else
|
||||||
|
if (strlen(buff)==strlen(cmd_list.name))
|
||||||
|
{
|
||||||
|
if (strcicmp(buff,cmd_list.name)==0) //ignore device ID
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
//LOG("calling function");
|
||||||
|
//return 1;
|
||||||
|
return (*cmd_list.function)(ptrUart,numArgs,ptrArgv);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
i=i+1;
|
||||||
|
memcpy(&cmd_list, &ptrCmds[i], sizeof(sCommand));
|
||||||
|
}
|
||||||
|
CommandPrintf(ptrUart,PSTR("Unknown command (try 'help')\n\r"));
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
//This function will process commands from the UART
|
||||||
|
int CommandProcess(sCmdUart *ptrUart,sCommand *ptrCmds, char delimitor, char *cmdPrompt)
|
||||||
|
{
|
||||||
|
if(ptrUart->kbhit())
|
||||||
|
{
|
||||||
|
ptrUart->data=ptrUart->getch();
|
||||||
|
|
||||||
|
//echo the data
|
||||||
|
ptrUart->putch(ptrUart->data);
|
||||||
|
|
||||||
|
//if the data is the CR we need to process buffer
|
||||||
|
if (ptrUart->data==0x0D)
|
||||||
|
{
|
||||||
|
ptrUart->putch(0x0A);
|
||||||
|
if (strlen(ptrUart->buffer)>0)
|
||||||
|
{
|
||||||
|
if (ptrUart->lastChar!=ASCII_UP_ARROW)
|
||||||
|
{
|
||||||
|
strcpy(ptrUart->bufferHist[ptrUart->histIndex],ptrUart->buffer);
|
||||||
|
ptrUart->histIndex=(ptrUart->histIndex+1) % CMD_HISTORY;
|
||||||
|
}
|
||||||
|
CommandParse(ptrUart,ptrCmds,ptrUart->buffer,delimitor);
|
||||||
|
}
|
||||||
|
|
||||||
|
CommandPrintf(ptrUart,PSTR("\n\r%s"),cmdPrompt);
|
||||||
|
ptrUart->buffIndex=0;
|
||||||
|
ptrUart->buffer[ptrUart->buffIndex]=0;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ptrUart->data==ASCII_BACKSPACE) //backspace
|
||||||
|
{
|
||||||
|
if (ptrUart->buffIndex>0)
|
||||||
|
{
|
||||||
|
ptrUart->buffIndex--;
|
||||||
|
ptrUart->buffer[ptrUart->buffIndex]='\0';
|
||||||
|
//Echo the backspace
|
||||||
|
ptrUart->putch(' ');
|
||||||
|
ptrUart->putch(ASCII_BACKSPACE);
|
||||||
|
}
|
||||||
|
}else if (ptrUart->data != 0x0A && ptrUart->data !=0x0D && ptrUart->data<127)
|
||||||
|
{
|
||||||
|
ptrUart->buffer[ptrUart->buffIndex++]=ptrUart->data;
|
||||||
|
ptrUart->buffer[ptrUart->buffIndex]=0;
|
||||||
|
}
|
||||||
|
if (ptrUart->buffIndex>=(MAX_CMD_LENGTH-1))
|
||||||
|
{
|
||||||
|
CommandPrintf(ptrUart,PSTR("\n\rERROR: Command buffer overflow\n\r"));\
|
||||||
|
ERROR("Command buffer overflow");
|
||||||
|
ptrUart->buffIndex=0;
|
||||||
|
ptrUart->buffer[0]=0;
|
||||||
|
CommandPrintf(ptrUart,PSTR("\n\r%s"),cmdPrompt);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
if (strstr(ptrUart->buffer,ANSI_UP)) //up arrow
|
||||||
|
{
|
||||||
|
uint8_t i;
|
||||||
|
|
||||||
|
CommandPrintf(ptrUart,PSTR("\n\r%s"),cmdPrompt);
|
||||||
|
i=CMD_HISTORY-1;
|
||||||
|
if (ptrUart->histIndex>0)
|
||||||
|
{
|
||||||
|
i=ptrUart->histIndex-1;
|
||||||
|
}
|
||||||
|
if (strlen(ptrUart->bufferHist[i])>0)
|
||||||
|
{
|
||||||
|
strcpy(ptrUart->buffer,ptrUart->bufferHist[i]);
|
||||||
|
ptrUart->buffIndex=strlen(ptrUart->buffer);
|
||||||
|
CommandPrintf(ptrUart,PSTR("%s"),ptrUart->buffer);
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
ptrUart->buffIndex=0;
|
||||||
|
ptrUart->buffer[0]=0;
|
||||||
|
}
|
||||||
|
ptrUart->data=ASCII_UP_ARROW;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
ptrUart->lastChar=ptrUart->data;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
179
firmware_smartstepper_trikarus/stepper_nano_zero/command.h
Normal file
@ -0,0 +1,179 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#ifndef __COMMAND_H
|
||||||
|
#define __COMMAND_H
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include <stdarg.h>
|
||||||
|
#include "syslog.h"
|
||||||
|
/*
|
||||||
|
* Usage:
|
||||||
|
*
|
||||||
|
#include <command.h>
|
||||||
|
#include "uart_e0.h"
|
||||||
|
|
||||||
|
sCmdUart KeyfobCmdUart; // UART used for the keyfob command line interface
|
||||||
|
|
||||||
|
CMD_STR(help,"Displays this message");
|
||||||
|
|
||||||
|
//List of supported commands
|
||||||
|
sCommand KeyfobCmds[] =
|
||||||
|
{
|
||||||
|
COMMAND(help),
|
||||||
|
{"",0,""}, //End of list signal
|
||||||
|
};
|
||||||
|
|
||||||
|
// print out the help strings for the commands
|
||||||
|
static int help_cmd(sCmdUart *ptrUart,int argc, char * argv[])
|
||||||
|
{
|
||||||
|
sCommand cmd_list;
|
||||||
|
int i;
|
||||||
|
|
||||||
|
//now let's parse the command
|
||||||
|
i=0;
|
||||||
|
memcpy(&cmd_list, &KeyfobCmds[i], sizeof(sCommand));
|
||||||
|
while(cmd_list.function!=0)
|
||||||
|
{
|
||||||
|
|
||||||
|
CommandPrintf(ptrUart,(cmd_list.name));
|
||||||
|
CommandPrintf(ptrUart,PSTR(" - "));
|
||||||
|
CommandPrintf(ptrUart,(cmd_list.help));
|
||||||
|
CommandPrintf(ptrUart,PSTR("\n\r"));
|
||||||
|
i=i+1;
|
||||||
|
memcpy(&cmd_list, &KeyfobCmds[i], sizeof(sCommand));
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t KeyfobCmdGetChar(void)
|
||||||
|
{
|
||||||
|
uint8_t c;
|
||||||
|
if (UARTE0_getc(&c)!=0)
|
||||||
|
{
|
||||||
|
ERROR("Uart getchar failed");
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
return c;
|
||||||
|
}
|
||||||
|
int KeyfobCmdInit(PIN tx_pin, PIN rx_pin, uint32_t baud)
|
||||||
|
{
|
||||||
|
LOG("UARTE0 init");
|
||||||
|
UARTE0_Init(tx_pin, rx_pin, baud);
|
||||||
|
CommandInit(&KeyfobCmdUart, UARTE0_kbhit, KeyfobCmdGetChar, UARTE0_putc,NULL); //set up the UART structure
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
int KeyfobCmdProcess(void)
|
||||||
|
{
|
||||||
|
return CommandProcess(&KeyfobCmdUart,KeyfobCmds,' ',KEYFOB_CMD_PROMPT);
|
||||||
|
}
|
||||||
|
|
||||||
|
Advantages:
|
||||||
|
1. You can actually have more than one UART/device connected to same command line interface.
|
||||||
|
2. works with harvard machines to save SRAM space using the PSTR functionality
|
||||||
|
3. You can swap out commands "on the fly"
|
||||||
|
|
||||||
|
|
||||||
|
*/
|
||||||
|
#define MAX_CMD_LENGTH 60
|
||||||
|
#define MAX_ARGS 10
|
||||||
|
#define MAX_ARG_LENGTH 40
|
||||||
|
#define CMD_HISTORY 3 //number of commands in history buffer
|
||||||
|
#define ASCII_BACKSPACE 0x08
|
||||||
|
#define ASCII_ESC 0x1B
|
||||||
|
#define ASCII_UP_ARROW 0x9b
|
||||||
|
#define ANSI_UP "\x1B[A\0"
|
||||||
|
|
||||||
|
#define MAX_STRING 255
|
||||||
|
//const char ANSI_UP[]= {ASCII_ESC,'[','A',0};
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
uint8_t (*kbhit)(void);
|
||||||
|
uint8_t (*getch)(void);
|
||||||
|
uint8_t (*putch)(char data);
|
||||||
|
uint8_t (*puts)(uint8_t *buffer, uint8_t size);
|
||||||
|
uint8_t data;
|
||||||
|
char buffer[MAX_CMD_LENGTH];
|
||||||
|
|
||||||
|
char bufferHist[CMD_HISTORY][MAX_CMD_LENGTH];
|
||||||
|
uint8_t histIndex;
|
||||||
|
uint8_t buffIndex;
|
||||||
|
uint8_t lastChar;
|
||||||
|
}sCmdUart;
|
||||||
|
|
||||||
|
|
||||||
|
#define COMMAND(NAME) { NAME ## _str, NAME ## _cmd, NAME ## _help}
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef PGM_P //check and see if the PGM_P is defined for the AVR
|
||||||
|
|
||||||
|
//If so then we use the strings in flash not SRAM
|
||||||
|
#define CMD_STR(NAME,STR) static const char NAME ## _help[] PROGMEM = STR; static const char NAME ## _str[] PROGMEM = #NAME; static int NAME ##_cmd(sCmdUart *ptrUart,int, char **);
|
||||||
|
//Command structure
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
PGM_P name;
|
||||||
|
int (*function) (sCmdUart *ptrUart,int, char **);
|
||||||
|
PGM_P help;
|
||||||
|
} sCommand;
|
||||||
|
int CommandPrintf(sCmdUart *ptrUart, const char *fmt, ...);
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
#define CMD_STR(NAME,STR) static char NAME ## _help[] = STR; static char NAME ## _str[] = #NAME; static int NAME ##_cmd(sCmdUart *ptrUart,int, char **);
|
||||||
|
|
||||||
|
//Command structure
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
char *name;
|
||||||
|
int (*function) (sCmdUart *ptrUart,int, char **);
|
||||||
|
char *help;
|
||||||
|
} sCommand;
|
||||||
|
|
||||||
|
int CommandPrintf(sCmdUart *ptrUart, char *fmt, ...);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
int CommandInit(sCmdUart *ptrUart, uint8_t (*kbhit)(void), uint8_t (*getch)(void),uint8_t (*putch)(char data),uint8_t (*puts)(uint8_t *buffer, uint8_t size));
|
||||||
|
unsigned int CommandParse(sCmdUart *ptrUart,sCommand *ptrCmds, char *str, char delimitor);
|
||||||
|
int CommandProcess(sCmdUart *ptrUart,sCommand *ptrCmds, char delimitor, char *cmdPrompt);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
1658
firmware_smartstepper_trikarus/stepper_nano_zero/commands.cpp
Normal file
51
firmware_smartstepper_trikarus/stepper_nano_zero/commands.h
Normal file
@ -0,0 +1,51 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#ifndef __COMMANDS_H__
|
||||||
|
#define __COMMANDS_H__
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "stepper_controller.h"
|
||||||
|
#include "nzs.h"
|
||||||
|
|
||||||
|
extern StepperCtrl stepperCtrl;
|
||||||
|
extern eepromData_t PowerupEEPROM;
|
||||||
|
|
||||||
|
void commandsInit(void);
|
||||||
|
int commandsProcess(void);
|
||||||
|
void torqueSetToZeroSpecialBehaviour(void);
|
||||||
|
|
||||||
|
#endif //__COMMANDS_H__
|
309
firmware_smartstepper_trikarus/stepper_nano_zero/eeprom.cpp
Normal file
@ -0,0 +1,309 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#include "eeprom.h"
|
||||||
|
#include "calibration.h"
|
||||||
|
#include "Flash.h"
|
||||||
|
#include "board.h" //for divide with rounding macro
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "syslog.h"
|
||||||
|
|
||||||
|
//since we will write the following structure into each page, we need to find our latest page
|
||||||
|
// to do this we will use the header to contain a checksum and write counter.
|
||||||
|
#define EEPROM_SIZE (FLASH_ROW_SIZE*2)
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
uint16_t checksum;
|
||||||
|
uint16_t count;
|
||||||
|
}eepromHeader_t;
|
||||||
|
|
||||||
|
#define EEPROM_DATA_SIZE (FLASH_PAGE_SIZE_NZS-sizeof(eepromHeader_t))
|
||||||
|
typedef struct {
|
||||||
|
eepromHeader_t header;
|
||||||
|
uint8_t data[EEPROM_DATA_SIZE];
|
||||||
|
} eepromData_t;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
static eepromData_t EEPROMCache;
|
||||||
|
|
||||||
|
static int32_t NextPageWrite=-1;
|
||||||
|
|
||||||
|
//we need to reserve two pages for EEPROM
|
||||||
|
__attribute__((__aligned__(FLASH_ROW_SIZE))) const uint8_t NVM_eeprom[EEPROM_SIZE]={0xFF};
|
||||||
|
|
||||||
|
|
||||||
|
static uint16_t checksum(uint8_t *ptrData, uint32_t nBytes)
|
||||||
|
{
|
||||||
|
uint16_t sum=0;
|
||||||
|
uint32_t i;
|
||||||
|
i=0;
|
||||||
|
//LOG("running checksum %d",nBytes);
|
||||||
|
while(i<nBytes)
|
||||||
|
{
|
||||||
|
sum += ptrData[i];
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
|
||||||
|
return sum;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool isPageGood(uint32_t page)
|
||||||
|
{
|
||||||
|
eepromData_t *ptrData;
|
||||||
|
uint16_t cs;
|
||||||
|
ptrData=(eepromData_t *)&NVM_eeprom[page];
|
||||||
|
|
||||||
|
cs=checksum(ptrData->data, EEPROM_DATA_SIZE);
|
||||||
|
//LOG("checksum is %d %d",cs,ptrData->header.checksum);
|
||||||
|
|
||||||
|
if (cs==ptrData->header.checksum)
|
||||||
|
{
|
||||||
|
//LOG("Page good %d",page);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
//LOG("page bad %d",page);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void printEEPROM(uint32_t page)
|
||||||
|
{
|
||||||
|
eepromData_t *ptrData;
|
||||||
|
int i;
|
||||||
|
ptrData=(eepromData_t *)&NVM_eeprom[page];
|
||||||
|
LOG("count %d", ptrData->header.count);
|
||||||
|
LOG("checksum %d", ptrData->header.checksum);
|
||||||
|
for (i=0; i<10; i++)
|
||||||
|
{
|
||||||
|
LOG("Data[%d]=%02X",i,ptrData->data[i]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static uint32_t findLastGoodPage(void)
|
||||||
|
{
|
||||||
|
uint32_t lastGoodPage=0;
|
||||||
|
uint32_t page;
|
||||||
|
uint16_t lastCnt=0;
|
||||||
|
eepromData_t *ptrData;
|
||||||
|
|
||||||
|
page=0;
|
||||||
|
while(page < (EEPROM_SIZE))
|
||||||
|
{
|
||||||
|
//LOG("checking page %d",page);
|
||||||
|
if (isPageGood(page))
|
||||||
|
{
|
||||||
|
ptrData=(eepromData_t *)&NVM_eeprom[page];
|
||||||
|
|
||||||
|
//check for roll over which is OK
|
||||||
|
if (lastCnt==16534 && ptrData->header.count==1)
|
||||||
|
{
|
||||||
|
lastCnt=ptrData->header.count;
|
||||||
|
lastGoodPage=page;
|
||||||
|
}
|
||||||
|
if (ptrData->header.count>lastCnt)
|
||||||
|
{
|
||||||
|
//make sure we have not rolled over.
|
||||||
|
if ((ptrData->header.count-lastCnt)<(16534/2))
|
||||||
|
{
|
||||||
|
lastCnt=ptrData->header.count;
|
||||||
|
lastGoodPage=page;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
page=page + FLASH_PAGE_SIZE_NZS;
|
||||||
|
}
|
||||||
|
//LOG("last good page %d",lastGoodPage);
|
||||||
|
return lastGoodPage;
|
||||||
|
}
|
||||||
|
|
||||||
|
//find the next page to write
|
||||||
|
static uint32_t eepromGetNextWritPage(void)
|
||||||
|
{
|
||||||
|
eepromHeader_t *ptrHeader;
|
||||||
|
uint32_t page;
|
||||||
|
uint32_t row;
|
||||||
|
int blockCount;
|
||||||
|
int done=0;
|
||||||
|
|
||||||
|
//start at first address:
|
||||||
|
page=0;
|
||||||
|
|
||||||
|
while(page < (EEPROM_SIZE))
|
||||||
|
{
|
||||||
|
//LOG("checking page %d",page);
|
||||||
|
ptrHeader=(eepromHeader_t *) &NVM_eeprom[page];
|
||||||
|
if (ptrHeader->count == 0xFFFF)
|
||||||
|
{
|
||||||
|
uint32_t i;
|
||||||
|
uint8_t *ptrData;
|
||||||
|
//uint8_t erasedByte=(uint8_t)ptrHeader->count;
|
||||||
|
bool erased=true;
|
||||||
|
|
||||||
|
//verify page is erased
|
||||||
|
ptrData= (uint8_t *)&NVM_eeprom[page];
|
||||||
|
|
||||||
|
for (i=0; i<FLASH_PAGE_SIZE_NZS; i++)
|
||||||
|
{
|
||||||
|
if (ptrData[i] != FLASH_ERASE_VALUE)
|
||||||
|
{
|
||||||
|
erased=false;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (erased)
|
||||||
|
{
|
||||||
|
//LOG("Found Page %d erased",page);
|
||||||
|
return page;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
page=page+FLASH_PAGE_SIZE_NZS;
|
||||||
|
}
|
||||||
|
//if we get get here all the pages are full...
|
||||||
|
// we need to find the page with last good data.
|
||||||
|
page=findLastGoodPage();
|
||||||
|
|
||||||
|
//find which row the page is in
|
||||||
|
row=page/FLASH_ROW_SIZE;
|
||||||
|
|
||||||
|
//increment to next row for erase
|
||||||
|
row++;
|
||||||
|
if ((row*FLASH_ROW_SIZE)>=EEPROM_SIZE)
|
||||||
|
{
|
||||||
|
row=0;
|
||||||
|
//TODO we should make sure this not where good data is
|
||||||
|
// however if it is what should we do?
|
||||||
|
}
|
||||||
|
|
||||||
|
//now we need to erase that row
|
||||||
|
//WARNING("Erasing page %d",row*FLASH_ROW_SIZE);
|
||||||
|
flashErase(&NVM_eeprom[row*FLASH_ROW_SIZE],FLASH_ROW_SIZE);
|
||||||
|
page=row*FLASH_ROW_SIZE;
|
||||||
|
//LOG("Next free page is %d",page);
|
||||||
|
return page;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
eepromError_t eepromInit(void)
|
||||||
|
{
|
||||||
|
uint32_t page;
|
||||||
|
|
||||||
|
|
||||||
|
//find the last good page offset in flash
|
||||||
|
page=findLastGoodPage();
|
||||||
|
LOG("EEPROM Init found page %d",page);
|
||||||
|
if (isPageGood(page))
|
||||||
|
{
|
||||||
|
LOG("EEPROM page good %d",page);
|
||||||
|
memcpy(&EEPROMCache, &NVM_eeprom[page], sizeof(EEPROMCache));
|
||||||
|
|
||||||
|
NextPageWrite=eepromGetNextWritPage();
|
||||||
|
return EEPROM_OK;
|
||||||
|
}
|
||||||
|
//ERROR("page is bad");
|
||||||
|
memset(&EEPROMCache, 0, sizeof(EEPROMCache));
|
||||||
|
NextPageWrite=eepromGetNextWritPage();
|
||||||
|
return EEPROM_CORRUPT;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int eepromWriteCache(uint8_t *ptrData, uint32_t size)
|
||||||
|
{
|
||||||
|
//LOG("Cache write %d",size);
|
||||||
|
if (NextPageWrite==-1) //some one did not init the module
|
||||||
|
{
|
||||||
|
//lets handle gracefully and do it ourselves
|
||||||
|
eepromInit();
|
||||||
|
}
|
||||||
|
if (size>EEPROM_DATA_SIZE)
|
||||||
|
{
|
||||||
|
size =EEPROM_DATA_SIZE;
|
||||||
|
}
|
||||||
|
memcpy(EEPROMCache.data, ptrData, size);
|
||||||
|
EEPROMCache.header.checksum=checksum(EEPROMCache.data,EEPROM_DATA_SIZE);
|
||||||
|
|
||||||
|
|
||||||
|
return size;
|
||||||
|
}
|
||||||
|
|
||||||
|
int eepromRead(uint8_t *ptrData, uint32_t size) //returns number of bytes actually read, whcih could be less than size requested
|
||||||
|
{
|
||||||
|
if (NextPageWrite==-1) //some one did not init the module
|
||||||
|
{
|
||||||
|
//lets handle gracefully and do it ourselves
|
||||||
|
eepromInit();
|
||||||
|
}
|
||||||
|
if (size>EEPROM_DATA_SIZE)
|
||||||
|
{
|
||||||
|
size =EEPROM_DATA_SIZE;
|
||||||
|
}
|
||||||
|
if (EEPROMCache.header.count == 0)
|
||||||
|
{
|
||||||
|
return 0; //cache is new/corrupt
|
||||||
|
}
|
||||||
|
memcpy(ptrData, EEPROMCache.data, size);
|
||||||
|
return size;
|
||||||
|
}
|
||||||
|
|
||||||
|
eepromError_t eepromFlush(void) //flush the cache to flash memory
|
||||||
|
{
|
||||||
|
if (NextPageWrite==-1)
|
||||||
|
{
|
||||||
|
ERROR("EEPROM WRITE FAILED");
|
||||||
|
return EEPROM_FAILED; //most likely no one has written to cache
|
||||||
|
}
|
||||||
|
EEPROMCache.header.count++;
|
||||||
|
if (EEPROMCache.header.count>=16535)
|
||||||
|
{
|
||||||
|
EEPROMCache.header.count=1;
|
||||||
|
}
|
||||||
|
//WARNING("Writting to Page %d",NextPageWrite);
|
||||||
|
flashWrite(&NVM_eeprom[NextPageWrite], &EEPROMCache, sizeof(EEPROMCache));
|
||||||
|
|
||||||
|
// printEEPROM(NextPageWrite);
|
||||||
|
|
||||||
|
if (!SYSCTRL->PCLKSR.bit.BOD33DET) //if not in brown out condition find next write location
|
||||||
|
{
|
||||||
|
//LOG("getting next page to write");
|
||||||
|
NextPageWrite=eepromGetNextWritPage(); //find next write location and erase if needed
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
//LOG("BOD active");
|
||||||
|
NextPageWrite=-1; //else we will just clear NextPageWrite location just in case we recover from brown out
|
||||||
|
}
|
||||||
|
return EEPROM_OK;
|
||||||
|
}
|
62
firmware_smartstepper_trikarus/stepper_nano_zero/eeprom.h
Normal file
@ -0,0 +1,62 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#ifndef EEPROM_H_
|
||||||
|
#define EEPROM_H_
|
||||||
|
#include "Flash.h"
|
||||||
|
#include "calibration.h"
|
||||||
|
#include "board.h"
|
||||||
|
|
||||||
|
/*
|
||||||
|
* This EEPROM implementation provides 60bytes of "eeprom space" (we reserve 4 bytes for overhead)
|
||||||
|
* The EEPROM uses two rows of flash (256 bytes per row), which
|
||||||
|
* for the SAMD21G18A this allows a minimual 200k writes, but typically 1200k
|
||||||
|
*/
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
EEPROM_OK =0,
|
||||||
|
EEPROM_FAILED=1,
|
||||||
|
EEPROM_CORRUPT=2,
|
||||||
|
} eepromError_t;
|
||||||
|
|
||||||
|
|
||||||
|
eepromError_t eepromInit(void);
|
||||||
|
int eepromWriteCache(uint8_t *ptrData, uint32_t size); //returns number bytes written to cache
|
||||||
|
eepromError_t eepromFlush(void); //flush the cache to flash memory
|
||||||
|
int eepromRead(uint8_t *ptrData, uint32_t size); //returns number of bytes actually read, whcih could be less than size requested
|
||||||
|
|
||||||
|
#endif /* EEPROM_H_ */
|
1685
firmware_smartstepper_trikarus/stepper_nano_zero/fet_driver.cpp
Normal file
124
firmware_smartstepper_trikarus/stepper_nano_zero/fet_driver.h
Normal file
@ -0,0 +1,124 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
#ifndef FET_DRIVER_H_
|
||||||
|
#define FET_DRIVER_H_
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "board.h"
|
||||||
|
#include "angle.h"
|
||||||
|
#include "sine.h"
|
||||||
|
|
||||||
|
#ifdef NEMA_23_10A_HW
|
||||||
|
#define FET_DRIVER_NUM_MICROSTEPS (SINE_STEPS/4) //number of steps to use for microstepping, default is 256
|
||||||
|
#define FET_DRIVER_NUM_ZERO_AVG (100)
|
||||||
|
|
||||||
|
|
||||||
|
#define FET_ADC_TO_MA(x) (((x)*2537)/1000)
|
||||||
|
#define FET_MA_TO_ADC(x) (((x)*1000)/2537)
|
||||||
|
//prvent someone for making a mistake with the code
|
||||||
|
#if ((FET_DRIVER_NUM_MICROSTEPS*4) != SINE_STEPS)
|
||||||
|
#error "SINE_STEPS must be 4x of Micro steps for the move function"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*
|
||||||
|
* When it comes to the stepper driver if we use angles
|
||||||
|
* we will always have a rounding error. For example
|
||||||
|
* a 0-65536(360) angle for 1.8 degree step is 327.68 so
|
||||||
|
* if you increment 200 of these as 327 you have a 13.6 error
|
||||||
|
* after one rotation.
|
||||||
|
* If you use floating point the effect is the same but takes longer.
|
||||||
|
*
|
||||||
|
* The only error-less accumulation system is to use native units, ie full
|
||||||
|
* steps and microsteps.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
class FetDriver
|
||||||
|
{
|
||||||
|
static FetDriver *ptrInstance;
|
||||||
|
private:
|
||||||
|
uint32_t lastStepMicros; // time in microseconds that last step happened
|
||||||
|
|
||||||
|
int32_t PWM_Table_B[512];
|
||||||
|
int32_t PWM_Table_A[512];
|
||||||
|
|
||||||
|
bool forwardRotation=true;
|
||||||
|
volatile bool enabled=true;
|
||||||
|
|
||||||
|
volatile int32_t adc;
|
||||||
|
|
||||||
|
|
||||||
|
volatile int32_t coilB_value=0;
|
||||||
|
volatile int32_t coilB_Zero=-1;
|
||||||
|
volatile int32_t coilB_SetPoint=100;
|
||||||
|
volatile int32_t coilB_error=0;
|
||||||
|
|
||||||
|
volatile int32_t coilA_value=0;
|
||||||
|
volatile int32_t coilA_Zero=-1;
|
||||||
|
volatile int32_t coilA_SetPoint=200;
|
||||||
|
volatile int32_t coilA_error=0;
|
||||||
|
void ctrl_update(uint16_t channel, uint16_t value);
|
||||||
|
void measureCoilB_zero(void);
|
||||||
|
void measureCoilA_zero(void);
|
||||||
|
void CalTableB(int32_t maxMA);
|
||||||
|
void CalTableA(int32_t maxMA);
|
||||||
|
int coilA_PWM(int32_t value);
|
||||||
|
void coilB_PWM(int32_t value);
|
||||||
|
int32_t getCoilB_mA(void);
|
||||||
|
int32_t getCoilA_mA(void);
|
||||||
|
public:
|
||||||
|
|
||||||
|
static void ADC_Callback(uint16_t channel, uint16_t value);
|
||||||
|
void begin(void);
|
||||||
|
|
||||||
|
//moves motor where the modulo of A4954_NUM_MICROSTEPS is a full step.
|
||||||
|
int32_t move(int32_t stepAngle, uint32_t mA);
|
||||||
|
|
||||||
|
uint32_t microsSinceStep(void) {return micros()-lastStepMicros;};
|
||||||
|
void setRotationDirection(bool forward) {forwardRotation=forward;};
|
||||||
|
|
||||||
|
void enable(bool enable) {enabled=enable;};
|
||||||
|
void limitCurrent(uint8_t x) {return;};
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
#endif //#ifdef NEMA_23_10A_HW
|
||||||
|
#endif /* FET_DRIVER_H_ */
|
193
firmware_smartstepper_trikarus/stepper_nano_zero/ftoa.cpp
Normal file
@ -0,0 +1,193 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#include "board.h"
|
||||||
|
#include "ftoa.h"
|
||||||
|
/*******************************************************************
|
||||||
|
* FUNCTION: ftoa
|
||||||
|
* AUTHOR = TRAMPAS STERN
|
||||||
|
* FILE = strio.c
|
||||||
|
* DATE = 2/6/2003 4:27:14 PM
|
||||||
|
*
|
||||||
|
* PARAMETERS: long,*str, int count
|
||||||
|
*
|
||||||
|
* DESCRIPTION: Convets an float to string
|
||||||
|
* format 'f', 'E', or 'e'
|
||||||
|
*
|
||||||
|
*
|
||||||
|
* RETURNS:
|
||||||
|
*
|
||||||
|
* NOTE this code was found on the web and modified to actually work
|
||||||
|
*******************************************************************/
|
||||||
|
int ftoa (float x, char *str, char prec, char format)
|
||||||
|
{
|
||||||
|
|
||||||
|
int ie, i, k, ndig, fstyle;
|
||||||
|
double y;
|
||||||
|
char *start;
|
||||||
|
|
||||||
|
start=str;
|
||||||
|
|
||||||
|
//based on percission set number digits
|
||||||
|
ndig=prec+1;
|
||||||
|
if (prec<0)
|
||||||
|
ndig=7;
|
||||||
|
if (prec>22)
|
||||||
|
ndig=23;
|
||||||
|
|
||||||
|
fstyle = 0; //exponent 'e'
|
||||||
|
if (format == 'f' || format == 'F')
|
||||||
|
fstyle = 1; //normal 'f'
|
||||||
|
if (format=='g' || format=='G')
|
||||||
|
fstyle=2;
|
||||||
|
|
||||||
|
ie = 0;
|
||||||
|
/* if x negative, write minus and reverse */
|
||||||
|
if ( x < 0)
|
||||||
|
{
|
||||||
|
*str++ = '-';
|
||||||
|
x = -x;
|
||||||
|
}
|
||||||
|
|
||||||
|
//if (x<0.0) then increment by 10 till betwen 1.0 and 10.0
|
||||||
|
if (x!=0.0)
|
||||||
|
{
|
||||||
|
while (x < 1.0)
|
||||||
|
{
|
||||||
|
x =x* 10.0;
|
||||||
|
ie--;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
//if x>10 then let's shift it down
|
||||||
|
while (x >= 10.0)
|
||||||
|
{
|
||||||
|
x = x*(1.0/10.0);
|
||||||
|
ie++;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ABS(ie)>MAX_MANTISA)
|
||||||
|
{
|
||||||
|
if (fstyle==1)
|
||||||
|
{
|
||||||
|
fstyle=0;
|
||||||
|
format='e';
|
||||||
|
//ie=2;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/* in f format, number of digits is related to size */
|
||||||
|
if (fstyle)
|
||||||
|
ndig =ndig + ie;
|
||||||
|
|
||||||
|
if(prec==0 && ie>ndig && fstyle)
|
||||||
|
{
|
||||||
|
ndig=ie;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* round. x is between 1 and 10 and ndig will be printed to
|
||||||
|
right of decimal point so rounding is ... */
|
||||||
|
y=1;
|
||||||
|
for (i = 1; i < ndig; i++) //find lest significant digit
|
||||||
|
y = y *(1.0/10.0); //multiply by 1/10 is faster than divides
|
||||||
|
|
||||||
|
x = x+ y *(1.0/2.0); //add rounding
|
||||||
|
|
||||||
|
/* repair rounding disasters */
|
||||||
|
if (x >= 10.0)
|
||||||
|
{
|
||||||
|
x = 1.0;
|
||||||
|
ie++;
|
||||||
|
ndig++;
|
||||||
|
}
|
||||||
|
|
||||||
|
//check and see if the number is less than 1.0
|
||||||
|
if (fstyle && ie<0)
|
||||||
|
{
|
||||||
|
*str++ = '0';
|
||||||
|
if (prec!=0)
|
||||||
|
*str++ = '.';
|
||||||
|
if (ndig < 0)
|
||||||
|
ie = ie-ndig; /* limit zeros if underflow */
|
||||||
|
for (i = -1; i > ie; i--)
|
||||||
|
*str++ = '0';
|
||||||
|
}
|
||||||
|
|
||||||
|
//for each digit
|
||||||
|
for (i=0; i < ndig; i++)
|
||||||
|
{
|
||||||
|
float b;
|
||||||
|
k = x; //k = most significant digit
|
||||||
|
*str++ = k + '0'; //output the char representation
|
||||||
|
if (((!fstyle && i==0) || (fstyle && i==ie)) && prec!=0)
|
||||||
|
*str++ = '.'; //output a decimal point
|
||||||
|
b=(float)k;
|
||||||
|
//multiply by 10 before subtraction to remove
|
||||||
|
//errors from limited number of bits in float.
|
||||||
|
b=b*10.0;
|
||||||
|
x=x*10.0;
|
||||||
|
x =x - b; //subtract k from x
|
||||||
|
//b=x+b;
|
||||||
|
//x =x* 10.0; //get next digit
|
||||||
|
}
|
||||||
|
|
||||||
|
/* now, in estyle, put out exponent if not zero */
|
||||||
|
if (!fstyle && ie != 0)
|
||||||
|
{
|
||||||
|
*str++ = format;
|
||||||
|
if (ie < 0) //if number has negative exponent
|
||||||
|
{
|
||||||
|
ie = -ie;
|
||||||
|
*str++ = '-';
|
||||||
|
}
|
||||||
|
|
||||||
|
//now we need to convert the exponent to string
|
||||||
|
for (k=1000; k>ie; k=k/10); //find the decade of exponent
|
||||||
|
|
||||||
|
for (; k > 0; k=k/10)
|
||||||
|
{
|
||||||
|
char t;
|
||||||
|
t=DIV(ie,k);
|
||||||
|
*str++ = t + '0';
|
||||||
|
ie = ie -(t*k);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
*str++ = '\0';
|
||||||
|
return (str-start); //return string length
|
||||||
|
}
|
48
firmware_smartstepper_trikarus/stepper_nano_zero/ftoa.h
Normal file
@ -0,0 +1,48 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
#ifndef FTOA_H_
|
||||||
|
#define FTOA_H_
|
||||||
|
|
||||||
|
#define MAX_MANTISA (1000)
|
||||||
|
|
||||||
|
int ftoa (float x, char *str, char prec, char format);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* FTOA_H_ */
|
24
firmware_smartstepper_trikarus/stepper_nano_zero/gfxfont.h
Normal file
@ -0,0 +1,24 @@
|
|||||||
|
// Font structures for newer Adafruit_GFX (1.1 and later).
|
||||||
|
// Example fonts are included in 'Fonts' directory.
|
||||||
|
// To use a font in your Arduino sketch, #include the corresponding .h
|
||||||
|
// file and pass address of GFXfont struct to setFont(). Pass NULL to
|
||||||
|
// revert to 'classic' fixed-space bitmap font.
|
||||||
|
|
||||||
|
#ifndef _GFXFONT_H_
|
||||||
|
#define _GFXFONT_H_
|
||||||
|
|
||||||
|
typedef struct { // Data stored PER GLYPH
|
||||||
|
uint16_t bitmapOffset; // Pointer into GFXfont->bitmap
|
||||||
|
uint8_t width, height; // Bitmap dimensions in pixels
|
||||||
|
uint8_t xAdvance; // Distance to advance cursor (x axis)
|
||||||
|
int8_t xOffset, yOffset; // Dist from cursor pos to UL corner
|
||||||
|
} GFXglyph;
|
||||||
|
|
||||||
|
typedef struct { // Data stored for FONT AS A WHOLE:
|
||||||
|
uint8_t *bitmap; // Glyph bitmaps, concatenated
|
||||||
|
GFXglyph *glyph; // Glyph array
|
||||||
|
uint8_t first, last; // ASCII extents
|
||||||
|
uint8_t yAdvance; // Newline distance (y axis)
|
||||||
|
} GFXfont;
|
||||||
|
|
||||||
|
#endif // _GFXFONT_H_
|
276
firmware_smartstepper_trikarus/stepper_nano_zero/glcdfont.c
Normal file
@ -0,0 +1,276 @@
|
|||||||
|
// This is the 'classic' fixed-space bitmap font for Adafruit_GFX since 1.0.
|
||||||
|
// See gfxfont.h for newer custom bitmap font info.
|
||||||
|
|
||||||
|
#ifndef FONT5X7_H
|
||||||
|
#define FONT5X7_H
|
||||||
|
|
||||||
|
#ifdef __AVR__
|
||||||
|
#include <avr/io.h>
|
||||||
|
#include <avr/pgmspace.h>
|
||||||
|
#elif defined(ESP8266)
|
||||||
|
#include <pgmspace.h>
|
||||||
|
#else
|
||||||
|
#define PROGMEM
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Standard ASCII 5x7 font
|
||||||
|
|
||||||
|
static const unsigned char font[] PROGMEM = {
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x3E, 0x5B, 0x4F, 0x5B, 0x3E,
|
||||||
|
0x3E, 0x6B, 0x4F, 0x6B, 0x3E,
|
||||||
|
0x1C, 0x3E, 0x7C, 0x3E, 0x1C,
|
||||||
|
0x18, 0x3C, 0x7E, 0x3C, 0x18,
|
||||||
|
0x1C, 0x57, 0x7D, 0x57, 0x1C,
|
||||||
|
0x1C, 0x5E, 0x7F, 0x5E, 0x1C,
|
||||||
|
0x00, 0x18, 0x3C, 0x18, 0x00,
|
||||||
|
0xFF, 0xE7, 0xC3, 0xE7, 0xFF,
|
||||||
|
0x00, 0x18, 0x24, 0x18, 0x00,
|
||||||
|
0xFF, 0xE7, 0xDB, 0xE7, 0xFF,
|
||||||
|
0x30, 0x48, 0x3A, 0x06, 0x0E,
|
||||||
|
0x26, 0x29, 0x79, 0x29, 0x26,
|
||||||
|
0x40, 0x7F, 0x05, 0x05, 0x07,
|
||||||
|
0x40, 0x7F, 0x05, 0x25, 0x3F,
|
||||||
|
0x5A, 0x3C, 0xE7, 0x3C, 0x5A,
|
||||||
|
0x7F, 0x3E, 0x1C, 0x1C, 0x08,
|
||||||
|
0x08, 0x1C, 0x1C, 0x3E, 0x7F,
|
||||||
|
0x14, 0x22, 0x7F, 0x22, 0x14,
|
||||||
|
0x5F, 0x5F, 0x00, 0x5F, 0x5F,
|
||||||
|
0x06, 0x09, 0x7F, 0x01, 0x7F,
|
||||||
|
0x00, 0x66, 0x89, 0x95, 0x6A,
|
||||||
|
0x60, 0x60, 0x60, 0x60, 0x60,
|
||||||
|
0x94, 0xA2, 0xFF, 0xA2, 0x94,
|
||||||
|
0x08, 0x04, 0x7E, 0x04, 0x08,
|
||||||
|
0x10, 0x20, 0x7E, 0x20, 0x10,
|
||||||
|
0x08, 0x08, 0x2A, 0x1C, 0x08,
|
||||||
|
0x08, 0x1C, 0x2A, 0x08, 0x08,
|
||||||
|
0x1E, 0x10, 0x10, 0x10, 0x10,
|
||||||
|
0x0C, 0x1E, 0x0C, 0x1E, 0x0C,
|
||||||
|
0x30, 0x38, 0x3E, 0x38, 0x30,
|
||||||
|
0x06, 0x0E, 0x3E, 0x0E, 0x06,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x5F, 0x00, 0x00,
|
||||||
|
0x00, 0x07, 0x00, 0x07, 0x00,
|
||||||
|
0x14, 0x7F, 0x14, 0x7F, 0x14,
|
||||||
|
0x24, 0x2A, 0x7F, 0x2A, 0x12,
|
||||||
|
0x23, 0x13, 0x08, 0x64, 0x62,
|
||||||
|
0x36, 0x49, 0x56, 0x20, 0x50,
|
||||||
|
0x00, 0x08, 0x07, 0x03, 0x00,
|
||||||
|
0x00, 0x1C, 0x22, 0x41, 0x00,
|
||||||
|
0x00, 0x41, 0x22, 0x1C, 0x00,
|
||||||
|
0x2A, 0x1C, 0x7F, 0x1C, 0x2A,
|
||||||
|
0x08, 0x08, 0x3E, 0x08, 0x08,
|
||||||
|
0x00, 0x80, 0x70, 0x30, 0x00,
|
||||||
|
0x08, 0x08, 0x08, 0x08, 0x08,
|
||||||
|
0x00, 0x00, 0x60, 0x60, 0x00,
|
||||||
|
0x20, 0x10, 0x08, 0x04, 0x02,
|
||||||
|
0x3E, 0x51, 0x49, 0x45, 0x3E,
|
||||||
|
0x00, 0x42, 0x7F, 0x40, 0x00,
|
||||||
|
0x72, 0x49, 0x49, 0x49, 0x46,
|
||||||
|
0x21, 0x41, 0x49, 0x4D, 0x33,
|
||||||
|
0x18, 0x14, 0x12, 0x7F, 0x10,
|
||||||
|
0x27, 0x45, 0x45, 0x45, 0x39,
|
||||||
|
0x3C, 0x4A, 0x49, 0x49, 0x31,
|
||||||
|
0x41, 0x21, 0x11, 0x09, 0x07,
|
||||||
|
0x36, 0x49, 0x49, 0x49, 0x36,
|
||||||
|
0x46, 0x49, 0x49, 0x29, 0x1E,
|
||||||
|
0x00, 0x00, 0x14, 0x00, 0x00,
|
||||||
|
0x00, 0x40, 0x34, 0x00, 0x00,
|
||||||
|
0x00, 0x08, 0x14, 0x22, 0x41,
|
||||||
|
0x14, 0x14, 0x14, 0x14, 0x14,
|
||||||
|
0x00, 0x41, 0x22, 0x14, 0x08,
|
||||||
|
0x02, 0x01, 0x59, 0x09, 0x06,
|
||||||
|
0x3E, 0x41, 0x5D, 0x59, 0x4E,
|
||||||
|
0x7C, 0x12, 0x11, 0x12, 0x7C,
|
||||||
|
0x7F, 0x49, 0x49, 0x49, 0x36,
|
||||||
|
0x3E, 0x41, 0x41, 0x41, 0x22,
|
||||||
|
0x7F, 0x41, 0x41, 0x41, 0x3E,
|
||||||
|
0x7F, 0x49, 0x49, 0x49, 0x41,
|
||||||
|
0x7F, 0x09, 0x09, 0x09, 0x01,
|
||||||
|
0x3E, 0x41, 0x41, 0x51, 0x73,
|
||||||
|
0x7F, 0x08, 0x08, 0x08, 0x7F,
|
||||||
|
0x00, 0x41, 0x7F, 0x41, 0x00,
|
||||||
|
0x20, 0x40, 0x41, 0x3F, 0x01,
|
||||||
|
0x7F, 0x08, 0x14, 0x22, 0x41,
|
||||||
|
0x7F, 0x40, 0x40, 0x40, 0x40,
|
||||||
|
0x7F, 0x02, 0x1C, 0x02, 0x7F,
|
||||||
|
0x7F, 0x04, 0x08, 0x10, 0x7F,
|
||||||
|
0x3E, 0x41, 0x41, 0x41, 0x3E,
|
||||||
|
0x7F, 0x09, 0x09, 0x09, 0x06,
|
||||||
|
0x3E, 0x41, 0x51, 0x21, 0x5E,
|
||||||
|
0x7F, 0x09, 0x19, 0x29, 0x46,
|
||||||
|
0x26, 0x49, 0x49, 0x49, 0x32,
|
||||||
|
0x03, 0x01, 0x7F, 0x01, 0x03,
|
||||||
|
0x3F, 0x40, 0x40, 0x40, 0x3F,
|
||||||
|
0x1F, 0x20, 0x40, 0x20, 0x1F,
|
||||||
|
0x3F, 0x40, 0x38, 0x40, 0x3F,
|
||||||
|
0x63, 0x14, 0x08, 0x14, 0x63,
|
||||||
|
0x03, 0x04, 0x78, 0x04, 0x03,
|
||||||
|
0x61, 0x59, 0x49, 0x4D, 0x43,
|
||||||
|
0x00, 0x7F, 0x41, 0x41, 0x41,
|
||||||
|
0x02, 0x04, 0x08, 0x10, 0x20,
|
||||||
|
0x00, 0x41, 0x41, 0x41, 0x7F,
|
||||||
|
0x04, 0x02, 0x01, 0x02, 0x04,
|
||||||
|
0x40, 0x40, 0x40, 0x40, 0x40,
|
||||||
|
0x00, 0x03, 0x07, 0x08, 0x00,
|
||||||
|
0x20, 0x54, 0x54, 0x78, 0x40,
|
||||||
|
0x7F, 0x28, 0x44, 0x44, 0x38,
|
||||||
|
0x38, 0x44, 0x44, 0x44, 0x28,
|
||||||
|
0x38, 0x44, 0x44, 0x28, 0x7F,
|
||||||
|
0x38, 0x54, 0x54, 0x54, 0x18,
|
||||||
|
0x00, 0x08, 0x7E, 0x09, 0x02,
|
||||||
|
0x18, 0xA4, 0xA4, 0x9C, 0x78,
|
||||||
|
0x7F, 0x08, 0x04, 0x04, 0x78,
|
||||||
|
0x00, 0x44, 0x7D, 0x40, 0x00,
|
||||||
|
0x20, 0x40, 0x40, 0x3D, 0x00,
|
||||||
|
0x7F, 0x10, 0x28, 0x44, 0x00,
|
||||||
|
0x00, 0x41, 0x7F, 0x40, 0x00,
|
||||||
|
0x7C, 0x04, 0x78, 0x04, 0x78,
|
||||||
|
0x7C, 0x08, 0x04, 0x04, 0x78,
|
||||||
|
0x38, 0x44, 0x44, 0x44, 0x38,
|
||||||
|
0xFC, 0x18, 0x24, 0x24, 0x18,
|
||||||
|
0x18, 0x24, 0x24, 0x18, 0xFC,
|
||||||
|
0x7C, 0x08, 0x04, 0x04, 0x08,
|
||||||
|
0x48, 0x54, 0x54, 0x54, 0x24,
|
||||||
|
0x04, 0x04, 0x3F, 0x44, 0x24,
|
||||||
|
0x3C, 0x40, 0x40, 0x20, 0x7C,
|
||||||
|
0x1C, 0x20, 0x40, 0x20, 0x1C,
|
||||||
|
0x3C, 0x40, 0x30, 0x40, 0x3C,
|
||||||
|
0x44, 0x28, 0x10, 0x28, 0x44,
|
||||||
|
0x4C, 0x90, 0x90, 0x90, 0x7C,
|
||||||
|
0x44, 0x64, 0x54, 0x4C, 0x44,
|
||||||
|
0x00, 0x08, 0x36, 0x41, 0x00,
|
||||||
|
0x00, 0x00, 0x77, 0x00, 0x00,
|
||||||
|
0x00, 0x41, 0x36, 0x08, 0x00,
|
||||||
|
0x02, 0x01, 0x02, 0x04, 0x02,
|
||||||
|
0x3C, 0x26, 0x23, 0x26, 0x3C,
|
||||||
|
0x1E, 0xA1, 0xA1, 0x61, 0x12,
|
||||||
|
0x3A, 0x40, 0x40, 0x20, 0x7A,
|
||||||
|
0x38, 0x54, 0x54, 0x55, 0x59,
|
||||||
|
0x21, 0x55, 0x55, 0x79, 0x41,
|
||||||
|
0x22, 0x54, 0x54, 0x78, 0x42, // a-umlaut
|
||||||
|
0x21, 0x55, 0x54, 0x78, 0x40,
|
||||||
|
0x20, 0x54, 0x55, 0x79, 0x40,
|
||||||
|
0x0C, 0x1E, 0x52, 0x72, 0x12,
|
||||||
|
0x39, 0x55, 0x55, 0x55, 0x59,
|
||||||
|
0x39, 0x54, 0x54, 0x54, 0x59,
|
||||||
|
0x39, 0x55, 0x54, 0x54, 0x58,
|
||||||
|
0x00, 0x00, 0x45, 0x7C, 0x41,
|
||||||
|
0x00, 0x02, 0x45, 0x7D, 0x42,
|
||||||
|
0x00, 0x01, 0x45, 0x7C, 0x40,
|
||||||
|
0x7D, 0x12, 0x11, 0x12, 0x7D, // A-umlaut
|
||||||
|
0xF0, 0x28, 0x25, 0x28, 0xF0,
|
||||||
|
0x7C, 0x54, 0x55, 0x45, 0x00,
|
||||||
|
0x20, 0x54, 0x54, 0x7C, 0x54,
|
||||||
|
0x7C, 0x0A, 0x09, 0x7F, 0x49,
|
||||||
|
0x32, 0x49, 0x49, 0x49, 0x32,
|
||||||
|
0x3A, 0x44, 0x44, 0x44, 0x3A, // o-umlaut
|
||||||
|
0x32, 0x4A, 0x48, 0x48, 0x30,
|
||||||
|
0x3A, 0x41, 0x41, 0x21, 0x7A,
|
||||||
|
0x3A, 0x42, 0x40, 0x20, 0x78,
|
||||||
|
0x00, 0x9D, 0xA0, 0xA0, 0x7D,
|
||||||
|
0x3D, 0x42, 0x42, 0x42, 0x3D, // O-umlaut
|
||||||
|
0x3D, 0x40, 0x40, 0x40, 0x3D,
|
||||||
|
0x3C, 0x24, 0xFF, 0x24, 0x24,
|
||||||
|
0x48, 0x7E, 0x49, 0x43, 0x66,
|
||||||
|
0x2B, 0x2F, 0xFC, 0x2F, 0x2B,
|
||||||
|
0xFF, 0x09, 0x29, 0xF6, 0x20,
|
||||||
|
0xC0, 0x88, 0x7E, 0x09, 0x03,
|
||||||
|
0x20, 0x54, 0x54, 0x79, 0x41,
|
||||||
|
0x00, 0x00, 0x44, 0x7D, 0x41,
|
||||||
|
0x30, 0x48, 0x48, 0x4A, 0x32,
|
||||||
|
0x38, 0x40, 0x40, 0x22, 0x7A,
|
||||||
|
0x00, 0x7A, 0x0A, 0x0A, 0x72,
|
||||||
|
0x7D, 0x0D, 0x19, 0x31, 0x7D,
|
||||||
|
0x26, 0x29, 0x29, 0x2F, 0x28,
|
||||||
|
0x26, 0x29, 0x29, 0x29, 0x26,
|
||||||
|
0x30, 0x48, 0x4D, 0x40, 0x20,
|
||||||
|
0x38, 0x08, 0x08, 0x08, 0x08,
|
||||||
|
0x08, 0x08, 0x08, 0x08, 0x38,
|
||||||
|
0x2F, 0x10, 0xC8, 0xAC, 0xBA,
|
||||||
|
0x2F, 0x10, 0x28, 0x34, 0xFA,
|
||||||
|
0x00, 0x00, 0x7B, 0x00, 0x00,
|
||||||
|
0x08, 0x14, 0x2A, 0x14, 0x22,
|
||||||
|
0x22, 0x14, 0x2A, 0x14, 0x08,
|
||||||
|
0x55, 0x00, 0x55, 0x00, 0x55, // #176 (25% block) missing in old code
|
||||||
|
0xAA, 0x55, 0xAA, 0x55, 0xAA, // 50% block
|
||||||
|
0xFF, 0x55, 0xFF, 0x55, 0xFF, // 75% block
|
||||||
|
0x00, 0x00, 0x00, 0xFF, 0x00,
|
||||||
|
0x10, 0x10, 0x10, 0xFF, 0x00,
|
||||||
|
0x14, 0x14, 0x14, 0xFF, 0x00,
|
||||||
|
0x10, 0x10, 0xFF, 0x00, 0xFF,
|
||||||
|
0x10, 0x10, 0xF0, 0x10, 0xF0,
|
||||||
|
0x14, 0x14, 0x14, 0xFC, 0x00,
|
||||||
|
0x14, 0x14, 0xF7, 0x00, 0xFF,
|
||||||
|
0x00, 0x00, 0xFF, 0x00, 0xFF,
|
||||||
|
0x14, 0x14, 0xF4, 0x04, 0xFC,
|
||||||
|
0x14, 0x14, 0x17, 0x10, 0x1F,
|
||||||
|
0x10, 0x10, 0x1F, 0x10, 0x1F,
|
||||||
|
0x14, 0x14, 0x14, 0x1F, 0x00,
|
||||||
|
0x10, 0x10, 0x10, 0xF0, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0x1F, 0x10,
|
||||||
|
0x10, 0x10, 0x10, 0x1F, 0x10,
|
||||||
|
0x10, 0x10, 0x10, 0xF0, 0x10,
|
||||||
|
0x00, 0x00, 0x00, 0xFF, 0x10,
|
||||||
|
0x10, 0x10, 0x10, 0x10, 0x10,
|
||||||
|
0x10, 0x10, 0x10, 0xFF, 0x10,
|
||||||
|
0x00, 0x00, 0x00, 0xFF, 0x14,
|
||||||
|
0x00, 0x00, 0xFF, 0x00, 0xFF,
|
||||||
|
0x00, 0x00, 0x1F, 0x10, 0x17,
|
||||||
|
0x00, 0x00, 0xFC, 0x04, 0xF4,
|
||||||
|
0x14, 0x14, 0x17, 0x10, 0x17,
|
||||||
|
0x14, 0x14, 0xF4, 0x04, 0xF4,
|
||||||
|
0x00, 0x00, 0xFF, 0x00, 0xF7,
|
||||||
|
0x14, 0x14, 0x14, 0x14, 0x14,
|
||||||
|
0x14, 0x14, 0xF7, 0x00, 0xF7,
|
||||||
|
0x14, 0x14, 0x14, 0x17, 0x14,
|
||||||
|
0x10, 0x10, 0x1F, 0x10, 0x1F,
|
||||||
|
0x14, 0x14, 0x14, 0xF4, 0x14,
|
||||||
|
0x10, 0x10, 0xF0, 0x10, 0xF0,
|
||||||
|
0x00, 0x00, 0x1F, 0x10, 0x1F,
|
||||||
|
0x00, 0x00, 0x00, 0x1F, 0x14,
|
||||||
|
0x00, 0x00, 0x00, 0xFC, 0x14,
|
||||||
|
0x00, 0x00, 0xF0, 0x10, 0xF0,
|
||||||
|
0x10, 0x10, 0xFF, 0x10, 0xFF,
|
||||||
|
0x14, 0x14, 0x14, 0xFF, 0x14,
|
||||||
|
0x10, 0x10, 0x10, 0x1F, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0xF0, 0x10,
|
||||||
|
0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||||
|
0xF0, 0xF0, 0xF0, 0xF0, 0xF0,
|
||||||
|
0xFF, 0xFF, 0xFF, 0x00, 0x00,
|
||||||
|
0x00, 0x00, 0x00, 0xFF, 0xFF,
|
||||||
|
0x0F, 0x0F, 0x0F, 0x0F, 0x0F,
|
||||||
|
0x38, 0x44, 0x44, 0x38, 0x44,
|
||||||
|
0xFC, 0x4A, 0x4A, 0x4A, 0x34, // sharp-s or beta
|
||||||
|
0x7E, 0x02, 0x02, 0x06, 0x06,
|
||||||
|
0x02, 0x7E, 0x02, 0x7E, 0x02,
|
||||||
|
0x63, 0x55, 0x49, 0x41, 0x63,
|
||||||
|
0x38, 0x44, 0x44, 0x3C, 0x04,
|
||||||
|
0x40, 0x7E, 0x20, 0x1E, 0x20,
|
||||||
|
0x06, 0x02, 0x7E, 0x02, 0x02,
|
||||||
|
0x99, 0xA5, 0xE7, 0xA5, 0x99,
|
||||||
|
0x1C, 0x2A, 0x49, 0x2A, 0x1C,
|
||||||
|
0x4C, 0x72, 0x01, 0x72, 0x4C,
|
||||||
|
0x30, 0x4A, 0x4D, 0x4D, 0x30,
|
||||||
|
0x30, 0x48, 0x78, 0x48, 0x30,
|
||||||
|
0xBC, 0x62, 0x5A, 0x46, 0x3D,
|
||||||
|
0x3E, 0x49, 0x49, 0x49, 0x00,
|
||||||
|
0x7E, 0x01, 0x01, 0x01, 0x7E,
|
||||||
|
0x2A, 0x2A, 0x2A, 0x2A, 0x2A,
|
||||||
|
0x44, 0x44, 0x5F, 0x44, 0x44,
|
||||||
|
0x40, 0x51, 0x4A, 0x44, 0x40,
|
||||||
|
0x40, 0x44, 0x4A, 0x51, 0x40,
|
||||||
|
0x00, 0x00, 0xFF, 0x01, 0x03,
|
||||||
|
0xE0, 0x80, 0xFF, 0x00, 0x00,
|
||||||
|
0x08, 0x08, 0x6B, 0x6B, 0x08,
|
||||||
|
0x36, 0x12, 0x36, 0x24, 0x36,
|
||||||
|
0x06, 0x0F, 0x09, 0x0F, 0x06,
|
||||||
|
0x00, 0x00, 0x18, 0x18, 0x00,
|
||||||
|
0x00, 0x00, 0x10, 0x10, 0x00,
|
||||||
|
0x30, 0x40, 0xFF, 0x01, 0x01,
|
||||||
|
0x00, 0x1F, 0x01, 0x01, 0x1E,
|
||||||
|
0x00, 0x19, 0x1D, 0x17, 0x12,
|
||||||
|
0x00, 0x3C, 0x3C, 0x3C, 0x3C,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00 // #255 NBSP
|
||||||
|
};
|
||||||
|
#endif // FONT5X7_H
|
145
firmware_smartstepper_trikarus/stepper_nano_zero/nonvolatile.cpp
Normal file
@ -0,0 +1,145 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#include "nonvolatile.h"
|
||||||
|
#include "Flash.h" //thanks to Kent Larsen for pointing out the lower case error
|
||||||
|
#include <Arduino.h>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//we use this so we can hard code calibration table
|
||||||
|
// be sure to set the last word as status flag
|
||||||
|
// this save time calibrating each time we do a code build
|
||||||
|
#ifdef NZS_FAST_CAL
|
||||||
|
__attribute__((__aligned__(FLASH_ROW_SIZE))) const uint16_t NVM_flash[16767]={ //allocates 33280 bytes
|
||||||
|
#else
|
||||||
|
__attribute__((__aligned__(FLASH_ROW_SIZE))) const uint16_t NVM_flash[256]={ //allocates 512 bytes
|
||||||
|
#endif
|
||||||
|
25758,26078,26399,26720,27043,27372,27698,28024,28353,28688,29017,29345,29671,30009,30340,30663,30997,31335,31664,31994,32325,32666,32997,33324,33661,33997,34330,34657,34986,35324,35653,35981,36303,36637,36962,37282,37605,37938,38260,38581,38901,39232,39554,39877,40198,40528,40849,41178,41500,41835,42163,42485,42815,43149,43475,43804,44139,44476,44801,45136,45460,45804,46130,46460,46790,47119,47449,47777,48103,48442,48772,49099,49424,49759,50087,50410,50735,51067,51394,51716,52045,52379,52703,53024,53348,53680,54002,54326,54648,54987,55309,55629,55958,56292,56612,56936,57262,57594,57917,58246,58569,58902,59225,59552,59873,60206,60534,60862,61192,61531,61864,62194,62529,62873,63210,63544,63878,64222,64562,64899,65241,45,384,719,1058,1398,1733,2058,2390,2732,3060,3394,3720,4056,4386,4710,5036,5366,5693,6016,6340,6665,6989,7308,7622,7952,8263,8586,8903,9232,9551,9874,10200,10534,10859,11185,11513,11852,12184,12514,12848,13185,13511,13841,14170,14504,14830,15156,15490,15827,16153,16481,16808,17143,17474,17801,18121,18458,18783,19111,19433,19765,20084,20405,20721,21045,21360,21673,21984,22305,22614,22922,23231,23551,23861,24173,24482,24808,25118,25435,
|
||||||
|
|
||||||
|
0xFFFF
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
static_assert (sizeof(nvm_t)<sizeof(NVM_flash), "nvm_t structure larger than allocated memory");
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//FLASH_ALLOCATE(NVM_flash, sizeof(nvm_t));
|
||||||
|
|
||||||
|
|
||||||
|
bool nvmWriteCalTable(void *ptrData, uint32_t size)
|
||||||
|
{
|
||||||
|
bool x=true;
|
||||||
|
flashWrite(&NVM->CalibrationTable,ptrData,size);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool nvmWrite_sPID(float Kp, float Ki, float Kd)
|
||||||
|
{
|
||||||
|
PIDparams_t pid;
|
||||||
|
|
||||||
|
pid.Kp=Kp;
|
||||||
|
pid.Ki=Ki;
|
||||||
|
pid.Kd=Kd;
|
||||||
|
pid.parametersVaild=true;
|
||||||
|
|
||||||
|
flashWrite((void *)&NVM->sPID,&pid,sizeof(pid));
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool nvmWrite_vPID(float Kp, float Ki, float Kd)
|
||||||
|
{
|
||||||
|
PIDparams_t pid;
|
||||||
|
|
||||||
|
pid.Kp=Kp;
|
||||||
|
pid.Ki=Ki;
|
||||||
|
pid.Kd=Kd;
|
||||||
|
pid.parametersVaild=true;
|
||||||
|
|
||||||
|
flashWrite((void *)&NVM->vPID,&pid,sizeof(pid));
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool nvmWrite_pPID(float Kp, float Ki, float Kd)
|
||||||
|
{
|
||||||
|
PIDparams_t pid;
|
||||||
|
|
||||||
|
pid.Kp=Kp;
|
||||||
|
pid.Ki=Ki;
|
||||||
|
pid.Kd=Kd;
|
||||||
|
pid.parametersVaild=true;
|
||||||
|
|
||||||
|
flashWrite((void *)&NVM->pPID,&pid,sizeof(pid));
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool nvmWriteSystemParms(SystemParams_t &systemParams)
|
||||||
|
{
|
||||||
|
systemParams.parametersVaild=true;
|
||||||
|
|
||||||
|
flashWrite((void *)&NVM->SystemParams,&systemParams,sizeof(systemParams));
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool nvmWriteMotorParms(MotorParams_t &motorParams)
|
||||||
|
{
|
||||||
|
motorParams.parametersVaild=true;
|
||||||
|
|
||||||
|
flashWrite((void *)&NVM->motorParams,&motorParams,sizeof(motorParams));
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool nvmErase(void)
|
||||||
|
{
|
||||||
|
bool data=false;
|
||||||
|
uint16_t cs=0;
|
||||||
|
|
||||||
|
flashWrite((void *)&NVM->CalibrationTable.status,&data,sizeof(data));
|
||||||
|
flashWrite((void *)&NVM->sPID.parametersVaild ,&data,sizeof(data));
|
||||||
|
flashWrite((void *)&NVM->vPID.parametersVaild ,&data,sizeof(data));
|
||||||
|
flashWrite((void *)&NVM->pPID.parametersVaild ,&data,sizeof(data));
|
||||||
|
flashWrite((void *)&NVM->motorParams.parametersVaild ,&data,sizeof(data));
|
||||||
|
flashWrite((void *)&NVM->SystemParams.parametersVaild ,&data,sizeof(data));
|
||||||
|
#ifdef NZS_FAST_CAL
|
||||||
|
flashWrite((void *)&NVM->FastCal.checkSum,&cs,sizeof(cs));
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
108
firmware_smartstepper_trikarus/stepper_nano_zero/nonvolatile.h
Normal file
@ -0,0 +1,108 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
Copyright (C) 2018 MisfitTech LLC, All rights reserved.
|
||||||
|
|
||||||
|
MisfitTech uses a dual license model that allows the software to be used under
|
||||||
|
a standard GPL open source license, or a commercial license. The standard GPL
|
||||||
|
license requires that all software statically linked with MisfitTec Code is
|
||||||
|
also distributed under the same GPL V2 license terms. Details of both license
|
||||||
|
options follow:
|
||||||
|
|
||||||
|
- Open source licensing -
|
||||||
|
MisfitTech is a free download and may be used, modified, evaluated and
|
||||||
|
distributed without charge provided the user adheres to version two of the GNU
|
||||||
|
General Public License (GPL) and does not remove the copyright notice or this
|
||||||
|
text. The GPL V2 text is available on the gnu.org web site
|
||||||
|
|
||||||
|
- Commercial licensing -
|
||||||
|
Businesses and individuals that for commercial or other reasons cannot comply
|
||||||
|
with the terms of the GPL V2 license must obtain a low cost commercial license
|
||||||
|
before incorporating MisfitTech code into proprietary software for distribution in
|
||||||
|
any form. Commercial licenses can be purchased from www.misfittech.net
|
||||||
|
and do not require any source files to be changed.
|
||||||
|
|
||||||
|
|
||||||
|
This code is distributed in the hope that it will be useful. You cannot
|
||||||
|
use MisfitTech's code unless you agree that you use the software 'as is'.
|
||||||
|
MisfitTech's code is provided WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
warranties of NON-INFRINGEMENT, MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
||||||
|
PURPOSE. MisfitTech LLC disclaims all conditions and terms, be they
|
||||||
|
implied, expressed, or statutory.
|
||||||
|
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#ifndef __NONVOLATILE__H__
|
||||||
|
#define __NONVOLATILE__H__
|
||||||
|
|
||||||
|
#include "calibration.h"
|
||||||
|
#include "board.h"
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
float Kp;
|
||||||
|
float Ki;
|
||||||
|
float Kd;
|
||||||
|
bool parametersVaild;
|
||||||
|
} PIDparams_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
int32_t currentMa; //maximum current for the motor
|
||||||
|
int32_t currentHoldMa; //hold current for the motor
|
||||||
|
int32_t homeMa; //maximum current when error homing
|
||||||
|
int32_t homeHoldMa; //hold current when error homing
|
||||||
|
bool motorWiring; //forward wiring of motor or reverse
|
||||||
|
int32_t fullStepsPerRotation; //how many full steps per rotation is the motor
|
||||||
|
bool parametersVaild;
|
||||||
|
} MotorParams_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
int32_t microsteps; //number of microsteps on the dir/step pin interface from host
|
||||||
|
RotationDir_t dirPinRotation; //is the direction pin high for clockwise or counterClockWise
|
||||||
|
int32_t errorLimit; //error limit before error pin asserts 65536==360degrees
|
||||||
|
ErrorPinMode_t errorPinMode; //is error pin used for enable, error, or bidirectional
|
||||||
|
feedbackCtrl_t controllerMode; //feedback mode for the controller
|
||||||
|
int32_t homePin; //if greater than zero this is the pin we use trigger home current settings
|
||||||
|
bool errorLogic; //if high and error will be high on output pin
|
||||||
|
int32_t homeAngleDelay; //the angle to delay before switching to lower homing current
|
||||||
|
bool parametersVaild;
|
||||||
|
} SystemParams_t;
|
||||||
|
|
||||||
|
#ifdef NZS_FAST_CAL
|
||||||
|
typedef struct {
|
||||||
|
uint16_t angle[16384];
|
||||||
|
uint16_t checkSum;
|
||||||
|
}FastCal_t;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
FlashCalData_t CalibrationTable;
|
||||||
|
__attribute__((__aligned__(8))) PIDparams_t sPID; //simple PID parameters
|
||||||
|
__attribute__((__aligned__(8))) PIDparams_t pPID; //position PID parameters
|
||||||
|
__attribute__((__aligned__(8))) PIDparams_t vPID; //velocity PID parameters
|
||||||
|
__attribute__((__aligned__(8))) SystemParams_t SystemParams;
|
||||||
|
__attribute__((__aligned__(8))) MotorParams_t motorParams;
|
||||||
|
#ifdef NZS_FAST_CAL
|
||||||
|
__attribute__((__aligned__(8))) FastCal_t FastCal;
|
||||||
|
#endif
|
||||||
|
} nvm_t;
|
||||||
|
|
||||||
|
#ifdef NZS_FAST_CAL
|
||||||
|
extern const uint16_t NVM_flash[16767];
|
||||||
|
#else
|
||||||
|
extern const uint16_t NVM_flash[256];
|
||||||
|
#endif
|
||||||
|
#define NVM ((const nvm_t *)NVM_flash)
|
||||||
|
|
||||||
|
bool nvmWriteCalTable(void *ptrData, uint32_t size);
|
||||||
|
bool nvmWrite_sPID(float Kp, float Ki, float Kd);
|
||||||
|
bool nvmWrite_pPID(float Kp, float Ki, float Kd);
|
||||||
|
bool nvmWrite_vPID(float Kp, float Ki, float Kd);
|
||||||
|
bool nvmWriteSystemParms(SystemParams_t &systemParams);
|
||||||
|
bool nvmWriteMotorParms(MotorParams_t &motorParams);
|
||||||
|
bool nvmErase(void);
|
||||||
|
|
||||||
|
#endif // __NONVOLATILE__H__
|
902
firmware_smartstepper_trikarus/stepper_nano_zero/nzs.cpp
Normal file
@ -0,0 +1,902 @@
|
|||||||
|
/*
|
||||||
|
* nzs.cpp
|
||||||
|
*
|
||||||
|
* Created on: Dec 8, 2016
|
||||||
|
* Author: trampas
|
||||||
|
*
|
||||||
|
Copyright (C) 2018 MisfitTech, All rights reserved.
|
||||||
|
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
#include "nzs.h"
|
||||||
|
#include "commands.h"
|
||||||
|
#include "nonvolatile.h"
|
||||||
|
#include "angle.h"
|
||||||
|
#include "eeprom.h"
|
||||||
|
#include "steppin.h"
|
||||||
|
#include "wiring_private.h"
|
||||||
|
|
||||||
|
#pragma GCC push_options
|
||||||
|
#pragma GCC optimize ("-Ofast")
|
||||||
|
|
||||||
|
eepromData_t PowerupEEPROM={0};
|
||||||
|
|
||||||
|
|
||||||
|
volatile bool enableState=true;
|
||||||
|
|
||||||
|
int32_t dataEnabled=0;
|
||||||
|
|
||||||
|
StepperCtrl stepperCtrl;
|
||||||
|
LCD Lcd;
|
||||||
|
|
||||||
|
int menuCalibrate(int argc, char *argv[])
|
||||||
|
{
|
||||||
|
stepperCtrl.calibrateEncoder();
|
||||||
|
}
|
||||||
|
|
||||||
|
int menuTestCal(int argc, char *argv[])
|
||||||
|
{
|
||||||
|
Angle error;
|
||||||
|
int32_t x,y;
|
||||||
|
char str[25];
|
||||||
|
error=stepperCtrl.maxCalibrationError();
|
||||||
|
|
||||||
|
x=(36000*(int32_t)error)/ANGLE_STEPS;
|
||||||
|
LOG("Error %d %d", (int32_t)error, x);
|
||||||
|
y=x/100;
|
||||||
|
x=x-(y*100);
|
||||||
|
x=abs(x);
|
||||||
|
sprintf(str, "%d.%02d deg",y,x);
|
||||||
|
#ifndef DISABLE_LCD
|
||||||
|
Lcd.lcdShow("Cal Error", str,"");
|
||||||
|
#endif
|
||||||
|
|
||||||
|
LOG("Calibration error %s",str);
|
||||||
|
#ifndef MECHADUINO_HARDWARE
|
||||||
|
while(digitalRead(PIN_SW3)==1)
|
||||||
|
{
|
||||||
|
//wait for button press
|
||||||
|
}
|
||||||
|
while(digitalRead(PIN_SW3)==0)
|
||||||
|
{
|
||||||
|
//wait for button release
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
static options_t stepOptions[] {
|
||||||
|
{"200"},
|
||||||
|
{"400"},
|
||||||
|
{""},
|
||||||
|
};
|
||||||
|
|
||||||
|
//returns the index of the stepOptions when called
|
||||||
|
// with no arguments.
|
||||||
|
int motorSteps(int argc, char *argv[])
|
||||||
|
{
|
||||||
|
if (argc==0)
|
||||||
|
{
|
||||||
|
int i;
|
||||||
|
i=NVM->motorParams.fullStepsPerRotation;
|
||||||
|
if (i==400)
|
||||||
|
{
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
return 0; //default to 200
|
||||||
|
}
|
||||||
|
if (argc>0)
|
||||||
|
{
|
||||||
|
int32_t i;
|
||||||
|
MotorParams_t params;
|
||||||
|
memcpy((void *)¶ms, (void *)&NVM->motorParams, sizeof(params));
|
||||||
|
i=atol(argv[0]);
|
||||||
|
if (i!=params.fullStepsPerRotation)
|
||||||
|
{
|
||||||
|
params.fullStepsPerRotation=i;
|
||||||
|
nvmWriteMotorParms(params);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static options_t currentOptions[] {
|
||||||
|
{"0"},
|
||||||
|
{"100"},
|
||||||
|
{"200"},
|
||||||
|
{"300"},
|
||||||
|
{"400"},
|
||||||
|
{"500"},
|
||||||
|
{"600"},
|
||||||
|
{"700"},
|
||||||
|
{"800"},
|
||||||
|
{"900"},
|
||||||
|
{"1000"},
|
||||||
|
{"1100"},
|
||||||
|
{"1200"},
|
||||||
|
{"1300"},
|
||||||
|
{"1400"},
|
||||||
|
{"1500"},
|
||||||
|
{"1600"},
|
||||||
|
{"1700"},
|
||||||
|
{"1800"},
|
||||||
|
{"1900"},
|
||||||
|
{"2000"},
|
||||||
|
{"2100"},
|
||||||
|
{"2200"},
|
||||||
|
{"2300"},
|
||||||
|
{"2400"},
|
||||||
|
{"2500"},
|
||||||
|
{"2600"},
|
||||||
|
{"2700"},
|
||||||
|
{"2800"},
|
||||||
|
{"2900"},
|
||||||
|
{"3000"},
|
||||||
|
{"3100"},
|
||||||
|
{"3200"},
|
||||||
|
{"3300"},
|
||||||
|
{""},
|
||||||
|
};
|
||||||
|
|
||||||
|
int motorCurrent(int argc, char *argv[])
|
||||||
|
{
|
||||||
|
LOG("called motorCurrent %d",argc);
|
||||||
|
if (argc==1)
|
||||||
|
{
|
||||||
|
int i;
|
||||||
|
LOG("called %s",argv[0]);
|
||||||
|
i=atol(argv[0]);
|
||||||
|
i=i*100;
|
||||||
|
MotorParams_t params;
|
||||||
|
memcpy((void *)¶ms, (void *)&NVM->motorParams, sizeof(params));
|
||||||
|
if (i!=params.currentMa)
|
||||||
|
{
|
||||||
|
params.currentMa=i;
|
||||||
|
nvmWriteMotorParms(params);
|
||||||
|
}
|
||||||
|
return i/100;
|
||||||
|
}
|
||||||
|
int i;
|
||||||
|
i=NVM->motorParams.currentMa/100;
|
||||||
|
LOG(" motorCurrent return %d",i);
|
||||||
|
return i;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
int motorHoldCurrent(int argc, char *argv[])
|
||||||
|
{
|
||||||
|
if (argc==1)
|
||||||
|
{
|
||||||
|
int i;
|
||||||
|
i=atol(argv[0]);
|
||||||
|
i=i*100;
|
||||||
|
MotorParams_t params;
|
||||||
|
memcpy((void *)¶ms, (void *)&NVM->motorParams, sizeof(params));
|
||||||
|
if (i!=params.currentHoldMa)
|
||||||
|
{
|
||||||
|
params.currentHoldMa=i;
|
||||||
|
nvmWriteMotorParms(params);
|
||||||
|
}
|
||||||
|
return i/100;
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
int i;
|
||||||
|
i=NVM->motorParams.currentHoldMa/100;
|
||||||
|
return i;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static options_t microstepOptions[] {
|
||||||
|
{"1"},
|
||||||
|
{"2"},
|
||||||
|
{"4"},
|
||||||
|
{"8"},
|
||||||
|
{"16"},
|
||||||
|
{"32"},
|
||||||
|
{"64"},
|
||||||
|
{"128"},
|
||||||
|
{"256"},
|
||||||
|
{""}
|
||||||
|
};
|
||||||
|
|
||||||
|
int microsteps(int argc, char *argv[])
|
||||||
|
{
|
||||||
|
if (argc==1)
|
||||||
|
{
|
||||||
|
int i,steps;
|
||||||
|
i=atol(argv[0]);
|
||||||
|
SystemParams_t params;
|
||||||
|
memcpy((void *)¶ms, (void *)&NVM->SystemParams, sizeof(params));
|
||||||
|
steps=0x01<<i;
|
||||||
|
if (steps!=params.microsteps)
|
||||||
|
{
|
||||||
|
params.microsteps=steps;
|
||||||
|
nvmWriteSystemParms(params);
|
||||||
|
}
|
||||||
|
return i;
|
||||||
|
}
|
||||||
|
int i,j;
|
||||||
|
i=NVM->SystemParams.microsteps;
|
||||||
|
for (j=0; j<9; j++)
|
||||||
|
{
|
||||||
|
|
||||||
|
if ((0x01<<j) == i)
|
||||||
|
{
|
||||||
|
return j;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static options_t controlLoopOptions[] {
|
||||||
|
{"Off"},
|
||||||
|
{"Open"},
|
||||||
|
{"Simple"},
|
||||||
|
{"Pos PID"},
|
||||||
|
{"Vel PID"},
|
||||||
|
{""}
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
int controlLoop(int argc, char *argv[])
|
||||||
|
{
|
||||||
|
if (argc==1)
|
||||||
|
{
|
||||||
|
int i;
|
||||||
|
i=atol(argv[0]);
|
||||||
|
SystemParams_t params;
|
||||||
|
memcpy((void *)¶ms, (void *)&NVM->SystemParams, sizeof(params));
|
||||||
|
if (i!=params.controllerMode)
|
||||||
|
{
|
||||||
|
params.controllerMode=(feedbackCtrl_t)i;
|
||||||
|
nvmWriteSystemParms(params);
|
||||||
|
}
|
||||||
|
return i;
|
||||||
|
}
|
||||||
|
return NVM->SystemParams.controllerMode;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef PIN_ENABLE
|
||||||
|
static options_t errorPinOptions[] {
|
||||||
|
{"Enable"},
|
||||||
|
{"!Enable"}, //error pin works like enable on step sticks
|
||||||
|
{"Error"},
|
||||||
|
// {"BiDir"}, //12/12/2016 not implemented yet
|
||||||
|
{""}
|
||||||
|
};
|
||||||
|
|
||||||
|
int errorPin(int argc, char *argv[])
|
||||||
|
{
|
||||||
|
if (argc==1)
|
||||||
|
{
|
||||||
|
int i;
|
||||||
|
i=atol(argv[0]);
|
||||||
|
SystemParams_t params;
|
||||||
|
memcpy((void *)¶ms, (void *)&NVM->SystemParams, sizeof(params));
|
||||||
|
if (i!=params.errorPinMode)
|
||||||
|
{
|
||||||
|
params.errorPinMode=(ErrorPinMode_t)i;
|
||||||
|
nvmWriteSystemParms(params);
|
||||||
|
}
|
||||||
|
return i;
|
||||||
|
}
|
||||||
|
return NVM->SystemParams.errorPinMode;
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
|
||||||
|
static options_t errorPinOptions[] {
|
||||||
|
{"Enable"},
|
||||||
|
{"!Enable"}, //error pin works like enable on step sticks
|
||||||
|
// {"Error"},
|
||||||
|
// {"BiDir"}, //12/12/2016 not implemented yet
|
||||||
|
{""}
|
||||||
|
};
|
||||||
|
|
||||||
|
int enablePin(int argc, char *argv[])
|
||||||
|
{
|
||||||
|
if (argc==1)
|
||||||
|
{
|
||||||
|
int i;
|
||||||
|
i=atol(argv[0]);
|
||||||
|
SystemParams_t params;
|
||||||
|
memcpy((void *)¶ms, (void *)&NVM->SystemParams, sizeof(params));
|
||||||
|
if (i!=params.errorPinMode)
|
||||||
|
{
|
||||||
|
params.errorPinMode=(ErrorPinMode_t)i;
|
||||||
|
nvmWriteSystemParms(params);
|
||||||
|
}
|
||||||
|
return i;
|
||||||
|
}
|
||||||
|
return NVM->SystemParams.errorPinMode;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
static options_t dirPinOptions[] {
|
||||||
|
{"High CW"},
|
||||||
|
{"High CCW"},
|
||||||
|
{""}
|
||||||
|
};
|
||||||
|
|
||||||
|
int dirPin(int argc, char *argv[])
|
||||||
|
{
|
||||||
|
if (argc==1)
|
||||||
|
{
|
||||||
|
int i;
|
||||||
|
i=atol(argv[0]);
|
||||||
|
SystemParams_t params;
|
||||||
|
memcpy((void *)¶ms, (void *)&NVM->SystemParams, sizeof(params));
|
||||||
|
if (i!=params.dirPinRotation)
|
||||||
|
{
|
||||||
|
params.dirPinRotation=(RotationDir_t)i;
|
||||||
|
nvmWriteSystemParms(params);
|
||||||
|
}
|
||||||
|
return i;
|
||||||
|
}
|
||||||
|
return NVM->SystemParams.dirPinRotation;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
static menuItem_t MenuMain[] {
|
||||||
|
{"Calibrate", menuCalibrate,NULL},
|
||||||
|
{"Test Cal", menuTestCal,NULL},
|
||||||
|
// {"Mtr steps", motorSteps,stepOptions}, NOT GOOD for user to call this
|
||||||
|
{"Motor mA", motorCurrent,currentOptions},
|
||||||
|
{"Hold mA", motorHoldCurrent,currentOptions},
|
||||||
|
{"Microstep", microsteps,microstepOptions},
|
||||||
|
// {"Ctlr Mode", controlLoop,controlLoopOptions}, //this may not be good for user to call
|
||||||
|
#ifndef PIN_ENABLE
|
||||||
|
{"Error Pin", errorPin,errorPinOptions},
|
||||||
|
#else
|
||||||
|
{"EnablePin", enablePin,errorPinOptions},
|
||||||
|
#endif
|
||||||
|
{"Dir Pin", dirPin,dirPinOptions},
|
||||||
|
|
||||||
|
|
||||||
|
{ "", NULL}
|
||||||
|
};
|
||||||
|
|
||||||
|
static menuItem_t MenuCal[] {
|
||||||
|
{"Calibrate", menuCalibrate,NULL},
|
||||||
|
//{"Test Cal", menuTestCal,NULL},
|
||||||
|
{ "", NULL}
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//this function is called when error pin changes as enable signal
|
||||||
|
static void enableInput(void)
|
||||||
|
{
|
||||||
|
static bool lastState=true;
|
||||||
|
#ifdef PIN_ENABLE
|
||||||
|
if (NVM->SystemParams.errorPinMode == ERROR_PIN_MODE_ENABLE)
|
||||||
|
{
|
||||||
|
static int enable;
|
||||||
|
//read our enable pin
|
||||||
|
enable = digitalRead(PIN_ENABLE);
|
||||||
|
if (enable != enableState)
|
||||||
|
{
|
||||||
|
WARNING("Enable now %d",enable);
|
||||||
|
}
|
||||||
|
enableState=enable;
|
||||||
|
//stepperCtrl.enable(enable);
|
||||||
|
}
|
||||||
|
if (NVM->SystemParams.errorPinMode == ERROR_PIN_MODE_ACTIVE_LOW_ENABLE)
|
||||||
|
{
|
||||||
|
static int enable;
|
||||||
|
//read our enable pin
|
||||||
|
enable = !digitalRead(PIN_ENABLE);
|
||||||
|
if (enable != enableState)
|
||||||
|
{
|
||||||
|
WARNING("Enable now %d",enable);
|
||||||
|
}
|
||||||
|
enableState=enable;
|
||||||
|
//stepperCtrl.enable(enable);
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
if (NVM->SystemParams.errorPinMode == ERROR_PIN_MODE_ENABLE)
|
||||||
|
{
|
||||||
|
static int enable;
|
||||||
|
//read our enable pin
|
||||||
|
enable = digitalRead(PIN_ERROR);
|
||||||
|
enableState=enable;
|
||||||
|
//stepperCtrl.enable(enable);
|
||||||
|
}
|
||||||
|
if (NVM->SystemParams.errorPinMode == ERROR_PIN_MODE_ACTIVE_LOW_ENABLE)
|
||||||
|
{
|
||||||
|
static int enable;
|
||||||
|
//read our enable pin
|
||||||
|
enable = !digitalRead(PIN_ERROR);
|
||||||
|
enableState=enable;
|
||||||
|
//stepperCtrl.enable(enable);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_STEP_DIR_SERIAL
|
||||||
|
|
||||||
|
static uint8_t pinCFG[2];
|
||||||
|
static uint8_t pinMux[2];
|
||||||
|
if (enableState == false && lastState==true)
|
||||||
|
{
|
||||||
|
// turn the step/dir to serial port
|
||||||
|
|
||||||
|
//save pin config for restoring
|
||||||
|
pinCFG[0]=getPinCfg(PIN_STEP_INPUT);
|
||||||
|
pinCFG[1]=getPinCfg(PIN_DIR_INPUT);
|
||||||
|
pinMux[0]=getPinMux(PIN_STEP_INPUT);
|
||||||
|
pinMux[1]=getPinMux(PIN_DIR_INPUT);
|
||||||
|
|
||||||
|
//lets see if the step pin has interrupt enabled
|
||||||
|
if (pinMux[0] == PORT_PMUX_PMUXE_A_Val)
|
||||||
|
{
|
||||||
|
EExt_Interrupts in = g_APinDescription[PIN_STEP_INPUT].ulExtInt;
|
||||||
|
EIC->INTENCLR.reg = EIC_INTENCLR_EXTINT(1 << in); //disable the interrupt
|
||||||
|
//we need to disable the interrupt
|
||||||
|
}
|
||||||
|
|
||||||
|
//now we need to set the pins to serial port peripheral (sercom0)
|
||||||
|
setPinMux(PIN_STEP_INPUT,PORT_PMUX_PMUXE_C_Val);
|
||||||
|
setPinMux(PIN_DIR_INPUT,PORT_PMUX_PMUXE_C_Val);
|
||||||
|
|
||||||
|
//make sure that step pin is input with mux to peripheral
|
||||||
|
setPinCfg(PIN_STEP_INPUT, PORT_PINCFG_PMUXEN | PORT_PINCFG_INEN | PORT_PINCFG_PULLEN);
|
||||||
|
|
||||||
|
//make sure that dir pin is an output with mux to peripheral
|
||||||
|
setPinCfg(PIN_DIR_INPUT, PORT_PINCFG_PMUXEN );
|
||||||
|
|
||||||
|
Serial1.begin(STEP_DIR_BAUD);
|
||||||
|
|
||||||
|
}
|
||||||
|
if (enableState == true && lastState==false)
|
||||||
|
{
|
||||||
|
Serial1.end();
|
||||||
|
setPinMux(PIN_STEP_INPUT,pinMux[0]);
|
||||||
|
setPinMux(PIN_DIR_INPUT,pinMux[1]);
|
||||||
|
setPinCfg(PIN_STEP_INPUT,pinCFG[0]);
|
||||||
|
setPinCfg(PIN_DIR_INPUT,pinCFG[1]);
|
||||||
|
//turn step/dir pins back to GPIO
|
||||||
|
if (PORT_PMUX_PMUXE_A_Val == pinMux[0])
|
||||||
|
{
|
||||||
|
//if interrupt was enabled for step pin renable it.
|
||||||
|
EExt_Interrupts in = g_APinDescription[PIN_STEP_INPUT].ulExtInt;
|
||||||
|
EIC->INTENSET.reg = EIC_INTENCLR_EXTINT(1 << in); //enable the interrupt
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif //USE_STEP_DIR_SERIAL
|
||||||
|
lastState=enableState;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void TC5_Handler()
|
||||||
|
{
|
||||||
|
// static bool led=false;
|
||||||
|
// YELLOW_LED(led);
|
||||||
|
// led=!led;
|
||||||
|
interrupts(); //allow other interrupts
|
||||||
|
if (TC5->COUNT16.INTFLAG.bit.OVF == 1)
|
||||||
|
{
|
||||||
|
int error=0;
|
||||||
|
|
||||||
|
|
||||||
|
error=(stepperCtrl.processFeedback()); //handle the control loop
|
||||||
|
YELLOW_LED(error);
|
||||||
|
#ifdef PIN_ENABLE
|
||||||
|
GPIO_OUTPUT(PIN_ERROR);
|
||||||
|
bool level;
|
||||||
|
level = !NVM->SystemParams.errorLogic;
|
||||||
|
if (error)
|
||||||
|
{ //assume high is inactive and low is active on error pin
|
||||||
|
digitalWrite(PIN_ERROR,level);
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
digitalWrite(PIN_ERROR,!level);
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
|
||||||
|
if (NVM->SystemParams.errorPinMode == ERROR_PIN_MODE_ERROR)
|
||||||
|
{
|
||||||
|
GPIO_OUTPUT(PIN_ERROR);
|
||||||
|
if (error)
|
||||||
|
{ //assume high is inactive and low is active on error pin
|
||||||
|
digitalWrite(PIN_ERROR,LOW);
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
digitalWrite(PIN_ERROR,HIGH);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
TC5->COUNT16.INTFLAG.bit.OVF = 1; // writing a one clears the flag ovf flag
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
//check the NVM and set to defaults if there is any
|
||||||
|
void validateAndInitNVMParams(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
if (false == NVM->sPID.parametersVaild)
|
||||||
|
{
|
||||||
|
nvmWrite_sPID(0.9,0.0001, 0.01);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (false == NVM->pPID.parametersVaild)
|
||||||
|
{
|
||||||
|
nvmWrite_pPID(1.0, 0, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (false == NVM->vPID.parametersVaild)
|
||||||
|
{
|
||||||
|
nvmWrite_vPID(2.0, 1.0, 1.0);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (false == NVM->SystemParams.parametersVaild)
|
||||||
|
{
|
||||||
|
SystemParams_t params;
|
||||||
|
params.microsteps=16;
|
||||||
|
#if defined(CTRL_POS_PID_AS_DEFAULT)
|
||||||
|
params.controllerMode=CTRL_POS_PID;
|
||||||
|
#else
|
||||||
|
params.controllerMode=CTRL_SIMPLE;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
params.dirPinRotation=CW_ROTATION; //default to clockwise rotation when dir is high
|
||||||
|
params.errorLimit=(int32_t)ANGLE_FROM_DEGREES(1.8);
|
||||||
|
params.errorPinMode=ERROR_PIN_MODE_ENABLE; //default to enable pin
|
||||||
|
params.homePin=-1;
|
||||||
|
params.errorLogic=false;
|
||||||
|
params.homeAngleDelay=ANGLE_FROM_DEGREES(10);
|
||||||
|
nvmWriteSystemParms(params);
|
||||||
|
}
|
||||||
|
|
||||||
|
//the motor parameters are check in the stepper_controller code
|
||||||
|
// as that there we can auto set much of them.
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void SYSCTRL_Handler(void)
|
||||||
|
{
|
||||||
|
if (SYSCTRL->INTFLAG.reg & SYSCTRL_INTFLAG_BOD33DET)
|
||||||
|
{
|
||||||
|
eepromFlush(); //flush the eeprom
|
||||||
|
SYSCTRL->INTFLAG.reg |= SYSCTRL_INTFLAG_BOD33DET;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Wait for synchronization of registers between the clock domains
|
||||||
|
static __inline__ void syncBOD33(void) __attribute__((always_inline, unused));
|
||||||
|
static void syncBOD33(void) {
|
||||||
|
//int32_t t0=1000;
|
||||||
|
while (SYSCTRL->PCLKSR.bit.BOD33RDY==1)
|
||||||
|
{
|
||||||
|
// t0--;
|
||||||
|
// if (t0==0)
|
||||||
|
// {
|
||||||
|
// break;
|
||||||
|
// }
|
||||||
|
}
|
||||||
|
}
|
||||||
|
static void configure_bod(void)
|
||||||
|
{
|
||||||
|
//syncBOD33();
|
||||||
|
//SYSCTRL->BOD33.reg=0; //disable BOD33 before starting
|
||||||
|
//syncBOD33();
|
||||||
|
SYSCTRL->BOD33.reg=SYSCTRL_BOD33_ACTION_INTERRUPT | //generate interrupt when BOD is triggered
|
||||||
|
SYSCTRL_BOD33_LEVEL(48) | //about 3.2V
|
||||||
|
//SYSCTRL_BOD33_HYST | //enable hysteresis
|
||||||
|
SYSCTRL_BOD33_ENABLE; //turn module on
|
||||||
|
|
||||||
|
LOG("BOD33 %02X", SYSCTRL->BOD33.reg );
|
||||||
|
SYSCTRL->INTENSET.reg |= SYSCTRL_INTENSET_BOD33DET;
|
||||||
|
|
||||||
|
NVIC_SetPriority(SYSCTRL_IRQn, 1); //make highest priority as we need to save eeprom
|
||||||
|
// Enable InterruptVector
|
||||||
|
NVIC_EnableIRQ(SYSCTRL_IRQn);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void NZS::begin(void)
|
||||||
|
{
|
||||||
|
int to=20;
|
||||||
|
stepCtrlError_t stepCtrlError;
|
||||||
|
|
||||||
|
//set up the pins correctly on the board.
|
||||||
|
boardSetupPins();
|
||||||
|
|
||||||
|
//start up the USB serial interface
|
||||||
|
//TODO check for power on USB before doing this...
|
||||||
|
#ifndef MECHADUINO_HARDWARE
|
||||||
|
SerialUSB.begin(SERIAL_BAUD);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//setup the serial port for syslog
|
||||||
|
Serial5.begin(SERIAL_BAUD);
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef CMD_SERIAL_PORT
|
||||||
|
SysLogInit(&Serial5,LOG_DEBUG);
|
||||||
|
pinPeripheral(PIN_TXD, PIO_SERCOM_ALT);
|
||||||
|
pinPeripheral(PIN_RXD, PIO_SERCOM_ALT);
|
||||||
|
#else
|
||||||
|
SysLogInit(NULL, LOG_WARNING);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
LOG("Power up!");
|
||||||
|
pinMode(PIN_USB_PWR, INPUT);
|
||||||
|
|
||||||
|
#ifndef MECHADUINO_HARDWARE
|
||||||
|
if (digitalRead(PIN_USB_PWR))
|
||||||
|
{
|
||||||
|
//wait for USB serial port to come alive
|
||||||
|
while (!SerialUSB)
|
||||||
|
{
|
||||||
|
to--;
|
||||||
|
if (to == 0)
|
||||||
|
{
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
delay(500);
|
||||||
|
}; //wait for serial
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
WARNING("USB Not connected");
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
validateAndInitNVMParams();
|
||||||
|
|
||||||
|
LOG("EEPROM INIT");
|
||||||
|
if (EEPROM_OK == eepromInit()) //init the EEPROM
|
||||||
|
{
|
||||||
|
eepromRead((uint8_t *)&PowerupEEPROM, sizeof(PowerupEEPROM));
|
||||||
|
}
|
||||||
|
configure_bod(); //configure the BOD
|
||||||
|
#ifndef DISABLE_LCD
|
||||||
|
LOG("Testing LCD");
|
||||||
|
Lcd.begin(&stepperCtrl);
|
||||||
|
|
||||||
|
#ifdef A5995_DRIVER
|
||||||
|
Lcd.lcdShow("MisfitTech","NEMA 23", VERSION);
|
||||||
|
#else
|
||||||
|
Lcd.lcdShow("MisfitTech","NEMA 17", VERSION);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
LOG("command init!");
|
||||||
|
commandsInit(); //setup command handler system
|
||||||
|
|
||||||
|
|
||||||
|
stepCtrlError=STEPCTRL_NO_CAL;
|
||||||
|
|
||||||
|
|
||||||
|
while (STEPCTRL_NO_ERROR != stepCtrlError)
|
||||||
|
{
|
||||||
|
LOG("init the stepper controller");
|
||||||
|
stepCtrlError=stepperCtrl.begin(); //start controller before accepting step inputs
|
||||||
|
|
||||||
|
//todo we need to handle error on LCD and through command line
|
||||||
|
if (STEPCTRL_NO_POWER == stepCtrlError)
|
||||||
|
{
|
||||||
|
#ifndef MECHADUINO_HARDWARE
|
||||||
|
SerialUSB.println("Appears that there is no Motor Power");
|
||||||
|
SerialUSB.println("Connect motor power!");
|
||||||
|
#else
|
||||||
|
Serial5.println("Appears that there is no Motor Power");
|
||||||
|
Serial5.println("Connect motor power!");
|
||||||
|
#endif
|
||||||
|
#ifndef DISABLE_LCD
|
||||||
|
Lcd.lcdShow("Waiting", "MOTOR", "POWER");
|
||||||
|
#endif
|
||||||
|
while (STEPCTRL_NO_POWER == stepCtrlError)
|
||||||
|
{
|
||||||
|
stepCtrlError=stepperCtrl.begin(); //start controller before accepting step inputs
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (STEPCTRL_NO_CAL == stepCtrlError)
|
||||||
|
{
|
||||||
|
#ifndef MECHADUINO_HARDWARE
|
||||||
|
SerialUSB.println("You need to Calibrate");
|
||||||
|
#else
|
||||||
|
Serial5.println("You need to Calibrate");
|
||||||
|
#endif
|
||||||
|
#ifndef DISABLE_LCD
|
||||||
|
Lcd.lcdShow(" NOT ", "Calibrated", " ");
|
||||||
|
delay(1000);
|
||||||
|
Lcd.setMenu(MenuCal);
|
||||||
|
Lcd.forceMenuActive();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//TODO add code here for LCD and command line loop
|
||||||
|
while(false == stepperCtrl.calibrationValid())
|
||||||
|
{
|
||||||
|
commandsProcess(); //handle commands
|
||||||
|
|
||||||
|
#ifndef DISABLE_LCD
|
||||||
|
Lcd.process();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifndef DISABLE_LCD
|
||||||
|
Lcd.setMenu(NULL);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
if (STEPCTRL_NO_ENCODER == stepCtrlError)
|
||||||
|
{
|
||||||
|
#ifndef MECHADUINO_HARDWARE
|
||||||
|
SerialUSB.println("AS5047D not working");
|
||||||
|
SerialUSB.println(" try disconnecting power from board for 15+mins");
|
||||||
|
SerialUSB.println(" you might have to short out power pins to ground");
|
||||||
|
#else
|
||||||
|
Serial5.println("AS5047D not working");
|
||||||
|
Serial5.println(" try disconnecting power from board for 15+mins");
|
||||||
|
Serial5.println(" you might have to short out power pins to ground");
|
||||||
|
#endif
|
||||||
|
#ifndef DISABLE_LCD
|
||||||
|
Lcd.lcdShow("Encoder", " Error!", " REBOOT");
|
||||||
|
#endif
|
||||||
|
while(1)
|
||||||
|
{
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
#ifndef DISABLE_LCD
|
||||||
|
Lcd.setMenu(MenuMain);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
stepPinSetup(); //setup the step pin
|
||||||
|
|
||||||
|
#ifdef PIN_ENABLE
|
||||||
|
//attachInterrupt(digitalPinToInterrupt(PIN_ENABLE), enableInput, CHANGE);
|
||||||
|
NVIC_SetPriority(EIC_IRQn, 0); //set port A interrupt as highest priority
|
||||||
|
#else
|
||||||
|
attachInterrupt(digitalPinToInterrupt(PIN_ERROR), enableInput, CHANGE);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
SmartPlanner.begin(&stepperCtrl);
|
||||||
|
RED_LED(false);
|
||||||
|
LOG("SETUP DONE!");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void printLocation(void)
|
||||||
|
{
|
||||||
|
char buf[128]={0};
|
||||||
|
Location_t loc;
|
||||||
|
int32_t n, i, len;
|
||||||
|
int32_t pktSize;
|
||||||
|
|
||||||
|
if (dataEnabled==0)
|
||||||
|
{
|
||||||
|
//RED_LED(false);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
//the packet length for binary print is 12bytes
|
||||||
|
// assuming rate of 6Khz this would be 72,000 baud
|
||||||
|
i=0;
|
||||||
|
n=stepperCtrl.getLocation(&loc);
|
||||||
|
if (n==-1)
|
||||||
|
{
|
||||||
|
//RED_LED(false);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
len=0;
|
||||||
|
pktSize=sizeof(Location_t)+1; //packet lenght is size location plus sync byte
|
||||||
|
|
||||||
|
// //binary write
|
||||||
|
|
||||||
|
while(n>=0 && (len)<=(128-pktSize))
|
||||||
|
{
|
||||||
|
memcpy(&buf[len],&loc,sizeof(Location_t));
|
||||||
|
len+=sizeof(Location_t);
|
||||||
|
buf[len]=0XAA; //sync
|
||||||
|
len++;
|
||||||
|
buf[len]=sizeof(Location_t); //data len
|
||||||
|
len++;
|
||||||
|
|
||||||
|
n=stepperCtrl.getLocation(&loc);
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
#ifndef MECHADUINO_HARDWARE
|
||||||
|
SerialUSB.write(buf,len);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//hex write
|
||||||
|
// hex write is 29 bytes per tick, @ 6khz this 174000 baud
|
||||||
|
// while(n>=0 && (i*29)<(200-29))
|
||||||
|
// {
|
||||||
|
// sprintf(buf,"%s%08X\t%08X\t%08X\n\r",buf,loc.microSecs,loc.desiredLoc,loc.actualLoc);
|
||||||
|
// n=stepperCtrl.getLocation(&loc);
|
||||||
|
// i++;
|
||||||
|
// }
|
||||||
|
// SerialUSB.write(buf,strlen(buf));
|
||||||
|
|
||||||
|
// if (n<=0)
|
||||||
|
// {
|
||||||
|
// RED_LED(false);
|
||||||
|
// }else
|
||||||
|
// {
|
||||||
|
// RED_LED(true);
|
||||||
|
// }
|
||||||
|
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
void NZS::loop(void)
|
||||||
|
{
|
||||||
|
eepromData_t eepromData;
|
||||||
|
|
||||||
|
|
||||||
|
// if (dataEnabled==0)
|
||||||
|
// {
|
||||||
|
// LOG("loop time is %dus",stepperCtrl.getLoopTime());
|
||||||
|
// }
|
||||||
|
|
||||||
|
//read the enable pin and update
|
||||||
|
// this is also done as an edge interrupt but does not always see
|
||||||
|
// to trigger the ISR.
|
||||||
|
enableInput();
|
||||||
|
|
||||||
|
if (enableState != stepperCtrl.getEnable())
|
||||||
|
{
|
||||||
|
stepperCtrl.enable(enableState);
|
||||||
|
}
|
||||||
|
|
||||||
|
//handle EEPROM
|
||||||
|
eepromData.angle=stepperCtrl.getCurrentAngle();
|
||||||
|
eepromData.encoderAngle=stepperCtrl.getEncoderAngle();
|
||||||
|
eepromData.valid=1;
|
||||||
|
eepromWriteCache((uint8_t *)&eepromData,sizeof(eepromData));
|
||||||
|
|
||||||
|
commandsProcess(); //handle commands
|
||||||
|
#ifndef DISABLE_LCD
|
||||||
|
Lcd.process();
|
||||||
|
#endif
|
||||||
|
//stepperCtrl.PrintData(); //prints steps and angle to serial USB.
|
||||||
|
|
||||||
|
|
||||||
|
printLocation(); //print out the current location
|
||||||
|
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
#pragma GCC pop_options
|
53
firmware_smartstepper_trikarus/stepper_nano_zero/nzs.h
Normal file
@ -0,0 +1,53 @@
|
|||||||
|
/*
|
||||||
|
* nzs.h
|
||||||
|
*
|
||||||
|
* Created on: Dec 8, 2016
|
||||||
|
* Author: trampas
|
||||||
|
*
|
||||||
|
Copyright (C) 2018 MisfitTech, All rights reserved.
|
||||||
|
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
#ifndef NZS_H_
|
||||||
|
#define NZS_H_
|
||||||
|
|
||||||
|
#include "board.h"
|
||||||
|
#include "nzs_lcd.h"
|
||||||
|
#include "stepper_controller.h"
|
||||||
|
#include "planner.h"
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
int64_t angle;
|
||||||
|
uint16_t encoderAngle;
|
||||||
|
uint8_t valid;
|
||||||
|
}eepromData_t;
|
||||||
|
|
||||||
|
class NZS //nano Zero Stepper
|
||||||
|
{
|
||||||
|
|
||||||
|
public:
|
||||||
|
void begin(void);
|
||||||
|
void loop(void);
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* NZS_H_ */
|
600
firmware_smartstepper_trikarus/stepper_nano_zero/nzs_lcd.cpp
Normal file
@ -0,0 +1,600 @@
|
|||||||
|
/*
|
||||||
|
* nzs_lcd.cpp
|
||||||
|
*
|
||||||
|
* Created on: Dec 8, 2016
|
||||||
|
* Author: trampas
|
||||||
|
*
|
||||||
|
Copyright (C) 2018 MisfitTech, All rights reserved.
|
||||||
|
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
#include "nzs_lcd.h"
|
||||||
|
#include <string.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <Wire.h>
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef DISABLE_LCD
|
||||||
|
void LCD::begin(StepperCtrl *ptrsCtrl)
|
||||||
|
{
|
||||||
|
#ifndef MECHADUINO_HARDWARE
|
||||||
|
pinMode(PIN_SW1, INPUT_PULLUP);
|
||||||
|
pinMode(PIN_SW3, INPUT_PULLUP);
|
||||||
|
pinMode(PIN_SW4, INPUT_PULLUP);
|
||||||
|
#endif
|
||||||
|
buttonState=0;
|
||||||
|
|
||||||
|
//we need access to the stepper controller
|
||||||
|
ptrStepperCtrl=ptrsCtrl; //save a pointer to the stepper controller
|
||||||
|
|
||||||
|
|
||||||
|
ptrMenu=NULL;
|
||||||
|
menuIndex=0;
|
||||||
|
menuActive=false;
|
||||||
|
optionIndex=0;
|
||||||
|
ptrOptions=NULL;
|
||||||
|
displayEnabled=true;
|
||||||
|
|
||||||
|
//check that the SCL and SDA are pulled high
|
||||||
|
pinMode(PIN_SDA, INPUT);
|
||||||
|
pinMode(PIN_SCL, INPUT);
|
||||||
|
if (digitalRead(PIN_SDA)==0)
|
||||||
|
{
|
||||||
|
//pin is not pulled up
|
||||||
|
displayEnabled=false;
|
||||||
|
}
|
||||||
|
if (digitalRead(PIN_SCL)==0)
|
||||||
|
{
|
||||||
|
//pin is not pulled up
|
||||||
|
displayEnabled=false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (displayEnabled)
|
||||||
|
{
|
||||||
|
displayEnabled=display.begin(SSD1306_SWITCHCAPVCC, 0x3C);
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
WARNING("SCL/SDA not pulled up");
|
||||||
|
}
|
||||||
|
if (false == displayEnabled)
|
||||||
|
{
|
||||||
|
WARNING("NO display found, LCD will not be used");
|
||||||
|
}
|
||||||
|
Wire.setClock(800000);
|
||||||
|
|
||||||
|
//showSplash();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void __attribute__ ((optimize("Ofast"))) LCD::lcdShow(const char *line1, const char *line2,const char *line3)
|
||||||
|
{
|
||||||
|
|
||||||
|
if (false == displayEnabled)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
display.clearDisplay();
|
||||||
|
display.setTextSize(2);
|
||||||
|
display.setTextColor(WHITE);
|
||||||
|
display.setCursor(0,0);
|
||||||
|
display.println(line1);
|
||||||
|
display.setCursor(0,20);
|
||||||
|
display.println(line2);
|
||||||
|
display.setCursor(0,40);
|
||||||
|
display.println(line3);
|
||||||
|
display.display();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void LCD::showSplash(void)
|
||||||
|
{
|
||||||
|
if (false == displayEnabled)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
#ifdef A5995_DRIVER
|
||||||
|
lcdShow("MisfitTech","NEMA 23", VERSION);
|
||||||
|
#else
|
||||||
|
lcdShow("MisfitTech","NEMA 17", VERSION);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void LCD::setMenu(menuItem_t *pMenu)
|
||||||
|
{
|
||||||
|
if (false == displayEnabled)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
ptrMenu=pMenu;
|
||||||
|
menuIndex=0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void LCD::showOptions(void)
|
||||||
|
{
|
||||||
|
int32_t i,j;
|
||||||
|
char str[3][26]={0};
|
||||||
|
if (false == displayEnabled)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
i=optionIndex;
|
||||||
|
j=0;
|
||||||
|
while(strlen(ptrOptions[i].str)>0 && j<3)
|
||||||
|
{
|
||||||
|
if (i == optionIndex)
|
||||||
|
{
|
||||||
|
sprintf(str[j],"*%s",ptrOptions[i].str);
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
sprintf(str[j]," %s",ptrOptions[i].str);
|
||||||
|
}
|
||||||
|
j++;
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
|
||||||
|
lcdShow(str[0], str[1], str[2]);
|
||||||
|
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void __attribute__ ((optimize("Ofast"))) LCD::showMenu(void)
|
||||||
|
{
|
||||||
|
int32_t i,j;
|
||||||
|
char str[3][26]={0};
|
||||||
|
if (false == displayEnabled)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
i=menuIndex;
|
||||||
|
j=0;
|
||||||
|
while(ptrMenu[i].func!=NULL && j<3)
|
||||||
|
{
|
||||||
|
if (i == menuIndex)
|
||||||
|
{
|
||||||
|
sprintf(str[j],"*%s",ptrMenu[i].str);
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
sprintf(str[j]," %s",ptrMenu[i].str);
|
||||||
|
}
|
||||||
|
j++;
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
|
||||||
|
//show exit if there is room
|
||||||
|
if (j<3)
|
||||||
|
{
|
||||||
|
if (j==0)
|
||||||
|
{
|
||||||
|
sprintf(str[j],"*Exit");
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
sprintf(str[j]," Exit");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
lcdShow(str[0], str[1], str[2]);
|
||||||
|
|
||||||
|
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void __attribute__ ((optimize("Ofast"))) LCD::updateMenu(void)
|
||||||
|
{
|
||||||
|
if (false == displayEnabled)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ptrOptions != NULL)
|
||||||
|
{
|
||||||
|
showOptions();
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
showMenu();
|
||||||
|
}
|
||||||
|
|
||||||
|
//handle push buttons
|
||||||
|
if (digitalRead(PIN_SW3)==0 && (buttonState & 0x02)==0)
|
||||||
|
{
|
||||||
|
buttonState |= 0x02;
|
||||||
|
|
||||||
|
LOG("SW3 pressed");
|
||||||
|
if (ptrMenu[menuIndex].func == NULL)
|
||||||
|
{
|
||||||
|
//exit pressed
|
||||||
|
menuIndex=0; //reset menu index
|
||||||
|
menuActive=false;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ptrMenu[menuIndex].func != NULL)
|
||||||
|
{
|
||||||
|
LOG("Calling function for %s",ptrMenu[menuIndex].str);
|
||||||
|
if (ptrOptions != NULL)
|
||||||
|
{
|
||||||
|
char *ptrArgV[1];
|
||||||
|
char str[25]={0};
|
||||||
|
ptrArgV[0]=str;
|
||||||
|
sprintf(str,"%d",optionIndex);
|
||||||
|
LOG("Calling function for %s %s",ptrMenu[menuIndex].str,str);
|
||||||
|
ptrMenu[menuIndex].func(1,ptrArgV);
|
||||||
|
ptrOptions=NULL;
|
||||||
|
optionIndex=0;
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
int i;
|
||||||
|
i=ptrMenu[menuIndex].func(0,NULL);
|
||||||
|
if (ptrMenu[menuIndex].ptrOptions != NULL)
|
||||||
|
{
|
||||||
|
LOG("displaying options for %s %d",ptrMenu[menuIndex].str,i);
|
||||||
|
ptrOptions=ptrMenu[menuIndex].ptrOptions;
|
||||||
|
optionIndex=i;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
if (digitalRead(PIN_SW1)==0 && (buttonState & 0x01)==0)
|
||||||
|
{
|
||||||
|
buttonState |= 0x01;
|
||||||
|
LOG("SW1 pressed");
|
||||||
|
if (ptrOptions != NULL)
|
||||||
|
{
|
||||||
|
optionIndex++;
|
||||||
|
if (strlen(ptrOptions[optionIndex].str) == 0)
|
||||||
|
{
|
||||||
|
optionIndex=0;
|
||||||
|
}
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
if (ptrMenu[menuIndex].func != NULL)
|
||||||
|
{
|
||||||
|
menuIndex++;
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
menuIndex=0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (digitalRead(PIN_SW1))
|
||||||
|
{
|
||||||
|
buttonState &= ~0x01;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (digitalRead(PIN_SW3))
|
||||||
|
{
|
||||||
|
buttonState &= ~0x02;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void LCD::forceMenuActive(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
menuActive=true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void __attribute__((optimize("Ofast")))LCD::process(void)
|
||||||
|
{
|
||||||
|
if (false == displayEnabled)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (false == menuActive || ptrMenu==NULL)
|
||||||
|
{
|
||||||
|
updateLCD();
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
updateMenu();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (digitalRead(PIN_SW4)==0 && (buttonState & 0x04)==0)
|
||||||
|
{
|
||||||
|
buttonState |= 0x04;
|
||||||
|
menuActive=!menuActive;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (digitalRead(PIN_SW4))
|
||||||
|
{
|
||||||
|
buttonState &= ~0x04;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
/*
|
||||||
|
//does the LCD menu system
|
||||||
|
void StepperCtrl::menu(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
bool done=false;
|
||||||
|
int menuItem=0;
|
||||||
|
char str[100];
|
||||||
|
int sw1State=0;
|
||||||
|
int sw3State=0;
|
||||||
|
|
||||||
|
pinMode(PIN_SW1, INPUT_PULLUP);
|
||||||
|
pinMode(PIN_SW3, INPUT_PULLUP);
|
||||||
|
pinMode(PIN_SW4, INPUT_PULLUP);
|
||||||
|
|
||||||
|
|
||||||
|
while (!done)
|
||||||
|
{
|
||||||
|
display.clearDisplay();
|
||||||
|
display.setTextSize(2);
|
||||||
|
display.setTextColor(WHITE);
|
||||||
|
|
||||||
|
if (menuItem==0)
|
||||||
|
{
|
||||||
|
sprintf(str,"*Run Cal");
|
||||||
|
display.setCursor(0,0);
|
||||||
|
display.println(str);
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
sprintf(str," Run Cal");
|
||||||
|
display.setCursor(0,0);
|
||||||
|
display.println(str);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (menuItem==1)
|
||||||
|
{
|
||||||
|
sprintf(str,"*Check Cal");
|
||||||
|
display.setCursor(0,20);
|
||||||
|
display.println(str);
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
sprintf(str," Check Cal");
|
||||||
|
display.setCursor(0,20);
|
||||||
|
display.println(str);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (menuItem==2)
|
||||||
|
{
|
||||||
|
sprintf(str,"*Exit");
|
||||||
|
display.setCursor(0,40);
|
||||||
|
display.println(str);
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
sprintf(str," Exit");
|
||||||
|
display.setCursor(0,40);
|
||||||
|
display.println(str);
|
||||||
|
}
|
||||||
|
|
||||||
|
display.display();
|
||||||
|
|
||||||
|
if (sw1State==1)
|
||||||
|
{
|
||||||
|
while (digitalRead(PIN_SW1)==0);
|
||||||
|
sw1State=0;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (digitalRead(PIN_SW1)==0)
|
||||||
|
{
|
||||||
|
sw1State=1;
|
||||||
|
menuItem=(menuItem+1)%3;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (sw3State==1)
|
||||||
|
{
|
||||||
|
while (digitalRead(PIN_SW3)==0);
|
||||||
|
sw3State=0;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (digitalRead(PIN_SW3)==0)
|
||||||
|
{
|
||||||
|
sw3State=1;
|
||||||
|
switch(menuItem)
|
||||||
|
{
|
||||||
|
case 0:
|
||||||
|
display.clearDisplay();
|
||||||
|
display.setTextSize(2);
|
||||||
|
display.setTextColor(WHITE);
|
||||||
|
display.setCursor(0,0);
|
||||||
|
display.println("Running");
|
||||||
|
display.setCursor(0,20);
|
||||||
|
display.println("Cal");
|
||||||
|
display.display();
|
||||||
|
calibrateEncoder();
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
{
|
||||||
|
display.clearDisplay();
|
||||||
|
display.setTextSize(2);
|
||||||
|
display.setTextColor(WHITE);
|
||||||
|
display.setCursor(0,0);
|
||||||
|
display.println("Testing");
|
||||||
|
display.setCursor(0,20);
|
||||||
|
display.println("Cal");
|
||||||
|
display.display();
|
||||||
|
int32_t error,x,y,m;
|
||||||
|
error=maxCalibrationError();
|
||||||
|
x=(error*100 *360)/ANGLE_STEPS;
|
||||||
|
m=x/100;
|
||||||
|
y=abs(x-(m*100));
|
||||||
|
display.clearDisplay();
|
||||||
|
display.setTextSize(2);
|
||||||
|
display.setTextColor(WHITE);
|
||||||
|
display.setCursor(0,0);
|
||||||
|
display.println("Error");
|
||||||
|
|
||||||
|
sprintf(str, "%02d.%02d deg",m,y);
|
||||||
|
display.setCursor(0,20);
|
||||||
|
display.println(str);
|
||||||
|
display.display();
|
||||||
|
while (digitalRead(PIN_SW3));
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 2:
|
||||||
|
return;
|
||||||
|
break;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
*/
|
||||||
|
|
||||||
|
void LCD::updateLCD(void)
|
||||||
|
{
|
||||||
|
if (false == displayEnabled)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
char str[3][25];
|
||||||
|
static int highRPM=0;
|
||||||
|
int32_t y,z,err;
|
||||||
|
|
||||||
|
static int64_t lastAngle,deg;
|
||||||
|
static int32_t RPM=0;
|
||||||
|
static int32_t lasttime=0;
|
||||||
|
|
||||||
|
bool state;
|
||||||
|
static int32_t dt=40;
|
||||||
|
static uint32_t t0=0;
|
||||||
|
|
||||||
|
static bool rpmDone=false;
|
||||||
|
|
||||||
|
if ((millis()-t0)>500)
|
||||||
|
{
|
||||||
|
|
||||||
|
int32_t x,d;
|
||||||
|
|
||||||
|
//do first half of RPM measurement
|
||||||
|
if (!rpmDone)
|
||||||
|
{
|
||||||
|
//LOG("loop time is %dus",ptrStepperCtrl->getLoopTime());
|
||||||
|
lastAngle=ptrStepperCtrl->getCurrentAngle();
|
||||||
|
lasttime=millis();
|
||||||
|
rpmDone=true;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
//do the second half of rpm measurement and update LCD.
|
||||||
|
if (rpmDone && (millis()-lasttime)>(dt))
|
||||||
|
{
|
||||||
|
rpmDone=false;
|
||||||
|
deg=ptrStepperCtrl->getCurrentAngle();
|
||||||
|
y=millis()-lasttime;
|
||||||
|
err=ptrStepperCtrl->getLoopError();
|
||||||
|
|
||||||
|
t0=millis();
|
||||||
|
d=(int64_t)(lastAngle-deg);
|
||||||
|
|
||||||
|
d=abs(d);
|
||||||
|
|
||||||
|
x=0;
|
||||||
|
if (d>0)
|
||||||
|
{
|
||||||
|
x=((int64_t)d*(60*1000UL))/((int64_t)y * ANGLE_STEPS);
|
||||||
|
}
|
||||||
|
|
||||||
|
lastAngle=deg;
|
||||||
|
RPM=(int32_t)x; //(7*RPM+x)/8; //average RPMs
|
||||||
|
if (RPM>500)
|
||||||
|
{
|
||||||
|
dt=10;
|
||||||
|
}
|
||||||
|
if (RPM<100)
|
||||||
|
{
|
||||||
|
dt=100;
|
||||||
|
}
|
||||||
|
str[0][0]='\0';
|
||||||
|
//LOG("RPMs is %d, %d, %d",(int32_t)x,(int32_t)d,(int32_t)y);
|
||||||
|
switch(ptrStepperCtrl->getControlMode())
|
||||||
|
{
|
||||||
|
case CTRL_SIMPLE:
|
||||||
|
sprintf(str[0], "%dRPM simp",RPM);
|
||||||
|
break;
|
||||||
|
case CTRL_TORQUE:
|
||||||
|
sprintf(str[0], "%dRPM torque",RPM);
|
||||||
|
break;
|
||||||
|
case CTRL_POS_PID:
|
||||||
|
sprintf(str[0], "%dRPM pPID",RPM);
|
||||||
|
break;
|
||||||
|
case CTRL_POS_VELOCITY_PID:
|
||||||
|
sprintf(str[0], "%dRPM vPID",RPM);
|
||||||
|
break;
|
||||||
|
case CTRL_OPEN:
|
||||||
|
sprintf(str[0], "%dRPM open",RPM);
|
||||||
|
break;
|
||||||
|
case CTRL_OFF:
|
||||||
|
sprintf(str[0], "%dRPM off",RPM);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
sprintf(str[0], "error %u",ptrStepperCtrl->getControlMode());
|
||||||
|
break;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
err=(err*360*100)/(int32_t)ANGLE_STEPS;
|
||||||
|
//LOG("error is %d %d %d",err,(int32_t)ptrStepperCtrl->getCurrentLocation(),(int32_t)ptrStepperCtrl->getDesiredLocation());
|
||||||
|
z=(err)/100;
|
||||||
|
y=abs(err-(z*100));
|
||||||
|
|
||||||
|
sprintf(str[1],"%01d.%02d err", z,y);
|
||||||
|
|
||||||
|
|
||||||
|
deg=ptrStepperCtrl->getDesiredAngle();
|
||||||
|
|
||||||
|
#ifndef NZS_LCD_ABSOULTE_ANGLE
|
||||||
|
deg=deg & ANGLE_MAX; //limit to 360 degrees
|
||||||
|
#endif
|
||||||
|
|
||||||
|
deg=(deg*360*10)/(int32_t)ANGLE_STEPS;
|
||||||
|
int K=0;
|
||||||
|
if (abs(deg)>9999)
|
||||||
|
{
|
||||||
|
K=1;
|
||||||
|
deg=deg/1000;
|
||||||
|
}
|
||||||
|
|
||||||
|
x=(deg)/10;
|
||||||
|
y=abs(deg-(x*10));
|
||||||
|
|
||||||
|
if (K==1)
|
||||||
|
{
|
||||||
|
sprintf(str[2],"%03d.%01uKdeg", x,y);
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
sprintf(str[2],"%03d.%01udeg", x,y);
|
||||||
|
}
|
||||||
|
str[0][10]='\0';
|
||||||
|
str[1][10]='\0';
|
||||||
|
str[2][10]='\0';
|
||||||
|
lcdShow(str[0],str[1],str[2]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
90
firmware_smartstepper_trikarus/stepper_nano_zero/nzs_lcd.h
Normal file
@ -0,0 +1,90 @@
|
|||||||
|
/*
|
||||||
|
* nzs_lcd.h
|
||||||
|
*
|
||||||
|
* Created on: Dec 8, 2016
|
||||||
|
* Author: trampas
|
||||||
|
*
|
||||||
|
*
|
||||||
|
Copyright (C) 2018 MisfitTech, All rights reserved.
|
||||||
|
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
#ifndef NZS_LCD_H_
|
||||||
|
#define NZS_LCD_H_
|
||||||
|
|
||||||
|
#include "Arduino.h"
|
||||||
|
#include "syslog.h"
|
||||||
|
#include "board.h"
|
||||||
|
#include "stepper_controller.h"
|
||||||
|
|
||||||
|
#include "Adafruit_GFX.h"
|
||||||
|
#include "Adafruit_SSD1306.h"
|
||||||
|
#include "gfxfont.h"
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
char str[15];
|
||||||
|
} options_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
char str[15];
|
||||||
|
|
||||||
|
//only one of the following should be not null
|
||||||
|
int (*func)(int argc, char *argv[]);
|
||||||
|
options_t *ptrOptions;
|
||||||
|
|
||||||
|
} menuItem_t;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
class LCD
|
||||||
|
{
|
||||||
|
private:
|
||||||
|
bool displayEnabled;
|
||||||
|
Adafruit_SSD1306 display;
|
||||||
|
StepperCtrl *ptrStepperCtrl;
|
||||||
|
menuItem_t *ptrMenu;
|
||||||
|
int32_t menuIndex;
|
||||||
|
bool menuActive;
|
||||||
|
|
||||||
|
options_t *ptrOptions;
|
||||||
|
int32_t optionIndex;
|
||||||
|
|
||||||
|
int32_t buttonState;
|
||||||
|
|
||||||
|
void updateLCD(void);
|
||||||
|
void showMenu(void);
|
||||||
|
void updateMenu(void);
|
||||||
|
void showOptions(void);
|
||||||
|
public:
|
||||||
|
void forceMenuActive(void);
|
||||||
|
void setMenu(menuItem_t *pMenu);
|
||||||
|
void begin(StepperCtrl *ptrStepperCtrl); //sets up the LCD
|
||||||
|
void process(void); //processes the LCD and updates as needed
|
||||||
|
void showSplash(void);
|
||||||
|
void lcdShow(const char *line1, const char *line2,const char *line3);
|
||||||
|
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* NZS_LCD_H_ */
|
207
firmware_smartstepper_trikarus/stepper_nano_zero/planner.cpp
Normal file
@ -0,0 +1,207 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
* Author: tstern
|
||||||
|
*
|
||||||
|
Copyright (C) 2018 MisfitTech, All rights reserved.
|
||||||
|
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#include "planner.h"
|
||||||
|
|
||||||
|
#include "board.h"
|
||||||
|
#include "wiring_private.h"
|
||||||
|
#include "syslog.h"
|
||||||
|
#include "angle.h"
|
||||||
|
#include "Arduino.h"
|
||||||
|
|
||||||
|
#define WAIT_TC16_REGS_SYNC(x) while(x->COUNT16.STATUS.bit.SYNCBUSY);
|
||||||
|
|
||||||
|
//define the planner class as being global
|
||||||
|
Planner SmartPlanner;
|
||||||
|
|
||||||
|
static bool enterTC3CriticalSection()
|
||||||
|
{
|
||||||
|
bool state=NVIC_IS_IRQ_ENABLED(TC3_IRQn);
|
||||||
|
NVIC_DisableIRQ(TC3_IRQn);
|
||||||
|
return state;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void exitTC3CriticalSection(bool prevState)
|
||||||
|
{
|
||||||
|
if (prevState)
|
||||||
|
{
|
||||||
|
NVIC_EnableIRQ(TC3_IRQn);
|
||||||
|
} //else do nothing
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void TC3_Init(void)
|
||||||
|
{
|
||||||
|
// Enable GCLK for TC3
|
||||||
|
GCLK->CLKCTRL.reg = (uint16_t) (GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID( GCM_TCC2_TC3 )) ;
|
||||||
|
while (GCLK->STATUS.bit.SYNCBUSY);
|
||||||
|
|
||||||
|
TC3->COUNT16.CTRLA.reg &= ~TC_CTRLA_ENABLE; // Disable TCx
|
||||||
|
WAIT_TC16_REGS_SYNC(TC3) // wait for sync
|
||||||
|
|
||||||
|
TC3->COUNT16.CTRLA.reg |= TC_CTRLA_MODE_COUNT16; // Set Timer counter Mode to 16 bits
|
||||||
|
WAIT_TC16_REGS_SYNC(TC3)
|
||||||
|
|
||||||
|
TC3->COUNT16.CTRLA.reg |= TC_CTRLA_WAVEGEN_MFRQ; // Set TC as normal Normal Frq
|
||||||
|
WAIT_TC16_REGS_SYNC(TC3)
|
||||||
|
|
||||||
|
TC3->COUNT16.CTRLA.reg |= TC_CTRLA_PRESCALER_DIV2; // Set perscaler
|
||||||
|
WAIT_TC16_REGS_SYNC(TC3)
|
||||||
|
|
||||||
|
|
||||||
|
TC3->COUNT16.CC[0].reg = F_CPU/PLANNER_UPDATE_RATE_HZ/2; //divide by two because of prescaler
|
||||||
|
|
||||||
|
WAIT_TC16_REGS_SYNC(TC3)
|
||||||
|
|
||||||
|
|
||||||
|
TC3->COUNT16.INTENSET.reg = 0; // disable all interrupts
|
||||||
|
TC3->COUNT16.INTENSET.bit.OVF = 1; // enable overfollow
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
NVIC_SetPriority(TC3_IRQn, 3);
|
||||||
|
|
||||||
|
|
||||||
|
// Enable InterruptVector
|
||||||
|
NVIC_EnableIRQ(TC3_IRQn);
|
||||||
|
|
||||||
|
|
||||||
|
// Enable TC
|
||||||
|
TC3->COUNT16.CTRLA.reg |= TC_CTRLA_ENABLE;
|
||||||
|
WAIT_TC16_REGS_SYNC(TC3);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void TC3_Handler(void)
|
||||||
|
{
|
||||||
|
interrupts(); //allow other interrupts
|
||||||
|
//do the planner tick
|
||||||
|
SmartPlanner.tick();
|
||||||
|
//SerialUSB.println('x');
|
||||||
|
TC3->COUNT16.INTFLAG.bit.OVF = 1; //clear interrupt by writing 1 to flag
|
||||||
|
}
|
||||||
|
|
||||||
|
void Planner::begin(StepperCtrl *ptrStepper)
|
||||||
|
{
|
||||||
|
|
||||||
|
ptrStepperCtrl=ptrStepper;
|
||||||
|
currentMode=PLANNER_NONE;
|
||||||
|
//setup the timer and interrupt as the last thing
|
||||||
|
TC3_Init();
|
||||||
|
}
|
||||||
|
|
||||||
|
void Planner::tick(void)
|
||||||
|
{
|
||||||
|
if (currentMode == PLANNER_NONE)
|
||||||
|
{
|
||||||
|
return; //do nothing
|
||||||
|
}
|
||||||
|
|
||||||
|
if (PLANNER_CV == currentMode)
|
||||||
|
{
|
||||||
|
// SerialUSB.println(currentSetAngle);
|
||||||
|
// SerialUSB.println(endAngle);
|
||||||
|
// SerialUSB.println(tickIncrement);
|
||||||
|
// SerialUSB.println(fabs(currentSetAngle-endAngle));
|
||||||
|
// SerialUSB.println(fabs(tickIncrement*2));
|
||||||
|
// SerialUSB.println();
|
||||||
|
int32_t x;
|
||||||
|
if (fabs(currentSetAngle-endAngle) >= fabs(tickIncrement))
|
||||||
|
{
|
||||||
|
currentSetAngle+=tickIncrement;
|
||||||
|
x=ANGLE_FROM_DEGREES(currentSetAngle);
|
||||||
|
ptrStepperCtrl->moveToAbsAngle(x);
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
//we are done, make sure we end at the right point
|
||||||
|
//SerialUSB.println("done");
|
||||||
|
x=ANGLE_FROM_DEGREES(endAngle);
|
||||||
|
ptrStepperCtrl->moveToAbsAngle(x);
|
||||||
|
currentMode=PLANNER_NONE;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void Planner::stop(void)
|
||||||
|
{
|
||||||
|
bool state;
|
||||||
|
state = enterTC3CriticalSection();
|
||||||
|
currentMode=PLANNER_NONE;
|
||||||
|
exitTC3CriticalSection(state);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Planner::moveConstantVelocity(float finalAngle, float rpm)
|
||||||
|
{
|
||||||
|
bool state;
|
||||||
|
state = enterTC3CriticalSection();
|
||||||
|
|
||||||
|
//first determine if operation is in progress
|
||||||
|
if (PLANNER_NONE != currentMode)
|
||||||
|
{
|
||||||
|
#ifndef MECHADUINO_HARDWARE
|
||||||
|
//we are in operation return false
|
||||||
|
SerialUSB.println("planner operational");
|
||||||
|
#else
|
||||||
|
Serial5.println("planner operational");
|
||||||
|
#endif
|
||||||
|
exitTC3CriticalSection(state);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
//get current posistion
|
||||||
|
startAngle = ANGLE_T0_DEGREES(ptrStepperCtrl->getCurrentAngle());
|
||||||
|
|
||||||
|
//deterime the tick increment
|
||||||
|
tickIncrement=360.0*fabs(rpm)/60/PLANNER_UPDATE_RATE_HZ;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//set the desired end angle
|
||||||
|
endAngle=finalAngle;
|
||||||
|
|
||||||
|
|
||||||
|
//set the current angle
|
||||||
|
currentSetAngle=startAngle;
|
||||||
|
|
||||||
|
if (startAngle>endAngle)
|
||||||
|
{
|
||||||
|
#ifndef MECHADUINO_HARDWARE
|
||||||
|
SerialUSB.println("reverse");
|
||||||
|
#endif
|
||||||
|
tickIncrement=-tickIncrement;
|
||||||
|
}
|
||||||
|
|
||||||
|
// SerialUSB.println(currentSetAngle);
|
||||||
|
// SerialUSB.println(endAngle);
|
||||||
|
// SerialUSB.println(tickIncrement);
|
||||||
|
// SerialUSB.println();
|
||||||
|
|
||||||
|
currentMode=PLANNER_CV;
|
||||||
|
|
||||||
|
exitTC3CriticalSection(state);
|
||||||
|
return true;
|
||||||
|
}
|
68
firmware_smartstepper_trikarus/stepper_nano_zero/planner.h
Normal file
@ -0,0 +1,68 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
* Author: tstern
|
||||||
|
*
|
||||||
|
Copyright (C) 2018 MisfitTech, All rights reserved.
|
||||||
|
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
/*
|
||||||
|
* This file implements a trajectory planner for use with serial
|
||||||
|
* interface. It allows the smart stepper to move at constant velocity.
|
||||||
|
* Additionally you can move to some location at constant velocity or
|
||||||
|
* with a trajectory curve
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef PLANNER_H_
|
||||||
|
#define PLANNER_H_
|
||||||
|
#include "board.h"
|
||||||
|
#include "stepper_controller.h"
|
||||||
|
|
||||||
|
#define PLANNER_UPDATE_RATE_HZ (3000UL) //how often planner updates PID
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
PLANNER_NONE =0,
|
||||||
|
PLANNER_CV =1, //constant velocity
|
||||||
|
//PLANNER_CA =2, //constant accleration
|
||||||
|
//PLANNER_S_CURVE =3, //s-curve move
|
||||||
|
} PlannerMode;
|
||||||
|
class Planner
|
||||||
|
{
|
||||||
|
private:
|
||||||
|
StepperCtrl *ptrStepperCtrl;
|
||||||
|
volatile PlannerMode currentMode=PLANNER_NONE;
|
||||||
|
//todo we should not use floating point, rather use "Angle"
|
||||||
|
volatile float endAngle;
|
||||||
|
volatile float startAngle;
|
||||||
|
volatile float currentSetAngle;
|
||||||
|
volatile float tickIncrement;
|
||||||
|
|
||||||
|
public:
|
||||||
|
void begin(StepperCtrl *ptrStepper);
|
||||||
|
bool moveConstantVelocity(float finalAngle, float rpm); //moves to the final location at a constant RPM
|
||||||
|
void tick(void); //this is called on regular tick interval
|
||||||
|
void stop(void);
|
||||||
|
bool done(void) {return currentMode==PLANNER_NONE;}
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
extern Planner SmartPlanner;
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* PLANNER_H_ */
|
198
firmware_smartstepper_trikarus/stepper_nano_zero/sine.cpp
Normal file
@ -0,0 +1,198 @@
|
|||||||
|
/*
|
||||||
|
* since.cpp
|
||||||
|
*
|
||||||
|
* Created on: Dec 24, 2016
|
||||||
|
* Author: tstern
|
||||||
|
*
|
||||||
|
Copyright (C) 2018 MisfitTech, All rights reserved.
|
||||||
|
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
#include "sine.h"
|
||||||
|
|
||||||
|
#pragma GCC push_options
|
||||||
|
#pragma GCC optimize ("-Ofast")
|
||||||
|
|
||||||
|
#ifdef NZS_FAST_SINE
|
||||||
|
static const int16_t sineTable[1280]={
|
||||||
|
0,201,402,603,804,1005,1206,1407,1608,1808,2009,2210,2410,2611,2811,3011,
|
||||||
|
3212,3412,3611,3811,4011,4210,4410,4609,4808,5007,5205,5404,5602,5800,5998,6195,
|
||||||
|
6392,6589,6786,6983,7179,7375,7571,7766,7962,8156,8351,8545,8739,8933,9126,9319,
|
||||||
|
9512,9704,9896,10087,10278,10469,10659,10849,11039,11228,11417,11605,11793,11980,12167,12353,
|
||||||
|
12539,12725,12910,13094,13278,13462,13645,13828,14010,14191,14372,14553,14732,14912,15090,15269,
|
||||||
|
15446,15623,15800,15976,16151,16325,16499,16673,16846,17018,17189,17360,17530,17700,17869,18037,
|
||||||
|
18204,18371,18537,18703,18868,19032,19195,19357,19519,19680,19841,20000,20159,20317,20475,20631,
|
||||||
|
20787,20942,21097,21250,21403,21554,21705,21856,22005,22154,22301,22448,22594,22739,22884,23027,
|
||||||
|
23170,23312,23452,23592,23732,23870,24007,24143,24279,24413,24547,24680,24812,24942,25072,25201,
|
||||||
|
25329,25456,25583,25708,25832,25955,26077,26199,26319,26438,26556,26674,26790,26905,27019,27133,
|
||||||
|
27245,27356,27466,27575,27683,27791,27897,28001,28105,28208,28310,28411,28510,28609,28706,28803,
|
||||||
|
28898,28992,29085,29178,29268,29358,29447,29535,29621,29707,29791,29874,29956,30037,30117,30195,
|
||||||
|
30273,30349,30425,30499,30572,30643,30714,30783,30852,30919,30985,31050,31113,31176,31237,31297,
|
||||||
|
31356,31414,31471,31526,31580,31633,31685,31736,31785,31834,31881,31926,31971,32015,32057,32098,
|
||||||
|
32138,32176,32214,32250,32285,32319,32351,32382,32413,32441,32469,32496,32521,32545,32568,32589,
|
||||||
|
32609,32629,32646,32663,32678,32693,32706,32717,32728,32737,32745,32752,32757,32762,32765,32767,
|
||||||
|
32767,32767,32765,32762,32757,32752,32745,32737,32728,32717,32706,32693,32678,32663,32646,32629,
|
||||||
|
32609,32589,32568,32545,32521,32496,32469,32441,32413,32382,32351,32319,32285,32250,32214,32176,
|
||||||
|
32138,32098,32057,32015,31971,31926,31881,31834,31785,31736,31685,31633,31580,31526,31471,31414,
|
||||||
|
31356,31297,31237,31176,31113,31050,30985,30919,30852,30783,30714,30643,30572,30499,30425,30349,
|
||||||
|
30273,30195,30117,30037,29956,29874,29791,29707,29621,29535,29447,29358,29268,29178,29085,28992,
|
||||||
|
28898,28803,28706,28609,28510,28411,28310,28208,28105,28001,27897,27791,27683,27575,27466,27356,
|
||||||
|
27245,27133,27019,26905,26790,26674,26556,26438,26319,26199,26077,25955,25832,25708,25583,25456,
|
||||||
|
25329,25201,25072,24942,24812,24680,24547,24413,24279,24143,24007,23870,23732,23592,23452,23312,
|
||||||
|
23170,23027,22884,22739,22594,22448,22301,22154,22005,21856,21705,21554,21403,21250,21097,20942,
|
||||||
|
20787,20631,20475,20317,20159,20000,19841,19680,19519,19357,19195,19032,18868,18703,18537,18371,
|
||||||
|
18204,18037,17869,17700,17530,17360,17189,17018,16846,16673,16499,16325,16151,15976,15800,15623,
|
||||||
|
15446,15269,15090,14912,14732,14553,14372,14191,14010,13828,13645,13462,13278,13094,12910,12725,
|
||||||
|
12539,12353,12167,11980,11793,11605,11417,11228,11039,10849,10659,10469,10278,10087,9896,9704,
|
||||||
|
9512,9319,9126,8933,8739,8545,8351,8156,7962,7766,7571,7375,7179,6983,6786,6589,
|
||||||
|
6392,6195,5998,5800,5602,5404,5205,5007,4808,4609,4410,4210,4011,3811,3611,3412,
|
||||||
|
3212,3011,2811,2611,2410,2210,2009,1808,1608,1407,1206,1005,804,603,402,201,
|
||||||
|
0,-201,-402,-603,-804,-1005,-1206,-1407,-1608,-1809,-2010,-2210,-2411,-2611,-2812,-3012,
|
||||||
|
-3212,-3412,-3612,-3812,-4011,-4211,-4410,-4609,-4808,-5007,-5206,-5404,-5602,-5800,-5998,-6196,
|
||||||
|
-6393,-6590,-6787,-6983,-7180,-7376,-7571,-7767,-7962,-8157,-8352,-8546,-8740,-8933,-9127,-9320,
|
||||||
|
-9512,-9704,-9896,-10088,-10279,-10470,-10660,-10850,-11039,-11228,-11417,-11605,-11793,-11980,-12167,-12354,
|
||||||
|
-12540,-12725,-12910,-13095,-13279,-13463,-13646,-13828,-14010,-14192,-14373,-14553,-14733,-14912,-15091,-15269,
|
||||||
|
-15447,-15624,-15800,-15976,-16151,-16326,-16500,-16673,-16846,-17018,-17190,-17361,-17531,-17700,-17869,-18037,
|
||||||
|
-18205,-18372,-18538,-18703,-18868,-19032,-19195,-19358,-19520,-19681,-19841,-20001,-20160,-20318,-20475,-20632,
|
||||||
|
-20788,-20943,-21097,-21250,-21403,-21555,-21706,-21856,-22006,-22154,-22302,-22449,-22595,-22740,-22884,-23028,
|
||||||
|
-23170,-23312,-23453,-23593,-23732,-23870,-24007,-24144,-24279,-24414,-24548,-24680,-24812,-24943,-25073,-25202,
|
||||||
|
-25330,-25457,-25583,-25708,-25832,-25956,-26078,-26199,-26319,-26439,-26557,-26674,-26790,-26906,-27020,-27133,
|
||||||
|
-27245,-27357,-27467,-27576,-27684,-27791,-27897,-28002,-28106,-28209,-28310,-28411,-28511,-28609,-28707,-28803,
|
||||||
|
-28899,-28993,-29086,-29178,-29269,-29359,-29448,-29535,-29622,-29707,-29791,-29875,-29957,-30038,-30117,-30196,
|
||||||
|
-30273,-30350,-30425,-30499,-30572,-30644,-30715,-30784,-30852,-30919,-30985,-31050,-31114,-31176,-31238,-31298,
|
||||||
|
-31357,-31415,-31471,-31527,-31581,-31634,-31686,-31736,-31786,-31834,-31881,-31927,-31972,-32015,-32057,-32098,
|
||||||
|
-32138,-32177,-32214,-32250,-32285,-32319,-32352,-32383,-32413,-32442,-32470,-32496,-32521,-32545,-32568,-32590,
|
||||||
|
-32610,-32629,-32647,-32664,-32679,-32693,-32706,-32718,-32728,-32738,-32746,-32752,-32758,-32762,-32765,-32767,
|
||||||
|
-32768,-32767,-32765,-32762,-32758,-32752,-32746,-32738,-32728,-32718,-32706,-32693,-32679,-32664,-32647,-32629,
|
||||||
|
-32610,-32590,-32568,-32545,-32521,-32496,-32470,-32442,-32413,-32383,-32352,-32319,-32285,-32250,-32214,-32177,
|
||||||
|
-32138,-32098,-32057,-32015,-31972,-31927,-31881,-31834,-31786,-31736,-31686,-31634,-31581,-31527,-31471,-31415,
|
||||||
|
-31357,-31298,-31238,-31176,-31114,-31050,-30985,-30919,-30852,-30784,-30715,-30644,-30572,-30499,-30425,-30350,
|
||||||
|
-30273,-30196,-30117,-30038,-29957,-29875,-29791,-29707,-29622,-29535,-29448,-29359,-29269,-29178,-29086,-28993,
|
||||||
|
-28899,-28803,-28707,-28609,-28511,-28411,-28310,-28209,-28106,-28002,-27897,-27791,-27684,-27576,-27467,-27357,
|
||||||
|
-27245,-27133,-27020,-26906,-26790,-26674,-26557,-26439,-26319,-26199,-26078,-25956,-25832,-25708,-25583,-25457,
|
||||||
|
-25330,-25202,-25073,-24943,-24812,-24680,-24548,-24414,-24279,-24144,-24007,-23870,-23732,-23593,-23453,-23312,
|
||||||
|
-23170,-23028,-22884,-22740,-22595,-22449,-22302,-22154,-22006,-21856,-21706,-21555,-21403,-21250,-21097,-20943,
|
||||||
|
-20788,-20632,-20475,-20318,-20160,-20001,-19841,-19681,-19520,-19358,-19195,-19032,-18868,-18703,-18538,-18372,
|
||||||
|
-18205,-18037,-17869,-17700,-17531,-17361,-17190,-17018,-16846,-16673,-16500,-16326,-16151,-15976,-15800,-15624,
|
||||||
|
-15447,-15269,-15091,-14912,-14733,-14553,-14373,-14192,-14010,-13828,-13646,-13463,-13279,-13095,-12910,-12725,
|
||||||
|
-12540,-12354,-12167,-11980,-11793,-11605,-11417,-11228,-11039,-10850,-10660,-10470,-10279,-10088,-9896,-9704,
|
||||||
|
-9512,-9320,-9127,-8933,-8740,-8546,-8352,-8157,-7962,-7767,-7571,-7376,-7180,-6983,-6787,-6590,
|
||||||
|
-6393,-6196,-5998,-5800,-5602,-5404,-5206,-5007,-4808,-4609,-4410,-4211,-4011,-3812,-3612,-3412,
|
||||||
|
-3212,-3012,-2812,-2611,-2411,-2210,-2010,-1809,-1608,-1407,-1206,-1005,-804,-603,-402,-201,
|
||||||
|
0,201,402,603,804,1005,1206,1407,1608,1808,2009,2210,2410,2611,2811,3011,
|
||||||
|
3212,3412,3611,3811,4011,4210,4410,4609,4808,5007,5205,5404,5602,5800,5998,6195,
|
||||||
|
6392,6589,6786,6983,7179,7375,7571,7766,7962,8156,8351,8545,8739,8933,9126,9319,
|
||||||
|
9512,9704,9896,10087,10278,10469,10659,10849,11039,11228,11417,11605,11793,11980,12167,12353,
|
||||||
|
12539,12725,12910,13094,13278,13462,13645,13828,14010,14191,14372,14553,14732,14912,15090,15269,
|
||||||
|
15446,15623,15800,15976,16151,16325,16499,16673,16846,17018,17189,17360,17530,17700,17869,18037,
|
||||||
|
18204,18371,18537,18703,18868,19032,19195,19357,19519,19680,19841,20000,20159,20317,20475,20631,
|
||||||
|
20787,20942,21097,21250,21403,21554,21705,21856,22005,22154,22301,22448,22594,22739,22884,23027,
|
||||||
|
23170,23312,23452,23592,23732,23870,24007,24143,24279,24413,24547,24680,24812,24942,25072,25201,
|
||||||
|
25329,25456,25583,25708,25832,25955,26077,26199,26319,26438,26556,26674,26790,26905,27019,27133,
|
||||||
|
27245,27356,27466,27575,27683,27791,27897,28001,28105,28208,28310,28411,28510,28609,28706,28803,
|
||||||
|
28898,28992,29085,29178,29268,29358,29447,29535,29621,29707,29791,29874,29956,30037,30117,30195,
|
||||||
|
30273,30349,30425,30499,30572,30643,30714,30783,30852,30919,30985,31050,31113,31176,31237,31297,
|
||||||
|
31356,31414,31471,31526,31580,31633,31685,31736,31785,31834,31881,31926,31971,32015,32057,32098,
|
||||||
|
32138,32176,32214,32250,32285,32319,32351,32382,32413,32441,32469,32496,32521,32545,32568,32589,
|
||||||
|
32609,32629,32646,32663,32678,32693,32706,32717,32728,32737,32745,32752,32757,32762,32765,32767
|
||||||
|
};
|
||||||
|
#else
|
||||||
|
static const uint16_t sineTable[257]={
|
||||||
|
0,402,804,1206,1608,2010,2412,2814,3216,3617,4019,4420,4821,5222,5623,6023,
|
||||||
|
6424,6824,7223,7623,8022,8421,8820,9218,9616,10014,10411,10808,11204,11600,11996,12391,
|
||||||
|
12785,13179,13573,13966,14359,14751,15142,15533,15924,16313,16703,17091,17479,17866,18253,18639,
|
||||||
|
19024,19408,19792,20175,20557,20939,21319,21699,22078,22456,22834,23210,23586,23960,24334,24707,
|
||||||
|
25079,25450,25820,26189,26557,26925,27291,27656,28020,28383,28745,29106,29465,29824,30181,30538,
|
||||||
|
30893,31247,31600,31952,32302,32651,32999,33346,33692,34036,34379,34721,35061,35400,35738,36074,
|
||||||
|
36409,36743,37075,37406,37736,38064,38390,38715,39039,39361,39682,40001,40319,40635,40950,41263,
|
||||||
|
41575,41885,42194,42500,42806,43109,43411,43712,44011,44308,44603,44897,45189,45479,45768,46055,
|
||||||
|
46340,46624,46905,47185,47464,47740,48014,48287,48558,48827,49095,49360,49624,49885,50145,50403,
|
||||||
|
50659,50913,51166,51416,51664,51911,52155,52398,52638,52877,53113,53348,53580,53811,54039,54266,
|
||||||
|
54490,54713,54933,55151,55367,55582,55794,56003,56211,56417,56620,56822,57021,57218,57413,57606,
|
||||||
|
57797,57985,58171,58356,58537,58717,58895,59070,59243,59414,59582,59749,59913,60075,60234,60391,
|
||||||
|
60546,60699,60850,60998,61144,61287,61429,61567,61704,61838,61970,62100,62227,62352,62475,62595,
|
||||||
|
62713,62829,62942,63053,63161,63267,63371,63472,63571,63668,63762,63853,63943,64030,64114,64196,
|
||||||
|
64276,64353,64428,64500,64570,64638,64703,64765,64826,64883,64939,64992,65042,65090,65136,65179,
|
||||||
|
65219,65258,65293,65327,65357,65386,65412,65435,65456,65475,65491,65504,65515,65524,65530,65534,
|
||||||
|
65535,
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
int16_t sine(uint16_t angle)
|
||||||
|
{
|
||||||
|
#ifdef NZS_FAST_SINE
|
||||||
|
return sineTable[angle];
|
||||||
|
#else
|
||||||
|
int sign=1;
|
||||||
|
int16_t ret;
|
||||||
|
//our sine table has 1024 points per rotation so convert angle to closest step
|
||||||
|
|
||||||
|
if (angle>=(SINE_STEPS/2))
|
||||||
|
{
|
||||||
|
sign=-1;
|
||||||
|
}
|
||||||
|
|
||||||
|
angle=angle % (SINE_STEPS/2); //limit to 0-180 as sign takes care of 180-360
|
||||||
|
|
||||||
|
if (angle>(SINE_STEPS/4-1)) //if we are greater than 90 we need to look up table backwards
|
||||||
|
{
|
||||||
|
angle=(SINE_STEPS/2)-angle;
|
||||||
|
}
|
||||||
|
|
||||||
|
ret=(int16_t)(sineTable[angle]/2)*sign;
|
||||||
|
return ret;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
int16_t cosine(uint16_t angle)
|
||||||
|
{
|
||||||
|
#ifdef NZS_FAST_SINE
|
||||||
|
angle=angle+(SINE_STEPS/4);
|
||||||
|
return sineTable[angle];
|
||||||
|
#else
|
||||||
|
|
||||||
|
int sign=1;
|
||||||
|
int16_t ret;
|
||||||
|
//our sine table has 1024 points per rotation so convert angle to closest step
|
||||||
|
|
||||||
|
if (angle>=(SINE_STEPS/4) and angle<(3*(SINE_STEPS/4)))
|
||||||
|
{
|
||||||
|
sign=-1;
|
||||||
|
}
|
||||||
|
|
||||||
|
angle=angle % (SINE_STEPS/2); //limit to 0-180 as sign takes care of 180-360
|
||||||
|
|
||||||
|
if (angle>(SINE_STEPS/4-1)) //if we are greater than 90 we need to look up table backwards
|
||||||
|
{
|
||||||
|
angle=(SINE_STEPS/2)-angle;
|
||||||
|
}
|
||||||
|
|
||||||
|
//for cosine we need 90 degree phase shift
|
||||||
|
angle=(SINE_STEPS/4)-angle;
|
||||||
|
|
||||||
|
ret=(int16_t)(sineTable[angle]/2)*sign;
|
||||||
|
return ret;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#pragma GCC pop_options
|
43
firmware_smartstepper_trikarus/stepper_nano_zero/sine.h
Normal file
@ -0,0 +1,43 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
* sine.h
|
||||||
|
*
|
||||||
|
* Created on: Dec 24, 2016
|
||||||
|
* Author: tstern
|
||||||
|
*
|
||||||
|
Copyright (C) 2018 MisfitTech, All rights reserved.
|
||||||
|
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef SINE_H_
|
||||||
|
#define SINE_H_
|
||||||
|
|
||||||
|
#include "board.h"
|
||||||
|
|
||||||
|
#define SINE_STEPS (1024L)
|
||||||
|
|
||||||
|
#define SINE_MAX ((int32_t)(32768L))
|
||||||
|
|
||||||
|
|
||||||
|
int16_t sine(uint16_t angle);
|
||||||
|
int16_t cosine(uint16_t angle);
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* SINE_H_ */
|
@ -0,0 +1,224 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
* Author: tstern
|
||||||
|
*
|
||||||
|
Copyright (C) 2018 MisfitTech, All rights reserved.
|
||||||
|
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#ifndef __STEPPER_CONTROLLER_H__
|
||||||
|
#define __STEPPER_CONTROLLER_H__
|
||||||
|
|
||||||
|
#include "syslog.h"
|
||||||
|
#include "board.h"
|
||||||
|
#include "as5047d.h"
|
||||||
|
#include "A1333.h"
|
||||||
|
#include "calibration.h"
|
||||||
|
#include "A4954.h"
|
||||||
|
#include "A5995.h"
|
||||||
|
#include "nonvolatile.h"
|
||||||
|
#include "fet_driver.h" //for the NEMA23 10A
|
||||||
|
|
||||||
|
|
||||||
|
#define N_DATA (1024)
|
||||||
|
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
STEPCTRL_NO_ERROR=0,
|
||||||
|
STEPCTRL_NO_POWER=1, //no power to motor
|
||||||
|
STEPCTRL_NO_CAL=2, //calibration not set
|
||||||
|
STEPCTRL_NO_ENCODER=3, //encoder not working
|
||||||
|
} stepCtrlError_t;
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
int32_t Kp;
|
||||||
|
int32_t Ki;
|
||||||
|
int32_t Kd;
|
||||||
|
} PID_t;
|
||||||
|
|
||||||
|
|
||||||
|
typedef __attribute__((aligned(4))) struct {
|
||||||
|
int32_t microSecs;
|
||||||
|
int32_t desiredLoc;
|
||||||
|
int32_t actualLoc;
|
||||||
|
int32_t angle;
|
||||||
|
int32_t ma;
|
||||||
|
} Location_t;
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
int32_t angle;
|
||||||
|
int32_t ma;
|
||||||
|
}Control_t;
|
||||||
|
|
||||||
|
#define MAX_NUM_LOCATIONS (64) //maximum number of locations to buffer
|
||||||
|
|
||||||
|
|
||||||
|
//this scales the PID parameters from Flash to floating point
|
||||||
|
// to fixed point int32_t values
|
||||||
|
#define CTRL_PID_SCALING (1024)
|
||||||
|
|
||||||
|
// Uncommenting this will make motor go into ctrl_pos_pid mode
|
||||||
|
// at startup and when exiting ctrl_torque mode by setting torque=0
|
||||||
|
//#define CTRL_POS_PID_AS_DEFAULT
|
||||||
|
|
||||||
|
class StepperCtrl
|
||||||
|
{
|
||||||
|
private:
|
||||||
|
volatile bool enableFeedback; //true if we are using PID control algorithm
|
||||||
|
|
||||||
|
#ifdef A1333_ENCODER
|
||||||
|
A1333 encoder;
|
||||||
|
#else
|
||||||
|
AS5047D encoder;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef NEMA_23_10A_HW
|
||||||
|
FetDriver stepperDriver;
|
||||||
|
#else
|
||||||
|
#ifdef A5995_DRIVER
|
||||||
|
A5995 stepperDriver;
|
||||||
|
#else
|
||||||
|
A4954 stepperDriver;
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
uint16_t startUpEncoder;
|
||||||
|
volatile int32_t ticks=0;
|
||||||
|
volatile Location_t locs[MAX_NUM_LOCATIONS];
|
||||||
|
volatile int32_t locReadIndx=0;
|
||||||
|
volatile int32_t locWriteIndx=0;
|
||||||
|
|
||||||
|
volatile MotorParams_t motorParams;
|
||||||
|
volatile SystemParams_t systemParams;
|
||||||
|
volatile bool enabled;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
volatile int32_t loopTimeus; //time to run loop in microseconds
|
||||||
|
|
||||||
|
volatile PID_t sPID; //simple control loop PID parameters
|
||||||
|
volatile PID_t pPID; //positional current based PID control parameters
|
||||||
|
volatile PID_t vPID; //velocity PID control parameters
|
||||||
|
|
||||||
|
volatile int64_t numSteps; //this is the number of steps we have taken from our start angle
|
||||||
|
|
||||||
|
volatile int32_t loopError;
|
||||||
|
|
||||||
|
volatile int64_t currentLocation; //estimate of the current location from encoder feedback
|
||||||
|
// the current location lower 16 bits is angle (0-360 degrees in 65536 steps) while upper
|
||||||
|
// bits is the number of full rotations.
|
||||||
|
|
||||||
|
//this is used for the velocity PID feedback
|
||||||
|
// units are in Angles/sec where 1 Angle=360deg/65536
|
||||||
|
volatile int64_t velocity;
|
||||||
|
volatile int8_t torque=0;
|
||||||
|
|
||||||
|
int64_t zeroAngleOffset=0;
|
||||||
|
|
||||||
|
|
||||||
|
//volatile int16_t data[N_DATA];
|
||||||
|
|
||||||
|
//does linear interpolation of the encoder calibration table
|
||||||
|
int32_t getAngleCalibration(int32_t encoderAngle);
|
||||||
|
|
||||||
|
//updates the currentMeasuredAngle with our best guess where we are
|
||||||
|
Angle sampleAngle(void);
|
||||||
|
Angle sampleMeanEncoder(int32_t numSamples);
|
||||||
|
|
||||||
|
float measureStepSize(void); //steps motor and estimates step size
|
||||||
|
uint32_t measureMaxCalibrationError(void);
|
||||||
|
void setLocationFromEncoder(void);
|
||||||
|
|
||||||
|
void motorReset(void);
|
||||||
|
void updateStep(int dir, uint16_t steps);
|
||||||
|
|
||||||
|
bool torqueLoop(int64_t currentLoc, Control_t *ptrCtrl);
|
||||||
|
bool pidFeedback(int64_t desiredLoc, int64_t currentLoc, Control_t *ptrCtrl);
|
||||||
|
bool simpleFeedback(int64_t desiredLoc, int64_t currentLoc,Control_t *ptrCtrl);
|
||||||
|
bool vpidFeedback(int64_t desiredLoc, int64_t currentLoc,Control_t *ptrCtrl);
|
||||||
|
int64_t getCurrentLocation(void);
|
||||||
|
int64_t getDesiredLocation(void);
|
||||||
|
void updateLocTable(int64_t desiredLoc, int64_t currentLoc,Control_t *ptrCtrl);
|
||||||
|
|
||||||
|
int64_t calculatePhasePrediction(int64_t currentLoc);
|
||||||
|
bool determineError(int64_t currentLoc, int64_t error);
|
||||||
|
|
||||||
|
public:
|
||||||
|
uint16_t getStartupEncoder(void) {return startUpEncoder;}
|
||||||
|
int32_t getLocation(Location_t *ptrLoc);
|
||||||
|
|
||||||
|
//int32_t getSteps(void);
|
||||||
|
Angle getEncoderAngle(void);
|
||||||
|
|
||||||
|
void setAngle(int64_t loc);
|
||||||
|
|
||||||
|
int64_t getZeroAngleOffset(void);
|
||||||
|
void PrintData(void);
|
||||||
|
void setTorque(int8_t tor); //set torqu for torque mode
|
||||||
|
int8_t getTorque(void);
|
||||||
|
void setVelocity(int64_t vel); //set velocity for vPID mode
|
||||||
|
int64_t getVelocity(void);
|
||||||
|
int32_t getLoopError(void) {return loopError;}; //assume atomic read
|
||||||
|
|
||||||
|
bool calibrationValid(void) { return calTable.calValid();} //returns true if calbiration is good
|
||||||
|
|
||||||
|
void updateParamsFromNVM(void); //updates the parameters from NVM
|
||||||
|
CalibrationTable calTable;
|
||||||
|
//void printData(void);
|
||||||
|
|
||||||
|
bool calibrateEncoder(void); //do manual calibration of the encoder
|
||||||
|
Angle maxCalibrationError(void); //measures the maximum calibration error as an angle
|
||||||
|
|
||||||
|
void moveToAbsAngle(int32_t a);
|
||||||
|
void moveToAngle(int32_t a, uint32_t ma);
|
||||||
|
|
||||||
|
stepCtrlError_t begin(void); //returns false if we can not use motor
|
||||||
|
|
||||||
|
bool processFeedback(void); // does the feedback loop
|
||||||
|
|
||||||
|
feedbackCtrl_t getControlMode(void) { return systemParams.controllerMode;};
|
||||||
|
|
||||||
|
void updateSteps(int64_t steps);
|
||||||
|
void requestStep(int dir, uint16_t steps); //requests a step, if feedback controller is off motor does not move
|
||||||
|
|
||||||
|
void feedback(bool enable);
|
||||||
|
bool getFeedback(void) {return enableFeedback;}
|
||||||
|
|
||||||
|
void encoderDiagnostics(char *ptrStr);
|
||||||
|
int32_t measureError(void);
|
||||||
|
|
||||||
|
//these two functions are compenstated by the zero offset
|
||||||
|
int64_t getCurrentAngle(void);
|
||||||
|
int64_t getDesiredAngle(void);
|
||||||
|
|
||||||
|
void move(int dir, uint16_t steps); //forces motor to move even if feedback controller is turned off.
|
||||||
|
void currentLocationIsDesiredLocation();
|
||||||
|
void stealthSwitchMode(feedbackCtrl_t m);
|
||||||
|
void acceptPositionAndStealthSwitchMode(feedbackCtrl_t m);
|
||||||
|
void enable(bool enable);
|
||||||
|
bool getEnable(void) {return enabled;}
|
||||||
|
|
||||||
|
int32_t getLoopTime(void) { return loopTimeus;}
|
||||||
|
|
||||||
|
void PID_Autotune(void);
|
||||||
|
void setZero(void);
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif //__STEPPER_CONTROLLER_H__
|
||||||
|
|
@ -0,0 +1,13 @@
|
|||||||
|
#include "nzs.h"
|
||||||
|
|
||||||
|
NZS nzs;
|
||||||
|
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
nzs.begin();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
nzs.loop();
|
||||||
|
}
|
314
firmware_smartstepper_trikarus/stepper_nano_zero/steppin.cpp
Normal file
@ -0,0 +1,314 @@
|
|||||||
|
/*
|
||||||
|
* Copyright (C) 2018 MisfitTech, All rights reserved.
|
||||||
|
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*/
|
||||||
|
#include "steppin.h"
|
||||||
|
#include "stepper_controller.h"
|
||||||
|
#include "wiring_private.h"
|
||||||
|
#include "Arduino.h"
|
||||||
|
|
||||||
|
extern StepperCtrl stepperCtrl;
|
||||||
|
|
||||||
|
volatile int32_t stepsChanged=0;
|
||||||
|
volatile int64_t steps=0;
|
||||||
|
|
||||||
|
|
||||||
|
#if (PIN_STEP_INPUT != 0)
|
||||||
|
#error "this code only works with step pin being D0 (PA11, EXTINT11)"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#define WAIT_TCC2_SYNC() while(TCC2->SYNCBUSY.reg)
|
||||||
|
|
||||||
|
void checkDir(void)
|
||||||
|
{
|
||||||
|
int dir=1;
|
||||||
|
static int lastDir=-1;
|
||||||
|
|
||||||
|
|
||||||
|
if (CW_ROTATION == NVM->SystemParams.dirPinRotation)
|
||||||
|
{
|
||||||
|
dir=0; //reverse the rotation
|
||||||
|
}
|
||||||
|
|
||||||
|
if (lastDir != dir)
|
||||||
|
{
|
||||||
|
if (dir)
|
||||||
|
{
|
||||||
|
EIC->CONFIG[1].reg &= ~EIC_CONFIG_SENSE2_Msk;
|
||||||
|
EIC->CONFIG[1].reg |= EIC_CONFIG_SENSE2_HIGH;
|
||||||
|
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
EIC->CONFIG[1].reg &= ~EIC_CONFIG_SENSE2_Msk;
|
||||||
|
EIC->CONFIG[1].reg |= EIC_CONFIG_SENSE2_LOW;
|
||||||
|
}
|
||||||
|
lastDir=dir;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
//this function can not be called in interrupt context as the overflow interrupt for tC4 needs to run.
|
||||||
|
int64_t getSteps(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
//#ifndef USE_NEW_STEP
|
||||||
|
// return 0;
|
||||||
|
//#endif
|
||||||
|
int64_t x;
|
||||||
|
#ifdef USE_TC_STEP
|
||||||
|
uint16_t y;
|
||||||
|
static uint16_t lasty=0;
|
||||||
|
|
||||||
|
TCC2->CTRLBSET.reg=TCC_CTRLBSET_CMD_READSYNC;
|
||||||
|
WAIT_TCC2_SYNC();
|
||||||
|
|
||||||
|
|
||||||
|
y=(uint16_t)(TCC2->COUNT.reg & 0x0FFFFul); //use only lowest 16bits
|
||||||
|
//LOG("count is %d",y);
|
||||||
|
steps += (int16_t)(y-lasty);
|
||||||
|
lasty=y;
|
||||||
|
|
||||||
|
checkDir();
|
||||||
|
return steps;
|
||||||
|
|
||||||
|
#else
|
||||||
|
EIC->INTENCLR.reg = EIC_INTENCLR_EXTINT11;
|
||||||
|
x=stepsChanged;
|
||||||
|
stepsChanged=0;
|
||||||
|
EIC->INTENSET.reg = EIC_INTENSET_EXTINT11;
|
||||||
|
return x;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//this function is called on the rising edge of a step from external device
|
||||||
|
static void stepInput(void)
|
||||||
|
{
|
||||||
|
static int dir;
|
||||||
|
|
||||||
|
//read our direction pin
|
||||||
|
dir = digitalRead(PIN_DIR_INPUT);
|
||||||
|
|
||||||
|
if (CW_ROTATION == NVM->SystemParams.dirPinRotation)
|
||||||
|
{
|
||||||
|
dir=!dir; //reverse the rotation
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifndef USE_NEW_STEP
|
||||||
|
stepperCtrl.requestStep(dir,1);
|
||||||
|
#else
|
||||||
|
if (dir)
|
||||||
|
{
|
||||||
|
stepsChanged++;
|
||||||
|
}else
|
||||||
|
{
|
||||||
|
stepsChanged--;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void enableEIC(void)
|
||||||
|
{
|
||||||
|
PM->APBAMASK.reg |= PM_APBAMASK_EIC;
|
||||||
|
if (EIC->CTRL.bit.ENABLE == 0)
|
||||||
|
{
|
||||||
|
// Enable GCLK for IEC (External Interrupt Controller)
|
||||||
|
GCLK->CLKCTRL.reg = (uint16_t) (GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(GCM_EIC));
|
||||||
|
|
||||||
|
// Enable EIC
|
||||||
|
EIC->CTRL.bit.ENABLE = 1;
|
||||||
|
while (EIC->STATUS.bit.SYNCBUSY == 1) { }
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void setupStepEvent(void)
|
||||||
|
{
|
||||||
|
//we will set up the EIC to generate an even on rising edge of step pin
|
||||||
|
//make sure EIC is setup
|
||||||
|
enableEIC();
|
||||||
|
|
||||||
|
|
||||||
|
// Assign step pin to EIC
|
||||||
|
// Step pin is PA11, EXTINT11
|
||||||
|
pinPeripheral(PIN_STEP_INPUT, PIO_EXTINT);
|
||||||
|
|
||||||
|
//set up the direction pin PA10 to trigger external interrupt
|
||||||
|
pinPeripheral(PIN_DIR_INPUT, PIO_EXTINT); //EXTINT10
|
||||||
|
|
||||||
|
|
||||||
|
//***** setup EIC ******
|
||||||
|
EIC->EVCTRL.bit.EXTINTEO11=1; //enable event for EXTINT11
|
||||||
|
EIC->EVCTRL.bit.EXTINTEO10=1; //enable event for EXTINT10
|
||||||
|
//setup up external interurpt 11 to be rising edge triggered
|
||||||
|
//setup up external interurpt 10 to be both edge triggered
|
||||||
|
EIC->CONFIG[1].reg |= EIC_CONFIG_SENSE3_RISE | EIC_CONFIG_SENSE2_HIGH;
|
||||||
|
|
||||||
|
checkDir();
|
||||||
|
|
||||||
|
//disable actually generating an interrupt, we only want event triggered
|
||||||
|
EIC->INTENCLR.reg = EIC_INTENCLR_EXTINT11;
|
||||||
|
EIC->INTENCLR.reg = EIC_INTENCLR_EXTINT10;
|
||||||
|
|
||||||
|
//**** setup the event system ***
|
||||||
|
// Enable GCLK for EVSYS channel 0
|
||||||
|
PM->APBCMASK.reg |= PM_APBCMASK_EVSYS;
|
||||||
|
|
||||||
|
GCLK->CLKCTRL.reg = (uint16_t) (GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(GCM_EVSYS_CHANNEL_0));
|
||||||
|
while (GCLK->STATUS.bit.SYNCBUSY);
|
||||||
|
GCLK->CLKCTRL.reg = (uint16_t) (GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(GCM_EVSYS_CHANNEL_1));
|
||||||
|
while (GCLK->STATUS.bit.SYNCBUSY);
|
||||||
|
|
||||||
|
//setup the step pin to trigger event 0 on the TCC2 (step)
|
||||||
|
EVSYS->CHANNEL.reg=EVSYS_CHANNEL_CHANNEL(0)
|
||||||
|
| EVSYS_CHANNEL_EDGSEL_RISING_EDGE
|
||||||
|
| EVSYS_CHANNEL_EVGEN(EVSYS_ID_GEN_EIC_EXTINT_11)
|
||||||
|
| EVSYS_CHANNEL_PATH_ASYNCHRONOUS;
|
||||||
|
|
||||||
|
EVSYS->USER.reg = EVSYS_USER_CHANNEL(1)
|
||||||
|
| EVSYS_USER_USER(EVSYS_ID_USER_TCC2_EV_0);
|
||||||
|
|
||||||
|
//setup the dir pin to trigger event 2 on the TCC2 (dir change)
|
||||||
|
EVSYS->CHANNEL.reg=EVSYS_CHANNEL_CHANNEL(1)
|
||||||
|
| EVSYS_CHANNEL_EDGSEL_BOTH_EDGES
|
||||||
|
| EVSYS_CHANNEL_EVGEN(EVSYS_ID_GEN_EIC_EXTINT_10)
|
||||||
|
| EVSYS_CHANNEL_PATH_ASYNCHRONOUS;
|
||||||
|
|
||||||
|
EVSYS->USER.reg = EVSYS_USER_CHANNEL(2)
|
||||||
|
| EVSYS_USER_USER(EVSYS_ID_USER_TCC2_EV_1);
|
||||||
|
|
||||||
|
//**** setup the Timer counter ******
|
||||||
|
PM->APBCMASK.reg |= PM_APBCMASK_TCC2;
|
||||||
|
|
||||||
|
// Enable GCLK for TCC2 (timer counter input clock)
|
||||||
|
GCLK->CLKCTRL.reg = (uint16_t) (GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(GCM_TCC2_TC3));
|
||||||
|
while (GCLK->STATUS.bit.SYNCBUSY);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
TCC2->CTRLA.reg &= ~TCC_CTRLA_ENABLE;
|
||||||
|
WAIT_TCC2_SYNC();
|
||||||
|
|
||||||
|
TCC2->CTRLA.reg= TCC_CTRLA_SWRST; //reset TCC2
|
||||||
|
WAIT_TCC2_SYNC();
|
||||||
|
while(TCC2->CTRLA.bit.SWRST ==1);
|
||||||
|
|
||||||
|
|
||||||
|
//TCC2->WAVE.reg = TCC_WAVE_WAVEGEN_NFRQ;
|
||||||
|
//WAIT_TCC2_SYNC();
|
||||||
|
|
||||||
|
TCC2->EVCTRL.reg=TCC_EVCTRL_EVACT0_COUNTEV | TCC_EVCTRL_TCEI0
|
||||||
|
| TCC_EVCTRL_EVACT1_DIR | TCC_EVCTRL_TCEI1;
|
||||||
|
WAIT_TCC2_SYNC();
|
||||||
|
|
||||||
|
|
||||||
|
TCC2->COUNT.reg=0;
|
||||||
|
WAIT_TCC2_SYNC();
|
||||||
|
|
||||||
|
//TCC2->CTRLBSET.bit.CMD=TCC_CTRLBSET_CMD_RETRIGGER;
|
||||||
|
//checkDirPin();
|
||||||
|
TCC2->CTRLBSET.bit.DIR=1;
|
||||||
|
|
||||||
|
WAIT_TCC2_SYNC();
|
||||||
|
TCC2->CTRLA.reg |=TCC_CTRLA_ENABLE;
|
||||||
|
WAIT_TCC2_SYNC();
|
||||||
|
|
||||||
|
|
||||||
|
//checkDirPin();
|
||||||
|
|
||||||
|
//
|
||||||
|
// TC4->COUNT16.CTRLA.reg = TC_CTRLA_MODE_COUNT16 // Set Timer counter Mode to 16 bits
|
||||||
|
// | TC_CTRLA_WAVEGEN_NFRQ //normal counting mode (not using waveforms)
|
||||||
|
// | TC_CTRLA_PRESCALER_DIV1; //count each pulse
|
||||||
|
// WAIT_TC32_REGS_SYNC(TC4)
|
||||||
|
//
|
||||||
|
// TC4->COUNT16.CTRLBCLR.reg=0xFF; //clear all values.
|
||||||
|
// WAIT_TC32_REGS_SYNC(TC4)
|
||||||
|
//
|
||||||
|
// TC4->COUNT16.EVCTRL.reg=TC_EVCTRL_TCEI | TC_EVCTRL_EVACT_COUNT; //enable event input and count
|
||||||
|
// WAIT_TC32_REGS_SYNC(TC4)
|
||||||
|
//
|
||||||
|
// TC4->COUNT16.COUNT.reg=0;
|
||||||
|
// WAIT_TC32_REGS_SYNC(TC4)
|
||||||
|
//
|
||||||
|
// TC4->COUNT16.INTENSET.bit.OVF = 1; //enable over/under flow interrupt
|
||||||
|
// //setup the TC overflow/underflow interrupt
|
||||||
|
// NVIC_SetPriority(TC4_IRQn, 0);
|
||||||
|
// // Enable InterruptVector
|
||||||
|
// NVIC_EnableIRQ(TC4_IRQn);
|
||||||
|
//
|
||||||
|
//
|
||||||
|
// // Enable TC
|
||||||
|
// TC4->COUNT16.CTRLA.reg |= TC_CTRLA_ENABLE;
|
||||||
|
// WAIT_TC32_REGS_SYNC(TC4)
|
||||||
|
}
|
||||||
|
|
||||||
|
//static void dirChanged_ISR(void)
|
||||||
|
//{
|
||||||
|
// int dir=0;
|
||||||
|
// //read our direction pin
|
||||||
|
// //dir = digitalRead(PIN_DIR_INPUT);
|
||||||
|
// if ( (PORT->Group[g_APinDescription[PIN_DIR_INPUT].ulPort].IN.reg & (1ul << g_APinDescription[PIN_DIR_INPUT].ulPin)) != 0 )
|
||||||
|
// {
|
||||||
|
// dir=1;
|
||||||
|
// }
|
||||||
|
//
|
||||||
|
//
|
||||||
|
// if (CW_ROTATION == NVM->SystemParams.dirPinRotation)
|
||||||
|
// {
|
||||||
|
// dir=!dir; //reverse the rotation
|
||||||
|
// }
|
||||||
|
// if (dir)
|
||||||
|
// {
|
||||||
|
// TC4->COUNT16.CTRLBSET.bit.DIR=1;
|
||||||
|
// } else
|
||||||
|
// {
|
||||||
|
// TC4->COUNT16.CTRLBCLR.bit.DIR=1;
|
||||||
|
// }
|
||||||
|
//}
|
||||||
|
|
||||||
|
|
||||||
|
void stepPinSetup(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef USE_TC_STEP
|
||||||
|
|
||||||
|
// //setup the direction pin
|
||||||
|
// dirChanged_ISR();
|
||||||
|
//
|
||||||
|
// //attachInterrupt configures the EIC as highest priority interrupts.
|
||||||
|
// attachInterrupt(digitalPinToInterrupt(PIN_DIR_INPUT), dirChanged_ISR, CHANGE);
|
||||||
|
setupStepEvent();
|
||||||
|
// NVIC_SetPriority(EIC_IRQn, 1); //set port A interrupt as highest priority
|
||||||
|
|
||||||
|
|
||||||
|
#else
|
||||||
|
attachInterrupt(digitalPinToInterrupt(PIN_STEP_INPUT), stepInput, RISING);
|
||||||
|
NVIC_SetPriority(EIC_IRQn, 0); //set port A interrupt as highest priority
|
||||||
|
#endif
|
||||||
|
|
||||||
|
}
|
31
firmware_smartstepper_trikarus/stepper_nano_zero/steppin.h
Normal file
@ -0,0 +1,31 @@
|
|||||||
|
/*
|
||||||
|
* Copyright (C) 2018 MisfitTech, All rights reserved.
|
||||||
|
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*/
|
||||||
|
#ifndef __STEPPIN_H___
|
||||||
|
#define __STEPPIN_H___
|
||||||
|
#include "board.h"
|
||||||
|
|
||||||
|
void stepPinSetup(void); //setup step pin
|
||||||
|
|
||||||
|
int64_t getSteps(void); //returns the number of steps changed since last call
|
||||||
|
|
||||||
|
|
||||||
|
#endif // __STEPPIN_H___
|
243
firmware_smartstepper_trikarus/stepper_nano_zero/syslog.cpp
Normal file
@ -0,0 +1,243 @@
|
|||||||
|
/*
|
||||||
|
* syslog.c
|
||||||
|
*
|
||||||
|
* Created on: Sep 14, 2011
|
||||||
|
* Author: trampas.stern
|
||||||
|
*
|
||||||
|
Copyright (C) 2018 MisfitTech, All rights reserved.
|
||||||
|
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
#include "syslog.h"
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "board.h"
|
||||||
|
|
||||||
|
|
||||||
|
#define ANSI_WHITE "\033[37m"
|
||||||
|
#define ANSI_NORMAL "\033[0m"
|
||||||
|
#define ANSI_BLINK "\033[5m"
|
||||||
|
#define ANSI_BLUE "\033[34m"
|
||||||
|
#define ANSI_MAGENTA "\033[35m"
|
||||||
|
#define ANSI_CYAN "\033[36m"
|
||||||
|
#define ANSI_WHITE "\033[37m"
|
||||||
|
#define ANSI_RED "\033[31m"
|
||||||
|
#define ANSI_GREEN "\033[32m"
|
||||||
|
#define ANSI_PINK "\033[35m\033[1m"
|
||||||
|
#define ANSI_BROWN "\033[33m"
|
||||||
|
#define ANSI_YELLOW "\033[33m\033[1m"
|
||||||
|
#define ANSI_BLACK "\033[30m"
|
||||||
|
#define ANSI_BELL_AND_RED "\a\033[31m"
|
||||||
|
|
||||||
|
#define NEW_LINE "\n\r"
|
||||||
|
|
||||||
|
Stream *ptrSerial=NULL;
|
||||||
|
eLogLevel SyslogLevelToWrite;
|
||||||
|
|
||||||
|
bool DebugUART=false;
|
||||||
|
static char buffer[SYSLOG_BUFFER_SIZE];
|
||||||
|
static unsigned int BufIndex=0;
|
||||||
|
|
||||||
|
static int SysLog_Enabled=1;
|
||||||
|
|
||||||
|
int SysLogDisable(void)
|
||||||
|
{
|
||||||
|
SysLog_Enabled=0;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
int SysLogEnable(void)
|
||||||
|
{
|
||||||
|
SysLog_Enabled=1;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
int SysLogIsEnabled(void)
|
||||||
|
{
|
||||||
|
return SysLog_Enabled;
|
||||||
|
}
|
||||||
|
void SysLogDebug(bool x)
|
||||||
|
{
|
||||||
|
DebugUART=x;
|
||||||
|
}
|
||||||
|
|
||||||
|
void SysLogPuts(const char *ptrStr)
|
||||||
|
{
|
||||||
|
if (!SysLog_Enabled)
|
||||||
|
return;
|
||||||
|
|
||||||
|
if (NULL == ptrSerial)
|
||||||
|
{
|
||||||
|
while(*ptrStr)
|
||||||
|
{
|
||||||
|
|
||||||
|
SYSLOG_PUTC(*ptrStr);
|
||||||
|
ptrStr++;
|
||||||
|
}
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
ptrSerial->write(ptrStr);
|
||||||
|
}
|
||||||
|
#ifndef MECHADUINO_HARDWARE
|
||||||
|
if (DebugUART)
|
||||||
|
{
|
||||||
|
SerialUSB.write(ptrStr);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
int SysLogInitDone=0;
|
||||||
|
void SysLogInit(Stream *ptrSerialObj, eLogLevel LevelToWrite)
|
||||||
|
{
|
||||||
|
ptrSerial=ptrSerialObj;
|
||||||
|
SyslogLevelToWrite=LevelToWrite;
|
||||||
|
|
||||||
|
SysLogInitDone=1;
|
||||||
|
BufIndex=0;
|
||||||
|
memset(buffer,0,SYSLOG_BUFFER_SIZE);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int SysLogProcessing=0; // this is used such that syslog can be reentrent
|
||||||
|
int SysLogMissed=0;
|
||||||
|
|
||||||
|
|
||||||
|
void SysLog(eLogLevel priorty, const char *fmt, ...)
|
||||||
|
{
|
||||||
|
//UINT32 ret;
|
||||||
|
int previousState=SysLog_Enabled;
|
||||||
|
char vastr[MAX_SYSLOG_STRING]={0};
|
||||||
|
//char outstr[MAX_SYSLOG_STRING]={0};
|
||||||
|
|
||||||
|
|
||||||
|
va_list ap;
|
||||||
|
|
||||||
|
if (SysLogProcessing)
|
||||||
|
{
|
||||||
|
//we have a syslog from a syslog call thus return as not much we can do...
|
||||||
|
//memset(buffer,0,SYSLOG_BUFFER_SIZE);
|
||||||
|
va_start(ap,fmt);
|
||||||
|
vsnprintf(&buffer[BufIndex],SYSLOG_BUFFER_SIZE-BufIndex,(char *)fmt,ap);
|
||||||
|
BufIndex=strlen(buffer);
|
||||||
|
snprintf(&buffer[BufIndex],SYSLOG_BUFFER_SIZE-BufIndex,NEW_LINE);
|
||||||
|
BufIndex=strlen(buffer);
|
||||||
|
SysLogMissed++; //set flag that we missed a call
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
SysLogProcessing=1;
|
||||||
|
|
||||||
|
//stop the watch dog will doing a SysLog print
|
||||||
|
Sys_WDogHoldOn();
|
||||||
|
|
||||||
|
if(!SysLogInitDone)
|
||||||
|
{
|
||||||
|
SysLogInit(NULL, LOG_WARNING); //not sure who is reseting serial port but before we print set it up
|
||||||
|
WARNING("You should init SysLog");
|
||||||
|
//SysLogInitDone=0;
|
||||||
|
}
|
||||||
|
|
||||||
|
//Send out a * that we missed a SysLog Message before this current message
|
||||||
|
if (SysLogMissed)
|
||||||
|
{
|
||||||
|
//SysLogPuts(ANSI_RED);
|
||||||
|
SysLogPuts("*** Reentrant Log call possible loss of message(s):");
|
||||||
|
SysLogPuts(NEW_LINE);
|
||||||
|
if (BufIndex>0)
|
||||||
|
{
|
||||||
|
SysLogPuts(buffer);
|
||||||
|
memset(buffer,0,SYSLOG_BUFFER_SIZE);
|
||||||
|
BufIndex=0;
|
||||||
|
}
|
||||||
|
//SysLogPuts(ANSI_RED);
|
||||||
|
SysLogPuts("***********");
|
||||||
|
SysLogPuts(NEW_LINE);
|
||||||
|
SysLogMissed=0;
|
||||||
|
}
|
||||||
|
memset(vastr,0,MAX_SYSLOG_STRING);
|
||||||
|
va_start(ap,fmt);
|
||||||
|
//#ifndef PGM_P
|
||||||
|
#if 1
|
||||||
|
vsnprintf(vastr,MAX_SYSLOG_STRING,(char *)fmt,ap);
|
||||||
|
#else
|
||||||
|
vsprintf_P(vastr,(const char *)fmt,ap);
|
||||||
|
#endif
|
||||||
|
//get time and store in datetimestr if desired
|
||||||
|
//sprintf(outstr, "[%s] %s\r\n", datetimestr, vastr);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
if (priorty<=LOG_ERROR)
|
||||||
|
{
|
||||||
|
SysLog_Enabled=1;
|
||||||
|
SysLogPuts(ANSI_RED);
|
||||||
|
|
||||||
|
}else if (priorty==LOG_DEBUG)
|
||||||
|
{
|
||||||
|
SysLogPuts(ANSI_WHITE);
|
||||||
|
}else if (priorty==LOG_WARNING)
|
||||||
|
{
|
||||||
|
SysLogPuts(ANSI_BLUE);
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef RTC_H_
|
||||||
|
#ifdef TIME_H_
|
||||||
|
{
|
||||||
|
struct tm tp;
|
||||||
|
RTC_Time_s tm;
|
||||||
|
time_t secs;
|
||||||
|
char datetimestr[MAX_SYSLOG_STRING]={0};
|
||||||
|
|
||||||
|
RTC_ReadTime(&tm);
|
||||||
|
secs=tm.seconds;
|
||||||
|
convertFlexNetTime((time_t *)&secs, &tp);
|
||||||
|
time_str(datetimestr,&tp);
|
||||||
|
SysLogPuts(datetimestr);
|
||||||
|
|
||||||
|
if (priorty<=SyslogLevelToWrite && SysLogWriteFunc!=NULL)
|
||||||
|
{
|
||||||
|
SysLogWriteFunc(datetimestr,strlen(datetimestr));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
SysLogPuts(vastr);
|
||||||
|
//
|
||||||
|
// if (priorty<=SyslogLevelToWrite && SysLogWriteFunc!=NULL)
|
||||||
|
// {
|
||||||
|
// SysLogWriteFunc(vastr,strlen(vastr));
|
||||||
|
// SysLogWriteFunc(NEW_LINE,strlen(NEW_LINE));
|
||||||
|
// }
|
||||||
|
|
||||||
|
|
||||||
|
SysLogPuts(ANSI_NORMAL);
|
||||||
|
SysLogPuts(NEW_LINE);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
if (priorty == LOG_EMERG) {
|
||||||
|
//you can reboot processor here
|
||||||
|
}
|
||||||
|
|
||||||
|
//start the watch dog where left off..
|
||||||
|
Sys_WDogHoldOff();
|
||||||
|
SysLogProcessing=0;
|
||||||
|
SysLog_Enabled=previousState;
|
||||||
|
return;
|
||||||
|
}
|
210
firmware_smartstepper_trikarus/stepper_nano_zero/syslog.h
Normal file
@ -0,0 +1,210 @@
|
|||||||
|
/*
|
||||||
|
* syslog.h
|
||||||
|
*
|
||||||
|
* Created on: Sep 14, 2011
|
||||||
|
* Author: trampas.stern
|
||||||
|
Copyright (C) 2018 MisfitTech, All rights reserved.
|
||||||
|
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
#ifndef SYSLOG_H_
|
||||||
|
#define SYSLOG_H_
|
||||||
|
|
||||||
|
#include <stdarg.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
#include "Arduino.h"
|
||||||
|
#include "variant.h"
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif // __cplusplus
|
||||||
|
|
||||||
|
#define SYSLOG_BUFFER_SIZE (250)
|
||||||
|
|
||||||
|
#define MAX_SYSLOG_STRING (250)
|
||||||
|
#define __FILENAME1__ (__builtin_strrchr(__FILE__, '\\') ? __builtin_strrchr(__FILE__, '\\') + 1 : __FILE__)
|
||||||
|
#define __FILENAME__ (__builtin_strrchr(__FILENAME1__, '/') ? __builtin_strrchr(__FILENAME1__, '/') + 1 : __FILENAME1__)
|
||||||
|
|
||||||
|
#define SYSLOG_WRITE(buffer,nBytes)
|
||||||
|
|
||||||
|
#ifdef CMD_SERIAL_PORT
|
||||||
|
#define SYSLOG_PUTC(x)
|
||||||
|
#else
|
||||||
|
#define SYSLOG_PUTC(x) //SerialUSB.write(x)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define Sys_WDogHoldOn()
|
||||||
|
#define Sys_WDogHoldOff()
|
||||||
|
/*
|
||||||
|
* priorities/facilities are encoded into a single 32-bit quantity, where the
|
||||||
|
* bottom 3 bits are the priority (0-7) and the top 28 bits are the facility
|
||||||
|
* (0-big number). Both the priorities and the facilities map roughly
|
||||||
|
* one-to-one to strings in the syslogd(8) source code. This mapping is
|
||||||
|
* included in this file.
|
||||||
|
*
|
||||||
|
* priorities (these are ordered)
|
||||||
|
*/
|
||||||
|
|
||||||
|
typedef enum _eLogLevel {
|
||||||
|
LOG_EMERG = 0, // system is unusable
|
||||||
|
LOG_ALERT = 1, // action must be taken immediately
|
||||||
|
LOG_CRIT = 2, // critical conditions
|
||||||
|
LOG_ERROR = 3, // error conditions
|
||||||
|
LOG_WARNING = 4, // warning conditions
|
||||||
|
LOG_NOTICE = 5, // normal but significant condition
|
||||||
|
LOG_INFO = 6, // informational
|
||||||
|
LOG_DEBUG = 7, // debug-level messages
|
||||||
|
LOG_DISABLED = 8 // disabled messages
|
||||||
|
} eLogLevel;
|
||||||
|
|
||||||
|
#if 0
|
||||||
|
#define CONCAT(x, y) CONCAT_(x, y)
|
||||||
|
#define CONCAT_(x, y) x##y
|
||||||
|
|
||||||
|
#define ID(...) __VA_ARGS__
|
||||||
|
|
||||||
|
#define IFMULTIARG(if,then,else) \
|
||||||
|
CONCAT(IFMULTIARG_, IFMULTIARG_(if, \
|
||||||
|
1, 1, 1, 1, 1, 1, 1, 1, 1, 1, \
|
||||||
|
1, 1, 1, 1, 1, 1, 1, 1, 1, 1, \
|
||||||
|
1, 1, 1, 1, 1, 1, 1, 1, 1, 1, \
|
||||||
|
1, 1, 1, 1, 1, 1, 1, 1, 1, 1, \
|
||||||
|
1, 1, 1, 1, 1, 1, 1, 1, 1, 1, \
|
||||||
|
1, 1, 1, 1, 1, 1, 1, 1, 1, 1, \
|
||||||
|
1, 1, 0, ))(then,else)
|
||||||
|
#define IFMULTIARG_(_0, _1, _2, _3, _4, _5, _6, _7, _8, _9, \
|
||||||
|
_10, _11, _12, _13, _14, _15, _16, _17, _18, _19, \
|
||||||
|
_20, _21, _22, _23, _24, _25, _26, _27, _28, _29, \
|
||||||
|
_30, _31, _32, _33, _34, _35, _36, _37, _38, _39, \
|
||||||
|
_40, _41, _42, _43, _44, _45, _46, _47, _48, _49, \
|
||||||
|
_50, _51, _52, _53, _54, _55, _56, _57, _58, _59, \
|
||||||
|
_60, _61, _62, _63, ...) _63
|
||||||
|
#define IFMULTIARG_0(then, else) else
|
||||||
|
#define IFMULTIARG_1(then, else) then
|
||||||
|
|
||||||
|
#define PROVIDE_SECOND_ARGUMENT(x, ...) CONCAT( IFMULTIARG(ID(__VA_ARGS__), INSERT_, ADD_), SECOND_ARGUMENT ) (x, __VA_ARGS__)
|
||||||
|
#define PROVIDE_SECOND_ARGUMENT2(x, y, ...) CONCAT( IFMULTIARG(ID(__VA_ARGS__), INSERT_, ADD_), SECOND_ARGUMENT2 ) (x, y, __VA_ARGS__)
|
||||||
|
|
||||||
|
#define ADD_SECOND_ARGUMENT(x, y) y, x
|
||||||
|
#define INSERT_SECOND_ARGUMENT(x, y, ...) y, x, __VA_ARGS__
|
||||||
|
|
||||||
|
#define ADD_SECOND_ARGUMENT2(x, z, y) y, x, z
|
||||||
|
#define INSERT_SECOND_ARGUMENT2(x, z, y, ...) y, x, z, __VA_ARGS__
|
||||||
|
|
||||||
|
#endif
|
||||||
|
//#define DEBUG1(...) printf( "DEBUG %s %s: "
|
||||||
|
//PROVIDE_SECOND_ARGUMENT2(__FILE__, __LINE__, __VA_ARGS__))
|
||||||
|
|
||||||
|
|
||||||
|
//TXT(x) macro is used for system which can store strings in flash, like AVR processors
|
||||||
|
#ifndef TXT
|
||||||
|
#define TXT(x) x
|
||||||
|
#endif
|
||||||
|
|
||||||
|
void SysLog(eLogLevel priorty, const char *fmt, ...);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
static inline const char * __file__( const char *filename ) {
|
||||||
|
char const *p = strrchr( filename, '/' );
|
||||||
|
if ( p )
|
||||||
|
return p+1;
|
||||||
|
else
|
||||||
|
return filename;
|
||||||
|
} // __file__
|
||||||
|
|
||||||
|
|
||||||
|
//These macros abstract the logging and append the file and line number to errors.
|
||||||
|
#ifndef SYSLOG_DISABLE
|
||||||
|
//#ifndef PGM_P
|
||||||
|
#if 1
|
||||||
|
//EMERG means system is unstable thus will force a reboot!
|
||||||
|
#define EMERG(fmt, ...) SysLog( LOG_EMERG, "EMERG: %s %4d: " fmt, __FILENAME__, __LINE__, ## __VA_ARGS__ )
|
||||||
|
#define ALERT(fmt, ...) SysLog( LOG_ALERT, "ALERT: %s %4d: " fmt, __FILENAME__, __LINE__, ## __VA_ARGS__ )
|
||||||
|
#define CRITICAL(fmt, ...) SysLog( LOG_CRIT, "CRITICAL: %s %4d: " fmt, __FILENAME__, __LINE__, ## __VA_ARGS__ )
|
||||||
|
#define ERROR(fmt, ...) SysLog( LOG_ERROR, "ERROR: %s %4d: " fmt, __FILENAME__, __LINE__, ## __VA_ARGS__ )
|
||||||
|
#define WARNING(fmt, ...) SysLog( LOG_WARNING, "WARNING: %s %4d: " fmt, __FILENAME__, __LINE__, ## __VA_ARGS__ )
|
||||||
|
#define NOTICE(fmt, ...) SysLog( LOG_NOTICE, "NOTICE: %s %4d: " fmt, __FILENAME__, __LINE__, ## __VA_ARGS__ )
|
||||||
|
#define INFO(fmt, ...) SysLog( LOG_INFO, "INFO: %s %4d: " fmt, __FILENAME__, __LINE__, ## __VA_ARGS__ )
|
||||||
|
#define LOG(fmt, ...) SysLog( LOG_DEBUG, "%s %4d: " fmt, __FILENAME__ , __LINE__, ## __VA_ARGS__ )
|
||||||
|
//
|
||||||
|
//#define EMERG(...) SysLog( LOG_EMERG, "EMERG: %15s %4d: " PROVIDE_SECOND_ARGUMENT2(BASE_FILE_NAME, __LINE__,__VA_ARGS__ ) )
|
||||||
|
//#define ALERT(...) SysLog( LOG_ALERT, "ALERT: %15s %4d: " PROVIDE_SECOND_ARGUMENT2(BASE_FILE_NAME, __LINE__,__VA_ARGS__ ) )
|
||||||
|
//#define CRITICAL(...) SysLog( LOG_CRIT, "CRITICAL: %15s %4d: " PROVIDE_SECOND_ARGUMENT2(BASE_FILE_NAME, __LINE__,__VA_ARGS__ ) )
|
||||||
|
//#define ERROR(...) SysLog( LOG_ERROR, "ERROR: %15s %4d: " PROVIDE_SECOND_ARGUMENT2(BASE_FILE_NAME, __LINE__,__VA_ARGS__ ) )
|
||||||
|
//#define WARNING(...) SysLog( LOG_WARNING, "WARNING: %15s %4d: " PROVIDE_SECOND_ARGUMENT2(BASE_FILE_NAME, __LINE__,__VA_ARGS__ ) )
|
||||||
|
//#define NOTICE(...) SysLog( LOG_NOTICE, "NOTICE: %15s %4d: " PROVIDE_SECOND_ARGUMENT2(BASE_FILE_NAME, __LINE__,__VA_ARGS__ ) )
|
||||||
|
//#define INFO(...) SysLog( LOG_INFO, "INFO: %15s %4d: " PROVIDE_SECOND_ARGUMENT2(BASE_FILE_NAME, __LINE__,__VA_ARGS__ ) )
|
||||||
|
//#define LOG(...) SysLog( LOG_DEBUG, "%s %4d: " PROVIDE_SECOND_ARGUMENT2(BASE_FILE_NAME, __LINE__,__VA_ARGS__ ) )
|
||||||
|
#else
|
||||||
|
//EMERG means system is unstable thus will force a reboot!
|
||||||
|
#define EMERG(fmt, ...) SysLog( LOG_EMERG, PSTR("EMERG: %15s %4d: " fmt), __file__(__FILE__), __LINE__, ## __VA_ARGS__ )
|
||||||
|
#define ALERT(fmt, ...) SysLog( LOG_ALERT, PSTR("ALERT: %15s %4d: " fmt), __file__(__FILE__), __LINE__, ## __VA_ARGS__ )
|
||||||
|
#define CRITICAL(fmt, ...) SysLog( LOG_CRIT, PSTR("CRITICAL: %15s %4d: " fmt), __file__(__FILE__), __LINE__, ## __VA_ARGS__ )
|
||||||
|
#define ERROR(fmt, ...) SysLog( LOG_ERROR, PSTR("ERROR: %15s %4d: " fmt), __file__(__FILE__), __LINE__, ## __VA_ARGS__ )
|
||||||
|
#define WARNING(fmt, ...) SysLog( LOG_WARNING, PSTR("WARNING: %15s %4d: " fmt), __file__(__FILE__), __LINE__, ## __VA_ARGS__ )
|
||||||
|
#define NOTICE(fmt, ...) SysLog( LOG_NOTICE, PSTR("NOTICE: %15s %4d: " fmt), __file__(__FILE__), __LINE__, ## __VA_ARGS__ )
|
||||||
|
#define INFO(fmt, ...) SysLog( LOG_INFO, PSTR("INFO: %15s %4d: " fmt), __file__(__FILE__), __LINE__, ## __VA_ARGS__ )
|
||||||
|
#define LOG(fmt, ...) SysLog( LOG_DEBUG, PSTR("%15s %4d: " fmt), __file__(__FILE__), __LINE__, ## __VA_ARGS__ )
|
||||||
|
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
#define EMERG(fmt, ...)
|
||||||
|
#define ALERT(fmt, ...)
|
||||||
|
#define CRITICAL(fmt, ...)
|
||||||
|
#define ERROR(fmt, ...)
|
||||||
|
#define WARNING(fmt, ...)
|
||||||
|
#define NOTICE(fmt, ...)
|
||||||
|
#define INFO(fmt, ...)
|
||||||
|
#define LOG(fmt, ...)
|
||||||
|
|
||||||
|
#endif //SYSLOG_DIABLE
|
||||||
|
|
||||||
|
//Note that if you are running debug code with JTAG the assert will stop
|
||||||
|
// However you might want to run release code with syslog enabled for testing
|
||||||
|
// where you want error logging, but asserts are not enabled.
|
||||||
|
// Thus this macro does error logging and an assert.
|
||||||
|
//This macro assumed to take a constant string as argument
|
||||||
|
|
||||||
|
|
||||||
|
//this can be enabled to log asserts to the history file, if you have code space to do it.
|
||||||
|
#ifdef ASSERT_HISTORY
|
||||||
|
#define ASSERT(x) {if(!(x)){ERROR(#x); HISTORY_ASSERT();} assert(x);}
|
||||||
|
#define ASSERT_ERROR(x) {HISTORY_ASSERT(); ERROR(x); ASSERT_FAIL(x);}
|
||||||
|
#else
|
||||||
|
#define ASSERT(x) {if(!(x)){ERROR(#x);} assert(x);}
|
||||||
|
#define ASSERT_ERROR(x) {ERROR(x); ASSERT_FAIL(x);}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
void SysLogInit(Stream *ptrSerialObj, eLogLevel LevelToWrite);
|
||||||
|
int SysLogDisable(void);
|
||||||
|
int SysLogEnable(void);
|
||||||
|
int SysLogIsEnabled(void);
|
||||||
|
|
||||||
|
void SysLogDebug(bool x);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif // __cplusplus
|
||||||
|
|
||||||
|
#endif /* SYSLOG_H_ */
|
45
firmware_smartstepper_trikarus/stepper_nano_zero/utils.cpp
Normal file
@ -0,0 +1,45 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
* Author: tstern
|
||||||
|
*
|
||||||
|
Copyright (C) 2018 MisfitTech, All rights reserved.
|
||||||
|
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
#include "utils.h"
|
||||||
|
#include "syslog.h"
|
||||||
|
|
||||||
|
double CubicInterpolate(
|
||||||
|
double y0,double y1,
|
||||||
|
double y2,double y3,
|
||||||
|
double mu)
|
||||||
|
{
|
||||||
|
double a0,a1,a2,a3,mu2;
|
||||||
|
|
||||||
|
mu2 = mu*mu;
|
||||||
|
a0 = y3 - y2 - y0 + y1;
|
||||||
|
a1 = y0 - y1 - a0;
|
||||||
|
a2 = y2 - y0;
|
||||||
|
a3 = y1;
|
||||||
|
|
||||||
|
return(a0*mu*mu2+a1*mu2+a2*mu+a3);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
39
firmware_smartstepper_trikarus/stepper_nano_zero/utils.h
Normal file
@ -0,0 +1,39 @@
|
|||||||
|
/**********************************************************************
|
||||||
|
* Author: tstern
|
||||||
|
*
|
||||||
|
Copyright (C) 2018 MisfitTech, All rights reserved.
|
||||||
|
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
Written by Trampas Stern for MisfitTech.
|
||||||
|
|
||||||
|
Misfit Tech invests time and resources providing this open source code,
|
||||||
|
please support MisfitTech and open-source hardware by purchasing
|
||||||
|
products from MisfitTech, www.misifittech.net!
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
/* this file contains generic utilities and functions */
|
||||||
|
|
||||||
|
#ifndef UTILS_H_
|
||||||
|
#define UTILS_H_
|
||||||
|
|
||||||
|
|
||||||
|
double CubicInterpolate(
|
||||||
|
double y0,double y1,
|
||||||
|
double y2,double y3,
|
||||||
|
double mu);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* UTILS_H_ */
|
14085
grafana/collectd_InfluxDB Metrics.json
Normal file
BIN
grafana/grafana-hangprinter.jpg
Normal file
After Width: | Height: | Size: 3.2 MiB |
259
inkscape_drawings/alignment-60-degrees.svg
Normal file
@ -0,0 +1,259 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
sodipodi:docname="60degrees.svg"
|
||||||
|
inkscape:version="1.0 (4035a4fb49, 2020-05-01)"
|
||||||
|
id="svg866"
|
||||||
|
version="1.1"
|
||||||
|
viewBox="0 0 100.00001 86.011261"
|
||||||
|
height="86.011261mm"
|
||||||
|
width="100.00001mm">
|
||||||
|
<defs
|
||||||
|
id="defs860">
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-62"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-17"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-7-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-4" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-1-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-7-6" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-4-5"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064"
|
||||||
|
effect="spiro" />
|
||||||
|
</defs>
|
||||||
|
<sodipodi:namedview
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
inkscape:window-y="-8"
|
||||||
|
inkscape:window-x="1912"
|
||||||
|
inkscape:window-height="976"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
showborder="false"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-top="0"
|
||||||
|
showgrid="false"
|
||||||
|
inkscape:document-rotation="0"
|
||||||
|
inkscape:current-layer="g1692"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:cy="251.28519"
|
||||||
|
inkscape:cx="185.38959"
|
||||||
|
inkscape:zoom="1.28"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
borderopacity="1.0"
|
||||||
|
bordercolor="#666666"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
id="base" />
|
||||||
|
<metadata
|
||||||
|
id="metadata863">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
transform="translate(2589.2871,3027.3873)"
|
||||||
|
id="layer1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
inkscape:label="Layer 1">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.0381366,0,0,0.0381366,-1282.8902,-1414.8552)"
|
||||||
|
id="g1692">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.03028581,0,0,0.03028581,-31994.336,-39983.419)"
|
||||||
|
id="g2022">
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-97"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-1634713.7,-447528.16)"><flowRegion
|
||||||
|
id="flowRegion8812-7-0"><rect
|
||||||
|
id="rect8814-2-8"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1">60°</flowPara></flowRoot>
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="ccccccc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path4828-5-6-3-8"
|
||||||
|
d="m -74060.283,-13480.223 36936.476,-61926.638 h 13263.71 L 11307.692,-13480.223 4675.8414,-1986.9563 H -67428.412 Z"
|
||||||
|
style="display:inline;fill:none;fill-opacity:1;stroke:#000000;stroke-width:1048.86;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
transform="matrix(-0.63952475,-183.20961,183.20961,-0.63952475,-49619.929,-5311.4643)"
|
||||||
|
inkscape:randomized="0"
|
||||||
|
inkscape:rounded="0"
|
||||||
|
inkscape:flatsided="true"
|
||||||
|
sodipodi:arg2="1.0509414"
|
||||||
|
sodipodi:arg1="0.52734265"
|
||||||
|
sodipodi:r2="64.395599"
|
||||||
|
sodipodi:r1="74.357628"
|
||||||
|
sodipodi:cy="100.0744"
|
||||||
|
sodipodi:cx="145.14285"
|
||||||
|
sodipodi:sides="6"
|
||||||
|
id="path4828-5"
|
||||||
|
style="display:inline;fill:none;fill-opacity:1;stroke:#a0af9a;stroke-width:5.72489;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
sodipodi:type="star"
|
||||||
|
d="M 209.3988,137.49404 144.86447,174.43151 80.608517,137.01187 80.886902,62.65476 145.42124,25.717295 209.67719,63.136937 Z" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15371-9"
|
||||||
|
d="m -37758.409,-35404.732 -35328.793,23615.531"
|
||||||
|
style="display:inline;fill:none;stroke:#00ad00;stroke-width:524.431;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15371-6-9"
|
||||||
|
d="M -31729.036,-24994.592 -67914.087,-2361.6243"
|
||||||
|
style="display:inline;fill:none;stroke:#00ad00;stroke-width:524.431;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15371-6-1-5"
|
||||||
|
d="M 5456.3344,-3136.0263 -31024.729,-24928.651"
|
||||||
|
style="display:inline;fill:none;stroke:#4e6ab4;stroke-width:524.431;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15371-6-1-7-8"
|
||||||
|
d="M 10891.397,-12619.884 -25043.689,-35286.417"
|
||||||
|
style="display:inline;fill:none;stroke:#4e6ab4;stroke-width:524.431;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path8766-1-9-8"
|
||||||
|
d="m -24553.919,-75406.861 -775.09,39398.893"
|
||||||
|
style="display:inline;fill:none;fill-opacity:1;stroke:#a900a6;stroke-width:524.431;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path8766-1-9-6-8"
|
||||||
|
d="m -35708.408,-75406.861 -1486.194,39454.954"
|
||||||
|
style="display:inline;fill:none;fill-opacity:1;stroke:#a900a6;stroke-width:524.431;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="ccc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path16495-5"
|
||||||
|
d="m -38126.98,-36033.469 6630.518,4267.751 6866.697,-4271.894"
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path16497-6"
|
||||||
|
d="m -31496.462,-31765.718 121.691,7418.992"
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path6909-5-8"
|
||||||
|
d="m -31374.511,-24191.094 3439.861,-5962.139 3439.85,-5962.241 -6883.382,2.124 -6883.382,2.124 33.703,58.354 3409.819,5901.769 z m -0.264,-155.629 -3376.103,-5843.317 -3376.103,-5843.429 6748.606,-2.071 6748.607,-2.072 -3372.503,5845.498 z"
|
||||||
|
style="color:#000000;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:medium;line-height:normal;font-family:sans-serif;font-variant-ligatures:normal;font-variant-position:normal;font-variant-caps:normal;font-variant-numeric:normal;font-variant-alternates:normal;font-feature-settings:normal;text-indent:0;text-align:start;text-decoration:none;text-decoration-line:none;text-decoration-style:solid;text-decoration-color:#000000;letter-spacing:normal;word-spacing:normal;text-transform:none;writing-mode:lr-tb;direction:ltr;text-orientation:mixed;dominant-baseline:auto;baseline-shift:baseline;text-anchor:start;white-space:normal;shape-padding:0;clip-rule:nonzero;display:inline;overflow:visible;visibility:visible;isolation:auto;mix-blend-mode:normal;color-interpolation:sRGB;color-interpolation-filters:linearRGB;solid-color:#000000;solid-opacity:1;vector-effect:none;fill:none;fill-opacity:1;fill-rule:nonzero;stroke:#facf00;stroke-width:300.677;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill;color-rendering:auto;image-rendering:auto;shape-rendering:auto;text-rendering:auto;enable-background:accumulate" />
|
||||||
|
<circle
|
||||||
|
r="622.96948"
|
||||||
|
cy="-31828.615"
|
||||||
|
cx="-31501.23"
|
||||||
|
id="path7360-7-8-0-8-3-5"
|
||||||
|
style="display:inline;fill:#000900;fill-opacity:1;stroke:none;stroke-width:124.372;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="csc"
|
||||||
|
inkscape:original-d="m -12845.121,-4717.2923 c 1612.102,-5214.392 -8030.73,-11095.8677 -3922.613,-14689.2327 3780.164,-3306.514 -6194.621,-6390.045 -9335.279,-9281.551"
|
||||||
|
inkscape:path-effect="#path-effect7064"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path7062"
|
||||||
|
d="m -12845.121,-4717.2923 c 113.628,-5135.0526 -1264.136,-10294.4427 -3922.613,-14689.2327 -2293.93,-3792.148 -5529.954,-7009.548 -9335.279,-9281.551"
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:262.215;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start);marker-end:url(#ArrowDIN-end)" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 12 KiB |
315
inkscape_drawings/alignment-misalignment.svg
Normal file
@ -0,0 +1,315 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
sodipodi:docname="angle-misalignment.svg"
|
||||||
|
inkscape:version="1.0 (4035a4fb49, 2020-05-01)"
|
||||||
|
id="svg866"
|
||||||
|
version="1.1"
|
||||||
|
viewBox="0 0 100 86.011261"
|
||||||
|
height="86.011261mm"
|
||||||
|
width="100mm">
|
||||||
|
<defs
|
||||||
|
id="defs860">
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-62"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-17"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-7-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-4" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-1-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-7-6" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-4-5"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-71"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-379" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-24" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-1"
|
||||||
|
effect="spiro" />
|
||||||
|
</defs>
|
||||||
|
<sodipodi:namedview
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
inkscape:window-y="-8"
|
||||||
|
inkscape:window-x="1912"
|
||||||
|
inkscape:window-height="976"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
showborder="false"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-top="0"
|
||||||
|
showgrid="false"
|
||||||
|
inkscape:document-rotation="0"
|
||||||
|
inkscape:current-layer="g1692"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:cy="199.20219"
|
||||||
|
inkscape:cx="163.16912"
|
||||||
|
inkscape:zoom="1.8101934"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
borderopacity="1.0"
|
||||||
|
bordercolor="#666666"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
id="base" />
|
||||||
|
<metadata
|
||||||
|
id="metadata863">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
transform="translate(4217.4877,4375.2393)"
|
||||||
|
id="layer1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
inkscape:label="Layer 1">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.0381366,0,0,0.0381366,-1282.8902,-1414.8552)"
|
||||||
|
id="g1692">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.03028581,0,0,0.03028581,-74619.154,-75274.84)"
|
||||||
|
id="g2181">
|
||||||
|
<circle
|
||||||
|
r="178.38574"
|
||||||
|
cy="-36740.863"
|
||||||
|
cx="-26360.814"
|
||||||
|
id="path7360-7-8-0-8-3-5-1"
|
||||||
|
style="display:inline;fill:#000900;fill-opacity:1;stroke:none;stroke-width:35.6138;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="ccccccc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path4828-5-6-3-8-3"
|
||||||
|
d="m -76341.626,-15174.744 36936.46,-61926.638 H -26141.45 L 9026.3417,-15174.744 2394.5247,-3681.4778 H -69709.729 Z"
|
||||||
|
style="display:inline;fill:none;fill-opacity:1;stroke:#000000;stroke-width:1048.86;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15371-9-2"
|
||||||
|
d="m -40112.544,-37053.26 -35256.001,23569.537"
|
||||||
|
style="display:inline;fill:none;stroke:#00ad00;stroke-width:131.107;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15371-6-9-5"
|
||||||
|
d="M -34098.505,-26639.29 -70195.43,-4056.1458"
|
||||||
|
style="display:inline;fill:none;stroke:#00ad00;stroke-width:131.107;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15371-6-1-5-0"
|
||||||
|
d="M 3175.0047,-4830.5478 -33240.878,-26592.511"
|
||||||
|
style="display:inline;fill:none;stroke:#4e6ab4;stroke-width:131.107;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15371-6-1-7-8-5"
|
||||||
|
d="M 8324.7587,-15035.956 -27030.36,-37361.022"
|
||||||
|
style="display:inline;fill:none;stroke:#4e6ab4;stroke-width:131.107;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path8766-1-9-8-6"
|
||||||
|
d="m -26835.272,-77101.382 -769.654,39295.911"
|
||||||
|
style="display:inline;fill:none;fill-opacity:1;stroke:#a900a6;stroke-width:131.107;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path8766-1-9-6-8-1"
|
||||||
|
d="m -37989.727,-77101.382 -1480.756,39300.481"
|
||||||
|
style="display:inline;fill:none;fill-opacity:1;stroke:#a900a6;stroke-width:131.107;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path6909-5-8-2"
|
||||||
|
d="m -33655.833,-25885.615 3439.845,-5962.139 3439.846,-5962.241 -6883.388,2.125 -6883.388,2.123 33.721,58.354 3409.795,5901.769 z"
|
||||||
|
style="color:#000000;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:medium;line-height:normal;font-family:sans-serif;font-variant-ligatures:normal;font-variant-position:normal;font-variant-caps:normal;font-variant-numeric:normal;font-variant-alternates:normal;font-feature-settings:normal;text-indent:0;text-align:start;text-decoration:none;text-decoration-line:none;text-decoration-style:solid;text-decoration-color:#000000;letter-spacing:normal;word-spacing:normal;text-transform:none;writing-mode:lr-tb;direction:ltr;text-orientation:mixed;dominant-baseline:auto;baseline-shift:baseline;text-anchor:start;white-space:normal;shape-padding:0;clip-rule:nonzero;display:inline;overflow:visible;visibility:visible;isolation:auto;mix-blend-mode:normal;color-interpolation:sRGB;color-interpolation-filters:linearRGB;solid-color:#000000;solid-opacity:1;vector-effect:none;fill:none;fill-opacity:1;fill-rule:nonzero;stroke:#facf00;stroke-width:131.107;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill;color-rendering:auto;image-rendering:auto;shape-rendering:auto;text-rendering:auto;enable-background:accumulate"
|
||||||
|
sodipodi:nodetypes="cccccccc" />
|
||||||
|
<path
|
||||||
|
transform="matrix(21.333198,-181.96446,181.96446,21.333198,-54965.828,-9177.2938)"
|
||||||
|
inkscape:randomized="0"
|
||||||
|
inkscape:rounded="0"
|
||||||
|
inkscape:flatsided="true"
|
||||||
|
sodipodi:arg2="1.0509414"
|
||||||
|
sodipodi:arg1="0.52734265"
|
||||||
|
sodipodi:r2="64.395599"
|
||||||
|
sodipodi:r1="74.357628"
|
||||||
|
sodipodi:cy="100.0744"
|
||||||
|
sodipodi:cx="145.14285"
|
||||||
|
sodipodi:sides="6"
|
||||||
|
id="path4828-5-5-7"
|
||||||
|
style="display:inline;fill:none;fill-opacity:1;stroke:#a0af9a;stroke-width:5.72489;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
sodipodi:type="star"
|
||||||
|
d="M 209.3988,137.49404 144.86447,174.43151 80.608517,137.01187 80.886902,62.65476 145.42124,25.717295 209.67719,63.136937 Z" />
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path6909-5-8-2-0"
|
||||||
|
d="m -34588.271,-25732.955 4129.97,-5506.658 4129.944,-5506.763 -6833.987,-823.259 -6833.986,-823.257 26.483,61.975 2677.534,6268.047 z"
|
||||||
|
style="color:#000000;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:medium;line-height:normal;font-family:sans-serif;font-variant-ligatures:normal;font-variant-position:normal;font-variant-caps:normal;font-variant-numeric:normal;font-variant-alternates:normal;font-feature-settings:normal;text-indent:0;text-align:start;text-decoration:none;text-decoration-line:none;text-decoration-style:solid;text-decoration-color:#000000;letter-spacing:normal;word-spacing:normal;text-transform:none;writing-mode:lr-tb;direction:ltr;text-orientation:mixed;dominant-baseline:auto;baseline-shift:baseline;text-anchor:start;white-space:normal;shape-padding:0;clip-rule:nonzero;display:inline;overflow:visible;visibility:visible;isolation:auto;mix-blend-mode:normal;color-interpolation:sRGB;color-interpolation-filters:linearRGB;solid-color:#000000;solid-opacity:1;vector-effect:none;fill:none;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:52.4431;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:209.772, 209.772;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill;color-rendering:auto;image-rendering:auto;shape-rendering:auto;text-rendering:auto;enable-background:accumulate"
|
||||||
|
sodipodi:nodetypes="cccccccc" />
|
||||||
|
<circle
|
||||||
|
r="178.38574"
|
||||||
|
cy="-25913.945"
|
||||||
|
cx="-33628.633"
|
||||||
|
id="path7360-7-8-0-8-3-5-1-1"
|
||||||
|
style="display:inline;fill:#000900;fill-opacity:1;stroke:none;stroke-width:35.6138;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<circle
|
||||||
|
r="178.38574"
|
||||||
|
cy="-25745.299"
|
||||||
|
cx="-34594.422"
|
||||||
|
id="path7360-7-8-0-8-3-5-1-1-0"
|
||||||
|
style="display:inline;fill:#000900;fill-opacity:1;stroke:none;stroke-width:35.6138;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<circle
|
||||||
|
r="178.38574"
|
||||||
|
cy="-37779.727"
|
||||||
|
cx="-40527.301"
|
||||||
|
id="path7360-7-8-0-8-3-5-1-1-3"
|
||||||
|
style="display:inline;fill:#000900;fill-opacity:1;stroke:none;stroke-width:35.6138;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<circle
|
||||||
|
r="178.38574"
|
||||||
|
cy="-38423.602"
|
||||||
|
cx="-40006.098"
|
||||||
|
id="path7360-7-8-0-8-3-5-1-1-5"
|
||||||
|
style="display:inline;fill:#000900;fill-opacity:1;stroke:none;stroke-width:35.6138;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<circle
|
||||||
|
r="178.38574"
|
||||||
|
cy="-37841.055"
|
||||||
|
cx="-26898.559"
|
||||||
|
id="path7360-7-8-0-8-3-5-1-1-59"
|
||||||
|
style="display:inline;fill:#000900;fill-opacity:1;stroke:none;stroke-width:35.6138;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-97-4"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(45.001051,0,0,45.001051,-629830.14,-198314.55)"><flowRegion
|
||||||
|
id="flowRegion8812-7-0-0"><rect
|
||||||
|
id="rect8814-2-8-3"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-5">angle misalignment</flowPara></flowRoot>
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="csc"
|
||||||
|
inkscape:original-d="m -33461.243,-44292.846 c -1200.264,862.342 1292.931,2976.574 -355.826,3256.271 -1517.125,257.369 63.587,1975.577 504.004,2877.212"
|
||||||
|
inkscape:path-effect="#path-effect7064-1"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path7062-1"
|
||||||
|
d="m -33461.243,-44292.846 c -279.734,1059.648 -400.107,2161.216 -355.826,3256.271 39.457,975.753 209.441,1946.146 504.004,2877.212"
|
||||||
|
style="display:inline;fill:none;stroke:#000000;stroke-width:69.1242;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-71);marker-end:url(#ArrowDIN-end-5)" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 15 KiB |
564
inkscape_drawings/anchor-points.svg
Normal file
@ -0,0 +1,564 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
sodipodi:docname="anchor-points.svg"
|
||||||
|
inkscape:version="1.0 (4035a4fb49, 2020-05-01)"
|
||||||
|
id="svg866"
|
||||||
|
version="1.1"
|
||||||
|
viewBox="0 0 100.00001 110.79693"
|
||||||
|
height="110.79693mm"
|
||||||
|
width="100.00001mm">
|
||||||
|
<defs
|
||||||
|
id="defs860">
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-62"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-17"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-7-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-4" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-1-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-7-6" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-4-5"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-71"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-379" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-24" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-1"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-9-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-5-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="Arrow1Lstart-3-4"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lstart">
|
||||||
|
<path
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
style="fill:#ff0000;fill-opacity:1;fill-rule:evenodd;stroke:#ff0000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path15451-1-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lstart"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker21821"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path21819"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lstart"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker21821-0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path21819-2"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1-5-9"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3-2-5" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-9-3-5-4"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-5-1-9-4"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1-2-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3-8-3" />
|
||||||
|
</marker>
|
||||||
|
</defs>
|
||||||
|
<sodipodi:namedview
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
inkscape:window-y="-8"
|
||||||
|
inkscape:window-x="1912"
|
||||||
|
inkscape:window-height="976"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
showborder="false"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-top="0"
|
||||||
|
showgrid="false"
|
||||||
|
inkscape:document-rotation="0"
|
||||||
|
inkscape:current-layer="g1692"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:cy="260.2169"
|
||||||
|
inkscape:cx="288.77973"
|
||||||
|
inkscape:zoom="1.28"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
borderopacity="1.0"
|
||||||
|
bordercolor="#666666"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
id="base" />
|
||||||
|
<metadata
|
||||||
|
id="metadata863">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
transform="translate(20062.994,17868.852)"
|
||||||
|
id="layer1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
inkscape:label="Layer 1">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.0381366,0,0,0.0381366,-1282.8902,-1414.8552)"
|
||||||
|
id="g1692">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.01772198,0,0,0.01772198,-483716,-423802.85)"
|
||||||
|
id="g4657">
|
||||||
|
<g
|
||||||
|
id="g949-5"
|
||||||
|
transform="matrix(1060.2576,0,0,1060.2576,-536322.58,-411753.9)">
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837-2"
|
||||||
|
d="M 96.005952,-11.050597 C 95.155257,36.359034 110.42288,118.94994 127.37798,125.96577"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837-9-5"
|
||||||
|
d="M 96.005952,-11.050597 C 103.14693,30.268273 120.17333,93.540616 138.33929,96.105651"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837-4-9"
|
||||||
|
d="m 138.33929,96.105651 c -7.65427,3.375404 -12.41938,15.851739 -10.96131,29.860119"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837-4-7-8"
|
||||||
|
d="m 127.37798,125.96577 c -23.71826,-7.7749 -38.877716,-8.9057 -71.437501,-5.29167"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837-4-7-7-5"
|
||||||
|
d="M 96.005952,-11.050597 C 90.997519,46.564386 82.07467,83.798164 55.940479,120.6741"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837-4-7-7-1-2"
|
||||||
|
d="M 138.33929,96.105651 C 110.46329,109.49742 95.114848,114.79222 55.940479,120.6741"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:3, 3;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
</g>
|
||||||
|
<circle
|
||||||
|
transform="rotate(59.999989)"
|
||||||
|
r="1281.9651"
|
||||||
|
cy="271954.03"
|
||||||
|
cx="-484823.56"
|
||||||
|
id="path7360-7-5-4-3-5"
|
||||||
|
style="fill:#00ad00;fill-opacity:1;stroke:none;stroke-width:255.937;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<circle
|
||||||
|
transform="rotate(59.999989)"
|
||||||
|
r="1281.9651"
|
||||||
|
cy="181671.16"
|
||||||
|
cx="-462585.06"
|
||||||
|
id="path7360-7-8-9-0-2-3-4"
|
||||||
|
style="fill:#a900a6;fill-opacity:1;stroke:none;stroke-width:255.937;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<circle
|
||||||
|
transform="rotate(59.999989)"
|
||||||
|
r="1281.9651"
|
||||||
|
cy="208634.2"
|
||||||
|
cx="-441062.53"
|
||||||
|
id="path7360-7-8-1-5-4-8-2"
|
||||||
|
style="fill:#4e6ab4;fill-opacity:1;stroke:none;stroke-width:255.937;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(138.07627,0.07545793,-0.07545793,138.07627,-2244741.3,-754962.03)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#4e6ab4;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-6-7-7-50-1-8-7"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
style="fill:#4e6ab4;fill-opacity:1"
|
||||||
|
id="flowRegion8812-7-9-1-5-9-0-9"><rect
|
||||||
|
style="fill:#4e6ab4;fill-opacity:1"
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-7-8-2-8-1-2" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-5-8-9">A anchor point</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(138.07628,0.05186067,-0.05186067,138.07628,-2324707.2,-759769.14)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#00ad00;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-6-7-7-50-4-6-2-2"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
style="fill:#00ad00;fill-opacity:1"
|
||||||
|
id="flowRegion8812-7-9-1-5-7-2-9-0"><rect
|
||||||
|
style="fill:#00ad00;fill-opacity:1"
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-7-8-2-0-2-7-1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-9-2-7-7">C anchor point</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(138.07528,0.52780506,-0.52780506,138.07528,-2215219.7,-800076.85)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#a900a6;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-6-7-7-50-4-7-0-2-3"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
style="fill:#a900a6;fill-opacity:1"
|
||||||
|
id="flowRegion8812-7-9-1-5-7-9-4-4-1"><rect
|
||||||
|
style="fill:#a900a6;fill-opacity:1"
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-7-8-2-0-0-3-0-4" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-9-3-9-7-6">B anchor point</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(146.1374,0,0,146.1374,-2323194.6,-816226.8)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-95-8-3-7"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-5-33-4-5"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-0-3-6-9"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8816-1-4-9-5">X</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(146.1374,0,0,146.1374,-2413025.5,-834767.73)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-95-3-7-8-2"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-5-3-7-4-3"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-0-7-4-3-2"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8816-1-7-2-1-9">Y</flowPara></flowRoot>
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15449-3-0-1"
|
||||||
|
d="m -434374.08,-344296.6 v 55706.57"
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:536.322;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-1-5-9)" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15449-4-3-4-7"
|
||||||
|
d="m -467127.19,-318344.36 32753.11,29754.33"
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:536.322;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-9-3-5-4)" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15371-4-8-8-3"
|
||||||
|
d="m -434374.08,-288590.03 -42637.18,4781.76"
|
||||||
|
style="fill:none;stroke:#00ad00;stroke-width:593.663;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15371-6-1-0-6-7-2"
|
||||||
|
d="m -401269.08,-278197.7 -33105,-10392.33"
|
||||||
|
style="fill:none;stroke:#4963a8;stroke-width:593.663;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path8766-1-9-6-3-8-0-5"
|
||||||
|
d="m -389647.28,-309857.09 -44726.8,21267.06"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#a900a6;stroke-width:593.663;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path8650-5-6"
|
||||||
|
d="m -434531.52,-423470.39 157.44,134880.36"
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:636.156;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<circle
|
||||||
|
transform="rotate(59.999989)"
|
||||||
|
r="1281.9651"
|
||||||
|
cy="164746.89"
|
||||||
|
cx="-583957.5"
|
||||||
|
id="path7360-7-8-9-0-2-9-7"
|
||||||
|
style="fill:#bf4b00;fill-opacity:1;stroke:none;stroke-width:255.937;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(138.07528,0.52780506,-0.52780506,138.07528,-2273557.4,-919635.61)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#bf4b00;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-6-7-7-50-4-7-0-7-9"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
style="fill:#bf4b00;fill-opacity:1"
|
||||||
|
id="flowRegion8812-7-9-1-5-7-9-4-2-7"><rect
|
||||||
|
style="fill:#bf4b00;fill-opacity:1"
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-7-8-2-0-0-3-7-2" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-9-3-9-1-7">D anchor point</flowPara></flowRoot>
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15449-3-2-4"
|
||||||
|
d="m -387830.97,-304541.6 -46543.11,15951.57"
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:536.322;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-1-2-3)" />
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(146.1374,0,0,146.1374,-2376267.6,-862360.2)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-95-8-6-2"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-5-33-8-1"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-0-3-3-0"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8816-1-4-6-6">Z</flowPara></flowRoot>
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:52.4431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -434215.26,-332090.51 31487.02,-6489.69"
|
||||||
|
id="path8808-3-3"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-4"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-2020411.2,-765581.33)"><flowRegion
|
||||||
|
id="flowRegion8812-7-3"><rect
|
||||||
|
id="rect8814-2-31"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-4">origin line lengths</flowPara></flowRoot>
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:52.4431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -408705.36,-301429.56 5977.12,-37150.64"
|
||||||
|
id="path8808-3-3-8"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:52.4431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -420802.06,-284470.72 18073.82,-54109.48"
|
||||||
|
id="path8808-3-3-8-7"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:52.4431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -455604.19,-286125.43 52875.95,-52454.77"
|
||||||
|
id="path8808-3-3-8-7-2"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<text
|
||||||
|
xml:space="preserve"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:277.51px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:6.93777"
|
||||||
|
x="-486785.53"
|
||||||
|
y="-275551.28"
|
||||||
|
id="text6410"><tspan
|
||||||
|
sodipodi:role="line"
|
||||||
|
id="tspan6408"
|
||||||
|
x="-486785.53"
|
||||||
|
y="-275551.28"
|
||||||
|
style="stroke-width:6.93777">a</tspan></text>
|
||||||
|
<text
|
||||||
|
xml:space="preserve"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:277.51px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:6.93777"
|
||||||
|
x="-486662.88"
|
||||||
|
y="-275551.28"
|
||||||
|
id="text6414"><tspan
|
||||||
|
sodipodi:role="line"
|
||||||
|
id="tspan6412"
|
||||||
|
x="-486662.88"
|
||||||
|
y="-275551.28"
|
||||||
|
style="stroke-width:6.93777">a</tspan></text>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 23 KiB |
3555
inkscape_drawings/anchor-positioning.svg
Normal file
After Width: | Height: | Size: 151 KiB |
1063
inkscape_drawings/bearing-shearoff.svg
Normal file
After Width: | Height: | Size: 50 KiB |
870
inkscape_drawings/build-volume-collisions.svg
Normal file
After Width: | Height: | Size: 58 KiB |
939
inkscape_drawings/build-volume.svg
Normal file
@ -0,0 +1,939 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
sodipodi:docname="build-volume.svg"
|
||||||
|
inkscape:version="1.0 (4035a4fb49, 2020-05-01)"
|
||||||
|
id="svg866"
|
||||||
|
version="1.1"
|
||||||
|
viewBox="0 0 99.999977 70.099099"
|
||||||
|
height="70.099098mm"
|
||||||
|
width="99.999977mm">
|
||||||
|
<defs
|
||||||
|
id="defs860">
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-62"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-17"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-7-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-4" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-1-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-7-6" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-4-5"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-71"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-379" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-24" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-1"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-9-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-5-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="Arrow1Lstart-3-4"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lstart">
|
||||||
|
<path
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
style="fill:#ff0000;fill-opacity:1;fill-rule:evenodd;stroke:#ff0000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path15451-1-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lstart"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker21821"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path21819"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lstart"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker21821-0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path21819-2"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
</defs>
|
||||||
|
<sodipodi:namedview
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
inkscape:window-y="-8"
|
||||||
|
inkscape:window-x="1912"
|
||||||
|
inkscape:window-height="976"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
showborder="false"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-top="0"
|
||||||
|
showgrid="false"
|
||||||
|
inkscape:document-rotation="0"
|
||||||
|
inkscape:current-layer="g1692"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:cy="132.98499"
|
||||||
|
inkscape:cx="180.41069"
|
||||||
|
inkscape:zoom="2.56"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
borderopacity="1.0"
|
||||||
|
bordercolor="#666666"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
id="base" />
|
||||||
|
<metadata
|
||||||
|
id="metadata863">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
transform="translate(17291.454,14789.283)"
|
||||||
|
id="layer1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
inkscape:label="Layer 1">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.0381366,0,0,0.0381366,-1282.8902,-1414.8552)"
|
||||||
|
id="g1692">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.0151136,0,0,0.0151136,-413424.81,-345397.65)"
|
||||||
|
id="g4337">
|
||||||
|
<rect
|
||||||
|
style="display:inline;fill:#ccc021;fill-opacity:1;stroke:#000000;stroke-width:867.472;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect9439-9-8-9-9-9-8-1-3-4-6-4-5-1"
|
||||||
|
width="9965.9053"
|
||||||
|
height="10906.118"
|
||||||
|
x="-261786.41"
|
||||||
|
y="-249729.06" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:215.841;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -260704.95,-244553.09 c 0,429.56 -641.35,777.81 -1432.54,777.81 -791.13,0 161.84,-331.6 161.84,-761.16 0,-429.59 -952.99,-794.47 -161.84,-794.47 791.16,0 1432.54,348.25 1432.54,777.82 z"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-8-0-5-7-5-3-6-6-8-5"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="scscs" />
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
style="display:inline;fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:93.8335;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -256831.58,-244983.55 a 458.88703,458.88701 0 0 0 -458.88,458.85 458.88703,458.88701 0 0 0 458.88,458.9 458.88703,458.88701 0 0 0 458.9,-458.9 458.88703,458.88701 0 0 0 -458.9,-458.85 z m 0,366.19 a 92.668216,92.668216 0 0 1 92.66,92.66 92.668216,92.668216 0 0 1 -92.66,92.69 92.668216,92.668216 0 0 1 -92.67,-92.69 92.668216,92.668216 0 0 1 92.67,-92.66 z"
|
||||||
|
id="path9422-5-4-6-3-7-3-0-9-0-5-8-4-4-5-0-2-8-6-5-0" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -253148.91,-246642.74 -3288.09,5821.78"
|
||||||
|
id="path9777-9-54-9-9-3-0-9-2-5-7-5"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -262018.81,-244523.44 5184.52,-12.58"
|
||||||
|
id="path9777-9-5-8-9-7-2-3-3-7-4-72-5"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:#000900;fill-opacity:1;stroke:none;stroke-width:226.09;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-0-8-7-0-7-1-95-9-3-2-2-0-5-6-1-7"
|
||||||
|
cx="-247405.28"
|
||||||
|
cy="-246079"
|
||||||
|
r="1132.4626" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:128.223;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:1025.79, 1025.79;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -256834.29,-244536.02 9468.1,-1522.85"
|
||||||
|
id="path9777-9-5-2-9-7-0-3-9-1-8-0-9-8"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<g
|
||||||
|
style="display:inline"
|
||||||
|
id="g3087-9-6-6-8-0-2-9-8-6-7"
|
||||||
|
transform="matrix(26.22153,0,0,26.22153,-495220.71,-502957.44)">
|
||||||
|
<ellipse
|
||||||
|
ry="32.502953"
|
||||||
|
rx="32.502956"
|
||||||
|
cy="9754.8525"
|
||||||
|
cx="9206.0586"
|
||||||
|
id="path9422-5-4-6-3-7-3-4-6-8-76-9-7-3-8-4-4-3-4-2"
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:6.6462;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<circle
|
||||||
|
r="6.5636878"
|
||||||
|
cy="9754.8525"
|
||||||
|
cx="9206.0586"
|
||||||
|
id="path7360-7-8-0-8-7-3-4-67-5-5-7-3-1-7-7-2-0-8-9"
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:1.3104;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
style="display:inline"
|
||||||
|
id="g3111-5-3-6-0-6-5-6-3-6-1-6"
|
||||||
|
transform="matrix(-26.22153,0,0,26.22153,-102836.14,-461989.32)">
|
||||||
|
<g
|
||||||
|
id="g3120-4-8-6-7-8-4-9-5-3-3-1">
|
||||||
|
<ellipse
|
||||||
|
ry="32.502953"
|
||||||
|
rx="32.502956"
|
||||||
|
cy="8418.7197"
|
||||||
|
cx="5887.2949"
|
||||||
|
id="path9422-5-4-6-3-7-3-4-6-4-7-2-8-9-6-4-0-8-7-9"
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:6.6462;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
transform="translate(-1.2291667e-4,-8.9583334e-5)" />
|
||||||
|
<g
|
||||||
|
id="g3114-4-8-9-0-4-3-6-4-3-0-2">
|
||||||
|
<circle
|
||||||
|
r="6.5636873"
|
||||||
|
cy="8418.7197"
|
||||||
|
cx="5887.2949"
|
||||||
|
id="path7360-7-8-0-8-7-3-4-67-1-3-1-2-4-3-9-0-7-6-6"
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:1.3104;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:215.841;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -260704.93,-240408.71 c 0,429.56 -641.35,777.79 -1432.53,777.79 -791.13,0 161.84,-331.57 161.84,-761.13 0,-429.59 -953,-794.46 -161.84,-794.46 791.16,0 1432.53,348.25 1432.53,777.8 z"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-8-0-5-7-5-3-0-1-4-1-2-9-7"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="scscs" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -262039.19,-240371.97 4873.05,3.02"
|
||||||
|
id="path9777-9-5-8-9-7-2-3-3-8-5-9-2-8"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<rect
|
||||||
|
style="fill:#ccc021;fill-opacity:1;stroke:#000000;stroke-width:894.044;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect9439-9-8-9-0-6-7-4"
|
||||||
|
width="8900.3145"
|
||||||
|
height="4064.0801"
|
||||||
|
x="-337342.16"
|
||||||
|
y="-339166.03" />
|
||||||
|
<rect
|
||||||
|
style="fill:#309ad1;fill-opacity:1;stroke:#000000;stroke-width:786.647;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect9439-3-9-1-7-4"
|
||||||
|
width="73642.016"
|
||||||
|
height="1485.5604"
|
||||||
|
x="-377336.44"
|
||||||
|
y="-244697.66" />
|
||||||
|
<rect
|
||||||
|
style="fill:#b2c0ae;fill-opacity:1;stroke:#000000;stroke-width:999.38;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect9439-3-90-9"
|
||||||
|
width="69584.297"
|
||||||
|
height="3567.8171"
|
||||||
|
x="-375307.53"
|
||||||
|
y="-343144.22" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#433ab2;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -306105.49,-332348.47 53017.21,84689.41"
|
||||||
|
id="path9777-64-9-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<ellipse
|
||||||
|
style="fill:#dcbb2e;fill-opacity:1;stroke:#332eb4;stroke-width:1311.07;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path9422-5-4-6-5-72-7"
|
||||||
|
cx="-312649.72"
|
||||||
|
cy="-329948.03"
|
||||||
|
rx="6411.7617"
|
||||||
|
ry="6411.7612" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:226.09;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-0-8-7-6-87-1"
|
||||||
|
cx="-312649.72"
|
||||||
|
cy="-329948.03"
|
||||||
|
r="1132.4626" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:226.09;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-0-8-7-0-7-8-9-7"
|
||||||
|
cx="-325804.94"
|
||||||
|
cy="-338288.88"
|
||||||
|
r="1132.4626" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:573.195;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -312669.94,-329977.02 -6340.21,-9425.91"
|
||||||
|
id="path9783-3-8-7"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:573.195;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -312636.07,-329977.02 6340.21,-9425.91"
|
||||||
|
id="path9783-6-78-78-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<rect
|
||||||
|
style="fill:#dcbb2e;fill-opacity:1;stroke:#433ab2;stroke-width:1311.07;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect10115-11-76-8"
|
||||||
|
width="1903.2184"
|
||||||
|
height="12512.872"
|
||||||
|
x="-369346.41"
|
||||||
|
y="-337153.62" />
|
||||||
|
<rect
|
||||||
|
style="fill:#dcbb2e;fill-opacity:1;stroke:#433ab2;stroke-width:1311.07;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect10115-7-0-60-1"
|
||||||
|
width="1903.2184"
|
||||||
|
height="12512.872"
|
||||||
|
x="-366763.16"
|
||||||
|
y="-337153.62" />
|
||||||
|
<rect
|
||||||
|
style="fill:#dcbb2e;fill-opacity:1;stroke:#433ab2;stroke-width:1311.07;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect10115-7-8-4-31-0"
|
||||||
|
width="1903.2184"
|
||||||
|
height="12512.872"
|
||||||
|
x="-364193.81"
|
||||||
|
y="-337153.62" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -363227.94,-337418.19 c 34.51,-1605.02 18160.01,-1350.44 27960.78,-1521.51"
|
||||||
|
id="path9777-8-7-1-9-3-8"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -363227.94,-337418.19 -20.61,6917.6"
|
||||||
|
id="path9777-8-7-1-6-8-2-9"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#433ab2;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -365862.1,-337439.88 -20.61,6917.61"
|
||||||
|
id="path9777-8-7-1-6-0-7-3-6"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#433ab2;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -368544.17,-337413.81 -20.61,6917.6"
|
||||||
|
id="path9777-8-7-1-6-0-9-8-1-8"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<ellipse
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:292.923;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path9422-5-4-6-3-7-3-4-32-87-60-0"
|
||||||
|
cx="-335204.84"
|
||||||
|
cy="-337462.66"
|
||||||
|
rx="1432.5289"
|
||||||
|
ry="1432.5288" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:57.7545;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-0-8-7-3-4-6-25-4-8"
|
||||||
|
cx="-335204.84"
|
||||||
|
cy="-337462.66"
|
||||||
|
r="289.28665" />
|
||||||
|
<path
|
||||||
|
style="fill:#423c2f;fill-opacity:1;stroke:none;stroke-width:530.567;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -357876.33,-339143.99 h 4303.32 v 21755.11 l 1257.48,1312.71 h -6818.28 l 1257.48,-1312.71 z"
|
||||||
|
id="rect10590-4-8-3"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="ccccccc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#0042b3;stroke-width:209.772;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:2517.27, 2517.27;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -340508.6,-350697.95 -13.64,121619.28"
|
||||||
|
id="path10700-4-1-2"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -333710.86,-334549.27 -17266.46,80710.45"
|
||||||
|
id="path9777-8-7-1-6-6-4-6-9-0-0"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:149.799;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -333703.99,-335519.33 c -298.14,0 -539.82,445.13 -539.82,994.21 0,549.08 230.12,-112.33 528.26,-112.33 298.11,0 551.36,661.41 551.36,112.33 0,-549.08 -241.69,-994.21 -539.8,-994.21 z"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-4-4-4-4-5"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="scscs" />
|
||||||
|
<ellipse
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:292.923;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path9422-5-4-6-3-7-3-4-32-5-4-7-4"
|
||||||
|
cx="-330481.22"
|
||||||
|
cy="-337378.34"
|
||||||
|
rx="1432.5289"
|
||||||
|
ry="1432.5288" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:57.7545;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-0-8-7-3-4-6-2-3-0-4"
|
||||||
|
cx="-330481.22"
|
||||||
|
cy="-337378.34"
|
||||||
|
r="289.28665" />
|
||||||
|
<path
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:149.799;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -331983.07,-335510.99 c -298.14,0 -539.82,445.11 -539.82,994.18 0,549.08 230.12,-112.3 528.25,-112.3 298.09,0 551.37,661.38 551.37,112.3 0,-549.07 -241.69,-994.18 -539.8,-994.18 z"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-4-4-9-2-7-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="scscs" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -333703.99,-335519.33 15.31,-2032.83"
|
||||||
|
id="path9777-8-7-1-6-6-4-61-54-6-9"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -331983.07,-335510.99 15.34,-2032.83"
|
||||||
|
id="path9777-8-7-1-6-6-4-61-5-05-8-7"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -330409.23,-338880.83 4332.4,30.68"
|
||||||
|
id="path9777-8-7-1-6-6-4-61-5-0-1-1-0"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:573.195;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -370433.09,-330866.19 6.61,-8199.45"
|
||||||
|
id="path9783-2-0-0-8"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:573.195;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -369249.42,-329151.96 6.6,-8199.47"
|
||||||
|
id="path9783-2-9-6-8-0"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="m -331428.38,-327145.12 367.1,-141.23"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:131.107px"
|
||||||
|
inkscape:label="helpline"
|
||||||
|
id="path13660-7-0-2" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#0042b3;stroke-width:209.772;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:2517.27, 2517.27;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -313462.12,-246767.35 -13.61,17688.55"
|
||||||
|
id="path10700-5-85-2-9"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#0042b3;stroke-width:209.772;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:2517.27, 2517.27;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -367723.93,-246767.35 -13.61,17688.55"
|
||||||
|
id="path10700-5-8-4-8-1"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<rect
|
||||||
|
y="-318748.94"
|
||||||
|
x="-360309.69"
|
||||||
|
height="2649.3413"
|
||||||
|
width="1826.9905"
|
||||||
|
id="rect5917-42-5-5"
|
||||||
|
style="fill:#689bec;fill-opacity:1;stroke:none;stroke-width:256.649;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:3079.77, 3079.77;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<rect
|
||||||
|
y="-316076.12"
|
||||||
|
x="-359140.28"
|
||||||
|
height="2649.3413"
|
||||||
|
width="6824.7246"
|
||||||
|
id="rect5917-7-3-5-5"
|
||||||
|
style="opacity:0.501003;fill:#423c2f;fill-opacity:1;stroke:none;stroke-width:496.035;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:5952.44, 5952.44;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -331931.15,-334564.69 -17266.46,80710.48"
|
||||||
|
id="path9777-8-7-1-6-6-4-6-2-0-3-7"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<rect
|
||||||
|
style="fill:#ccc021;fill-opacity:1;stroke:#000000;stroke-width:719.441;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect9439-9-8-0-3-4-8"
|
||||||
|
width="2143.1802"
|
||||||
|
height="6388.5771"
|
||||||
|
x="-377876.22"
|
||||||
|
y="-253456.27" />
|
||||||
|
<rect
|
||||||
|
style="fill:#ccc021;fill-opacity:1;stroke:#000000;stroke-width:786.647;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect9439-9-5-39-4"
|
||||||
|
width="29999.105"
|
||||||
|
height="2718.1392"
|
||||||
|
x="-377842.62"
|
||||||
|
y="-253422.67" />
|
||||||
|
<path
|
||||||
|
style="fill:#b2c032;fill-opacity:1;stroke:#000000;stroke-width:786.647;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -369095.87,-250303.51 h 2731.73 v 3536.19 l -1328.12,1452.62 -1403.61,-1452.62 z"
|
||||||
|
id="rect9439-9-1-4-4-99"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cccccc" />
|
||||||
|
<ellipse
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:174.274;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path9422-5-4-6-3-7-3-4-7-2-8"
|
||||||
|
cx="-350079.75"
|
||||||
|
cy="-251675.75"
|
||||||
|
rx="852.27722"
|
||||||
|
ry="852.27716" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:34.3607;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-0-8-7-3-4-9-8-3"
|
||||||
|
cx="-350079.75"
|
||||||
|
cy="-251675.75"
|
||||||
|
r="172.10992" />
|
||||||
|
<path
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:149.799;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -350928.39,-252921.04 c -298.14,0 -539.82,-445.11 -539.82,-994.22 0,-549.07 230.12,112.34 528.26,112.34 298.08,0 551.36,-661.41 551.36,-112.34 0,549.11 -241.69,994.22 -539.8,994.22 z"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-4-0-3-9"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="scscs" />
|
||||||
|
<path
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:149.799;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -349165.09,-252923.01 c -298.14,0 -539.83,-445.11 -539.83,-994.21 0,-549.09 230.12,112.33 528.26,112.33 298.12,0 551.36,-661.42 551.36,-112.33 0,549.1 -241.71,994.21 -539.79,994.21 z"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-4-2-5-5-65"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="scscs" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -349197.61,-253854.18 18.83,2332.61"
|
||||||
|
id="path9777-8-7-1-6-6-4-4-6-2-0"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -350977.32,-253838.8 9.34,2316.36"
|
||||||
|
id="path9777-8-7-1-6-6-4-4-7-9-20-5"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#a50000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:1573.29, 1573.29;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -410323.85,-334935.51 h 72981.68"
|
||||||
|
id="path8030-3-8-4-9-0"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:1573.29, 1573.29;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -347698.52,-313426.78 h 13548.97"
|
||||||
|
id="path8030-6-4-1"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#a50000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:1573.29, 1573.29;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -412319.91,-313426.78 h 64888.53"
|
||||||
|
id="path8030-3-3-3-3"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:1573.29, 1573.29;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -351433.78,-307039.16 h 20294.39"
|
||||||
|
id="path8030-6-5-3-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#a50000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:1573.29, 1573.29;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -412389.71,-307039.16 h 60718.62"
|
||||||
|
id="path8030-3-3-7-4-7"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#433ab2;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -343216.5,-247853.13 81177.34,7481.16"
|
||||||
|
id="path9777-9-7-1-9-2-94-0-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#433ab2;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -343196.13,-252004.6 81174.65,7387.65"
|
||||||
|
id="path9777-9-7-1-9-02-7-6"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<rect
|
||||||
|
style="fill:#ccc021;fill-opacity:1;stroke:#000000;stroke-width:719.441;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect9439-9-8-0-3-4-5-2"
|
||||||
|
width="2143.1802"
|
||||||
|
height="6388.5771"
|
||||||
|
x="-359140.28"
|
||||||
|
y="-313426.78" />
|
||||||
|
<rect
|
||||||
|
style="fill:#ccc021;fill-opacity:1;stroke:#000000;stroke-width:786.647;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect9439-9-5-39-2-3"
|
||||||
|
width="29999.105"
|
||||||
|
height="2718.1392"
|
||||||
|
x="-359106.69"
|
||||||
|
y="-313393.19" />
|
||||||
|
<path
|
||||||
|
style="fill:#b2c032;fill-opacity:1;stroke:#000000;stroke-width:786.647;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -350359.93,-310274.03 h 2731.73 v 3536.18 l -1328.12,1452.62 -1403.61,-1452.62 z"
|
||||||
|
id="rect9439-9-1-4-4-9-0"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cccccc" />
|
||||||
|
<ellipse
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:174.274;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path9422-5-4-6-3-7-3-4-7-2-5-6"
|
||||||
|
cx="-331343.81"
|
||||||
|
cy="-311646.28"
|
||||||
|
rx="852.27722"
|
||||||
|
ry="852.27716" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:34.3607;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-0-8-7-3-4-9-8-8-6"
|
||||||
|
cx="-331343.81"
|
||||||
|
cy="-311646.28"
|
||||||
|
r="172.10992" />
|
||||||
|
<path
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:149.799;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -332192.45,-312891.57 c -298.13,0 -539.82,-445.11 -539.82,-994.21 0,-549.08 230.12,112.33 528.26,112.33 298.09,0 551.36,-661.41 551.36,-112.33 0,549.1 -241.69,994.21 -539.8,994.21 z"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-4-0-3-8-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="scscs" />
|
||||||
|
<path
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:149.799;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -330429.15,-312893.54 c -298.14,0 -539.83,-445.11 -539.83,-994.21 0,-549.08 230.12,112.33 528.26,112.33 298.12,0 551.36,-661.41 551.36,-112.33 0,549.1 -241.71,994.21 -539.79,994.21 z"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-4-2-5-5-6-3"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="scscs" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -330461.67,-313824.71 18.83,2332.61"
|
||||||
|
id="path9777-8-7-1-6-6-4-4-6-2-7-7"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -332241.38,-313809.32 9.34,2316.36"
|
||||||
|
id="path9777-8-7-1-6-6-4-4-7-9-20-1-6"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -331931.15,-334564.69 1469.48,20739.98"
|
||||||
|
id="path9777-8-7-1-6-6-4-6-2-0-3-8-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -333710.86,-334549.27 1469.48,20739.95"
|
||||||
|
id="path9777-8-7-1-6-6-4-6-2-0-3-1-3"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#433ab2;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -324587.16,-311953.36 62568.38,67429.92"
|
||||||
|
id="path9777-9-7-1-9-02-7-2-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path9847-2"
|
||||||
|
d="m -324607.53,-307801.89 62568.37,67429.92"
|
||||||
|
style="fill:none;stroke:#433ab2;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<rect
|
||||||
|
style="display:inline;fill:#ccc021;fill-opacity:1;stroke:#000000;stroke-width:764.384;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect9439-9-8-24-0-8-9-1-3-5-5-6-5"
|
||||||
|
width="4085.2632"
|
||||||
|
height="6729.3799"
|
||||||
|
x="-329052.06"
|
||||||
|
y="-313393.19" />
|
||||||
|
<g
|
||||||
|
id="g10954"
|
||||||
|
transform="matrix(26.22153,0,0,26.22153,-946769.24,-905280.59)">
|
||||||
|
<rect
|
||||||
|
y="24858.812"
|
||||||
|
x="22847.949"
|
||||||
|
height="256.63565"
|
||||||
|
width="155.79805"
|
||||||
|
id="rect9439-9-8-24-0-8-9-1-3-5-5-6-4"
|
||||||
|
style="display:inline;fill:#ccc021;fill-opacity:1;stroke:#000000;stroke-width:29.151;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path9777-9-7-1-1-4-9-2-6-0-1-7-6-4"
|
||||||
|
d="m 22891.275,24943.924 2.037,104.346"
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<g
|
||||||
|
transform="translate(17036.615,16643.097)"
|
||||||
|
id="g3124-7-1-2-0-4-9-7-3-9-8"
|
||||||
|
style="display:inline">
|
||||||
|
<ellipse
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:6.6462;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path9422-5-4-6-3-7-3-4-2-1-1-6-6-4-5-3-1-3-4"
|
||||||
|
cx="5888.1216"
|
||||||
|
cy="8303.792"
|
||||||
|
rx="32.502956"
|
||||||
|
ry="32.502953" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:1.3104;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-0-8-7-3-4-0-4-5-6-5-7-3-07-6-1-49"
|
||||||
|
cx="5888.1216"
|
||||||
|
cy="8303.792"
|
||||||
|
r="6.5636873" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
transform="translate(17037.443,16619.352)"
|
||||||
|
id="g3111-5-3-6-0-6-5-5-2-6-5"
|
||||||
|
style="display:inline">
|
||||||
|
<g
|
||||||
|
id="g3120-4-8-6-7-8-4-1-4-7-4">
|
||||||
|
<ellipse
|
||||||
|
transform="translate(-1.2291667e-4,-8.9583334e-5)"
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:6.6462;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path9422-5-4-6-3-7-3-4-6-4-7-2-8-9-6-5-9-1-1"
|
||||||
|
cx="5887.2949"
|
||||||
|
cy="8418.7197"
|
||||||
|
rx="32.502956"
|
||||||
|
ry="32.502953" />
|
||||||
|
<g
|
||||||
|
id="g3114-4-8-9-0-4-3-7-5-39-7">
|
||||||
|
<circle
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:1.3104;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-0-8-7-3-4-67-1-3-1-2-4-3-4-9-2-2"
|
||||||
|
cx="5887.2949"
|
||||||
|
cy="8418.7197"
|
||||||
|
r="6.5636873" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="scscs"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-8-0-5-7-5-3-0-11-0-6-3"
|
||||||
|
d="m 22968.053,24914.523 c 0,16.382 24.459,29.662 54.631,29.662 30.172,0 -6.172,-12.645 -6.172,-29.027 0,-16.383 36.344,-30.298 6.172,-30.298 -30.172,0 -54.631,13.281 -54.631,29.663 z"
|
||||||
|
style="display:inline;fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:8.23143;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="scscs"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-8-0-5-7-5-3-0-1-5-1-6-7"
|
||||||
|
d="m 22968.053,25072.575 c 0,16.382 24.459,29.662 54.631,29.662 30.172,0 -6.172,-12.645 -6.172,-29.027 0,-16.383 36.344,-30.298 6.172,-30.298 -30.172,0 -54.631,13.281 -54.631,29.663 z"
|
||||||
|
style="display:inline;fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:8.23143;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path9777-9-7-1-1-4-9-2-6-0-4-3-7-04-8"
|
||||||
|
d="m 23018.226,24913.725 -95.009,-0.507"
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path9777-9-7-1-1-4-9-2-6-0-4-2-0-2-3-3"
|
||||||
|
d="m 23017.449,25072.048 -95.009,-0.507"
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:5;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
</g>
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cccc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837-1-1-5-2-1-6"
|
||||||
|
d="m -419768.69,-244618.1 h 157748.44 c -17272.86,20.19 -74347.8,-73807.76 -78874.26,-90152.37 -4006.07,16518.04 -61601.35,90172.56 -78874.18,90152.37"
|
||||||
|
style="display:inline;fill:#b2c0ae;fill-opacity:0.485714;stroke:#000000;stroke-width:589.777;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -327916.01,-311161.5 53.42,2736.11"
|
||||||
|
id="path9777-9-7-1-1-4-9-2-6-0-1-7-6-3"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<rect
|
||||||
|
style="display:inline;opacity:0.501003;fill:#00c0ae;fill-opacity:0.485714;stroke:#000000;stroke-width:510.006;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect8082-0-6-2"
|
||||||
|
width="54103.5"
|
||||||
|
height="61320.324"
|
||||||
|
x="-367615.16"
|
||||||
|
y="-306400.69" />
|
||||||
|
<g
|
||||||
|
style="display:inline"
|
||||||
|
id="g3124-7-1-2-0-4-9-7-3-9-2"
|
||||||
|
transform="matrix(26.22153,0,0,26.22153,-481434.15,-528821.86)">
|
||||||
|
<ellipse
|
||||||
|
ry="32.502953"
|
||||||
|
rx="32.502956"
|
||||||
|
cy="8303.792"
|
||||||
|
cx="5888.1216"
|
||||||
|
id="path9422-5-4-6-3-7-3-4-2-1-1-6-6-4-5-3-1-3-5"
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:6.6462;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<circle
|
||||||
|
r="6.5636873"
|
||||||
|
cy="8303.792"
|
||||||
|
cx="5888.1216"
|
||||||
|
id="path7360-7-8-0-8-7-3-4-0-4-5-6-5-7-3-07-6-1-4"
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:1.3104;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
style="display:inline"
|
||||||
|
id="g3111-5-3-6-0-6-5-5-2-6-1"
|
||||||
|
transform="matrix(26.22153,0,0,26.22153,-481412.44,-529444.49)">
|
||||||
|
<g
|
||||||
|
id="g3120-4-8-6-7-8-4-1-4-7-2">
|
||||||
|
<ellipse
|
||||||
|
ry="32.502953"
|
||||||
|
rx="32.502956"
|
||||||
|
cy="8418.7197"
|
||||||
|
cx="5887.2949"
|
||||||
|
id="path9422-5-4-6-3-7-3-4-6-4-7-2-8-9-6-5-9-1-0"
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:6.6462;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
transform="translate(-1.2291667e-4,-8.9583334e-5)" />
|
||||||
|
<g
|
||||||
|
id="g3114-4-8-9-0-4-3-7-5-39-3">
|
||||||
|
<circle
|
||||||
|
r="6.5636873"
|
||||||
|
cy="8418.7197"
|
||||||
|
cx="5887.2949"
|
||||||
|
id="path7360-7-8-0-8-7-3-4-67-1-3-1-2-4-3-4-9-2-4"
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:1.3104;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:215.841;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -325902.77,-311932.44 c 0,429.56 641.35,777.79 1432.51,777.79 791.16,0 -161.84,-331.58 -161.84,-761.14 0,-429.58 953,-794.46 161.84,-794.46 -791.16,0 -1432.51,348.25 -1432.51,777.81 z"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-8-0-5-7-5-3-0-11-0-6-0"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="scscs" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:215.841;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -325902.77,-307788.07 c 0,429.56 641.35,777.78 1432.51,777.78 791.16,0 -161.84,-331.57 -161.84,-761.13 0,-429.59 953,-794.46 161.84,-794.46 -791.16,0 -1432.51,348.25 -1432.51,777.81 z"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-8-0-5-7-5-3-0-1-5-1-6-1"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="scscs" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -324587.16,-311953.36 -2491.28,-13.3"
|
||||||
|
id="path9777-9-7-1-1-4-9-2-6-0-4-3-7-04-9"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -324607.53,-307801.89 -2491.28,-13.3"
|
||||||
|
id="path9777-9-7-1-1-4-9-2-6-0-4-2-0-2-3-6"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 49 KiB |
436
inkscape_drawings/coordinate-system-minimized.svg
Normal file
@ -0,0 +1,436 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
sodipodi:docname="coords-cheat.svg"
|
||||||
|
inkscape:version="1.0 (4035a4fb49, 2020-05-01)"
|
||||||
|
id="svg8"
|
||||||
|
version="1.1"
|
||||||
|
viewBox="0 0 99.999992 102.73526"
|
||||||
|
height="102.73526mm"
|
||||||
|
width="99.999992mm">
|
||||||
|
<defs
|
||||||
|
id="defs2">
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect1225"
|
||||||
|
is_visible="true" />
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="ArrowDIN-start"
|
||||||
|
style="overflow:visible"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
orient="auto"
|
||||||
|
id="ArrowDIN-start-7-6">
|
||||||
|
<path
|
||||||
|
id="path13335-9-7"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="ArrowDIN-end"
|
||||||
|
style="overflow:visible"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
orient="auto"
|
||||||
|
id="ArrowDIN-end-1-8">
|
||||||
|
<path
|
||||||
|
id="path13338-7-5"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect7064-4-4"
|
||||||
|
is_visible="true" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect1225-5"
|
||||||
|
is_visible="true" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect1225-9"
|
||||||
|
is_visible="true" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect1225-9-8"
|
||||||
|
is_visible="true" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-9"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-7"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-7"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-9-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-7-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-7-2"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-5-7"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-76"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-53"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-8-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-76-7"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-8-0"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-53-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-8-0"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-76-0"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-8-4"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-53-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-8-5-2"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-76-7-6"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-8-0-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-53-9-8"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lend"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker1150"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path1148"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(-0.8,0,0,-0.8,-10,0)" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lend"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="Arrow1Lend"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path829"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(-0.8,0,0,-0.8,-10,0)" />
|
||||||
|
</marker>
|
||||||
|
</defs>
|
||||||
|
<sodipodi:namedview
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
inkscape:window-y="-8"
|
||||||
|
inkscape:window-x="-8"
|
||||||
|
inkscape:window-height="976"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
showborder="false"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-top="0"
|
||||||
|
showgrid="false"
|
||||||
|
inkscape:document-rotation="0"
|
||||||
|
inkscape:current-layer="layer1"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:cy="740.76634"
|
||||||
|
inkscape:cx="146.00828"
|
||||||
|
inkscape:zoom="0.24748737"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
borderopacity="1.0"
|
||||||
|
bordercolor="#666666"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
id="base" />
|
||||||
|
<metadata
|
||||||
|
id="metadata5">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
transform="translate(1115.743,1177.1015)"
|
||||||
|
id="layer1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
inkscape:label="Layer 1">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.0384431,0,0,0.0384431,-1070.7646,-1141.9065)"
|
||||||
|
id="layer1-7"
|
||||||
|
inkscape:label="Ebene 1">
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
id="path833"
|
||||||
|
d="m 0,1756.8901 v -1170"
|
||||||
|
style="fill:none;stroke:#4964aa;stroke-width:10;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#07ac07;stroke-width:10;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="M -1013.2497,1.8901 0,586.8901"
|
||||||
|
id="path833-1"
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
id="path833-1-8"
|
||||||
|
d="M 1013.2498,1.8901 0,586.8901"
|
||||||
|
style="fill:none;stroke:#a900a6;stroke-width:10;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:10;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-end:url(#Arrow1Lend)"
|
||||||
|
d="M 0,586.8901 V -583.10989"
|
||||||
|
id="path833-2"
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
id="path833-2-7"
|
||||||
|
d="m 0,586.89 1170,10e-5"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:10;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-end:url(#marker1150)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<text
|
||||||
|
id="text905"
|
||||||
|
y="764.29883"
|
||||||
|
x="1176.6508"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:390.279px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:9.75701"
|
||||||
|
xml:space="preserve"><tspan
|
||||||
|
style="stroke-width:9.75701"
|
||||||
|
y="764.29883"
|
||||||
|
x="1176.6508"
|
||||||
|
id="tspan903"
|
||||||
|
sodipodi:role="line">X</tspan></text>
|
||||||
|
<text
|
||||||
|
xml:space="preserve"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:390.279px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:9.75701"
|
||||||
|
x="-121.42204"
|
||||||
|
y="-631.75507"
|
||||||
|
id="text905-5"><tspan
|
||||||
|
sodipodi:role="line"
|
||||||
|
id="tspan903-7"
|
||||||
|
x="-121.42204"
|
||||||
|
y="-631.75507"
|
||||||
|
style="stroke-width:9.75701">Y</tspan></text>
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#646464;stroke-width:10;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="M 1013.2498,1.89 H -3e-5"
|
||||||
|
id="path833-1-8-2"
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
id="path833-1-8-2-8"
|
||||||
|
d="m 1013.2501,1.89 v 585"
|
||||||
|
style="fill:none;stroke:#646464;stroke-width:10;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
id="path833-1-8-2-4"
|
||||||
|
d="M -3e-5,1.89 H -1013.2498"
|
||||||
|
style="fill:none;stroke:#646464;stroke-width:10;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#646464;stroke-width:10;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="M -1013.2498,1.89 V 586.88999"
|
||||||
|
id="path833-1-8-2-8-0"
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
id="path833-2-7-7"
|
||||||
|
d="M -1170.0001,586.89 0,586.8901"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:10;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:80, 80;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 14 KiB |
459
inkscape_drawings/coordinate-system.svg
Normal file
@ -0,0 +1,459 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
sodipodi:docname="coordinate-system.svg"
|
||||||
|
inkscape:version="1.0 (4035a4fb49, 2020-05-01)"
|
||||||
|
id="svg866"
|
||||||
|
version="1.1"
|
||||||
|
viewBox="0 0 99.999489 81.734001"
|
||||||
|
height="81.734001mm"
|
||||||
|
width="99.999489mm">
|
||||||
|
<defs
|
||||||
|
id="defs860">
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-62"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-17"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-7-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-4" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-1-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-7-6" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-4-5"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-71"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-379" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-24" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-1"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-9-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-5-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="Arrow1Lstart-3-4"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lstart">
|
||||||
|
<path
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
style="fill:#ff0000;fill-opacity:1;fill-rule:evenodd;stroke:#ff0000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path15451-1-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
</defs>
|
||||||
|
<sodipodi:namedview
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
inkscape:window-y="-8"
|
||||||
|
inkscape:window-x="1912"
|
||||||
|
inkscape:window-height="976"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
showborder="false"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-top="0"
|
||||||
|
showgrid="false"
|
||||||
|
inkscape:document-rotation="0"
|
||||||
|
inkscape:current-layer="g1692"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:cy="166.2105"
|
||||||
|
inkscape:cx="194.40856"
|
||||||
|
inkscape:zoom="1.8101934"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
borderopacity="1.0"
|
||||||
|
bordercolor="#666666"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
id="base" />
|
||||||
|
<metadata
|
||||||
|
id="metadata863">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
transform="translate(6851.365,6500.5424)"
|
||||||
|
id="layer1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
inkscape:label="Layer 1">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.0381366,0,0,0.0381366,-1282.8902,-1414.8552)"
|
||||||
|
id="g1692">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.01874409,0,0,0.01874409,-143277.03,-130854.89)"
|
||||||
|
id="g2449">
|
||||||
|
<circle
|
||||||
|
style="fill:#00ad00;fill-opacity:1;stroke:none;stroke-width:226.09;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-5-4"
|
||||||
|
cx="-144998.06"
|
||||||
|
cy="56319.141"
|
||||||
|
r="1132.4626"
|
||||||
|
transform="rotate(60)" />
|
||||||
|
<circle
|
||||||
|
style="fill:#a900a6;fill-opacity:1;stroke:none;stroke-width:226.09;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-9-0-2"
|
||||||
|
cx="-104741.58"
|
||||||
|
cy="-11552.343"
|
||||||
|
r="1132.4626"
|
||||||
|
transform="rotate(60)" />
|
||||||
|
<circle
|
||||||
|
style="fill:#4e6ab4;fill-opacity:1;stroke:none;stroke-width:226.09;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-1-5-4"
|
||||||
|
cx="-66362.375"
|
||||||
|
cy="55833.223"
|
||||||
|
r="1132.4626"
|
||||||
|
transform="rotate(60)" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-50-1"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#4e6ab4;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97385,0.06665798,-0.06665798,121.97385,-1710325,-448706.16)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-5-9"
|
||||||
|
style="fill:#4e6ab4;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-2-8"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#4e6ab4;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-5">A anchor</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-50-4-6"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#00ad00;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97386,0.04581266,-0.04581266,121.97386,-1764599.9,-525642.41)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-5-7-2"
|
||||||
|
style="fill:#00ad00;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-2-0-2"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#00ad00;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-9-2">C anchor</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-50-4-7-0"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#a900a6;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97298,0.46625238,-0.46625238,121.97298,-1656209.6,-530614.75)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-5-7-9-4"
|
||||||
|
style="fill:#a900a6;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-2-0-0-3"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#a900a6;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-9-3-9">B anchor</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-9-3-8"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-1675636.4,-479584.87)"><flowRegion
|
||||||
|
id="flowRegion8812-7-1-2-9"><rect
|
||||||
|
id="rect8814-2-3-2-4"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-9-1-1">origin 0,0,0 ("origo")</flowPara></flowRoot>
|
||||||
|
<g
|
||||||
|
transform="matrix(26.22153,0,0,26.22153,214562.56,-133064.87)"
|
||||||
|
id="g3926">
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(4.9232402,0,0,4.9232402,-74488.709,-15026.213)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-95-8"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-5-33"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-0-3"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8816-1-4">X</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(4.9232402,0,0,4.9232402,-76597.329,-17172.418)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-95-3-7"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-5-3-7"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-0-7-4"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8816-1-7-2">Y</flowPara></flowRoot>
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15449-3"
|
||||||
|
d="M -11204.178,327.28783 V 2203.9918"
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:18.0682;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-1)"
|
||||||
|
transform="translate(-1.2291667e-4,-8.9583334e-5)" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15449-4-3"
|
||||||
|
d="M -9327.4743,2203.9918 H -11204.178"
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:18.0682;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-9-3)"
|
||||||
|
transform="translate(-1.2291667e-4,-8.9583334e-5)" />
|
||||||
|
</g>
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#00ad00;stroke-width:52.4431;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="M -87890.509,-89688.289 -118327.99,-102802.03"
|
||||||
|
id="path15371-3"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#00ad00;stroke-width:52.4431;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="M -93239.622,-80343.36 -124049.11,-92773.687"
|
||||||
|
id="path15371-6-92"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#4e6ab4;stroke-width:52.4431;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -87546.64,-29534.673 -5108.4,-49788.043"
|
||||||
|
id="path15371-6-1-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#4e6ab4;stroke-width:52.4431;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -75947.666,-29427.449 -5094.739,-49899.103"
|
||||||
|
id="path15371-6-1-7-85"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#a900a6;stroke-width:52.4431;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -39482.113,-91592.661 -41003.923,11314.576"
|
||||||
|
id="path8766-1-9-1"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#a900a6;stroke-width:52.4431;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -45258.266,-101535.93 -41095.53,11094.595"
|
||||||
|
id="path8766-1-9-6-9"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -86907.097,-91146.143 -380.736,7876.072 7132.948,3810.788"
|
||||||
|
id="path16495-1"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="ccc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -87287.807,-83270.066 -6364.201,3814.879"
|
||||||
|
id="path16497-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="color:#000000;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:medium;line-height:normal;font-family:sans-serif;font-variant-ligatures:normal;font-variant-position:normal;font-variant-caps:normal;font-variant-numeric:normal;font-variant-alternates:normal;font-feature-settings:normal;text-indent:0;text-align:start;text-decoration:none;text-decoration-line:none;text-decoration-style:solid;text-decoration-color:#000000;letter-spacing:normal;word-spacing:normal;text-transform:none;writing-mode:lr-tb;direction:ltr;text-orientation:mixed;dominant-baseline:auto;baseline-shift:baseline;text-anchor:start;white-space:normal;shape-padding:0;clip-rule:nonzero;display:inline;overflow:visible;visibility:visible;isolation:auto;mix-blend-mode:normal;color-interpolation:sRGB;color-interpolation-filters:linearRGB;solid-color:#000000;solid-opacity:1;vector-effect:none;fill:none;fill-opacity:1;fill-rule:nonzero;stroke:#facf00;stroke-width:300.677;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill;color-rendering:auto;image-rendering:auto;shape-rendering:auto;text-rendering:auto;enable-background:accumulate"
|
||||||
|
d="m -93786.656,-79377.147 6883.283,-2.071 6883.398,-2.124 -3443.542,-5960.122 -3443.527,-5960.123 -33.695,58.364 -3406.177,5903.875 z m 134.648,-78.043 3372.403,-5845.447 3372.508,-5845.506 3376.111,5843.429 3376.101,5843.428 -6748.619,2.072 z"
|
||||||
|
id="path6909-5-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:124.372;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-0-8-3-7"
|
||||||
|
cx="-115762.66"
|
||||||
|
cy="33895.559"
|
||||||
|
r="622.96948"
|
||||||
|
transform="rotate(60)" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#ff0000;stroke-width:78.6647;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#Arrow1Lstart-3-4)"
|
||||||
|
d="m -79228.164,-75272.837 21734.291,23037.79"
|
||||||
|
id="path8808-3-5-4-9"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#4e6ab4;stroke-width:0;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -81766.591,-29573.6 -4932.254,-49942.854"
|
||||||
|
id="path15371-6-1-7-2-5"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#00ad00;stroke-width:524.431;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -90563.27,-84901.803 -30774.64,-12507.148"
|
||||||
|
id="path15371-4-8"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#4963a8;stroke-width:524.431;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="M -81531.647,-29549.922 -87229.91,-79453.281"
|
||||||
|
id="path15371-6-1-0-6"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#a900a6;stroke-width:524.431;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -42259.292,-96320.603 -41297.81,10896.606"
|
||||||
|
id="path8766-1-9-6-3-8"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:52.4431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -87287.833,-83270.074 c 1214.843,-767.761 2515.914,-1386.156 3730.731,-2153.923"
|
||||||
|
id="path7282-0"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:52.4431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -87229.91,-79453.281 -57.923,-3816.793"
|
||||||
|
id="path7284-2"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:52.4431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -87287.833,-83270.063 -3275.437,-1631.74"
|
||||||
|
id="path7284-4-7"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 20 KiB |
179
inkscape_drawings/d-drive-unit.svg
Normal file
After Width: | Height: | Size: 558 KiB |
2288
inkscape_drawings/effector-angles.svg
Normal file
After Width: | Height: | Size: 104 KiB |
1230
inkscape_drawings/effector-coordinate-system.svg
Normal file
After Width: | Height: | Size: 1.6 MiB |
459
inkscape_drawings/effector-d-offset.svg
Normal file
After Width: | Height: | Size: 182 KiB |
401
inkscape_drawings/effector-line-angle.svg
Normal file
After Width: | Height: | Size: 176 KiB |
315
inkscape_drawings/effector-line-guiding.svg
Normal file
@ -0,0 +1,315 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
sodipodi:docname="effector-line-guiding.svg"
|
||||||
|
inkscape:version="1.0 (4035a4fb49, 2020-05-01)"
|
||||||
|
id="svg8"
|
||||||
|
version="1.1"
|
||||||
|
viewBox="0 0 100.00053 44.215004"
|
||||||
|
height="44.215004mm"
|
||||||
|
width="100.00053mm">
|
||||||
|
<defs
|
||||||
|
id="defs2" />
|
||||||
|
<sodipodi:namedview
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
inkscape:window-y="-8"
|
||||||
|
inkscape:window-x="1912"
|
||||||
|
inkscape:window-height="976"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
showborder="false"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-top="0"
|
||||||
|
showgrid="false"
|
||||||
|
inkscape:document-rotation="0"
|
||||||
|
inkscape:current-layer="layer1"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:cy="138.37077"
|
||||||
|
inkscape:cx="197.42218"
|
||||||
|
inkscape:zoom="1.979899"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
borderopacity="1.0"
|
||||||
|
bordercolor="#666666"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
id="base" />
|
||||||
|
<metadata
|
||||||
|
id="metadata5">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
transform="translate(1017.1069,321.35564)"
|
||||||
|
id="layer1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
inkscape:label="Layer 1">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.04416939,0,0,0.04416939,-972.18189,-307.16156)"
|
||||||
|
id="g975">
|
||||||
|
<rect
|
||||||
|
style="fill:#ccc021;fill-opacity:1;stroke:#000000;stroke-width:27.437;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect9439-9-8-0-3-3-1-9-6-4"
|
||||||
|
width="81.733612"
|
||||||
|
height="243.63861"
|
||||||
|
x="-1003.3881"
|
||||||
|
y="244.60229" />
|
||||||
|
<rect
|
||||||
|
style="fill:#ccc021;fill-opacity:1;stroke:#000000;stroke-width:30;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect9439-9-5-3-8-3-8-5"
|
||||||
|
width="1144.0638"
|
||||||
|
height="103.66059"
|
||||||
|
x="-1002.1069"
|
||||||
|
y="245.8855" />
|
||||||
|
<path
|
||||||
|
style="fill:#b2c032;fill-opacity:1;stroke:#000000;stroke-width:30;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -668.53591,364.83876 h 104.179 v 134.858 l -50.64998,55.39901 -53.52902,-55.39901 z"
|
||||||
|
id="rect9439-9-1-4-6-1-9-2-6"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cccccc" />
|
||||||
|
<rect
|
||||||
|
style="fill:#ccc021;fill-opacity:1;stroke:#000000;stroke-width:29.151;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect9439-9-8-24-0-8-9-1-3"
|
||||||
|
width="155.79805"
|
||||||
|
height="256.63565"
|
||||||
|
x="141.53377"
|
||||||
|
y="245.46167" />
|
||||||
|
<ellipse
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:6.6462;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path9422-5-4-6-3-7-3-4-7-6-5-8-6-0"
|
||||||
|
cx="56.674393"
|
||||||
|
cy="312.50269"
|
||||||
|
rx="32.502956"
|
||||||
|
ry="32.502953" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:1.3104;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-0-8-7-3-4-9-3-0-8-1-4"
|
||||||
|
cx="56.674393"
|
||||||
|
cy="312.50269"
|
||||||
|
r="6.5636883" />
|
||||||
|
<path
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:5.71283;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m 24.310144,265.01475 c -11.37,0 -20.5869998,-16.975 -20.5869998,-37.91601 0,-20.93899 8.7769998,4.28401 20.1469998,4.28401 11.368,0 21.026,-25.223 21.026,-4.28401 0,20.94101 -9.217,37.91601 -20.586,37.91601 z"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-4-0-7-8-2-6-7"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="scscs" />
|
||||||
|
<path
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:5.71283;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m 91.556144,264.93974 c -11.37,0 -20.587,-16.97497 -20.587,-37.91598 0,-20.93899 8.777,4.284 20.146,4.284 11.368996,0 21.026996,-25.22299 21.026996,-4.284 0,20.94101 -9.218,37.91598 -20.585996,37.91598 z"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-4-2-5-4-8-6-6-5"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="scscs" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:4.99999;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m 90.316144,229.42777 0.719,88.95799"
|
||||||
|
id="path9777-8-7-1-6-6-4-4-6-3-7-2-1-0"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:4.99999;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m 22.444144,230.01474 0.357,88.33803"
|
||||||
|
id="path9777-8-7-1-6-6-4-4-7-9-2-9-3-9-0"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#433ab2;stroke-width:4.99999;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m 184.86214,330.57075 2.038,104.34601"
|
||||||
|
id="path9777-9-7-1-1-4-9-2-6-0"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<g
|
||||||
|
id="g3124-7-1-2-0-4-9"
|
||||||
|
transform="translate(-5669.7971,-7970.2537)">
|
||||||
|
<ellipse
|
||||||
|
ry="32.502953"
|
||||||
|
rx="32.502956"
|
||||||
|
cy="8303.792"
|
||||||
|
cx="5888.1216"
|
||||||
|
id="path9422-5-4-6-3-7-3-4-2-1-1-6-6-4-5"
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:6.6462;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<circle
|
||||||
|
r="6.5636873"
|
||||||
|
cy="8303.792"
|
||||||
|
cx="5888.1216"
|
||||||
|
id="path7360-7-8-0-8-7-3-4-0-4-5-6-5-7-3"
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:1.3104;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
id="g3111-5-3-6-0-6-5"
|
||||||
|
transform="translate(-5668.9701,-7993.9995)">
|
||||||
|
<g
|
||||||
|
id="g3120-4-8-6-7-8-4">
|
||||||
|
<ellipse
|
||||||
|
ry="32.502953"
|
||||||
|
rx="32.502956"
|
||||||
|
cy="8418.7197"
|
||||||
|
cx="5887.2949"
|
||||||
|
id="path9422-5-4-6-3-7-3-4-6-4-7-2-8-9-6"
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:6.6462;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
transform="translate(-1.2291667e-4,-8.9583334e-5)" />
|
||||||
|
<g
|
||||||
|
id="g3114-4-8-9-0-4-3">
|
||||||
|
<circle
|
||||||
|
r="6.5636873"
|
||||||
|
cy="8418.7197"
|
||||||
|
cx="5887.2949"
|
||||||
|
id="path7360-7-8-0-8-7-3-4-67-1-3-1-2-4-3"
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:1.3104;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<rect
|
||||||
|
style="display:inline;fill:#ccc021;fill-opacity:1;stroke:#000000;stroke-width:33.0824;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect9439-9-8-9-9-9-8-1-3-4"
|
||||||
|
width="380.06577"
|
||||||
|
height="415.92224"
|
||||||
|
x="655.27985"
|
||||||
|
y="247.21362" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:8.23143;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m 696.52114,444.60175 c 0,16.38202 -24.459,29.66201 -54.631,29.66201 -30.172,0 6.172,-12.64499 6.172,-29.02701 0,-16.383 -36.344,-30.29799 -6.172,-30.29799 30.172,0 54.631,13.28099 54.631,29.66299 z"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-8-0-5-7-5-3"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="scscs" />
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
style="display:inline;fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:3.57849;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m 844.23914,428.18475 a 17.500391,17.50039 0 0 0 -17.5,17.50002 17.500391,17.50039 0 0 0 17.5,17.501 17.500391,17.50039 0 0 0 17.501,-17.501 17.500391,17.50039 0 0 0 -17.501,-17.50002 z m 0,13.96601 a 3.5340507,3.5340507 0 0 1 3.534,3.53401 3.5340507,3.5340507 0 0 1 -3.534,3.53499 3.5340507,3.5340507 0 0 1 -3.534,-3.53499 3.5340507,3.5340507 0 0 1 3.534,-3.53401 z"
|
||||||
|
id="path9422-5-4-6-3-7-3-0-9-0-5-8-4-4-5-0-2" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:4.99999;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m 984.68414,364.90975 -125.397,222.02201"
|
||||||
|
id="path9777-9-54-9-9-3-0-9"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:4.99999;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m 646.41614,445.73176 197.719,-0.48001"
|
||||||
|
id="path9777-9-5-8-9-7-2-3-3"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:4.99999;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m 311.81414,300.37177 334.602,145.35999"
|
||||||
|
id="path9777-9-7-1-9-02-1-1-4-5-9"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<circle
|
||||||
|
style="display:inline;fill:#000900;fill-opacity:1;stroke:none;stroke-width:8.62229;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-0-8-7-0-7-1-95-9-3-2-2-0"
|
||||||
|
cx="1203.7281"
|
||||||
|
cy="386.41284"
|
||||||
|
r="43.188274" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:4.89;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:39.12, 39.12;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="M 844.13514,445.25175 1205.2161,387.17677"
|
||||||
|
id="path9777-9-5-2-9-7-0-3-9-1"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<g
|
||||||
|
style="display:inline"
|
||||||
|
id="g3087-9-6-6-8-0-2"
|
||||||
|
transform="translate(-8247.11,-9410.0579)">
|
||||||
|
<ellipse
|
||||||
|
ry="32.502953"
|
||||||
|
rx="32.502956"
|
||||||
|
cy="9754.8525"
|
||||||
|
cx="9206.0586"
|
||||||
|
id="path9422-5-4-6-3-7-3-4-6-8-76-9-7-3-8-4"
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:6.6462;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<circle
|
||||||
|
r="6.5636878"
|
||||||
|
cy="9754.8525"
|
||||||
|
cx="9206.0586"
|
||||||
|
id="path7360-7-8-0-8-7-3-4-67-5-5-7-3-1-7-7"
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:1.3104;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
</g>
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:8.23143;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m 261.64114,301.16975 c 0,16.38202 24.459,29.66201 54.631,29.66201 30.172,0 -6.172,-12.64499 -6.172,-29.02701 0,-16.383 36.344,-30.29799 6.172,-30.29799 -30.172,0 -54.631,13.28099 -54.631,29.66299 z"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-8-0-5-7-5-3-0"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="scscs" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:8.23143;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m 261.64114,459.22175 c 0,16.38202 24.459,29.66202 54.631,29.66202 30.172,0 -6.172,-12.645 -6.172,-29.02702 0,-16.383 36.344,-30.29799 6.172,-30.29799 -30.172,0 -54.631,13.281 -54.631,29.66299 z"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-8-0-5-7-5-3-0-1"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="scscs" />
|
||||||
|
<g
|
||||||
|
style="display:inline"
|
||||||
|
id="g3111-5-3-6-0-6-5-6"
|
||||||
|
transform="matrix(-1,0,0,1,6717.0978,-7847.6733)">
|
||||||
|
<g
|
||||||
|
id="g3120-4-8-6-7-8-4-9">
|
||||||
|
<ellipse
|
||||||
|
ry="32.502953"
|
||||||
|
rx="32.502956"
|
||||||
|
cy="8418.7197"
|
||||||
|
cx="5887.2949"
|
||||||
|
id="path9422-5-4-6-3-7-3-4-6-4-7-2-8-9-6-4"
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:6.6462;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
transform="translate(-1.2291667e-4,-8.9583334e-5)" />
|
||||||
|
<g
|
||||||
|
id="g3114-4-8-9-0-4-3-6">
|
||||||
|
<circle
|
||||||
|
r="6.5636873"
|
||||||
|
cy="8418.7197"
|
||||||
|
cx="5887.2949"
|
||||||
|
id="path7360-7-8-0-8-7-3-4-67-1-3-1-2-4-3-9"
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:1.3104;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:8.23143;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m 696.52114,602.65375 c 0,16.38202 -24.458,29.66202 -54.63,29.66202 -30.173,0 6.171,-12.645 6.171,-29.02702 0,-16.383 -36.344,-30.29799 -6.171,-30.29799 30.172,0 54.63,13.281 54.63,29.66299 z"
|
||||||
|
id="path9422-5-4-6-3-7-0-8-4-8-0-5-7-5-3-0-1-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="scscs" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:4.99999;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m 645.63914,604.05477 185.841,0.11499"
|
||||||
|
id="path9777-9-5-8-9-7-2-3-3-8"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:4.99999;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m 311.03714,458.69475 334.602,145.36002"
|
||||||
|
id="path9777-9-7-1-9-02-1-1-4-5-9-1"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:4.99999;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m 311.81414,300.37177 -95.009,-0.507"
|
||||||
|
id="path9777-9-7-1-1-4-9-2-6-0-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:4.99999;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m 311.03714,458.69475 -95.009,-0.50699"
|
||||||
|
id="path9777-9-7-1-1-4-9-2-6-0-4-2"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:none;stroke:#433ab2;stroke-width:4.99999;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m 986.79814,327.81676 -441.698,-647.76397"
|
||||||
|
id="path9777-9-7-1-9-02-1-1-4-5-9-1-1-6-9"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 17 KiB |
1045
inkscape_drawings/effector-tool-offsets.svg
Normal file
After Width: | Height: | Size: 40 KiB |
744
inkscape_drawings/feature-double-lines.svg
Normal file
@ -0,0 +1,744 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
sodipodi:docname="feature-double-lines.svg"
|
||||||
|
inkscape:version="1.0 (4035a4fb49, 2020-05-01)"
|
||||||
|
id="svg866"
|
||||||
|
version="1.1"
|
||||||
|
viewBox="0 0 100.00049 91.145996"
|
||||||
|
height="91.145996mm"
|
||||||
|
width="100.00049mm">
|
||||||
|
<defs
|
||||||
|
id="defs860">
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-62"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-17"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-7-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-4" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-1-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-7-6" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-4-5"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-71"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-379" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-24" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-1"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-9-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-5-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="Arrow1Lstart-3-4"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lstart">
|
||||||
|
<path
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
style="fill:#ff0000;fill-opacity:1;fill-rule:evenodd;stroke:#ff0000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path15451-1-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:collect="always"
|
||||||
|
inkscape:stockid="Arrow1Lstart"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker19587"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path19585"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:collect="always"
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="marker19013"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lstart">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path19011" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:collect="always"
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="marker21247"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lstart">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path21245" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lstart"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker21821"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path21819"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:collect="always"
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="Arrow1Lend"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lend">
|
||||||
|
<path
|
||||||
|
transform="matrix(-0.8,0,0,-0.8,-10,0)"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path13852" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:collect="always"
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="marker15683"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lend">
|
||||||
|
<path
|
||||||
|
transform="matrix(-0.8,0,0,-0.8,-10,0)"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path15681" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:collect="always"
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="Arrow1Lstart"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lstart">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path15451" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:collect="always"
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="Arrow1Lend-3"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lend">
|
||||||
|
<path
|
||||||
|
transform="matrix(-0.8,0,0,-0.8,-10,0)"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path13852-4"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
</defs>
|
||||||
|
<sodipodi:namedview
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
inkscape:window-y="-8"
|
||||||
|
inkscape:window-x="1912"
|
||||||
|
inkscape:window-height="976"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
showborder="false"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-top="0"
|
||||||
|
showgrid="false"
|
||||||
|
inkscape:document-rotation="0"
|
||||||
|
inkscape:current-layer="g1692"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:cy="200.7687"
|
||||||
|
inkscape:cx="262.12529"
|
||||||
|
inkscape:zoom="1.28"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
borderopacity="1.0"
|
||||||
|
bordercolor="#666666"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
id="base" />
|
||||||
|
<metadata
|
||||||
|
id="metadata863">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
transform="translate(10072.646,9320.788)"
|
||||||
|
id="layer1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
inkscape:label="Layer 1">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.0381366,0,0,0.0381366,-1282.8902,-1414.8552)"
|
||||||
|
id="g1692">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.01584392,0,0,0.01584392,-226829.12,-204021.12)"
|
||||||
|
id="g3115">
|
||||||
|
<path
|
||||||
|
style="fill:#00a300;fill-opacity:0.0857143;stroke:#00a600;stroke-width:524.431;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:6293.17, 6293.17;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
d="m -188963.43,-110625.04 41330.95,-27742.64 33955.52,19604.22 -41330.96,27742.631 z"
|
||||||
|
id="rect30955"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="ccccc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#marker19587)"
|
||||||
|
d="m -130689.41,-133820.62 -16973.44,-9799.6"
|
||||||
|
id="path12500"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -130689.41,-123958.86 -16973.44,-9799.6"
|
||||||
|
id="path12500-1"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#marker19013)"
|
||||||
|
d="m -172020.37,-106077.99 -16973.4,-9799.61"
|
||||||
|
id="path12500-0"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -172020.37,-96216.227 -16973.4,-9799.593"
|
||||||
|
id="path12500-1-2"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-end:url(#marker21247)"
|
||||||
|
d="m -147662.85,-143620.22 30194.7,-33560.09"
|
||||||
|
id="path12535"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-end:url(#marker21821)"
|
||||||
|
d="m -188993.77,-115877.6 65025.51,-62994.59"
|
||||||
|
id="path12535-0"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:1048.86, 1048.86;stroke-dashoffset:0;stroke-opacity:1;marker-end:url(#Arrow1Lend)"
|
||||||
|
d="M -123869.93,-68416.585 -170480.8,-95327.373"
|
||||||
|
id="path12500-0-8-8"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#00a600;stroke-width:262.215;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:524.431, 1048.86;stroke-dashoffset:0;stroke-opacity:0.587255"
|
||||||
|
d="m -147662.85,-143620.22 v 9861.76"
|
||||||
|
id="path12606"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#00a600;stroke-width:262.215;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:524.431, 524.431;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -90787.756,-105548.37 -56844.724,-32819.31"
|
||||||
|
id="path12500-0-8-8-3-8"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#00a600;stroke-width:262.215;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:524.431, 1048.86;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -188993.77,-115877.6 v 9861.78"
|
||||||
|
id="path12606-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#00a600;stroke-width:262.215;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:524.431, 524.431;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -147676.66,-138444.22 -41330.95,27742.62"
|
||||||
|
id="path12671"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-end:url(#marker15683)"
|
||||||
|
d="m -147662.85,-133758.46 -18019.25,12046.47"
|
||||||
|
id="path12500-1-8"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#Arrow1Lstart)"
|
||||||
|
d="m -165682.1,-121711.99 -23311.67,15696.17"
|
||||||
|
id="path12500-1-8-5"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:#00a600;fill-opacity:1;stroke:none;stroke-width:489.721;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:979.448, 979.448;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -166533.35,-124953.23 a 1143.8364,1143.8364 0 0 1 -1143.81,1143.84 1143.8364,1143.8364 0 0 1 -1143.87,-1143.84 1143.8364,1143.8364 0 0 1 1143.87,-1143.84 1143.8364,1143.8364 0 0 1 1143.81,1143.84 z"
|
||||||
|
id="path12603"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:1048.86, 1048.86;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -117542.88,-177113.08 18619.064,-20694.32"
|
||||||
|
id="path12535-7"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:1048.86, 1048.86;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -124095.38,-178740.98 19721.21,-19105.26"
|
||||||
|
id="path12535-0-7"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-50-4-6-0"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:39.9997px;line-height:1.25;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Bold';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#00ad00;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97386,0.04581266,-0.04581266,121.97386,-1818729.1,-560062.43)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-5-7-2-0"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:39.9997px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Bold';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#00ad00;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-2-0-2-5"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:39.99974823px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Bold';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#00ad00;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-9-2-5">C anchor</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-9-3-8-4"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(86.749888,0,0,86.749888,-1271313.2,-509566.92)"><flowRegion
|
||||||
|
id="flowRegion8812-7-1-2-9-9"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-3-2-4-8"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-9-1-1-0">C1/C2 line pair from </flowPara><flowPara
|
||||||
|
id="flowPara28589">C drive spool</flowPara></flowRoot>
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:0;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -130689.41,-133820.62 -2293.18,-4113.68"
|
||||||
|
id="path12793"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:6.93777px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="M -130689.41,-133820.62 Z"
|
||||||
|
id="path12795"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-50-1-5"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#00a600;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97385,0.06665798,-0.06665798,121.97385,-1761886.1,-571525.9)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-5-9-8"
|
||||||
|
style="fill:#00a600;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-2-8-8"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#00a600;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-5-2">C1T pivot point</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-50-1-5-7"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#00a600;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97385,0.06665798,-0.06665798,121.97385,-1848993.4,-534011.73)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-5-9-8-6"
|
||||||
|
style="fill:#00a600;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-2-8-8-5"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#00a600;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-5-2-1">C2B pivot point</flowPara></flowRoot>
|
||||||
|
<ellipse
|
||||||
|
style="fill:#00a600;fill-opacity:0.153571;stroke:#000000;stroke-width:262.215;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:524.431, 524.431;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path24092"
|
||||||
|
cx="-188970.11"
|
||||||
|
cy="-105717.24"
|
||||||
|
rx="3309.4775"
|
||||||
|
ry="3309.4839" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-50-1-5-2"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;line-height:1.25;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(105.59912,61.044652,-61.044652,105.59912,-1302563.6,-1290712.2)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-5-9-8-7"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-2-8-8-1"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.78525162px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-5-2-7">bottom of line C1</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-50-1-5-2-1"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;line-height:1.25;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(105.59912,61.044652,-61.044652,105.59912,-1292913.6,-1300875.2)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-5-9-8-7-4"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-2-8-8-1-4"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.78525162px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-5-2-7-0">top of line C1</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-50-1-5-2-12"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;line-height:1.25;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(105.59912,61.044652,-61.044652,105.59912,-1341819.4,-1262072.5)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-5-9-8-7-2"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-2-8-8-1-2"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.78525162px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-5-2-7-7">bottom of line C2</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-50-1-5-2-1-0"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;line-height:1.25;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(105.59912,61.044652,-61.044652,105.59912,-1332637.3,-1272146.7)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-5-9-8-7-4-7"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-2-8-8-1-4-8"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.78525162px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-5-2-7-0-3">top of line C2</flowPara></flowRoot>
|
||||||
|
<path
|
||||||
|
style="fill:#00a600;fill-opacity:1;stroke:none;stroke-width:489.721;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:979.448, 979.448;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -146522.78,-138103.76 a 1143.8364,1143.8364 0 0 1 -1143.82,1143.83 1143.8364,1143.8364 0 0 1 -1143.86,-1143.83 1143.8364,1143.8364 0 0 1 1143.86,-1143.84 1143.8364,1143.8364 0 0 1 1143.82,1143.84 z"
|
||||||
|
id="path12603-8"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:#00a600;fill-opacity:1;stroke:none;stroke-width:489.721;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:979.448, 979.448;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -187995.02,-110701.6 a 1143.8364,1143.8364 0 0 1 -1143.81,1143.83 1143.8364,1143.8364 0 0 1 -1143.86,-1143.83 1143.8364,1143.8364 0 0 1 1143.86,-1143.84 1143.8364,1143.8364 0 0 1 1143.81,1143.84 z"
|
||||||
|
id="path12603-8-4"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:1048.86, 1048.86;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -125409.5,-79167.203 -46610.87,-26910.787"
|
||||||
|
id="path12500-0-8-8-0"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:1048.86, 1048.86;stroke-dashoffset:0;stroke-opacity:1;marker-end:url(#Arrow1Lend-3)"
|
||||||
|
d="M -84078.562,-97048.081 -130689.41,-123958.86"
|
||||||
|
id="path12500-0-8-8-7"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:1048.86, 1048.86;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -85618.132,-107798.7 -46610.858,-26910.78"
|
||||||
|
id="path12500-0-8-8-0-9"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#00a600;stroke-width:262.215;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:524.431, 524.431;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="M -132162.91,-77882.291 -189007.64,-110701.6"
|
||||||
|
id="path12500-0-8-8-3-8-5"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-9-3-8-4-4"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;line-height:1.25;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(105.63247,60.986934,-60.986934,105.63247,-1273035,-1285503)"><flowRegion
|
||||||
|
id="flowRegion8812-7-1-2-9-9-4"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-3-2-4-8-5"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.78525162px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara28589-2">to effector</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-9-3-8-4-4-7"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;line-height:1.25;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(105.63247,60.986934,-60.986934,105.63247,-1271774.1,-1275173.3)"><flowRegion
|
||||||
|
id="flowRegion8812-7-1-2-9-9-4-7"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-3-2-4-8-5-0"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.78525162px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara28589-2-9">from effector</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-9-3-8-4-4-74"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;line-height:1.25;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(105.63247,60.986934,-60.986934,105.63247,-1312064,-1256256)"><flowRegion
|
||||||
|
id="flowRegion8812-7-1-2-9-9-4-9"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-3-2-4-8-5-7"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.78525162px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara28589-2-7">to effector</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-9-3-8-4-4-7-1"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;line-height:1.25;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(105.63247,60.986934,-60.986934,105.63247,-1310803.1,-1245926.4)"><flowRegion
|
||||||
|
id="flowRegion8812-7-1-2-9-9-4-7-1"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-3-2-4-8-5-0-1"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.78525162px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara28589-2-9-8">from effector</flowPara></flowRoot>
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:6.93777px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="m -147662.85,-133758.46 -41330.92,27742.64"
|
||||||
|
id="path34396"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:none;stroke-width:489.721;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:979.448, 979.448;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
d="m -164425.8,-121916.21 a 1143.8364,1143.8364 0 0 1 -1143.81,1143.84 1143.8364,1143.8364 0 0 1 -1143.86,-1143.84 1143.8364,1143.8364 0 0 1 1143.86,-1143.84 1143.8364,1143.8364 0 0 1 1143.81,1143.84 z"
|
||||||
|
id="path12603-2"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-9-3-8-4-1"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(86.749888,0,0,86.749888,-1315887.7,-423772.54)"><flowRegion
|
||||||
|
id="flowRegion8812-7-1-2-9-9-5"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-3-2-4-8-1"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara28589-0">knot</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-50-1-5-7-6"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#00a600;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97385,0.06665798,-0.06665798,121.97385,-1848993.4,-544031.34)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-5-9-8-6-9"
|
||||||
|
style="fill:#00a600;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-2-8-8-5-4"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#00a600;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-5-2-1-4">C2T pivot point</flowPara></flowRoot>
|
||||||
|
<ellipse
|
||||||
|
style="fill:#00a600;fill-opacity:0.153571;stroke:#000000;stroke-width:262.215;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:524.431, 524.431;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path24092-9"
|
||||||
|
cx="-188970.11"
|
||||||
|
cy="-115736.95"
|
||||||
|
rx="3309.4775"
|
||||||
|
ry="3309.4841" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-50-1-5-29"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#00a600;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97385,0.06665798,-0.06665798,121.97385,-1761886.1,-560959.99)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-5-9-8-9"
|
||||||
|
style="fill:#00a600;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-2-8-8-7"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#00a600;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-5-2-62">C1B pivot point</flowPara></flowRoot>
|
||||||
|
<ellipse
|
||||||
|
style="fill:#00a600;fill-opacity:0.153571;stroke:#000000;stroke-width:262.215;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:524.431, 524.431;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path24092-0"
|
||||||
|
cx="-147599.75"
|
||||||
|
cy="-133208.02"
|
||||||
|
rx="3309.4775"
|
||||||
|
ry="3309.4841" />
|
||||||
|
<ellipse
|
||||||
|
style="fill:#00a600;fill-opacity:0.153571;stroke:#000000;stroke-width:262.215;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:524.431, 524.431;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path24092-9-9"
|
||||||
|
cx="-147599.75"
|
||||||
|
cy="-143227.7"
|
||||||
|
rx="3309.4775"
|
||||||
|
ry="3309.4844" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 42 KiB |
491
inkscape_drawings/feature-single-lines.svg
Normal file
@ -0,0 +1,491 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
sodipodi:docname="feature-single-lines.svg"
|
||||||
|
inkscape:version="1.0 (4035a4fb49, 2020-05-01)"
|
||||||
|
id="svg866"
|
||||||
|
version="1.1"
|
||||||
|
viewBox="0 0 100.00001 85.494713"
|
||||||
|
height="85.494713mm"
|
||||||
|
width="100.00001mm">
|
||||||
|
<defs
|
||||||
|
id="defs860">
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-62"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-17"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-7-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-4" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-1-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-7-6" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-4-5"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-71"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-379" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-24" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-1"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-9-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-5-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="Arrow1Lstart-3-4"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lstart">
|
||||||
|
<path
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
style="fill:#ff0000;fill-opacity:1;fill-rule:evenodd;stroke:#ff0000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path15451-1-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lstart"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker21821"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path21819"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:collect="always"
|
||||||
|
inkscape:stockid="Arrow1Lstart"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker19587-1"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path19585-6"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:collect="always"
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="marker19013-1"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lstart">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path19011-7" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:collect="always"
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="marker21247-2"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lstart">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path21245-5" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lstart"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker21821-0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path21819-2"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
</defs>
|
||||||
|
<sodipodi:namedview
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
inkscape:window-y="-8"
|
||||||
|
inkscape:window-x="1912"
|
||||||
|
inkscape:window-height="976"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
showborder="false"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-top="0"
|
||||||
|
showgrid="false"
|
||||||
|
inkscape:document-rotation="0"
|
||||||
|
inkscape:current-layer="g1692"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:cy="261.60915"
|
||||||
|
inkscape:cx="283.35446"
|
||||||
|
inkscape:zoom="0.90509668"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
borderopacity="1.0"
|
||||||
|
bordercolor="#666666"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
id="base" />
|
||||||
|
<metadata
|
||||||
|
id="metadata863">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
transform="translate(13114.181,11901.61)"
|
||||||
|
id="layer1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
inkscape:label="Layer 1">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.0381366,0,0,0.0381366,-1282.8902,-1414.8552)"
|
||||||
|
id="g1692">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.01620016,0,0,0.01620016,-305208.69,-270524.05)"
|
||||||
|
id="g3744">
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#marker19587-1)"
|
||||||
|
d="m -209124.94,-201493.73 -16973.43,-9799.59"
|
||||||
|
id="path12500-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#marker19013-1)"
|
||||||
|
d="m -250455.89,-173751.09 -16973.41,-9799.62"
|
||||||
|
id="path12500-0-9"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-end:url(#marker21247-2)"
|
||||||
|
d="m -226098.35,-211293.32 30194.67,-33560.1"
|
||||||
|
id="path12535-4"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-end:url(#marker21821-0)"
|
||||||
|
d="m -267429.3,-183550.71 65025.51,-62994.57"
|
||||||
|
id="path12535-0-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:1048.86, 1048.86;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -195978.41,-244786.19 18619.1,-20694.32"
|
||||||
|
id="path12535-7-8"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:1048.86, 1048.86;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -202530.91,-246414.07 19721.22,-19105.27"
|
||||||
|
id="path12535-0-7-6"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-9-3-8-4-2"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(86.749888,0,0,86.749888,-1349748.7,-577240.02)"><flowRegion
|
||||||
|
id="flowRegion8812-7-1-2-9-9-9"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-3-2-4-8-9"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-9-1-1-0-4">C1/C2 line pair from </flowPara><flowPara
|
||||||
|
id="flowPara28589-20">C drive spool</flowPara></flowRoot>
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:0;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -209124.94,-201493.73 -2293.18,-4113.69"
|
||||||
|
id="path12793-8"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:6.93777px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||||
|
d="M -209124.94,-201493.73 Z"
|
||||||
|
id="path12795-4"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<ellipse
|
||||||
|
style="fill:#00a600;fill-opacity:0.153571;stroke:#000000;stroke-width:426.549;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:853.097, 853.097;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path24092-8"
|
||||||
|
cx="-267141.31"
|
||||||
|
cy="-183946.56"
|
||||||
|
rx="5425.7344"
|
||||||
|
ry="10889.211" />
|
||||||
|
<ellipse
|
||||||
|
style="fill:#00a600;fill-opacity:0.153571;stroke:#000000;stroke-width:426.549;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:853.097, 853.097;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path24092-2-4"
|
||||||
|
cx="-226014.02"
|
||||||
|
cy="-210876.42"
|
||||||
|
rx="5425.7344"
|
||||||
|
ry="10889.211" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-50-1-5-2-1-5"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;line-height:1.25;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(105.59912,61.044652,-61.044652,105.59912,-1374337.7,-1369942.9)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-5-9-8-7-4-70"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-2-8-8-1-4-4"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.78525162px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-5-2-7-0-1">line C1</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-50-1-5-2-1-0-5"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;line-height:1.25;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(105.59912,61.044652,-61.044652,105.59912,-1411072.8,-1339819.7)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-5-9-8-7-4-7-9"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-2-8-8-1-4-8-9"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.78525162px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#00a600;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-5-2-7-0-3-6">line C2</flowPara></flowRoot>
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:1048.86, 1048.86;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -203845.03,-146840.3 -46610.86,-26910.79"
|
||||||
|
id="path12500-0-8-8-0-6"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.431;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:1048.86, 1048.86;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m -164053.64,-175471.8 -46610.87,-26910.79"
|
||||||
|
id="path12500-0-8-8-0-9-9"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-9-3-8-4-4-5"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;line-height:1.25;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(105.63247,60.986934,-60.986934,105.63247,-1351470.6,-1353176.1)"><flowRegion
|
||||||
|
id="flowRegion8812-7-1-2-9-9-4-3"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-3-2-4-8-5-5"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.78525162px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara28589-2-6">to effector</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-9-3-8-4-4-74-2"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;line-height:1.25;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(105.63247,60.986934,-60.986934,105.63247,-1390499.6,-1323929.1)"><flowRegion
|
||||||
|
id="flowRegion8812-7-1-2-9-9-4-9-7"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.7853px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-3-2-4-8-5-7-1"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:25.78525162px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara28589-2-7-8">to effector</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-50-4-6-0-1"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:39.9997px;line-height:1.25;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Bold';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#00ad00;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97386,0.04581266,-0.04581266,121.97386,-1893980.5,-636153.61)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-5-7-2-0-9"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:39.9997px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Bold';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#00ad00;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-2-0-2-5-3"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;font-size:39.99974823px;font-family:sans-serif;-inkscape-font-specification:'sans-serif, Bold';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;font-feature-settings:normal;text-align:start;writing-mode:lr-tb;text-anchor:start;fill:#00ad00;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-9-2-5-3">C anchor</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-50-1-5-8"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#00a600;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97385,0.06665798,-0.06665798,121.97385,-1836765.9,-641503.96)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-5-9-8-8"
|
||||||
|
style="fill:#00a600;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-2-8-8-3"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#00a600;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-5-2-6">C1 pivot point</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-50-1-5-7-4"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#00a600;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97385,0.06665798,-0.06665798,121.97385,-1928747.1,-611596.45)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-5-9-8-6-0"
|
||||||
|
style="fill:#00a600;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-2-8-8-5-8"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#00a600;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-5-2-1-1">C2 pivot point</flowPara></flowRoot>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 24 KiB |
770
inkscape_drawings/frame-validation.svg
Normal file
@ -0,0 +1,770 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
sodipodi:docname="frame-testing.svg"
|
||||||
|
inkscape:version="1.0 (4035a4fb49, 2020-05-01)"
|
||||||
|
id="svg8"
|
||||||
|
version="1.1"
|
||||||
|
viewBox="0 0 100 91.346138"
|
||||||
|
height="91.346138mm"
|
||||||
|
width="100mm">
|
||||||
|
<defs
|
||||||
|
id="defs2">
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect1225"
|
||||||
|
is_visible="true" />
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="ArrowDIN-start"
|
||||||
|
style="overflow:visible"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
orient="auto"
|
||||||
|
id="ArrowDIN-start-7-6">
|
||||||
|
<path
|
||||||
|
id="path13335-9-7"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="ArrowDIN-end"
|
||||||
|
style="overflow:visible"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
orient="auto"
|
||||||
|
id="ArrowDIN-end-1-8">
|
||||||
|
<path
|
||||||
|
id="path13338-7-5"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect7064-4-4"
|
||||||
|
is_visible="true" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect1225-5"
|
||||||
|
is_visible="true" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect1225-9"
|
||||||
|
is_visible="true" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect1225-9-8"
|
||||||
|
is_visible="true" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-9"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-7"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-7"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-9-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-7-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-7-2"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-5-7"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-76"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-53"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-8-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-76-7"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-8-0"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-53-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-8-0"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-76-0"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-8-4"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-53-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-8-5-2"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-76-7-6"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-8-0-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-53-9-8"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
</defs>
|
||||||
|
<sodipodi:namedview
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
inkscape:window-y="-8"
|
||||||
|
inkscape:window-x="-8"
|
||||||
|
inkscape:window-height="976"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
showborder="false"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-top="0"
|
||||||
|
showgrid="false"
|
||||||
|
inkscape:document-rotation="0"
|
||||||
|
inkscape:current-layer="layer1"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:cy="272.97268"
|
||||||
|
inkscape:cx="-133.04639"
|
||||||
|
inkscape:zoom="0.35"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
borderopacity="1.0"
|
||||||
|
bordercolor="#666666"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
id="base" />
|
||||||
|
<metadata
|
||||||
|
id="metadata5">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
transform="translate(-141.03519,-75.942644)"
|
||||||
|
id="layer1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
inkscape:label="Layer 1">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.48126261,0,0,0.48126261,142.34824,67.727212)"
|
||||||
|
inkscape:label="Layer 1"
|
||||||
|
id="layer1-1">
|
||||||
|
<path
|
||||||
|
style="color:#000000;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:medium;line-height:normal;font-family:sans-serif;font-variant-ligatures:normal;font-variant-position:normal;font-variant-caps:normal;font-variant-numeric:normal;font-variant-alternates:normal;font-feature-settings:normal;text-indent:0;text-align:start;text-decoration:none;text-decoration-line:none;text-decoration-style:solid;text-decoration-color:#000000;letter-spacing:normal;word-spacing:normal;text-transform:none;writing-mode:lr-tb;direction:ltr;text-orientation:mixed;dominant-baseline:auto;baseline-shift:baseline;text-anchor:start;white-space:normal;shape-padding:0;clip-rule:nonzero;display:inline;overflow:visible;visibility:visible;opacity:1;isolation:auto;mix-blend-mode:normal;color-interpolation:sRGB;color-interpolation-filters:linearRGB;solid-color:#000000;solid-opacity:1;vector-effect:none;fill:#030000;fill-opacity:1;fill-rule:nonzero;stroke:none;stroke-width:5.4;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;color-rendering:auto;image-rendering:auto;shape-rendering:auto;text-rendering:auto;enable-background:accumulate"
|
||||||
|
d="M 85.375,35.214844 9.9863281,165.85938 l 0.7773439,1.3496 14.46289,25.0625 H 177.10938 l 15.23437,-26.40039 -74.0918,-130.468746 z m 3.107422,5.417968 26.615238,0.152344 71.02343,125.064454 -12.13086,21.02344 H 28.345703 l -12.125,-21.01367 z"
|
||||||
|
id="path4828-5-6-3-8"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<g
|
||||||
|
transform="matrix(1.6934676,0,0,1.6934676,-107.63163,-115.81563)"
|
||||||
|
id="g1881">
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-97-3-4-7-3-5"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-875.95493,-77.30423)"><flowRegion
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRegion8812-7-0-9-6-9-9-7"><rect
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="rect8814-2-8-0-0-1-8-3"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-4-3-8-3">l</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-97-3-6-1-3-5-8"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-874.272,-75.98124)"><flowRegion
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRegion8812-7-0-9-5-3-7-7-0"><rect
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="rect8814-2-8-0-5-7-6-1-6"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-5-7-6-9-6">AB</flowPara></flowRoot>
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
transform="matrix(1.6934676,0,0,1.6934676,-16.349028,-131.48332)"
|
||||||
|
id="g1881-9">
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-97-3-4-7-3-5-6"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-876.11813,-78.032372)"><flowRegion
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRegion8812-7-0-9-6-9-9-7-0"><rect
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="rect8814-2-8-0-0-1-8-3-7"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-4-3-8-3-4">l</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-97-3-6-1-3-5-8-8"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-875.43953,-76.58384)"><flowRegion
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRegion8812-7-0-9-5-3-7-7-0-0"><rect
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="rect8814-2-8-0-5-7-6-1-6-0"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-5-7-6-9-6-1">B</flowPara></flowRoot>
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
transform="matrix(1.6934676,0,0,1.6934676,-193.28635,-131.26859)"
|
||||||
|
id="g1881-9-0">
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-97-3-4-7-3-5-6-7"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-876.11813,-78.032372)"><flowRegion
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRegion8812-7-0-9-6-9-9-7-0-7"><rect
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="rect8814-2-8-0-0-1-8-3-7-0"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-4-3-8-3-4-6">l</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-97-3-6-1-3-5-8-8-0"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-875.43953,-76.58384)"><flowRegion
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRegion8812-7-0-9-5-3-7-7-0-0-3"><rect
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="rect8814-2-8-0-5-7-6-1-6-0-7"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-5-7-6-9-6-1-5">A</flowPara></flowRoot>
|
||||||
|
</g>
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:original-d="m 102.33762,129.21565 v 2.2334"
|
||||||
|
inkscape:path-effect="#path-effect1225"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path1223"
|
||||||
|
d="m 102.33762,129.21565 v 2.2334"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:0.193455;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
transform="matrix(2.5845768,0,0,2.5845768,-163.33568,-205.39989)" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:original-d="m 102.33762,129.21565 v 2.2334"
|
||||||
|
inkscape:path-effect="#path-effect1225-5"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path1223-0"
|
||||||
|
d="m 102.33762,129.21565 v 2.2334"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:0.193455;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
transform="matrix(0,2.5845768,-2.5845768,0,438.01773,-133.04536)" />
|
||||||
|
<g
|
||||||
|
transform="matrix(0.22505474,0,0,0.22505474,73.620751,57.555375)"
|
||||||
|
id="g5446-4-3"
|
||||||
|
style="fill:#000000;fill-opacity:1" />
|
||||||
|
<path
|
||||||
|
id="path13664-8-8-6-4-6"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
style="fill:none;stroke:#ff2082;stroke-width:0.480081;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-02-8-4-8-1);marker-end:url(#ArrowDIN-end-6-8-9-3-6)"
|
||||||
|
d="m 101.16503,43.374365 1e-5,140.737595"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-27-5-1"
|
||||||
|
d="M 25.226562,206.37577 V 192.27148"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:1;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-27-5-1-1"
|
||||||
|
d="M 177.10938,206.37576 V 192.27148"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:1;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-27-5-1-1-6"
|
||||||
|
d="M 118.25195,35.402344 V 21.298064"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:1;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-27-5-1-1-3"
|
||||||
|
d="M 85.375,35.214844 V 21.110565"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:1;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-27-5-1-1-3-8"
|
||||||
|
d="M 118.25195,35.402344 130.46661,28.3502"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:1;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-27-5-1-1-3-8-5"
|
||||||
|
d="m 192.34375,165.87109 12.21466,-7.05215"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:1;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-27-5-1-1-3-8-5-2"
|
||||||
|
d="m -2.2283319,172.91153 12.21466,-7.05215"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:1;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-27-5-1-1-3-8-5-9"
|
||||||
|
d="m 13.011902,199.32363 12.21466,-7.05215"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:1;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-27-5-1-1-3-8-5-93"
|
||||||
|
d="m -2.2283423,158.80725 12.2146704,7.05213"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:1;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-27-5-1-1-3-8-5-93-4"
|
||||||
|
d="M 73.16033,28.162714 85.375,35.214844"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:1;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-27-5-1-1-3-8-5-93-46"
|
||||||
|
d="m 192.34375,165.87109 12.21467,7.05213"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:1;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-27-5-1-1-3-8-5-93-3"
|
||||||
|
d="m 177.10938,192.27148 12.21467,7.05213"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:1;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
id="path13664-8-8-6-4-6-4"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
style="fill:none;stroke:#ff2082;stroke-width:0.480081;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-02-8-4-8-1-9);marker-end:url(#ArrowDIN-end-6-8-9-3-6-7)"
|
||||||
|
d="M 147.59723,104.46976 25.714913,174.83858"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
id="path13664-8-8-6-4-6-4-5"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
style="fill:none;stroke:#ff2082;stroke-width:0.480081;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-02-8-4-8-1-9-5);marker-end:url(#ArrowDIN-end-6-8-9-3-6-7-2)"
|
||||||
|
d="M 54.736774,104.47324 176.61909,174.84206"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<g
|
||||||
|
id="g1687">
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="m 172.7922,204.1553 -143.193818,10e-6"
|
||||||
|
style="fill:none;stroke:#ff2082;stroke-width:0.457366;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-02-8-4-8-1-8);marker-end:url(#ArrowDIN-end-6-8-9-3-6-8)"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
id="path13664-8-8-6-4-6-8" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 114.10215,24.725621 H 89.544717"
|
||||||
|
style="fill:none;stroke:#ff2082;stroke-width:0.451174;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-02-8-4-8-1-8-5);marker-end:url(#ArrowDIN-end-6-8-9-3-6-8-0)"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
id="path13664-8-8-6-4-6-8-7" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
id="g1846">
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 1.7274619,156.73411 73.324362,32.724624"
|
||||||
|
style="fill:none;stroke:#ff2082;stroke-width:0.457366;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-02-8-4-8-1-8-0);marker-end:url(#ArrowDIN-end-6-8-9-3-6-8-4)"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
id="path13664-8-8-6-4-6-8-3" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="m 187.22851,194.77148 12.27872,-21.26737"
|
||||||
|
style="fill:none;stroke:#ff2082;stroke-width:0.451174;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-02-8-4-8-1-8-5-2);marker-end:url(#ArrowDIN-end-6-8-9-3-6-8-0-3)"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
id="path13664-8-8-6-4-6-8-7-1" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
id="g1871"
|
||||||
|
transform="matrix(-1,0,0,1,201.20993,0)">
|
||||||
|
<path
|
||||||
|
id="path1867"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
style="fill:none;stroke:#ff2082;stroke-width:0.457366;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-02-8-4-8-1-8-0);marker-end:url(#ArrowDIN-end-6-8-9-3-6-8-4)"
|
||||||
|
d="M 1.7274619,156.73411 73.324362,32.724624"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
id="path1869"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
style="fill:none;stroke:#ff2082;stroke-width:0.451174;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-02-8-4-8-1-8-5-2);marker-end:url(#ArrowDIN-end-6-8-9-3-6-8-0-3)"
|
||||||
|
d="m 187.22851,194.77148 12.27872,-21.26737"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
id="g1881-9-0-1"
|
||||||
|
transform="matrix(1.6934676,0,0,1.6934676,-102.62838,-293.59088)">
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-876.11813,-78.032372)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRoot8810-6-97-3-4-7-3-5-6-7-9"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-7-0-9-6-9-9-7-0-7-7"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-8-0-0-1-8-3-7-0-1"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-4-3-8-3-4-6-9">l</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-875.1022,-76.45956)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRoot8810-6-97-3-6-1-3-5-8-8-0-3"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-7-0-9-5-3-7-7-0-0-3-9"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-8-0-5-7-6-1-6-0-7-4"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-5-7-6-9-6-1-5-7">C</flowPara></flowRoot>
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
transform="matrix(1.6934676,0,0,1.6934676,-38.289426,-224.68749)"
|
||||||
|
id="g1881-2">
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-97-3-4-7-3-5-7"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-875.95493,-77.30423)"><flowRegion
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRegion8812-7-0-9-6-9-9-7-2"><rect
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="rect8814-2-8-0-0-1-8-3-4"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-4-3-8-3-45">l</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-97-3-6-1-3-5-8-5"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-874.272,-75.98124)"><flowRegion
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRegion8812-7-0-9-5-3-7-7-0-5"><rect
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="rect8814-2-8-0-5-7-6-1-6-9"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-5-7-6-9-6-9">BC</flowPara></flowRoot>
|
||||||
|
</g>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(0.12709798,0,0,0.12709798,-1661.1393,-354.33605)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRoot8810-6-97-3-4-7-3-5-7-8"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-7-0-9-6-9-9-7-2-0"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-8-0-0-1-8-3-4-4"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-4-3-8-3-45-8">l</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(0.12709798,0,0,0.12709798,-1659.3949,-352.22317)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRoot8810-6-97-3-6-1-3-5-8-5-0"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-7-0-9-5-3-7-7-0-5-1"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-8-0-5-7-6-1-6-9-4"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-5-7-6-9-6-9-4">AC</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(0.12709798,0,0,0.12709798,-1582.5656,-350.4695)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRoot8810-6-97-3-4-7-3-5-7-8-9"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-7-0-9-6-9-9-7-2-0-7"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-8-0-0-1-8-3-4-4-4"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-4-3-8-3-45-8-6">s</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(0.12709798,0,0,0.12709798,-1580.4411,-347.66421)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRoot8810-6-97-3-6-1-3-5-8-5-0-3"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-7-0-9-5-3-7-7-0-5-1-66"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-8-0-5-7-6-1-6-9-4-3"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-5-7-6-9-6-9-4-6">C</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(0.12709798,0,0,0.12709798,-1633.1803,-297.35956)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRoot8810-6-97-3-4-7-3-5-7-8-9-2"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-7-0-9-6-9-9-7-2-0-7-2"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-8-0-0-1-8-3-4-4-4-8"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-4-3-8-3-45-8-6-7">s</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(0.12709798,0,0,0.12709798,-1631.0133,-295.14956)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRoot8810-6-97-3-6-1-3-5-8-5-0-3-1"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-7-0-9-5-3-7-7-0-5-1-66-1"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-8-0-5-7-6-1-6-9-4-3-8"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-5-7-6-9-6-9-4-6-6">A</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(0.12709798,0,0,0.12709798,-1545.1174,-295.66674)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRoot8810-6-97-3-4-7-3-5-7-8-9-2-0"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-7-0-9-6-9-9-7-2-0-7-2-7"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-8-0-0-1-8-3-4-4-4-8-9"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-4-3-8-3-45-8-6-7-0">s</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(0.12709798,0,0,0.12709798,-1542.6102,-292.56382)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRoot8810-6-97-3-6-1-3-5-8-5-0-3-1-3"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-7-0-9-5-3-7-7-0-5-1-66-1-6"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-8-0-5-7-6-1-6-9-4-3-8-7"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-5-7-6-9-6-9-4-6-6-0">B</flowPara></flowRoot>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 35 KiB |
853
inkscape_drawings/hangprinter.svg
Normal file
@ -0,0 +1,853 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
sodipodi:docname="hangprinter.svg"
|
||||||
|
inkscape:version="0.92.5 (2060ec1f9f, 2020-04-08)"
|
||||||
|
id="svg866"
|
||||||
|
version="1.1"
|
||||||
|
viewBox="0 0 99.999978 93.047607"
|
||||||
|
height="93.047607mm"
|
||||||
|
width="99.999977mm">
|
||||||
|
<defs
|
||||||
|
id="defs860">
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-62"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-17"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-7-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-4" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-1-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-7-6" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-4-5"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-71"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-379" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-24" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-1"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-9-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-5-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="Arrow1Lstart-3-4"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lstart">
|
||||||
|
<path
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
style="fill:#ff0000;fill-opacity:1;fill-rule:evenodd;stroke:#ff0000;stroke-width:1.00000003pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path15451-1-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lstart"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker21821"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path21819"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1.00000003pt;stroke-opacity:1"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lstart"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker21821-0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path21819-2"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1.00000003pt;stroke-opacity:1"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1-5-9"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3-2-5" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-9-3-5-4"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-5-1-9-4"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1-2-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3-8-3" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3-2" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-9-3-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-5-1-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="Arrow1Lstart-3-4-5"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lstart">
|
||||||
|
<path
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
style="fill:#ff0000;fill-opacity:1;fill-rule:evenodd;stroke:#ff0000;stroke-width:1.00000003pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path15451-1-1-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1-2"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3-8" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="Arrow1Lstart-3-4-7-5-0-2-0-1"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lstart">
|
||||||
|
<path
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
style="fill:#4e6ab4;fill-opacity:1;fill-rule:evenodd;stroke:#4e6ab4;stroke-width:1.00000003pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path15451-1-1-0-5-1-8-8-2"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
</defs>
|
||||||
|
<sodipodi:namedview
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
inkscape:window-y="-8"
|
||||||
|
inkscape:window-x="-8"
|
||||||
|
inkscape:window-height="976"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
showborder="false"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-top="0"
|
||||||
|
showgrid="false"
|
||||||
|
inkscape:document-rotation="0"
|
||||||
|
inkscape:current-layer="g1692"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:cy="191.119"
|
||||||
|
inkscape:cx="278.26924"
|
||||||
|
inkscape:zoom="1.28"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
borderopacity="1.0"
|
||||||
|
bordercolor="#666666"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
id="base" />
|
||||||
|
<metadata
|
||||||
|
id="metadata863">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
transform="translate(25432.276,20999.871)"
|
||||||
|
id="layer1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
inkscape:label="Layer 1">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.0381366,0,0,0.0381366,-1282.8902,-1414.8552)"
|
||||||
|
id="g1692">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.01531169,0,0,0.01531169,-623537.97,-505685.77)"
|
||||||
|
id="g5602">
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:1048.85998535;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
id="path4828-5-6-3_0_1"
|
||||||
|
d="m -621823.85,-404506.43 85286.6,-12446.86 11442.2,6606.16 -23084.39,48359.32 -15636,2421.29 -62202.19,-35912.46 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="color:#000000;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:medium;line-height:normal;font-family:sans-serif;font-variant-ligatures:normal;font-variant-position:normal;font-variant-caps:normal;font-variant-numeric:normal;font-variant-alternates:normal;font-feature-settings:normal;text-indent:0;text-align:start;text-decoration:none;text-decoration-line:none;text-decoration-style:solid;text-decoration-color:#000000;letter-spacing:normal;word-spacing:normal;text-transform:none;writing-mode:lr-tb;direction:ltr;text-orientation:mixed;dominant-baseline:auto;baseline-shift:baseline;text-anchor:start;white-space:normal;shape-padding:0;clip-rule:nonzero;display:inline;overflow:visible;visibility:visible;isolation:auto;mix-blend-mode:normal;color-interpolation:sRGB;color-interpolation-filters:linearRGB;solid-color:#000000;solid-opacity:1;vector-effect:none;fill:#000000;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:1048.85998535;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;color-rendering:auto;image-rendering:auto;shape-rendering:auto;text-rendering:auto;enable-background:accumulate"
|
||||||
|
id="path6909_2_1"
|
||||||
|
d="m -600932.04,-397076.45 20720.31,11955.53 20720.33,11955.5 7573.12,-16337.91 7573.13,-16337.92 -276.99,42.88 -28016.45,4339.51 z m 639.81,98.86 27739.43,-4296.6 27739.47,-4296.58 -7424.87,16018 -7424.84,16018.03 -20314.6,-11721.43 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:#309ad1;fill-opacity:1;stroke:none;stroke-width:91.00559998;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
id="path4828-4_1_1"
|
||||||
|
d="m -568013.78,-391658.44 -21155.14,-3338.11 3253.29,-7002.78 24462.21,-3780.47 8947.05,5168.14 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:#309ad1;fill-opacity:1;stroke:none;stroke-width:91.00559998;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
id="path4828-4-8_1_1"
|
||||||
|
d="m -567845.68,-391561.39 15584.74,-8908.53 8877.51,5128.05 -6560.41,14121.34 -12225.74,1889.45 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:#309ad1;fill-opacity:1;stroke:none;stroke-width:91.00559998;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
id="path4828-4-8-1_1_1"
|
||||||
|
d="m -568102.23,-391523.08 5570.43,12246.62 -12130.83,1874.74 -17901.8,-10340.88 3278.68,-7057.59 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:1048.85998535;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
id="path4828_1_1"
|
||||||
|
d="m -561344.2,-503514 -4305.68,9268.08 -16055.01,2481.18 -11749.28,-6786.89 4305.69,-9268.08 16055,-2481.18 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="ccc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path7171"
|
||||||
|
d="m -574412.58,-492647.48 8920.37,60775.1 17312.77,69884.57"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1048.85998535;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path7173"
|
||||||
|
d="m -565492.21,-431192.54 1676.77,71626.02"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:524.43103027;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
style="fill:#e6e5b4;fill-opacity:1;stroke:none;stroke-width:466.72698975;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
id="path4828_1_1-6"
|
||||||
|
d="m -562844.74,-503299.04 -3831.94,8248.33 -14288.49,2208.19 -10456.52,-6040.13 3831.94,-8248.32 14288.49,-2208.2 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1048.85998535;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -590930.4,-504019.79 -17051.69,55321.42 -13841.76,44191.94"
|
||||||
|
id="path7175"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="ccc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1048.85998535;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -567531.72,-507164.43 20735.05,52687.44 10259.42,37523.7"
|
||||||
|
id="path7177"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="ccc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1048.85998535;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -546796.67,-454476.99 21701.62,44129.86"
|
||||||
|
id="path7179"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1048.85998535;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -626017.63,-395478.98 15235.95,-45037.03"
|
||||||
|
id="path7181"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="color:#000000;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:medium;line-height:normal;font-family:sans-serif;font-variant-ligatures:normal;font-variant-position:normal;font-variant-caps:normal;font-variant-numeric:normal;font-variant-alternates:normal;font-feature-settings:normal;text-indent:0;text-align:start;text-decoration:none;text-decoration-line:none;text-decoration-style:solid;text-decoration-color:#000000;letter-spacing:normal;word-spacing:normal;text-transform:none;writing-mode:lr-tb;direction:ltr;text-orientation:mixed;dominant-baseline:auto;baseline-shift:baseline;text-anchor:start;white-space:normal;shape-padding:0;clip-rule:nonzero;display:inline;overflow:visible;visibility:visible;isolation:auto;mix-blend-mode:normal;color-interpolation:sRGB;color-interpolation-filters:linearRGB;solid-color:#000000;solid-opacity:1;vector-effect:none;fill:#000000;fill-opacity:1;fill-rule:nonzero;stroke:#facf00;stroke-width:630.59100342;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill;color-rendering:auto;image-rendering:auto;shape-rendering:auto;text-rendering:auto;enable-background:accumulate"
|
||||||
|
id="path6909-4_0_1"
|
||||||
|
d="m -566437.16,-422823.58 -5366.89,-3096.67 -5366.89,-3096.66 -1961.55,4231.77 -1961.56,4231.78 71.74,-11.11 7256.7,-1123.99 z m -165.73,-25.59 -7184.94,1112.87 -7184.96,1112.88 1923.16,-4148.91 1923.15,-4148.92 5261.8,3036.03 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<circle
|
||||||
|
style="fill:#bf4b00;fill-opacity:1;stroke:none;stroke-width:226.08999634;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360"
|
||||||
|
cx="-580248.06"
|
||||||
|
cy="-506059.25"
|
||||||
|
r="1132.4626" />
|
||||||
|
<circle
|
||||||
|
style="fill:#bf4b00;fill-opacity:1;stroke:none;stroke-width:226.08999634;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-1"
|
||||||
|
cx="-569669.69"
|
||||||
|
cy="-500125.91"
|
||||||
|
r="1132.4626" />
|
||||||
|
<circle
|
||||||
|
style="fill:#bf4b00;fill-opacity:1;stroke:none;stroke-width:226.08999634;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-3"
|
||||||
|
cx="-584230.25"
|
||||||
|
cy="-497901.62"
|
||||||
|
r="1132.4626" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:524.43103027;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -569714.22,-500221.78 3111.33,77372.61"
|
||||||
|
id="path8646"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:524.43103027;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -580237.81,-506293.85 3111.33,77372.6"
|
||||||
|
id="path8648"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:524.43103027;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -584205.38,-497925.98 3111.33,77372.62"
|
||||||
|
id="path8650"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<circle
|
||||||
|
style="fill:#00ad00;fill-opacity:1;stroke:none;stroke-width:226.08999634;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7"
|
||||||
|
cx="-625544.31"
|
||||||
|
cy="-396732.34"
|
||||||
|
r="1132.4626" />
|
||||||
|
<circle
|
||||||
|
style="fill:#00ad00;fill-opacity:1;stroke:none;stroke-width:226.08999634;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8"
|
||||||
|
cx="-622128.19"
|
||||||
|
cy="-403624.78"
|
||||||
|
r="1132.4626" />
|
||||||
|
<circle
|
||||||
|
style="fill:#a900a6;fill-opacity:1;stroke:none;stroke-width:226.08999634;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-9"
|
||||||
|
cx="-535259.94"
|
||||||
|
cy="-416268.69"
|
||||||
|
r="1132.4626" />
|
||||||
|
<circle
|
||||||
|
style="fill:#a900a6;fill-opacity:1;stroke:none;stroke-width:226.08999634;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-4"
|
||||||
|
cx="-527087.75"
|
||||||
|
cy="-411581.69"
|
||||||
|
r="1132.4626" />
|
||||||
|
<circle
|
||||||
|
style="fill:#4e6ab4;fill-opacity:1;stroke:none;stroke-width:226.08999634;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-1"
|
||||||
|
cx="-549381"
|
||||||
|
cy="-361887.44"
|
||||||
|
r="1132.4626" />
|
||||||
|
<circle
|
||||||
|
style="fill:#4e6ab4;fill-opacity:1;stroke:none;stroke-width:226.08999634;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-0"
|
||||||
|
cx="-562484.88"
|
||||||
|
cy="-359642.88"
|
||||||
|
r="1132.4626" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#00ad00;stroke-width:524.43103027;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -622218.33,-403594.74 45047.39,-25422.17"
|
||||||
|
id="path8715"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#00ad00;stroke-width:524.43103027;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -625671.49,-396673.25 44577.44,-23880.11"
|
||||||
|
id="path8715-6"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#a900a6;stroke-width:524.43103027;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -566602.89,-422849.17 39553.4,11265.71"
|
||||||
|
id="path8732"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#a900a6;stroke-width:524.43103027;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -577126.48,-428921.25 41911.2,12749.12"
|
||||||
|
id="path8734"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#4e6ab4;stroke-width:524.43103027;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -566602.89,-422849.17 17281.95,61051.85"
|
||||||
|
id="path8766"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#4e6ab4;stroke-width:524.43103027;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -580972.79,-420623.42 18479.48,61039.4"
|
||||||
|
id="path8766-1"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:131.10699463;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -577170.94,-429016.91 1651.12,4580.27 -5452.97,3813.22"
|
||||||
|
id="path8785"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:131.10699463;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -566602.89,-422849.17 -8916.93,-1587.47 -42.49,4673.88"
|
||||||
|
id="path8787"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:131.10699463;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -575838.5,-420214.21 276.19,451.45"
|
||||||
|
id="path8789"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:131.10699463;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -575286.12,-420214.21 -276.19,451.45"
|
||||||
|
id="path8789-3"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:131.10699463;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -575838.5,-420214.21 h 552.38"
|
||||||
|
id="path8806"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:52.44309998;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -551363.99,-465301.94 31487.03,-6489.69"
|
||||||
|
id="path8808"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-2138318.7,-898597.75)"><flowRegion
|
||||||
|
id="flowRegion8812"><rect
|
||||||
|
id="rect8814"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8816">frame</flowPara></flowRoot> <path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:52.44309998;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -543383.43,-395341.87 31487.03,-6489.69"
|
||||||
|
id="path8808-3"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-2129579.4,-828832.75)"><flowRegion
|
||||||
|
id="flowRegion8812-7"><rect
|
||||||
|
id="rect8814-2"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857">print bed</flowPara></flowRoot> <path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:52.44309998;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -567845.68,-391561.39 54218.06,9904.4"
|
||||||
|
id="path8808-3-5"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-9"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-2131496.2,-809270.09)"><flowRegion
|
||||||
|
id="flowRegion8812-7-1"><rect
|
||||||
|
id="rect8814-2-3"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-9">origin 0,0,0 ("origo")</flowPara></flowRoot> <path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:52.44309998;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -561344.2,-503514 20386.59,3223.18"
|
||||||
|
id="path8808-6"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-1"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-2158524.2,-927526.6)"><flowRegion
|
||||||
|
id="flowRegion8812-4"><rect
|
||||||
|
id="rect8814-25"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8816-3">ceiling unit</flowPara></flowRoot> <path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:52.44309998;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -572503.04,-426263.71 41004.76,-11545.98"
|
||||||
|
id="path8808-6-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-2149042.3,-865153.58)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9"><rect
|
||||||
|
id="rect8814-2-7"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7">effector ("mover")</flowPara></flowRoot> <path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:52.44309998;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -575562.31,-419762.76 61766.2,-4802.7"
|
||||||
|
id="path8808-6-4-6"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-2"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-2132554.2,-851788.65)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-9"><rect
|
||||||
|
id="rect8814-2-7-9"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-2">hotend nozzle tip</flowPara></flowRoot> <flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#4e6ab4;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-2183450.2,-782925.77)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1"
|
||||||
|
style="fill:#4e6ab4;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#4e6ab4;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22">A1</flowPara></flowRoot> <flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-5"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#4e6ab4;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-2169822.5,-785585.34)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-3"
|
||||||
|
style="fill:#4e6ab4;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-4"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#4e6ab4;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-3">A2</flowPara></flowRoot> <flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-5-5"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#00ad00;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-2251981,-822752.73)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-3-7"
|
||||||
|
style="fill:#00ad00;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-4-7"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#00ad00;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-3-8">C2</flowPara></flowRoot> <flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-5-5-2"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#00ad00;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-2249405.8,-830942.95)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-3-7-0"
|
||||||
|
style="fill:#00ad00;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-4-7-3"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#00ad00;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-3-8-2">C1</flowPara></flowRoot> <flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-5-5-2-3"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#a900a6;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-2152257.7,-844714.42)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-3-7-0-7"
|
||||||
|
style="fill:#a900a6;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-4-7-3-6"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#a900a6;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-3-8-2-9">B2</flowPara></flowRoot> <flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-5-5-2-3-0"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#a900a6;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-2143418.9,-838431.48)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-3-7-0-7-3"
|
||||||
|
style="fill:#a900a6;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-4-7-3-6-7"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#a900a6;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-3-8-2-9-3">B1</flowPara></flowRoot> <flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-5-5-2-3-0-9"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#bf4b00;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-2206176.8,-927580.09)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-3-7-0-7-3-8"
|
||||||
|
style="fill:#bf4b00;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-4-7-3-6-7-0"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#bf4b00;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-3-8-2-9-3-6">D1</flowPara></flowRoot> <flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-5-5-2-3-0-9-9"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#bf4b00;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-2192008.2,-930240.59)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-3-7-0-7-3-8-4"
|
||||||
|
style="fill:#bf4b00;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-4-7-3-6-7-0-4"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#bf4b00;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-3-8-2-9-3-6-0">D2</flowPara></flowRoot> <flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-7-7-5-5-2-3-0-9-9-3"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#bf4b00;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(121.97387,0,0,121.97387,-2202697.5,-938650.29)"><flowRegion
|
||||||
|
id="flowRegion8812-7-9-1-3-7-0-7-3-8-4-6"
|
||||||
|
style="fill:#bf4b00;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-7-8-4-7-3-6-7-0-4-5"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#bf4b00;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-3-8-2-9-3-6-0-1">D3</flowPara></flowRoot> <circle
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:226.08999634;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-0-8"
|
||||||
|
cx="-567932.56"
|
||||||
|
cy="-391652.91"
|
||||||
|
r="1132.4626" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#00ad00;stroke-width:524.43103027;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -625671.49,-396673.25 54452.97,-111001.66"
|
||||||
|
id="path8715-2"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#00ad00;stroke-width:524.43103027;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="M -625671.49,-396673.25 -572533,-508692.88"
|
||||||
|
id="path8715-2-9"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#a900a6;stroke-width:524.43103027;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -577660.3,-493445.09 42445.02,77272.96"
|
||||||
|
id="path8734-6"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#a900a6;stroke-width:524.43103027;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -576188.1,-494286.36 49138.61,82702.9"
|
||||||
|
id="path8734-6-0"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#4e6ab4;stroke-width:524.43103027;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -588415.69,-505556.81 25922.38,145972.79"
|
||||||
|
id="path8766-1-0"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#4e6ab4;stroke-width:524.43103027;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -586673.61,-506045.45 37352.67,144248.13"
|
||||||
|
id="path8766-7"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<circle
|
||||||
|
style="fill:#a900a6;fill-opacity:1;stroke:none;stroke-width:226.08999634;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-9-1"
|
||||||
|
cx="-576922"
|
||||||
|
cy="-493907.56"
|
||||||
|
r="1132.4626" />
|
||||||
|
<circle
|
||||||
|
style="fill:#4e6ab4;fill-opacity:1;stroke:none;stroke-width:226.08999634;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-0-83"
|
||||||
|
cx="-587508"
|
||||||
|
cy="-505742.34"
|
||||||
|
r="1132.4626" />
|
||||||
|
<circle
|
||||||
|
style="fill:#00ad00;fill-opacity:1;stroke:none;stroke-width:226.08999634;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-7"
|
||||||
|
cx="-571912.19"
|
||||||
|
cy="-508039.97"
|
||||||
|
r="1132.4626" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 41 KiB |
2181
inkscape_drawings/line-lengths.svg
Normal file
After Width: | Height: | Size: 96 KiB |
2610
inkscape_drawings/main-drawing.svg
Normal file
After Width: | Height: | Size: 147 KiB |
1716
inkscape_drawings/measuring-XY.svg
Normal file
After Width: | Height: | Size: 90 KiB |
1020
inkscape_drawings/measuring-Z.svg
Normal file
After Width: | Height: | Size: 42 KiB |
1110
inkscape_drawings/pivot-points.svg
Normal file
After Width: | Height: | Size: 46 KiB |
88
inkscape_drawings/platform.svg
Normal file
@ -0,0 +1,88 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
sodipodi:docname="platform.svg"
|
||||||
|
inkscape:version="1.0 (4035a4fb49, 2020-05-01)"
|
||||||
|
id="svg8"
|
||||||
|
version="1.1"
|
||||||
|
viewBox="0 0 99.999991 89.926879"
|
||||||
|
height="89.92688mm"
|
||||||
|
width="99.999992mm">
|
||||||
|
<defs
|
||||||
|
id="defs2" />
|
||||||
|
<sodipodi:namedview
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
inkscape:window-y="-8"
|
||||||
|
inkscape:window-x="1912"
|
||||||
|
inkscape:window-height="976"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
showborder="false"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-top="0"
|
||||||
|
showgrid="false"
|
||||||
|
inkscape:document-rotation="0"
|
||||||
|
inkscape:current-layer="layer1"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:cy="208.22018"
|
||||||
|
inkscape:cx="84.302757"
|
||||||
|
inkscape:zoom="1.4"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
borderopacity="1.0"
|
||||||
|
bordercolor="#666666"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
id="base" />
|
||||||
|
<metadata
|
||||||
|
id="metadata5">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
transform="translate(915.92267,683.24888)"
|
||||||
|
id="layer1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
inkscape:label="Layer 1">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.05213699,0,0,0.05213699,-868.16922,-647.62634)"
|
||||||
|
id="g858">
|
||||||
|
<path
|
||||||
|
style="color:#000000;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:medium;line-height:normal;font-family:sans-serif;font-variant-ligatures:normal;font-variant-position:normal;font-variant-caps:normal;font-variant-numeric:normal;font-variant-alternates:normal;font-feature-settings:normal;text-indent:0;text-align:start;text-decoration:none;text-decoration-line:none;text-decoration-style:solid;text-decoration-color:#000000;letter-spacing:normal;word-spacing:normal;text-transform:none;writing-mode:lr-tb;direction:ltr;text-orientation:mixed;dominant-baseline:auto;baseline-shift:baseline;text-anchor:start;white-space:normal;shape-padding:0;clip-rule:nonzero;display:inline;overflow:visible;visibility:visible;isolation:auto;mix-blend-mode:normal;color-interpolation:sRGB;color-interpolation-filters:linearRGB;solid-color:#000000;solid-opacity:1;vector-effect:none;fill:#000000;fill-opacity:1;fill-rule:nonzero;stroke:#000400;stroke-width:49.9999;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;color-rendering:auto;image-rendering:auto;shape-rendering:auto;text-rendering:auto;enable-background:accumulate"
|
||||||
|
d="m 42.596299,-633.2497 -457.613409,793.1585 -457.61211,793.17211 915.714019,-0.2816 915.714041,-0.2817 -4.4837,-7.7628 -453.6168,-785.12771 z m 0.01,20.7039 449.131641,777.3509 449.1317,777.36651 -897.784261,0.2749 -897.784299,0.2764 448.65266,-777.6414 z"
|
||||||
|
id="path6909-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:#309ad1;fill-opacity:1;stroke:none;stroke-width:13.5155;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m 39.715889,413.33331 -539.934999,308.1506 -177.91181,-308.3326 359.0808,-621.5809 358.766009,0.089 z"
|
||||||
|
id="path4828-4-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cccccc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:#309ad1;fill-opacity:1;stroke:none;stroke-width:13.5155;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m 46.454799,413.33331 3.10118,-621.67271 355.980061,0.091 358.7645,621.76371 -179.4599,310.656 z"
|
||||||
|
id="path4828-4-8-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cccccc" />
|
||||||
|
<path
|
||||||
|
style="display:inline;fill:#309ad1;fill-opacity:1;stroke:none;stroke-width:13.5155;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m 42.642599,419.80591 536.833941,313.5219 -178.0684,308.24249 -717.84555,-0.1827 -179.30611,-310.74489 z"
|
||||||
|
id="path4828-4-8-1-6"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cccccc" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 4.6 KiB |
379
inkscape_drawings/print diameter.svg
Normal file
@ -0,0 +1,379 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<!-- Created with Inkscape (http://www.inkscape.org/) -->
|
||||||
|
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
width="210mm"
|
||||||
|
height="297mm"
|
||||||
|
viewBox="0 0 210 297"
|
||||||
|
version="1.1"
|
||||||
|
id="svg5151"
|
||||||
|
inkscape:version="0.92.5 (2060ec1f9f, 2020-04-08)"
|
||||||
|
sodipodi:docname="print diameter.svg">
|
||||||
|
<defs
|
||||||
|
id="defs5145">
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="ArrowDIN-start"
|
||||||
|
style="overflow:visible"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
orient="auto"
|
||||||
|
id="ArrowDIN-start-7-6">
|
||||||
|
<path
|
||||||
|
id="path13335-9-7"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="ArrowDIN-end"
|
||||||
|
style="overflow:visible"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
orient="auto"
|
||||||
|
id="ArrowDIN-end-1-8">
|
||||||
|
<path
|
||||||
|
id="path13338-7-5"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect7064-4-4"
|
||||||
|
is_visible="true" />
|
||||||
|
</defs>
|
||||||
|
<sodipodi:namedview
|
||||||
|
id="base"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
bordercolor="#666666"
|
||||||
|
borderopacity="1.0"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:zoom="1.1"
|
||||||
|
inkscape:cx="393.55778"
|
||||||
|
inkscape:cy="649.164"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:current-layer="layer1"
|
||||||
|
showgrid="false"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
inkscape:window-height="950"
|
||||||
|
inkscape:window-x="-9"
|
||||||
|
inkscape:window-y="-9"
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
showguides="false"
|
||||||
|
showborder="false" />
|
||||||
|
<metadata
|
||||||
|
id="metadata5148">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title />
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
inkscape:label="Layer 1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
id="layer1">
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="ccccccc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path4828-5-6-3-8"
|
||||||
|
d="M 13.04691,165.85962 89.253593,38.093669 h 27.365457 l 72.55757,127.765951 -13.68272,23.7127 H 26.729669 Z"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#17796d;stroke-width:2.16399193;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6"
|
||||||
|
d="M 142.27061,106.13961 114.28983,38.60343"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#5cd680;stroke-width:0.327;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-2"
|
||||||
|
d="M 118.97488,106.14697 90.989276,38.60343"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#5cd680;stroke-width:0.327;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-2-6"
|
||||||
|
d="m 131.26874,130.94101 44.65125,56.88145"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#5cd680;stroke-width:0.327;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-2-6-1"
|
||||||
|
d="m 143.64907,109.53659 43.9212,58.10699"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#5cd680;stroke-width:0.327;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-7-0"
|
||||||
|
d="M 116.60054,109.56839 14.577306,167.50043"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#5cd680;stroke-width:0.327;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-2-6-2"
|
||||||
|
d="M 128.95977,130.94101 26.227584,187.6793"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#5cd680;stroke-width:0.327;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<circle
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#000002;stroke-width:0.5;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:1,2;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path10008"
|
||||||
|
cx="101.16153"
|
||||||
|
cy="131.45352"
|
||||||
|
r="95.199142" />
|
||||||
|
<circle
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.5;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:1, 2;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path10008-7"
|
||||||
|
cx="101.6907"
|
||||||
|
cy="131.45352"
|
||||||
|
r="58.380852" />
|
||||||
|
<path
|
||||||
|
style="color:#000000;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:medium;line-height:normal;font-family:sans-serif;font-variant-ligatures:normal;font-variant-position:normal;font-variant-caps:normal;font-variant-numeric:normal;font-variant-alternates:normal;font-feature-settings:normal;text-indent:0;text-align:start;text-decoration:none;text-decoration-line:none;text-decoration-style:solid;text-decoration-color:#000000;letter-spacing:normal;word-spacing:normal;text-transform:none;writing-mode:lr-tb;direction:ltr;text-orientation:mixed;dominant-baseline:auto;baseline-shift:baseline;text-anchor:start;white-space:normal;shape-padding:0;clip-rule:nonzero;display:inline;overflow:visible;visibility:visible;opacity:1;isolation:auto;mix-blend-mode:normal;color-interpolation:sRGB;color-interpolation-filters:linearRGB;solid-color:#000000;solid-opacity:1;vector-effect:none;fill:none;fill-opacity:1;fill-rule:nonzero;stroke:#5cd680;stroke-width:1.08199596;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill;color-rendering:auto;image-rendering:auto;shape-rendering:auto;text-rendering:auto;enable-background:accumulate"
|
||||||
|
d="m 130.12344,132.97386 -7.7493,-13.4124 -7.7493,-13.41265 15.49034,-0.005 15.49034,-0.005 -7.74104,13.4174 z"
|
||||||
|
id="path6909-5-8"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="ccccccc" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-7-0-0-0"
|
||||||
|
d="M 130.17344,115.13706 114.6518,106.17564"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#5cd680;stroke-width:0.38026467;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-7-0-0-0-6"
|
||||||
|
d="m 130.08388,115.10023 15.52164,-8.96142"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#5cd680;stroke-width:0.38026467;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-7-0-0-0-6-4"
|
||||||
|
d="m 130.08388,115.10023 v 17.92284"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#5cd680;stroke-width:0.38026467;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<circle
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.5;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path10008-7-8"
|
||||||
|
cx="101.16153"
|
||||||
|
cy="131.45352"
|
||||||
|
r="33.054626" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-7-0-0-0-6-4-1"
|
||||||
|
d="M 114.28983,38.724479 V 67.89781"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#4e2082;stroke-width:0.327;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-880.51675,-196.99059)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRoot8810-6-97"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-7-0"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-8"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1">angle</flowPara></flowRoot> <path
|
||||||
|
style="fill:none;stroke:#00000e;stroke-width:10;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-7-6);marker-end:url(#ArrowDIN-end-1-8)"
|
||||||
|
d="m -10229.879,4037.4811 c 35.622,-35.4133 67.401,-74.6903 94.598,-116.9199 31.349,-48.6752 56.6,-101.2728 74.978,-156.1752"
|
||||||
|
id="path7062-2-1"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
inkscape:path-effect="#path-effect7064-4-4"
|
||||||
|
inkscape:original-d="m -10229.879,4037.4811 c -63.679,109.5098 148.044,-293.0376 94.598,-116.9199 -55.619,183.2769 -84.875,-125.3076 74.978,-156.1752"
|
||||||
|
transform="matrix(0.01282356,0.01737065,-0.01737065,0.01282356,317.13947,189.29821)"
|
||||||
|
sodipodi:nodetypes="csc" />
|
||||||
|
<g
|
||||||
|
id="g10395"
|
||||||
|
transform="translate(-106.79545,-27.78125)">
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-97-3"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-821.96199,-196.88819)"><flowRegion
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRegion8812-7-0-9"><rect
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="rect8814-2-8-0"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4">d</flowPara></flowRoot> <flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-97-3-6"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-820.27904,-195.5652)"><flowRegion
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRegion8812-7-0-9-5"><rect
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="rect8814-2-8-0-5"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-5">1</flowPara></flowRoot> </g>
|
||||||
|
<g
|
||||||
|
transform="translate(-91.54589,5.9570615)"
|
||||||
|
id="g10480">
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-97-3-4"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-821.96199,-196.88819)"><flowRegion
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRegion8812-7-0-9-6"><rect
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="rect8814-2-8-0-0"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-4">d</flowPara></flowRoot> <flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-97-3-6-1"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-820.27904,-195.5652)"><flowRegion
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRegion8812-7-0-9-5-3"><rect
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="rect8814-2-8-0-5-7"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-5-7">2</flowPara></flowRoot> </g>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-909.27618,-174.36988)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRoot8810-6-97-3-4-7"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-7-0-9-6-9"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-8-0-0-1"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-4-3">d</flowPara></flowRoot> <flowRoot
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-907.59324,-173.04689)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRoot8810-6-97-3-6-1-3"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-7-0-9-5-3-7"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-8-0-5-7-6"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-5-7-6">3</flowPara></flowRoot> <path
|
||||||
|
style="color:#000000;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:medium;line-height:normal;font-family:sans-serif;font-variant-ligatures:normal;font-variant-position:normal;font-variant-caps:normal;font-variant-numeric:normal;font-variant-alternates:normal;font-feature-settings:normal;text-indent:0;text-align:start;text-decoration:none;text-decoration-line:none;text-decoration-style:solid;text-decoration-color:#000000;letter-spacing:normal;word-spacing:normal;text-transform:none;writing-mode:lr-tb;direction:ltr;text-orientation:mixed;dominant-baseline:auto;baseline-shift:baseline;text-anchor:start;white-space:normal;shape-padding:0;clip-rule:nonzero;display:inline;overflow:visible;visibility:visible;opacity:1;isolation:auto;mix-blend-mode:normal;color-interpolation:sRGB;color-interpolation-filters:linearRGB;solid-color:#000000;solid-opacity:1;vector-effect:none;fill:none;fill-opacity:1;fill-rule:nonzero;stroke:#ff2082;stroke-width:1.08199599;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:2.16399198, 2.16399198000000004;stroke-dashoffset:0;stroke-opacity:0.72941178;paint-order:stroke markers fill;color-rendering:auto;image-rendering:auto;shape-rendering:auto;text-rendering:auto;enable-background:accumulate"
|
||||||
|
d="m 137.47125,128.71179 -7.7493,-13.4124 -7.7493,-13.41265 15.49034,-0.005 15.49034,-0.005 -7.74104,13.4174 z"
|
||||||
|
id="path6909-5-8-1"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="ccccccc" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-7-0-0-0-0"
|
||||||
|
d="m 137.52125,110.87499 -15.52164,-8.96142"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:0.38;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:0.76, 1.52000000000000002;stroke-opacity:0.72941178;stroke-dashoffset:0" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-7-0-0-0-6-0"
|
||||||
|
d="m 137.43169,110.83816 15.52164,-8.96142"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:0.38026467;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:0.76052935, 1.52105869000000005;stroke-opacity:0.72941178;stroke-dashoffset:0" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-7-0-0-0-6-4-8"
|
||||||
|
d="M 137.43169,110.83816 V 128.761"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:0.38026467;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:0.76052935, 1.52105869000000005;stroke-opacity:0.72941178;stroke-dashoffset:0" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-27"
|
||||||
|
d="M 149.74237,101.37678 114.28732,38.721961"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:0.38;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:0.76, 1.52000000000000002;stroke-opacity:1;stroke-dashoffset:0" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-27-5"
|
||||||
|
d="M 187.57213,167.64545 151.97626,104.74177"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:0.38;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:0.76, 1.52000000000000002;stroke-opacity:1;stroke-dashoffset:0" />
|
||||||
|
<circle
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.5;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path10008-7-8-0"
|
||||||
|
cx="101.16153"
|
||||||
|
cy="131.45352"
|
||||||
|
r="41.610188" />
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-904.72046,-166.73898)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRoot8810-6-97-3-4-7-3"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-7-0-9-6-9-9"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-8-0-0-1-8"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-4-3-8">d</flowPara></flowRoot> <flowRoot
|
||||||
|
transform="matrix(0.07505191,0,0,0.07505191,-903.03753,-165.41598)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#00000e;stroke-opacity:1"
|
||||||
|
id="flowRoot8810-6-97-3-6-1-3-5"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-7-0-9-5-3-7-7"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-8-0-5-7-6-1"
|
||||||
|
style="stroke:#00000e;stroke-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-1-4-5-7-6-9">4</flowPara></flowRoot> <path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-27-6"
|
||||||
|
d="M 126.44433,101.25825 90.989276,38.60343"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:0.38;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:0.76, 1.52000000000000002;stroke-opacity:1;stroke-dashoffset:0" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-27-5-3"
|
||||||
|
d="M 175.91999,187.82246 140.32412,124.91878"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:0.38;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:0.76, 1.52000000000000002;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path912-7-7-6-7-0-4"
|
||||||
|
d="m 123.86711,105.4422 -7.26657,4.12619"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:0.38;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:0.76, 1.52000000000000002;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path10667"
|
||||||
|
d="m 136.22634,126.81482 -7.26657,4.12619"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#ff2082;stroke-width:0.38;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:0.76, 1.52000000000000002;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 21 KiB |
181
inkscape_drawings/print volume-shapes.svg
Normal file
@ -0,0 +1,181 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<!-- Created with Inkscape (http://www.inkscape.org/) -->
|
||||||
|
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
width="281.76974mm"
|
||||||
|
height="137.57664mm"
|
||||||
|
viewBox="0 0 281.76975 137.57664"
|
||||||
|
version="1.1"
|
||||||
|
id="svg8"
|
||||||
|
inkscape:version="0.92.5 (2060ec1f9f, 2020-04-08)"
|
||||||
|
sodipodi:docname="print volume.svg">
|
||||||
|
<defs
|
||||||
|
id="defs2">
|
||||||
|
<inkscape:path-effect
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect1000"
|
||||||
|
is_visible="true" />
|
||||||
|
<inkscape:perspective
|
||||||
|
sodipodi:type="inkscape:persp3d"
|
||||||
|
inkscape:vp_x="0 : 148.49998 : 1"
|
||||||
|
inkscape:vp_y="0 : 999.99992 : 0"
|
||||||
|
inkscape:vp_z="210.00001 : 148.49998 : 1"
|
||||||
|
inkscape:persp3d-origin="105 : 98.999992 : 1"
|
||||||
|
id="perspective926" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect839"
|
||||||
|
is_visible="true" />
|
||||||
|
</defs>
|
||||||
|
<sodipodi:namedview
|
||||||
|
id="base"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
bordercolor="#666666"
|
||||||
|
borderopacity="1.0"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:zoom="0.7"
|
||||||
|
inkscape:cx="477.16853"
|
||||||
|
inkscape:cy="212.76487"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:current-layer="g1010"
|
||||||
|
showgrid="false"
|
||||||
|
fit-margin-top="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
showborder="false"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
inkscape:window-height="950"
|
||||||
|
inkscape:window-x="-9"
|
||||||
|
inkscape:window-y="-9"
|
||||||
|
inkscape:window-maximized="1" />
|
||||||
|
<metadata
|
||||||
|
id="metadata5">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
inkscape:label="Ebene 1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
id="layer1"
|
||||||
|
transform="translate(-55.532538,6.6791818)">
|
||||||
|
<g
|
||||||
|
id="g954"
|
||||||
|
transform="translate(0.96555799,-6.7551595)">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path826"
|
||||||
|
d="M 192.89802,7.6108973 211.04088,136.68976 238.06617,114.01119 Z"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
sodipodi:nodetypes="cccc" />
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path828"
|
||||||
|
d="M 211.04088,136.68976 153.02153,123.64958 192.89802,7.6108973"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
sodipodi:nodetypes="ccc" />
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path830"
|
||||||
|
d="m 153.02153,123.64958 85.04464,-9.63839"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:3.00000008, 3.00000008;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
id="g949"
|
||||||
|
transform="translate(0,4.4565659)">
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837"
|
||||||
|
d="M 96.005952,-11.050597 C 95.155257,36.359034 110.42288,118.94994 127.37798,125.96577"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837-9"
|
||||||
|
d="M 96.005952,-11.050597 C 103.14693,30.268273 120.17333,93.540616 138.33929,96.105651"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837-4"
|
||||||
|
d="m 138.33929,96.105651 c -7.65427,3.375404 -12.41938,15.851739 -10.96131,29.860119"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837-4-7"
|
||||||
|
d="m 127.37798,125.96577 c -23.71826,-7.7749 -38.877716,-8.9057 -71.437501,-5.29167"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837-4-7-7"
|
||||||
|
d="M 96.005952,-11.050597 C 90.997519,46.564386 82.07467,83.798164 55.940479,120.6741"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837-4-7-7-1"
|
||||||
|
d="M 138.33929,96.105651 C 110.46329,109.49742 95.114848,114.79222 55.940479,120.6741"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:3.00000008, 3.00000008;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
id="g1010">
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="csc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path956"
|
||||||
|
d="m 255.0485,6.5032805 c 0,-4.4964 18.3012,-8.14146 40.87689,-8.14146 22.57567,0 40.87688,3.64506 40.87688,8.14146"
|
||||||
|
style="fill:#ffffff;fill-opacity:0.66408273;stroke:#000000;stroke-width:1.00000003;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="csc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path956-5"
|
||||||
|
d="m 255.0485,6.5032805 c 0,4.4963995 18.30121,8.1414595 40.87689,8.1414595 22.57568,0 40.87689,-3.64506 40.87689,-8.1414595"
|
||||||
|
style="fill:#ffffff;fill-opacity:0.66408273;stroke:#000000;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="csc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path956-2"
|
||||||
|
d="m 255.0485,122.256 c 0,-4.4964 18.3012,-8.14146 40.87688,-8.14146 22.57568,0 40.87689,3.64506 40.87689,8.14146"
|
||||||
|
style="fill:#ffffff;fill-opacity:0.66408273;stroke:#000000;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:3.00000011, 3.00000011;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="csc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path956-5-5"
|
||||||
|
d="m 255.0485,122.256 c 0,4.4964 18.30121,8.14146 40.87689,8.14146 22.57568,0 40.87689,-3.64506 40.87689,-8.14146"
|
||||||
|
style="fill:#ffffff;fill-opacity:0.66408273;stroke:#000000;stroke-width:1;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
transform="translate(195.79167,-177.64881)"
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:original-d="m 141.01061,184.15209 c 2.6e-4,27.29501 2.6e-4,88.45716 0,115.75272"
|
||||||
|
inkscape:path-effect="#path-effect1000"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path998"
|
||||||
|
d="M 141.01061,184.15209 V 299.90481"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path1002"
|
||||||
|
d="M 255.0485,6.5032805 V 122.256"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 8.2 KiB |
975
inkscape_drawings/random-positions.svg
Normal file
@ -0,0 +1,975 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
sodipodi:docname="random-positions.svg"
|
||||||
|
inkscape:version="1.0 (4035a4fb49, 2020-05-01)"
|
||||||
|
id="svg8"
|
||||||
|
version="1.1"
|
||||||
|
viewBox="0 0 100.00001 85.716865"
|
||||||
|
height="85.716866mm"
|
||||||
|
width="100.00001mm">
|
||||||
|
<defs
|
||||||
|
id="defs2">
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect1225"
|
||||||
|
is_visible="true" />
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="ArrowDIN-start"
|
||||||
|
style="overflow:visible"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
orient="auto"
|
||||||
|
id="ArrowDIN-start-7-6">
|
||||||
|
<path
|
||||||
|
id="path13335-9-7"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="ArrowDIN-end"
|
||||||
|
style="overflow:visible"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
orient="auto"
|
||||||
|
id="ArrowDIN-end-1-8">
|
||||||
|
<path
|
||||||
|
id="path13338-7-5"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect7064-4-4"
|
||||||
|
is_visible="true" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect1225-5"
|
||||||
|
is_visible="true" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect1225-9"
|
||||||
|
is_visible="true" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect1225-9-8"
|
||||||
|
is_visible="true" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-9"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-7"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-7"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-9-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-7-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-7-2"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-5-7"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-76"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-53"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-8-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-76-7"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-8-0"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-53-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-8-0"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-76-0"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-8-4"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-53-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-8-5-2"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-7-76-7-6"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-8-0-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-0-53-9-8"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lend"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker1150"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path1148"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(-0.8,0,0,-0.8,-10,0)" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lend"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="Arrow1Lend"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path829"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(-0.8,0,0,-0.8,-10,0)" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="ArrowDIN-start"
|
||||||
|
style="overflow:visible"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
orient="auto"
|
||||||
|
id="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
id="path13335"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="ArrowDIN-end"
|
||||||
|
style="overflow:visible"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
orient="auto"
|
||||||
|
id="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
id="path13338"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect7064"
|
||||||
|
is_visible="true" />
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="ArrowDIN-start"
|
||||||
|
style="overflow:visible"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
orient="auto"
|
||||||
|
id="ArrowDIN-start-7">
|
||||||
|
<path
|
||||||
|
id="path13335-9"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="ArrowDIN-end"
|
||||||
|
style="overflow:visible"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
orient="auto"
|
||||||
|
id="ArrowDIN-end-1">
|
||||||
|
<path
|
||||||
|
id="path13338-7"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect7064-4"
|
||||||
|
is_visible="true" />
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="ArrowDIN-start"
|
||||||
|
style="overflow:visible"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
orient="auto"
|
||||||
|
id="ArrowDIN-start-7-6-5">
|
||||||
|
<path
|
||||||
|
id="path13335-9-7-2"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="ArrowDIN-end"
|
||||||
|
style="overflow:visible"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
orient="auto"
|
||||||
|
id="ArrowDIN-end-1-8-0">
|
||||||
|
<path
|
||||||
|
id="path13338-7-5-7"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="ArrowDIN-start"
|
||||||
|
style="overflow:visible"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
orient="auto"
|
||||||
|
id="ArrowDIN-start-7-4">
|
||||||
|
<path
|
||||||
|
id="path13335-9-6"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="ArrowDIN-end"
|
||||||
|
style="overflow:visible"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
orient="auto"
|
||||||
|
id="ArrowDIN-end-1-6">
|
||||||
|
<path
|
||||||
|
id="path13338-7-9"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect7064-4-5"
|
||||||
|
is_visible="true" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1-0"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-62"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-17"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-7-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-4" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-1-8-7"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-7-6" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-9"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-4" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-58"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-6" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-71"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-379" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-24" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-1"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-9-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-5-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="Arrow1Lstart-3-4"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lstart">
|
||||||
|
<path
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
style="fill:#ff0000;fill-opacity:1;fill-rule:evenodd;stroke:#ff0000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path15451-1-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lstart"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker21821"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path21819"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lstart"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker21821-0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path21819-2"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1-5-9"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3-2-5" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-9-3-5-4"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-5-1-9-4"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1-2-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3-8-3" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3-2" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-9-3-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-5-1-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="Arrow1Lstart-3-4-5"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lstart">
|
||||||
|
<path
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
style="fill:#ff0000;fill-opacity:1;fill-rule:evenodd;stroke:#ff0000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path15451-1-1-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1-2"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3-8" />
|
||||||
|
</marker>
|
||||||
|
</defs>
|
||||||
|
<sodipodi:namedview
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
inkscape:window-y="-8"
|
||||||
|
inkscape:window-x="-8"
|
||||||
|
inkscape:window-height="976"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
showborder="false"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-top="0"
|
||||||
|
showgrid="false"
|
||||||
|
inkscape:document-rotation="0"
|
||||||
|
inkscape:current-layer="layer1"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:cy="133.80603"
|
||||||
|
inkscape:cx="209.20221"
|
||||||
|
inkscape:zoom="0.98994949"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
borderopacity="1.0"
|
||||||
|
bordercolor="#666666"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
id="base" />
|
||||||
|
<metadata
|
||||||
|
id="metadata5">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
transform="translate(5191.5128,2422.0038)"
|
||||||
|
id="layer1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
inkscape:label="Layer 1">
|
||||||
|
<g
|
||||||
|
transform="translate(-722.47255,-669.94263)"
|
||||||
|
id="g1326" />
|
||||||
|
<g
|
||||||
|
transform="matrix(5.228688e-4,0,0,5.228688e-4,-4885.4099,-2154.753)"
|
||||||
|
id="g5013">
|
||||||
|
<g
|
||||||
|
id="g949"
|
||||||
|
transform="matrix(1060.2576,0,0,1060.2576,-586017.24,-491428.98)">
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837"
|
||||||
|
d="M 96.005952,-11.050597 C 95.155257,36.359034 110.42288,118.94994 127.37798,125.96577"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837-9"
|
||||||
|
d="M 96.005952,-11.050597 C 103.14693,30.268273 120.17333,93.540616 138.33929,96.105651"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837-4"
|
||||||
|
d="m 138.33929,96.105651 c -7.65427,3.375404 -12.41938,15.851739 -10.96131,29.860119"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837-4-7"
|
||||||
|
d="m 127.37798,125.96577 c -23.71826,-7.7749 -38.877716,-8.9057 -71.437501,-5.29167"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837-4-7-7"
|
||||||
|
d="M 96.005952,-11.050597 C 90.997519,46.564386 82.07467,83.798164 55.940479,120.6741"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path837-4-7-7-1"
|
||||||
|
d="M 138.33929,96.105651 C 110.46329,109.49742 95.114848,114.79222 55.940479,120.6741"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:3, 3;stroke-dashoffset:0;stroke-opacity:1" />
|
||||||
|
</g>
|
||||||
|
<circle
|
||||||
|
transform="rotate(59.999989)"
|
||||||
|
r="1281.9651"
|
||||||
|
cy="275153.31"
|
||||||
|
cx="-578671.56"
|
||||||
|
id="path7360-7-5-4-3"
|
||||||
|
style="fill:#00ad00;fill-opacity:1;stroke:none;stroke-width:255.937;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<circle
|
||||||
|
transform="rotate(59.999989)"
|
||||||
|
r="1281.9651"
|
||||||
|
cy="184870.39"
|
||||||
|
cx="-556433.06"
|
||||||
|
id="path7360-7-8-9-0-2-3"
|
||||||
|
style="fill:#a900a6;fill-opacity:1;stroke:none;stroke-width:255.937;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<circle
|
||||||
|
transform="rotate(59.999989)"
|
||||||
|
r="1281.9651"
|
||||||
|
cy="211833.45"
|
||||||
|
cx="-534910.56"
|
||||||
|
id="path7360-7-8-1-5-4-8"
|
||||||
|
style="fill:#4e6ab4;fill-opacity:1;stroke:none;stroke-width:255.937;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(138.07627,0.07545793,-0.07545793,138.07627,-2294435.9,-834637.13)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#4e6ab4;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-6-7-7-50-1-8"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
style="fill:#4e6ab4;fill-opacity:1"
|
||||||
|
id="flowRegion8812-7-9-1-5-9-0"><rect
|
||||||
|
style="fill:#4e6ab4;fill-opacity:1"
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-7-8-2-8-1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-5-8">A anchor point</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(138.07628,0.05186067,-0.05186067,138.07628,-2374401.8,-839444.25)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#00ad00;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-6-7-7-50-4-6-2"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
style="fill:#00ad00;fill-opacity:1"
|
||||||
|
id="flowRegion8812-7-9-1-5-7-2-9"><rect
|
||||||
|
style="fill:#00ad00;fill-opacity:1"
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-7-8-2-0-2-7" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-9-2-7">C anchor point</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(138.07528,0.52780506,-0.52780506,138.07528,-2264914.3,-879751.96)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#a900a6;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-6-7-7-50-4-7-0-2"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
style="fill:#a900a6;fill-opacity:1"
|
||||||
|
id="flowRegion8812-7-9-1-5-7-9-4-4"><rect
|
||||||
|
style="fill:#a900a6;fill-opacity:1"
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-7-8-2-0-0-3-0" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-9-3-9-7">B anchor point</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(146.1374,0,0,146.1374,-2372889.3,-895901.91)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-95-8-3"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-5-33-4"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-0-3-6"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8816-1-4-9">X</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(146.1374,0,0,146.1374,-2462720.2,-914442.82)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-95-3-7-8"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-5-3-7-4"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-0-7-4-3"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8816-1-7-2-1">Y</flowPara></flowRoot>
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15449-3-0"
|
||||||
|
d="m -484068.71,-423971.69 v 55706.57"
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:536.322;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-1-5)" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15449-4-3-4"
|
||||||
|
d="m -516821.86,-398019.45 32753.15,29754.33"
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:536.322;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-9-3-5)" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path8808-3-5-4-9-8"
|
||||||
|
d="m -480250.19,-400049.1 -41277.41,8616.18"
|
||||||
|
style="fill:none;stroke:#ff0000;stroke-width:89.0499;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#Arrow1Lstart-3-4-5)" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15371-4-8-8"
|
||||||
|
d="m -480250.19,-400049.1 -46455.71,36565.74"
|
||||||
|
style="fill:none;stroke:#00ad00;stroke-width:593.663;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15371-6-1-0-6-7"
|
||||||
|
d="m -450963.76,-357872.79 -29286.43,-42176.31"
|
||||||
|
style="fill:none;stroke:#4963a8;stroke-width:593.663;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path8766-1-9-6-3-8-0"
|
||||||
|
d="m -439341.96,-389532.19 -40908.23,-10516.91"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#a900a6;stroke-width:593.663;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path8650-5"
|
||||||
|
d="m -484226.14,-503145.47 3975.95,103096.37"
|
||||||
|
style="fill:none;stroke:#bf4b00;stroke-width:636.156;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||||
|
<circle
|
||||||
|
transform="rotate(59.999989)"
|
||||||
|
r="1281.9651"
|
||||||
|
cy="167946.14"
|
||||||
|
cx="-677805.5"
|
||||||
|
id="path7360-7-8-9-0-2-9"
|
||||||
|
style="fill:#bf4b00;fill-opacity:1;stroke:none;stroke-width:255.937;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(138.07528,0.52780506,-0.52780506,138.07528,-2323252.1,-999310.73)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#bf4b00;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-6-7-7-50-4-7-0-7"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
style="fill:#bf4b00;fill-opacity:1"
|
||||||
|
id="flowRegion8812-7-9-1-5-7-9-4-2"><rect
|
||||||
|
style="fill:#bf4b00;fill-opacity:1"
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-7-8-2-0-0-3-7" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-7-22-2-9-3-9-1">D anchor point</flowPara></flowRoot>
|
||||||
|
<path
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
id="path15449-3-2"
|
||||||
|
d="m -437525.62,-384216.7 -46543.09,15951.58"
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:536.322;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-1-2)" />
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(146.1374,0,0,146.1374,-2425962.3,-942035.34)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-95-8-6"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
id="flowRegion8812-5-33-8"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-0-3-3"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8816-1-4-6">Z</flowPara></flowRoot>
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-9-3-86"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(139.01732,0,0,139.01732,-2430335.1,-879747.6)"><flowRegion
|
||||||
|
id="flowRegion8812-7-1-2-92"><rect
|
||||||
|
id="rect8814-2-3-2-49"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762" /></flowRegion><flowPara
|
||||||
|
id="flowPara5676">nozzle tip with effector</flowPara><flowPara
|
||||||
|
id="flowPara5680">at random position</flowPara></flowRoot>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 33 KiB |
718
inkscape_drawings/spool-buildup.svg
Normal file
@ -0,0 +1,718 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<!-- Created with Inkscape (http://www.inkscape.org/) -->
|
||||||
|
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
width="45.320217mm"
|
||||||
|
height="46.709221mm"
|
||||||
|
viewBox="0 0 45.320217 46.709221"
|
||||||
|
version="1.1"
|
||||||
|
id="svg8"
|
||||||
|
inkscape:version="0.92.5 (2060ec1f9f, 2020-04-08)"
|
||||||
|
sodipodi:docname="spool buildup.svg">
|
||||||
|
<defs
|
||||||
|
id="defs2">
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-2"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-4"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-5-9"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-2-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-3-4"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-4-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-5-7"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-2-95"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-3-2"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-4-8"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-2"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-5"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-8"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-2-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-5-0"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-6-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-8-7"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
</defs>
|
||||||
|
<sodipodi:namedview
|
||||||
|
id="base"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
bordercolor="#666666"
|
||||||
|
borderopacity="1.0"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:zoom="2.8"
|
||||||
|
inkscape:cx="41.220153"
|
||||||
|
inkscape:cy="76.059299"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:current-layer="g5446-4-3-5"
|
||||||
|
showgrid="false"
|
||||||
|
fit-margin-top="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
showborder="false"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
inkscape:window-height="976"
|
||||||
|
inkscape:window-x="-8"
|
||||||
|
inkscape:window-y="-8"
|
||||||
|
inkscape:window-maximized="1" />
|
||||||
|
<metadata
|
||||||
|
id="metadata5">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
inkscape:label="Layer 1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
id="layer1"
|
||||||
|
transform="translate(-40.151262,-104.4964)">
|
||||||
|
<rect
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.30000001;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="rect4747"
|
||||||
|
width="19.773357"
|
||||||
|
height="28.476133"
|
||||||
|
x="43.367786"
|
||||||
|
y="113.80679" />
|
||||||
|
<rect
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.30000001;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="rect4747-4"
|
||||||
|
width="2.906405"
|
||||||
|
height="46.021515"
|
||||||
|
x="40.301262"
|
||||||
|
y="105.0341" />
|
||||||
|
<rect
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.30000001;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="rect4747-4-9"
|
||||||
|
width="2.906405"
|
||||||
|
height="46.021515"
|
||||||
|
x="63.301262"
|
||||||
|
y="105.0341" />
|
||||||
|
<ellipse
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.156;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797"
|
||||||
|
cx="44.2813"
|
||||||
|
cy="112.75107"
|
||||||
|
rx="0.82201707"
|
||||||
|
ry="0.82201701" />
|
||||||
|
<ellipse
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.156;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0"
|
||||||
|
cx="47.70224"
|
||||||
|
cy="112.75107"
|
||||||
|
rx="0.82201713"
|
||||||
|
ry="0.82201707" />
|
||||||
|
<ellipse
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.156;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-4"
|
||||||
|
cx="51.672501"
|
||||||
|
cy="112.75107"
|
||||||
|
rx="0.82201719"
|
||||||
|
ry="0.82201713" />
|
||||||
|
<ellipse
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.156;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-5"
|
||||||
|
cx="55.681541"
|
||||||
|
cy="112.75107"
|
||||||
|
rx="0.82201719"
|
||||||
|
ry="0.82201713" />
|
||||||
|
<ellipse
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.156;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49"
|
||||||
|
cx="60.35339"
|
||||||
|
cy="112.75107"
|
||||||
|
rx="0.82201719"
|
||||||
|
ry="0.82201713" />
|
||||||
|
<ellipse
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-1"
|
||||||
|
cx="49.565735"
|
||||||
|
cy="112.75107"
|
||||||
|
rx="0.82201719"
|
||||||
|
ry="0.82201713" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-4-8"
|
||||||
|
cx="53.535995"
|
||||||
|
cy="112.75107" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-5-8"
|
||||||
|
cx="58.074203"
|
||||||
|
cy="112.75107" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5"
|
||||||
|
cx="62.216885"
|
||||||
|
cy="112.75107" />
|
||||||
|
<ellipse
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-5"
|
||||||
|
cx="-62.25465"
|
||||||
|
cy="-143.3367"
|
||||||
|
rx="0.82201713"
|
||||||
|
ry="0.82201707"
|
||||||
|
transform="scale(-1)" />
|
||||||
|
<ellipse
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-7"
|
||||||
|
cx="-59.89204"
|
||||||
|
cy="-143.3367"
|
||||||
|
rx="0.82201719"
|
||||||
|
ry="0.82201713"
|
||||||
|
transform="scale(-1)" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-4-9"
|
||||||
|
cx="-55.392612"
|
||||||
|
cy="-143.3367"
|
||||||
|
transform="scale(-1)" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-5-3"
|
||||||
|
cx="-50.325237"
|
||||||
|
cy="-143.3367"
|
||||||
|
transform="scale(-1)" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-6"
|
||||||
|
cx="-46.18256"
|
||||||
|
cy="-143.3367"
|
||||||
|
transform="scale(-1)" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-1-2"
|
||||||
|
cx="-57.499378"
|
||||||
|
cy="-143.3367"
|
||||||
|
transform="scale(-1)" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-4-8-2"
|
||||||
|
cx="-53.529118"
|
||||||
|
cy="-143.3367"
|
||||||
|
transform="scale(-1)" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-5-8-0"
|
||||||
|
cx="-48.461742"
|
||||||
|
cy="-143.3367"
|
||||||
|
transform="scale(-1)" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5-0"
|
||||||
|
cx="-44.319065"
|
||||||
|
cy="-143.3367"
|
||||||
|
transform="scale(-1)" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5-3"
|
||||||
|
cx="61.279388"
|
||||||
|
cy="111.27195" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5-3-0"
|
||||||
|
cx="59.247768"
|
||||||
|
cy="111.5318" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5-3-0-3"
|
||||||
|
cx="56.814548"
|
||||||
|
cy="111.57906" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5-3-0-9"
|
||||||
|
cx="54.570312"
|
||||||
|
cy="111.41369" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5-3-0-98"
|
||||||
|
cx="52.562313"
|
||||||
|
cy="111.34282" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5-3-0-98-6"
|
||||||
|
cx="50.625183"
|
||||||
|
cy="111.39007" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5-3-0-98-6-0"
|
||||||
|
cx="45.971352"
|
||||||
|
cy="112.61849" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5-3-0-98-6-0-3"
|
||||||
|
cx="48.617188"
|
||||||
|
cy="111.29557" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5-3-0-98-6-0-31"
|
||||||
|
cx="61.06678"
|
||||||
|
cy="144.47717" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5-3-0-98-6-0-31-4"
|
||||||
|
cx="58.70443"
|
||||||
|
cy="144.58109" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5-3-0-98-6-0-31-4-0"
|
||||||
|
cx="54.452194"
|
||||||
|
cy="144.77008" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5-3-0-98-6-0-31-4-0-9"
|
||||||
|
cx="51.877232"
|
||||||
|
cy="143.91963" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5-3-0-98-6-0-31-4-0-9-7"
|
||||||
|
cx="49.420387"
|
||||||
|
cy="144.72284" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5-3-0-98-6-0-31-4-0-9-7-9"
|
||||||
|
cx="47.247025"
|
||||||
|
cy="144.60472" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5-3-0-98-6-0-31-4-0-9-7-4"
|
||||||
|
cx="45.215401"
|
||||||
|
cy="144.72285" />
|
||||||
|
<circle
|
||||||
|
r="0.82201719"
|
||||||
|
style="opacity:1;fill:none;fill-opacity:1;stroke:#bbab00;stroke-width:0.15600002;stroke-linecap:round;stroke-linejoin:bevel;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
id="path4797-0-49-5-3-0-98-6-0-31-4-0-9-7-94"
|
||||||
|
cx="56.412949"
|
||||||
|
cy="144.65196" />
|
||||||
|
<path
|
||||||
|
id="path13664-8-8-6-4"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:0.09293991;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-02-8-4-8);marker-end:url(#ArrowDIN-end-6-8-9-3)"
|
||||||
|
d="m 53.179964,114.69603 2.84e-4,26.69132"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<g
|
||||||
|
style="fill:#000000;fill-opacity:1"
|
||||||
|
transform="matrix(0.22505474,0,0,0.22505474,62.812365,84.373051)"
|
||||||
|
id="g5446">
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-1-4-3-3-60-9-4-9"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(0.21691896,0,0,0.21691896,-2803.3268,-662.92462)"><flowRegion
|
||||||
|
id="flowRegion8812-7-2-4-0-4-2-4-2-4"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-78-2-1-7-6-3-8-2"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-0-0-9-7-47-8-8-3">d</flowPara></flowRoot> <flowRoot
|
||||||
|
inkscape:transform-center-x="-8.2682291"
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-1-4-3-3-5-7-9-8-2"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(0.21691896,0,0,0.21691896,-2796.2293,-658.91469)"><flowRegion
|
||||||
|
id="flowRegion8812-7-2-4-0-4-9-77-1-8-0"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-78-2-1-7-2-3-3-3-6"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-0-0-9-7-1-6-1-2-5">line</flowPara></flowRoot> </g>
|
||||||
|
<g
|
||||||
|
transform="matrix(0.22505474,0,0,0.22505474,33.837721,83.583174)"
|
||||||
|
id="g5446-4"
|
||||||
|
style="fill:#000000;fill-opacity:1">
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-1-4-3-3-60-9-4-9-4"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(0.21691896,0,0,0.21691896,-2803.3268,-662.92462)"><flowRegion
|
||||||
|
id="flowRegion8812-7-2-4-0-4-2-4-2-4-9"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-78-2-1-7-6-3-8-2-7"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-0-0-9-7-47-8-8-3-8">b</flowPara></flowRoot> <flowRoot
|
||||||
|
inkscape:transform-center-x="-8.2682291"
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-1-4-3-3-5-7-9-8-2-9"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(0.21691896,0,0,0.21691896,-2798.5806,-658.91469)"><flowRegion
|
||||||
|
id="flowRegion8812-7-2-4-0-4-9-77-1-8-0-2"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-78-2-1-7-2-3-3-3-6-1"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-0-0-9-7-1-6-1-2-5-3">coil</flowPara></flowRoot> </g>
|
||||||
|
<g
|
||||||
|
transform="matrix(0.22505474,0,0,0.22505474,36.747028,105.83098)"
|
||||||
|
id="g5446-4-3"
|
||||||
|
style="fill:#000000;fill-opacity:1">
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-1-4-3-3-60-9-4-9-4-5"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(0.21691896,0,0,0.21691896,-2803.3268,-662.92462)"><flowRegion
|
||||||
|
id="flowRegion8812-7-2-4-0-4-2-4-2-4-9-8"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-78-2-1-7-6-3-8-2-7-1"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-0-0-9-7-47-8-8-3-8-2">d</flowPara></flowRoot> <flowRoot
|
||||||
|
inkscape:transform-center-x="-8.2682291"
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-1-4-3-3-5-7-9-8-2-9-0"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(0.21691896,0,0,0.21691896,-2798.5806,-658.91469)"><flowRegion
|
||||||
|
id="flowRegion8812-7-2-4-0-4-9-77-1-8-0-2-6"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-78-2-1-7-2-3-3-3-6-1-5"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-0-0-9-7-1-6-1-2-5-3-7">coil</flowPara></flowRoot> </g>
|
||||||
|
<g
|
||||||
|
transform="matrix(0.22505474,0,0,0.22505474,59.228326,90.33173)"
|
||||||
|
id="g5446-5"
|
||||||
|
style="fill:#000000;fill-opacity:1">
|
||||||
|
<flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-1-4-3-3-60-9-4-9-8"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(0.21691896,0,0,0.21691896,-2803.3268,-663.51841)"><flowRegion
|
||||||
|
id="flowRegion8812-7-2-4-0-4-2-4-2-4-0"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-78-2-1-7-6-3-8-2-72"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-0-0-9-7-47-8-8-3-6">winding 1</flowPara></flowRoot> <flowRoot
|
||||||
|
xml:space="preserve"
|
||||||
|
id="flowRoot8810-6-1-4-3-3-60-9-4-9-8-0"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
transform="matrix(0.21691896,0,0,0.21691896,-2803.3696,-671.55813)"><flowRegion
|
||||||
|
id="flowRegion8812-7-2-4-0-4-2-4-2-4-0-5"
|
||||||
|
style="fill:#000000;fill-opacity:1"><rect
|
||||||
|
id="rect8814-2-78-2-1-7-6-3-8-2-72-9"
|
||||||
|
width="588.96417"
|
||||||
|
height="103.93485"
|
||||||
|
x="13269.016"
|
||||||
|
y="3478.3762"
|
||||||
|
style="fill:#000000;fill-opacity:1" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-0-0-9-7-47-8-8-3-6-1">winding 2</flowPara></flowRoot> </g>
|
||||||
|
<path
|
||||||
|
id="path13664-8-8-6-4-4"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:0.08542565;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-02-8-4-8-5);marker-end:url(#ArrowDIN-end-6-8-9-3-3)"
|
||||||
|
d="m 62.763941,107.38345 -18.78981,1.4e-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
id="path13664-8-8-6-4-4-8"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:0.1;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-end:url(#ArrowDIN-end-6-8-9-3-3-4)"
|
||||||
|
d="m 79.377455,106.81032 -17.344568,3.4426"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
id="path13664-8-8-6-4-4-9"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
style="fill:none;stroke:#879ebf;stroke-width:0.13530725;stroke-miterlimit:4;stroke-dasharray:0.40592175, 0.40592175;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m 75.682703,111.78889 -32.373971,2e-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
id="path13664-8-8-6-4-4-9-1"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
style="fill:none;stroke:#879ebf;stroke-width:0.13530725;stroke-miterlimit:4;stroke-dasharray:0.40592176, 0.40592176;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m 75.545706,110.32691 -32.373972,2e-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
id="path13664-8-8-6-4-4-9-6"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
style="fill:none;stroke:#879ebf;stroke-width:0.13530725;stroke-miterlimit:4;stroke-dasharray:0.40592176, 0.40592176;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m 75.731992,144.27322 -32.373972,2e-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<path
|
||||||
|
id="path13664-8-8-6-4-4-9-6-3"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
style="fill:none;stroke:#879ebf;stroke-width:0.13530725;stroke-miterlimit:4;stroke-dasharray:0.40592177, 0.40592177;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="m 75.769078,145.73565 -32.373972,2e-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<g
|
||||||
|
transform="matrix(0.22505474,0,0,0.22505474,51.561317,103.67051)"
|
||||||
|
id="g5446-4-3-5"
|
||||||
|
style="fill:#000000;fill-opacity:1">
|
||||||
|
<path
|
||||||
|
id="path13664-8-8-6-4-6"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:0.4431785;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-02-8-4-8-2);marker-end:url(#ArrowDIN-end-6-8-9-3-6)"
|
||||||
|
d="m 72.597998,38.227171 5.57e-4,138.415199"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<g
|
||||||
|
id="g6029"
|
||||||
|
transform="translate(-0.29689391,10.391287)">
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(0.21691896,0,0,0.21691896,-2803.7467,-662.50475)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:2.04839802;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
id="flowRoot8810-6-1-4-3-3-60-9-4-9-4-5-5"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke-width:2.04839802;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
id="flowRegion8812-7-2-4-0-4-2-4-2-4-9-8-4"><rect
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke-width:2.04839802;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-78-2-1-7-6-3-8-2-7-1-7" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-0-0-9-7-47-8-8-3-8-2-1">d + buildup for winding 1</flowPara></flowRoot> <flowRoot
|
||||||
|
transform="matrix(0.21691896,0,0,0.21691896,-2799.0005,-658.49482)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:2.04839802;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
id="flowRoot8810-6-1-4-3-3-5-7-9-8-2-9-0-2"
|
||||||
|
xml:space="preserve"
|
||||||
|
inkscape:transform-center-x="-8.2682291"><flowRegion
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke-width:2.04839802;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
id="flowRegion8812-7-2-4-0-4-9-77-1-8-0-2-6-6"><rect
|
||||||
|
style="fill:#000000;fill-opacity:1;stroke-width:2.04839802;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-78-2-1-7-2-3-3-3-6-1-5-0" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-0-0-9-7-1-6-1-2-5-3-7-4">coil</flowPara></flowRoot> </g>
|
||||||
|
<path
|
||||||
|
id="path13664-8-8-6-4-6-6"
|
||||||
|
inkscape:label="dimline"
|
||||||
|
style="fill:none;fill-opacity:1;stroke:#000000;stroke-width:0.44261289;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1;marker-start:url(#ArrowDIN-start-02-8-4-8-2-1);marker-end:url(#ArrowDIN-end-6-8-9-3-6-3)"
|
||||||
|
d="m 83.881095,31.620465 2.69e-4,151.900465"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<g
|
||||||
|
id="g6010"
|
||||||
|
transform="translate(-0.29689391,-8.9068173)">
|
||||||
|
<flowRoot
|
||||||
|
transform="matrix(0.21691896,0,0,0.21691896,-2792.4637,-669.40709)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-6-1-4-3-3-60-9-4-9-4-5-5-0"
|
||||||
|
xml:space="preserve"><flowRegion
|
||||||
|
style="fill:#000000;fill-opacity:1"
|
||||||
|
id="flowRegion8812-7-2-4-0-4-2-4-2-4-9-8-4-5"><rect
|
||||||
|
style="fill:#000000;fill-opacity:1"
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-78-2-1-7-6-3-8-2-7-1-7-6" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-0-0-9-7-47-8-8-3-8-2-1-9">d + buildup for winding 2 </flowPara></flowRoot> <flowRoot
|
||||||
|
transform="matrix(0.21691896,0,0,0.21691896,-2787.7175,-665.39716)"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:40px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none"
|
||||||
|
id="flowRoot8810-6-1-4-3-3-5-7-9-8-2-9-0-2-0"
|
||||||
|
xml:space="preserve"
|
||||||
|
inkscape:transform-center-x="-8.2682291"><flowRegion
|
||||||
|
style="fill:#000000;fill-opacity:1"
|
||||||
|
id="flowRegion8812-7-2-4-0-4-9-77-1-8-0-2-6-6-8"><rect
|
||||||
|
style="fill:#000000;fill-opacity:1"
|
||||||
|
y="3478.3762"
|
||||||
|
x="13269.016"
|
||||||
|
height="103.93485"
|
||||||
|
width="588.96417"
|
||||||
|
id="rect8814-2-78-2-1-7-2-3-3-3-6-1-5-0-2" /></flowRegion><flowPara
|
||||||
|
id="flowPara8857-0-0-9-7-1-6-1-2-5-3-7-4-7">coil</flowPara></flowRoot> </g>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 34 KiB |
392
inkscape_drawings/spool-line-deflection.svg
Normal file
@ -0,0 +1,392 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
sodipodi:docname="line-deflection.svg"
|
||||||
|
inkscape:version="1.0 (4035a4fb49, 2020-05-01)"
|
||||||
|
id="svg866"
|
||||||
|
version="1.1"
|
||||||
|
viewBox="0 0 100 68.849297"
|
||||||
|
height="68.849297mm"
|
||||||
|
width="100mm">
|
||||||
|
<defs
|
||||||
|
id="defs860">
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-02-8-4-8-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-2-1-5-62"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-6-8-9-3-17"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-9-2-0-0-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-7-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-9-4" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-1-8"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-7-6" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-4-5"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-71"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-379" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-end-5"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-end">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M 8,0 -8,2.11 v -4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13338-24" />
|
||||||
|
</marker>
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="0"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect7064-1"
|
||||||
|
effect="spiro" />
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-1"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-3" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
id="ArrowDIN-start-9-3"
|
||||||
|
orient="auto"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:stockid="ArrowDIN-start">
|
||||||
|
<path
|
||||||
|
d="M -8,0 8,-2.11 v 4.22 z"
|
||||||
|
style="fill:#000000;stroke:none"
|
||||||
|
id="path13335-5-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:isstock="true"
|
||||||
|
style="overflow:visible"
|
||||||
|
id="Arrow1Lstart-3-4"
|
||||||
|
refX="0"
|
||||||
|
refY="0"
|
||||||
|
orient="auto"
|
||||||
|
inkscape:stockid="Arrow1Lstart">
|
||||||
|
<path
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
style="fill:#ff0000;fill-opacity:1;fill-rule:evenodd;stroke:#ff0000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
id="path15451-1-1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lstart"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker21821"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path21819"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
<marker
|
||||||
|
inkscape:stockid="Arrow1Lstart"
|
||||||
|
orient="auto"
|
||||||
|
refY="0"
|
||||||
|
refX="0"
|
||||||
|
id="marker21821-0"
|
||||||
|
style="overflow:visible"
|
||||||
|
inkscape:isstock="true">
|
||||||
|
<path
|
||||||
|
id="path21819-2"
|
||||||
|
d="M 0,0 5,-5 -12.5,0 5,5 Z"
|
||||||
|
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1pt;stroke-opacity:1"
|
||||||
|
transform="matrix(0.8,0,0,0.8,10,0)"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</marker>
|
||||||
|
</defs>
|
||||||
|
<sodipodi:namedview
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
inkscape:window-y="-8"
|
||||||
|
inkscape:window-x="1912"
|
||||||
|
inkscape:window-height="976"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
showborder="false"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-top="0"
|
||||||
|
showgrid="false"
|
||||||
|
inkscape:document-rotation="0"
|
||||||
|
inkscape:current-layer="g1692"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:cy="87.001087"
|
||||||
|
inkscape:cx="374.0719"
|
||||||
|
inkscape:zoom="1.28"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:pageopacity="0.0"
|
||||||
|
borderopacity="1.0"
|
||||||
|
bordercolor="#666666"
|
||||||
|
pagecolor="#ffffff"
|
||||||
|
id="base" />
|
||||||
|
<metadata
|
||||||
|
id="metadata863">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title></dc:title>
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
transform="translate(14057.59,12512.791)"
|
||||||
|
id="layer1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
inkscape:label="Layer 1">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.0381366,0,0,0.0381366,-1282.8902,-1414.8552)"
|
||||||
|
id="g1692">
|
||||||
|
<g
|
||||||
|
transform="matrix(0.05096223,0,0,0.05096223,-317901.25,-276174.61)"
|
||||||
|
id="g3992">
|
||||||
|
<rect
|
||||||
|
style="fill:#ccc021;fill-opacity:1;stroke:#000000;stroke-width:531.127;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect9439-9-8-24-0-8-2"
|
||||||
|
width="4042.5703"
|
||||||
|
height="3283.322"
|
||||||
|
x="-330771.94"
|
||||||
|
y="-286140.34" />
|
||||||
|
<g
|
||||||
|
id="g3124-7-1-2-5"
|
||||||
|
transform="matrix(26.22153,0,0,26.22153,-483146.16,-502236.81)">
|
||||||
|
<ellipse
|
||||||
|
ry="32.502953"
|
||||||
|
rx="32.502956"
|
||||||
|
cy="8303.792"
|
||||||
|
cx="5888.1216"
|
||||||
|
id="path9422-5-4-6-3-7-3-4-2-1-1-6-7"
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:6.6462;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<circle
|
||||||
|
r="6.5636873"
|
||||||
|
cy="8303.792"
|
||||||
|
cx="5888.1216"
|
||||||
|
id="path7360-7-8-0-8-7-3-4-0-4-5-6-4"
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:1.3104;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
</g>
|
||||||
|
<rect
|
||||||
|
style="fill:#b2c0ae;fill-opacity:1;stroke:#000000;stroke-width:1048.86;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect9439-5"
|
||||||
|
width="23178.729"
|
||||||
|
height="3567.8171"
|
||||||
|
x="-334447.75"
|
||||||
|
y="-290480.44" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#433ab2;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -327986.2,-284969.05 3457.01,10736.98"
|
||||||
|
id="path9777-5"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<ellipse
|
||||||
|
style="fill:#dcbb2e;fill-opacity:1;stroke:#332eb4;stroke-width:1311.07;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path9422-5-4-6-7"
|
||||||
|
cx="-318195.5"
|
||||||
|
cy="-277284.28"
|
||||||
|
rx="6411.7617"
|
||||||
|
ry="6411.7612" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:226.09;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-0-8-7-5"
|
||||||
|
cx="-318195.5"
|
||||||
|
cy="-277284.28"
|
||||||
|
r="1132.4626" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:573.195;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -318215.66,-277313.2 -6340.21,-9425.91"
|
||||||
|
id="path9783-7"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:573.195;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -318181.78,-277313.2 6340.21,-9425.91"
|
||||||
|
id="path9783-6-3"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#433ab2;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -329593.19,-284297.57 8719.85,28676.42"
|
||||||
|
id="path9777-5-6"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<rect
|
||||||
|
style="fill:#ccc021;fill-opacity:1;stroke:#000000;stroke-width:531.127;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect9439-9-8-24-0-8-2-3"
|
||||||
|
width="4042.5703"
|
||||||
|
height="3283.322"
|
||||||
|
x="-303546.66"
|
||||||
|
y="-286118.19" />
|
||||||
|
<g
|
||||||
|
id="g3124-7-1-2-5-0"
|
||||||
|
transform="matrix(26.22153,0,0,26.22153,-455920.87,-502214.66)">
|
||||||
|
<ellipse
|
||||||
|
ry="32.502953"
|
||||||
|
rx="32.502956"
|
||||||
|
cy="8303.792"
|
||||||
|
cx="5888.1216"
|
||||||
|
id="path9422-5-4-6-3-7-3-4-2-1-1-6-7-6"
|
||||||
|
style="fill:#c2c7bd;fill-opacity:1;stroke:#7f8688;stroke-width:6.6462;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
<circle
|
||||||
|
r="6.5636873"
|
||||||
|
cy="8303.792"
|
||||||
|
cx="5888.1216"
|
||||||
|
id="path7360-7-8-0-8-7-3-4-0-4-5-6-4-2"
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:1.3104;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill" />
|
||||||
|
</g>
|
||||||
|
<rect
|
||||||
|
style="fill:#b2c0ae;fill-opacity:1;stroke:#000000;stroke-width:1048.86;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="rect9439-5-8"
|
||||||
|
width="23178.729"
|
||||||
|
height="3567.8171"
|
||||||
|
x="-307222.47"
|
||||||
|
y="-290458.28" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#433ab2;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -301420.13,-285360.83 11444.18,1186.11"
|
||||||
|
id="path9777-5-3"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
<ellipse
|
||||||
|
style="fill:#dcbb2e;fill-opacity:1;stroke:#332eb4;stroke-width:1311.07;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path9422-5-4-6-7-3"
|
||||||
|
cx="-290970.22"
|
||||||
|
cy="-277262.09"
|
||||||
|
rx="6411.7617"
|
||||||
|
ry="6411.7612" />
|
||||||
|
<circle
|
||||||
|
style="fill:#000900;fill-opacity:1;stroke:none;stroke-width:226.09;stroke-linecap:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;paint-order:stroke markers fill"
|
||||||
|
id="path7360-7-8-0-8-7-5-5"
|
||||||
|
cx="-290970.22"
|
||||||
|
cy="-277262.09"
|
||||||
|
r="1132.4626" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:573.195;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -290990.38,-277291.04 -6340.21,-9425.91"
|
||||||
|
id="path9783-7-7"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#000000;stroke-width:573.195;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -290956.5,-277291.04 6340.21,-9425.91"
|
||||||
|
id="path9783-6-3-9"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#433ab2;stroke-width:131.107;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -302367.91,-284275.41 8719.85,28676.41"
|
||||||
|
id="path9777-5-6-4"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
sodipodi:nodetypes="cc" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 14 KiB |
239
prusaslicer_profile/config.ini
Normal file
@ -0,0 +1,239 @@
|
|||||||
|
# generated by PrusaSlicer 2.2.0+win64 on 2020-07-11 at 20:15:29 UTC
|
||||||
|
avoid_crossing_perimeters = 0
|
||||||
|
bed_custom_texture = trikarus-bed.svg
|
||||||
|
bed_shape = 498.097x43.5779,492.404x86.8241,482.963x129.41,469.846x171.01,453.154x211.309,433.013x250,409.576x286.788,383.022x321.394,353.553x353.553,321.394x383.022,286.788x409.576,250x433.013,211.309x453.154,171.01x469.846,129.41x482.963,86.8241x492.404,43.5779x498.097,3.06162e-14x500,-43.5779x498.097,-86.8241x492.404,-129.41x482.963,-171.01x469.846,-211.309x453.154,-250x433.013,-286.788x409.576,-321.394x383.022,-353.553x353.553,-383.022x321.394,-409.576x286.788,-433.013x250,-453.154x211.309,-469.846x171.01,-482.963x129.41,-492.404x86.8241,-498.097x43.5779,-500x6.12323e-14,-498.097x-43.5779,-492.404x-86.8241,-482.963x-129.41,-469.846x-171.01,-453.154x-211.309,-433.013x-250,-409.576x-286.788,-383.022x-321.394,-353.553x-353.553,-321.394x-383.022,-286.788x-409.576,-250x-433.013,-211.309x-453.154,-171.01x-469.846,-129.41x-482.963,-86.8241x-492.404,-43.5779x-498.097,-9.18485e-14x-500,43.5779x-498.097,86.8241x-492.404,129.41x-482.963,171.01x-469.846,211.309x-453.154,250x-433.013,286.788x-409.576,321.394x-383.022,353.553x-353.553,383.022x-321.394,409.576x-286.788,433.013x-250,453.154x-211.309,469.846x-171.01,482.963x-129.41,492.404x-86.8241,498.097x-43.5779,500x-1.22465e-13
|
||||||
|
bed_temperature = 0
|
||||||
|
before_layer_gcode =
|
||||||
|
between_objects_gcode =
|
||||||
|
bottom_fill_pattern = rectilinear
|
||||||
|
bottom_solid_layers = 2
|
||||||
|
bottom_solid_min_thickness = 0
|
||||||
|
bridge_acceleration = 0
|
||||||
|
bridge_angle = 0
|
||||||
|
bridge_fan_speed = 100
|
||||||
|
bridge_flow_ratio = 1
|
||||||
|
bridge_speed = 60
|
||||||
|
brim_width = 0
|
||||||
|
clip_multipart_objects = 1
|
||||||
|
colorprint_heights =
|
||||||
|
complete_objects = 0
|
||||||
|
cooling = 1
|
||||||
|
cooling_tube_length = 5
|
||||||
|
cooling_tube_retraction = 91.5
|
||||||
|
default_acceleration = 0
|
||||||
|
default_filament_profile = ""
|
||||||
|
default_print_profile =
|
||||||
|
deretract_speed = 0
|
||||||
|
disable_fan_first_layers = 2
|
||||||
|
dont_support_bridges = 0
|
||||||
|
draft_shield = 0
|
||||||
|
duplicate_distance = 6
|
||||||
|
elefant_foot_compensation = 0.2
|
||||||
|
end_filament_gcode = "; Filament-specific end gcode \n;END gcode for filament\n"
|
||||||
|
end_gcode = ;PrusaSlicer automatically generates M107 command at the end which turns off the fan. But we want to cool down the last millimeters too for some more seconds\nM106 S255 ;re-enable blower fan\nM104 S0 ;turn off temperature\nG91 ;relative coordinates\nG0 Z3 ;move extruder 3 mm higher\nG90 ;absolute coordinates\nG4 S20 ;wait 30 seconds\nM106 S0 ;then turn off the blower fan again
|
||||||
|
ensure_vertical_shell_thickness = 1
|
||||||
|
external_perimeter_extrusion_width = 1.57
|
||||||
|
external_perimeter_speed = 75%
|
||||||
|
external_perimeters_first = 0
|
||||||
|
extra_loading_move = -2
|
||||||
|
extra_perimeters = 1
|
||||||
|
extruder_clearance_height = 20
|
||||||
|
extruder_clearance_radius = 20
|
||||||
|
extruder_colour = #0080FF
|
||||||
|
extruder_offset = 0x0
|
||||||
|
extrusion_axis = E
|
||||||
|
extrusion_multiplier = 1
|
||||||
|
extrusion_width = 1.57
|
||||||
|
fan_always_on = 1
|
||||||
|
fan_below_layer_time = 60
|
||||||
|
filament_colour = #FFFFFF
|
||||||
|
filament_cooling_final_speed = 3.4
|
||||||
|
filament_cooling_initial_speed = 2.2
|
||||||
|
filament_cooling_moves = 4
|
||||||
|
filament_cost = 18.81
|
||||||
|
filament_density = 1.25
|
||||||
|
filament_deretract_speed = nil
|
||||||
|
filament_diameter = 1.8
|
||||||
|
filament_load_time = 0
|
||||||
|
filament_loading_speed = 28
|
||||||
|
filament_loading_speed_start = 3
|
||||||
|
filament_max_volumetric_speed = 0
|
||||||
|
filament_minimal_purge_on_wipe_tower = 15
|
||||||
|
filament_notes = "offical data from spool:\n- density: 1.25 g/cm^3\n- diameter: 1.75 mm +/- 0.05 mm (90% of all filament spools below +/- 0.02 mm)\n- print temperature: 205 C +/- 10 C"
|
||||||
|
filament_ramming_parameters = "120 100 6.6 6.8 7.2 7.6 7.9 8.2 8.7 9.4 9.9 10.0| 0.05 6.6 0.45 6.8 0.95 7.8 1.45 8.3 1.95 9.7 2.45 10 2.95 7.6 3.45 7.6 3.95 7.6 4.45 7.6 4.95 7.6"
|
||||||
|
filament_retract_before_travel = nil
|
||||||
|
filament_retract_before_wipe = nil
|
||||||
|
filament_retract_layer_change = nil
|
||||||
|
filament_retract_length = nil
|
||||||
|
filament_retract_lift = nil
|
||||||
|
filament_retract_lift_above = nil
|
||||||
|
filament_retract_lift_below = nil
|
||||||
|
filament_retract_restart_extra = nil
|
||||||
|
filament_retract_speed = nil
|
||||||
|
filament_settings_id = "Trikarus - Redline Filament PLA"
|
||||||
|
filament_soluble = 0
|
||||||
|
filament_toolchange_delay = 0
|
||||||
|
filament_type = PLA
|
||||||
|
filament_unload_time = 0
|
||||||
|
filament_unloading_speed = 90
|
||||||
|
filament_unloading_speed_start = 100
|
||||||
|
filament_vendor = (Unknown)
|
||||||
|
filament_wipe = nil
|
||||||
|
fill_angle = 45
|
||||||
|
fill_density = 5%
|
||||||
|
fill_pattern = gyroid
|
||||||
|
first_layer_acceleration = 0
|
||||||
|
first_layer_bed_temperature = 0
|
||||||
|
first_layer_extrusion_width = 1.47
|
||||||
|
first_layer_height = 110%
|
||||||
|
first_layer_speed = 20%
|
||||||
|
first_layer_temperature = 205
|
||||||
|
gap_fill_speed = 40
|
||||||
|
gcode_comments = 0
|
||||||
|
gcode_flavor = marlin
|
||||||
|
gcode_label_objects = 0
|
||||||
|
high_current_on_filament_swap = 0
|
||||||
|
host_type = duet
|
||||||
|
infill_acceleration = 0
|
||||||
|
infill_every_layers = 1
|
||||||
|
infill_extruder = 1
|
||||||
|
infill_extrusion_width = 1.57
|
||||||
|
infill_first = 0
|
||||||
|
infill_only_where_needed = 0
|
||||||
|
infill_overlap = 25%
|
||||||
|
infill_speed = 45
|
||||||
|
interface_shells = 0
|
||||||
|
layer_gcode =
|
||||||
|
layer_height = 1
|
||||||
|
machine_max_acceleration_e = 1000,1000
|
||||||
|
machine_max_acceleration_extruding = 1500,1500
|
||||||
|
machine_max_acceleration_retracting = 1500,1500
|
||||||
|
machine_max_acceleration_x = 1000,1000
|
||||||
|
machine_max_acceleration_y = 1000,1000
|
||||||
|
machine_max_acceleration_z = 1000,1000
|
||||||
|
machine_max_feedrate_e = 3600,3600
|
||||||
|
machine_max_feedrate_x = 9500,9500
|
||||||
|
machine_max_feedrate_y = 9500,9500
|
||||||
|
machine_max_feedrate_z = 9500,9500
|
||||||
|
machine_max_jerk_e = 2.5,2.5
|
||||||
|
machine_max_jerk_x = 10,10
|
||||||
|
machine_max_jerk_y = 10,10
|
||||||
|
machine_max_jerk_z = 0.2,0.2
|
||||||
|
machine_min_extruding_rate = 0,0
|
||||||
|
machine_min_travel_rate = 0,0
|
||||||
|
max_fan_speed = 100
|
||||||
|
max_layer_height = 1.4
|
||||||
|
max_print_height = 2000
|
||||||
|
max_print_speed = 50
|
||||||
|
max_volumetric_speed = 110
|
||||||
|
min_fan_speed = 65
|
||||||
|
min_layer_height = 0.3
|
||||||
|
min_print_speed = 10
|
||||||
|
min_skirt_length = 100
|
||||||
|
notes =
|
||||||
|
nozzle_diameter = 1.4
|
||||||
|
only_retract_when_crossing_perimeters = 1
|
||||||
|
ooze_prevention = 0
|
||||||
|
output_filename_format = [input_filename_base].gcode
|
||||||
|
overhangs = 1
|
||||||
|
parking_pos_retraction = 92
|
||||||
|
perimeter_acceleration = 0
|
||||||
|
perimeter_extruder = 1
|
||||||
|
perimeter_extrusion_width = 1.57
|
||||||
|
perimeter_speed = 35
|
||||||
|
perimeters = 2
|
||||||
|
post_process =
|
||||||
|
print_host =
|
||||||
|
print_settings_id = Trikarus
|
||||||
|
printer_model =
|
||||||
|
printer_notes = - M203 command in PrusaSlicer takes mm/second but Duet RRF takes those values as mm/minute. So you need to enter the mm/minute values without conversion\n- M73 not supported by RRF
|
||||||
|
printer_settings_id = Trikarus
|
||||||
|
printer_technology = FFF
|
||||||
|
printer_variant =
|
||||||
|
printer_vendor =
|
||||||
|
printhost_apikey =
|
||||||
|
printhost_cafile =
|
||||||
|
raft_layers = 0
|
||||||
|
remaining_times = 0
|
||||||
|
resolution = 0
|
||||||
|
retract_before_travel = 2
|
||||||
|
retract_before_wipe = 0%
|
||||||
|
retract_layer_change = 1
|
||||||
|
retract_length = 3
|
||||||
|
retract_length_toolchange = 10
|
||||||
|
retract_lift = 1.5
|
||||||
|
retract_lift_above = 0
|
||||||
|
retract_lift_below = 0
|
||||||
|
retract_restart_extra = 0
|
||||||
|
retract_restart_extra_toolchange = 0
|
||||||
|
retract_speed = 60
|
||||||
|
seam_position = nearest
|
||||||
|
serial_port =
|
||||||
|
serial_speed = 250000
|
||||||
|
silent_mode = 1
|
||||||
|
single_extruder_multi_material = 0
|
||||||
|
single_extruder_multi_material_priming = 1
|
||||||
|
skirt_distance = 40
|
||||||
|
skirt_height = 1
|
||||||
|
skirts = 1
|
||||||
|
slice_closing_radius = 0.049
|
||||||
|
slowdown_below_layer_time = 5
|
||||||
|
small_perimeter_speed = 30
|
||||||
|
solid_infill_below_area = 70
|
||||||
|
solid_infill_every_layers = 0
|
||||||
|
solid_infill_extruder = 1
|
||||||
|
solid_infill_extrusion_width = 1.57
|
||||||
|
solid_infill_speed = 35
|
||||||
|
spiral_vase = 0
|
||||||
|
standby_temperature_delta = -5
|
||||||
|
start_filament_gcode = "; Filament gcode\n"
|
||||||
|
start_gcode = G28 ;reset coordinates - you must delete the files homex.g and homey.g on Duet Web Control because they contain dangerious moves when using default DWC config\n;deactivated stuff:\n;G92 X0 Y0 Z0 ;reset coordinates - does not always work so we use preceding G28\n;M106 P2 S0 ;turn off laser pointers - this is done by sms_prepare.sh script. no need to do twice\nM117 "Starting new GCode print job" ;M291 PMESSAGE does not work here. It just won't be displayed while printing
|
||||||
|
support_material = 0
|
||||||
|
support_material_angle = 0
|
||||||
|
support_material_auto = 1
|
||||||
|
support_material_buildplate_only = 1
|
||||||
|
support_material_contact_distance = 0.2
|
||||||
|
support_material_enforce_layers = 0
|
||||||
|
support_material_extruder = 1
|
||||||
|
support_material_extrusion_width = 1.22
|
||||||
|
support_material_interface_contact_loops = 0
|
||||||
|
support_material_interface_extruder = 1
|
||||||
|
support_material_interface_layers = 3
|
||||||
|
support_material_interface_spacing = 4
|
||||||
|
support_material_interface_speed = 100%
|
||||||
|
support_material_pattern = rectilinear
|
||||||
|
support_material_spacing = 10
|
||||||
|
support_material_speed = 60
|
||||||
|
support_material_synchronize_layers = 0
|
||||||
|
support_material_threshold = 0
|
||||||
|
support_material_with_sheath = 1
|
||||||
|
support_material_xy_spacing = 50%
|
||||||
|
temperature = 215
|
||||||
|
thin_walls = 1
|
||||||
|
threads = 8
|
||||||
|
thumbnails =
|
||||||
|
toolchange_gcode =
|
||||||
|
top_fill_pattern = rectilinear
|
||||||
|
top_infill_extrusion_width = 1.4
|
||||||
|
top_solid_infill_speed = 30
|
||||||
|
top_solid_layers = 2
|
||||||
|
top_solid_min_thickness = 0
|
||||||
|
travel_speed = 130
|
||||||
|
use_firmware_retraction = 1
|
||||||
|
use_relative_e_distances = 0
|
||||||
|
use_volumetric_e = 0
|
||||||
|
variable_layer_height = 1
|
||||||
|
wipe = 0
|
||||||
|
wipe_into_infill = 0
|
||||||
|
wipe_into_objects = 0
|
||||||
|
wipe_tower = 0
|
||||||
|
wipe_tower_bridging = 10
|
||||||
|
wipe_tower_no_sparse_layers = 0
|
||||||
|
wipe_tower_rotation_angle = 0
|
||||||
|
wipe_tower_width = 60
|
||||||
|
wipe_tower_x = 180
|
||||||
|
wipe_tower_y = 140
|
||||||
|
wiping_volumes_extruders = 70,70
|
||||||
|
wiping_volumes_matrix = 0
|
||||||
|
xy_size_compensation = 0
|
||||||
|
z_offset = 0
|
661
prusaslicer_profile/trikarus-bed.svg
Normal file
@ -0,0 +1,661 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<svg
|
||||||
|
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||||
|
xmlns:cc="http://creativecommons.org/ns#"
|
||||||
|
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||||
|
xmlns:svg="http://www.w3.org/2000/svg"
|
||||||
|
xmlns="http://www.w3.org/2000/svg"
|
||||||
|
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||||
|
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||||
|
sodipodi:docname="trikarus-bed.svg"
|
||||||
|
inkscape:version="0.92.5 (2060ec1f9f, 2020-04-08)"
|
||||||
|
id="svg8"
|
||||||
|
version="1.1"
|
||||||
|
viewBox="0 0 750.06994 750.07005"
|
||||||
|
height="1000mm"
|
||||||
|
width="1000mm">
|
||||||
|
<defs
|
||||||
|
id="defs2">
|
||||||
|
<inkscape:path-effect
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect941"
|
||||||
|
is_visible="true"
|
||||||
|
lpeversion="1" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="1"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect3475"
|
||||||
|
effect="spiro" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect3456"
|
||||||
|
is_visible="true"
|
||||||
|
lpeversion="1" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="1"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect3437"
|
||||||
|
effect="spiro" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect3433"
|
||||||
|
is_visible="true"
|
||||||
|
lpeversion="1" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="1"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect3339"
|
||||||
|
effect="spiro" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="1"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect2915"
|
||||||
|
effect="spiro" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="1"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect2911"
|
||||||
|
effect="spiro" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
lpeversion="1"
|
||||||
|
is_visible="true"
|
||||||
|
id="path-effect3437-9"
|
||||||
|
effect="spiro" />
|
||||||
|
<inkscape:path-effect
|
||||||
|
effect="spiro"
|
||||||
|
id="path-effect941-6"
|
||||||
|
is_visible="true"
|
||||||
|
lpeversion="1" />
|
||||||
|
</defs>
|
||||||
|
<sodipodi:namedview
|
||||||
|
inkscape:showpageshadow="false"
|
||||||
|
inkscape:window-maximized="1"
|
||||||
|
inkscape:window-y="-9"
|
||||||
|
inkscape:window-x="-9"
|
||||||
|
inkscape:window-height="950"
|
||||||
|
inkscape:window-width="1920"
|
||||||
|
showborder="true"
|
||||||
|
fit-margin-bottom="0"
|
||||||
|
fit-margin-right="0"
|
||||||
|
fit-margin-left="0"
|
||||||
|
fit-margin-top="0"
|
||||||
|
showgrid="false"
|
||||||
|
inkscape:document-rotation="0"
|
||||||
|
inkscape:current-layer="g3335"
|
||||||
|
inkscape:document-units="mm"
|
||||||
|
inkscape:cy="840.46602"
|
||||||
|
inkscape:cx="1696.0592"
|
||||||
|
inkscape:zoom="0.24748737"
|
||||||
|
inkscape:pageshadow="2"
|
||||||
|
inkscape:pageopacity="0"
|
||||||
|
borderopacity="1.0"
|
||||||
|
bordercolor="#666666"
|
||||||
|
pagecolor="#000000"
|
||||||
|
id="base" />
|
||||||
|
<metadata
|
||||||
|
id="metadata5">
|
||||||
|
<rdf:RDF>
|
||||||
|
<cc:Work
|
||||||
|
rdf:about="">
|
||||||
|
<dc:format>image/svg+xml</dc:format>
|
||||||
|
<dc:type
|
||||||
|
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||||
|
<dc:title />
|
||||||
|
</cc:Work>
|
||||||
|
</rdf:RDF>
|
||||||
|
</metadata>
|
||||||
|
<g
|
||||||
|
transform="translate(147.5762,208.87145)"
|
||||||
|
id="layer1"
|
||||||
|
inkscape:groupmode="layer"
|
||||||
|
inkscape:label="Ebene 1">
|
||||||
|
<g
|
||||||
|
id="g3335">
|
||||||
|
<g
|
||||||
|
aria-label="A"
|
||||||
|
id="text2499"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:34.61859894px;line-height:1.25;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:#536eb6;stroke-width:1.98456001;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
transform="translate(-150.03821,-259.29522)">
|
||||||
|
<path
|
||||||
|
d="m 403.95182,792.75848 -1.8694,-3.46186 h -10.55867 l 2.56177,-4.81198 h 5.43512 l -3.84266,-7.23529 -8.23923,15.50913 h -6.68139 l 11.49338,-20.84039 q 0.9347,-1.6617 2.70025,-1.6617 h 1.38474 q 1.76555,0 2.70025,1.6617 l 11.49338,20.84039 z"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:34.61859894px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke:#536eb6;stroke-width:1.98456001;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2837"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
aria-label="B"
|
||||||
|
id="text2499-1"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:34.61859894px;line-height:1.25;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:#a803a5;stroke-width:1.98456001;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
transform="translate(-215.42072,-147.81792)">
|
||||||
|
<path
|
||||||
|
d="m 730.85007,132.03928 v -22.50209 h 16.27074 q 1.80017,0 3.08105,0.45004 1.31551,0.45004 2.11174,1.24627 0.83085,0.79623 1.21165,1.90402 0.3808,1.07318 0.3808,2.31945 0,1.76555 -0.65775,3.01182 -0.65775,1.21165 -1.8694,1.69631 1.3155,0.41542 2.18097,1.76555 0.90008,1.35012 0.90008,3.49647 0,3.04644 -1.93864,4.84661 -1.90402,1.76555 -5.53898,1.76555 z m 8.06613,-9.03546 v -4.63889 h 7.443 q 0.79623,0 1.21165,-0.41542 0.45004,-0.41543 0.45004,-1.21165 0,-0.79623 -0.45004,-1.17704 -0.41542,-0.41542 -1.21165,-0.41542 h -9.45088 v 11.25104 h 9.76245 q 1.80016,0 1.80016,-1.62707 0,-0.83085 -0.45004,-1.28089 -0.45004,-0.48466 -1.3155,-0.48466 z"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:34.61859894px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke:#a803a5;stroke-width:1.98456001;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2834"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
aria-label="C"
|
||||||
|
id="text2499-1-9"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:34.61859894px;line-height:1.25;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:#02ac02;stroke-width:1.98456001;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
transform="translate(-83.600928,-147.53154)">
|
||||||
|
<path
|
||||||
|
d="m -6.8856757,162.71387 q -2.5963949,0 -4.7773663,-0.79623 -2.180972,-0.83085 -3.773428,-2.28483 -1.557837,-1.4886 -2.45792,-3.56571 -0.900084,-2.07712 -0.900084,-4.60428 0,-2.52716 0.900084,-4.56965 0.900083,-2.07712 2.45792,-3.56572 1.592456,-1.4886 3.773428,-2.28483 2.1809714,-0.83084 4.7773663,-0.83084 H 4.1230387 v 5.7813 H -7.3010989 q -1.1770324,0 -2.1809717,0.41543 -1.0039394,0.3808 -1.7309304,1.10779 -0.72699,0.72699 -1.142413,1.73093 -0.415424,1.00394 -0.415424,2.21559 0,1.21165 0.415424,2.21559 0.415423,1.00394 1.142413,1.73093 0.726991,0.69237 1.7309304,1.1078 1.0039393,0.3808 2.1809717,0.3808 H 4.1230387 v 5.81593 z"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:34.61859894px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke:#02ac02;stroke-width:1.98456001;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2831"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
style="stroke:#ffffff;stroke-width:1.98456001;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
transform="translate(-75.007006,-75.007155)"
|
||||||
|
id="g3429">
|
||||||
|
<g
|
||||||
|
style="stroke:#ffffff;stroke-width:5.40275002;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="g2567"
|
||||||
|
transform="matrix(0,0.36732431,-0.36732431,0,348.41195,339.65728)">
|
||||||
|
<path
|
||||||
|
id="path2558"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:5.40275002;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -791.20669,125.08343 c 0,-182.20545 97.20541,-350.57025 254.99997,-441.67298 m 0,883.34591 C -694.00128,475.65366 -791.20669,307.28885 -791.20669,125.08343"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
d="m -26.2067,566.75633 c -157.79455,91.1027 -352.20544,91.10274 -510.00002,0 M 228.79329,125.08339 c 4e-5,182.20546 -97.20547,350.57023 -254.99999,441.67294"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:5.40275002;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2560"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path2562"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:5.40275002;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -26.20678,-316.58955 c 157.79454,91.10273 255.00003,259.46749 255.00003,441.67294 m -765,-441.67294 c 157.79454,-91.10276 352.20545,-91.1027 509.99997,0"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
transform="matrix(0,0.07346486,-0.07346486,0,311.65503,261.82969)"
|
||||||
|
id="g2567-5"
|
||||||
|
style="stroke:#ffffff;stroke-width:27.01370049;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1">
|
||||||
|
<path
|
||||||
|
d="m -791.20669,125.08343 c 0,-182.20545 97.20541,-350.57025 254.99997,-441.67298 m 0,883.34591 C -694.00128,475.65366 -791.20669,307.28885 -791.20669,125.08343"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:27.01370049;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2558-6"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path2560-1"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:27.01370049;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -26.2067,566.75633 c -157.79455,91.1027 -352.20544,91.10274 -510.00002,0 M 228.79329,125.08339 c 4e-5,182.20546 -97.20547,350.57023 -254.99999,441.67294"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
d="m -26.20678,-316.58955 c 157.79454,91.10273 255.00003,259.46749 255.00003,441.67294 m -765,-441.67294 c 157.79454,-91.10276 352.20545,-91.1027 509.99997,0"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:27.01370049;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2562-8"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
style="stroke:#ffffff;stroke-width:13.50689983;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="g2599"
|
||||||
|
transform="matrix(0,0.14692972,-0.14692972,0,320.84426,282.4885)">
|
||||||
|
<path
|
||||||
|
id="path2593"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:13.50689983;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -791.20669,125.08343 c 0,-182.20545 97.20541,-350.57025 254.99997,-441.67298 m 0,883.34591 C -694.00128,475.65366 -791.20669,307.28885 -791.20669,125.08343"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
d="m -26.2067,566.75633 c -157.79455,91.1027 -352.20544,91.10274 -510.00002,0 M 228.79329,125.08339 c 4e-5,182.20546 -97.20547,350.57023 -254.99999,441.67294"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:13.50689983;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2595"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path2597"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:13.50689983;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -26.20678,-316.58955 c 157.79454,91.10273 255.00003,259.46749 255.00003,441.67294 m -765,-441.67294 c 157.79454,-91.10276 352.20545,-91.1027 509.99997,0"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
transform="matrix(0,0.22039458,-0.22039458,0,330.0335,303.14731)"
|
||||||
|
id="g2607"
|
||||||
|
style="stroke:#ffffff;stroke-width:9.00457954;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1">
|
||||||
|
<path
|
||||||
|
d="m -791.20669,125.08343 c 0,-182.20545 97.20541,-350.57025 254.99997,-441.67298 m 0,883.34591 C -694.00128,475.65366 -791.20669,307.28885 -791.20669,125.08343"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:9.00457954;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2601"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path2603"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:9.00457954;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -26.2067,566.75633 c -157.79455,91.1027 -352.20544,91.10274 -510.00002,0 M 228.79329,125.08339 c 4e-5,182.20546 -97.20547,350.57023 -254.99999,441.67294"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
d="m -26.20678,-316.58955 c 157.79454,91.10273 255.00003,259.46749 255.00003,441.67294 m -765,-441.67294 c 157.79454,-91.10276 352.20545,-91.1027 509.99997,0"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:9.00457954;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2605"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
style="stroke:#ffffff;stroke-width:6.75342989;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="g2615"
|
||||||
|
transform="matrix(0,0.29385945,-0.29385945,0,339.22274,323.80612)">
|
||||||
|
<path
|
||||||
|
id="path2609"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:6.75342989;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -791.20669,125.08343 c 0,-182.20545 97.20541,-350.57025 254.99997,-441.67298 m 0,883.34591 C -694.00128,475.65366 -791.20669,307.28885 -791.20669,125.08343"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
d="m -26.2067,566.75633 c -157.79455,91.1027 -352.20544,91.10274 -510.00002,0 M 228.79329,125.08339 c 4e-5,182.20546 -97.20547,350.57023 -254.99999,441.67294"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:6.75342989;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2611"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path2613"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:6.75342989;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -26.20678,-316.58955 c 157.79454,91.10273 255.00003,259.46749 255.00003,441.67294 m -765,-441.67294 c 157.79454,-91.10276 352.20545,-91.1027 509.99997,0"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
transform="matrix(0,0.44078917,-0.44078917,0,357.6012,365.12374)"
|
||||||
|
id="g2623"
|
||||||
|
style="stroke:#ffffff;stroke-width:4.50228977;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1">
|
||||||
|
<path
|
||||||
|
d="m -791.20669,125.08343 c 0,-182.20545 97.20541,-350.57025 254.99997,-441.67298 m 0,883.34591 C -694.00128,475.65366 -791.20669,307.28885 -791.20669,125.08343"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:4.50228977;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2617"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path2619"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:4.50228977;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -26.2067,566.75633 c -157.79455,91.1027 -352.20544,91.10274 -510.00002,0 M 228.79329,125.08339 c 4e-5,182.20546 -97.20547,350.57023 -254.99999,441.67294"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
d="m -26.20678,-316.58955 c 157.79454,91.10273 255.00003,259.46749 255.00003,441.67294 m -765,-441.67294 c 157.79454,-91.10276 352.20545,-91.1027 509.99997,0"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:4.50228977;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2621"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
style="stroke:#ffffff;stroke-width:3.8591001;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="g2631"
|
||||||
|
transform="matrix(0,0.51425403,-0.51425403,0,366.79044,385.78256)">
|
||||||
|
<path
|
||||||
|
id="path2625"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:3.8591001;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -791.20669,125.08343 c 0,-182.20545 97.20541,-350.57025 254.99997,-441.67298 m 0,883.34591 C -694.00128,475.65366 -791.20669,307.28885 -791.20669,125.08343"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
d="m -26.2067,566.75633 c -157.79455,91.1027 -352.20544,91.10274 -510.00002,0 M 228.79329,125.08339 c 4e-5,182.20546 -97.20547,350.57023 -254.99999,441.67294"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:3.8591001;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2627"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path2629"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:3.8591001;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -26.20678,-316.58955 c 157.79454,91.10273 255.00003,259.46749 255.00003,441.67294 m -765,-441.67294 c 157.79454,-91.10276 352.20545,-91.1027 509.99997,0"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
transform="matrix(0,0.58771889,-0.58771889,0,375.97967,406.44137)"
|
||||||
|
id="g2639"
|
||||||
|
style="stroke:#ffffff;stroke-width:3.37671995;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1">
|
||||||
|
<path
|
||||||
|
d="m -791.20669,125.08343 c 0,-182.20545 97.20541,-350.57025 254.99997,-441.67298 m 0,883.34591 C -694.00128,475.65366 -791.20669,307.28885 -791.20669,125.08343"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:3.37671995;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2633"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path2635"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:3.37671995;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -26.2067,566.75633 c -157.79455,91.1027 -352.20544,91.10274 -510.00002,0 M 228.79329,125.08339 c 4e-5,182.20546 -97.20547,350.57023 -254.99999,441.67294"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
d="m -26.20678,-316.58955 c 157.79454,91.10273 255.00003,259.46749 255.00003,441.67294 m -765,-441.67294 c 157.79454,-91.10276 352.20545,-91.1027 509.99997,0"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:3.37671995;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2637"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
style="stroke:#ffffff;stroke-width:3.00152993;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="g2647"
|
||||||
|
transform="matrix(0,0.66118375,-0.66118375,0,385.1689,427.10018)">
|
||||||
|
<path
|
||||||
|
id="path2641"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:3.00152993;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -791.20669,125.08343 c 0,-182.20545 97.20541,-350.57025 254.99997,-441.67298 m 0,883.34591 C -694.00128,475.65366 -791.20669,307.28885 -791.20669,125.08343"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
d="m -26.2067,566.75633 c -157.79455,91.1027 -352.20544,91.10274 -510.00002,0 M 228.79329,125.08339 c 4e-5,182.20546 -97.20547,350.57023 -254.99999,441.67294"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:3.00152993;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2643"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path2645"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:3.00152993;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -26.20678,-316.58955 c 157.79454,91.10273 255.00003,259.46749 255.00003,441.67294 m -765,-441.67294 c 157.79454,-91.10276 352.20545,-91.1027 509.99997,0"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
transform="matrix(0,0.73464861,-0.73464861,0,394.35814,447.75899)"
|
||||||
|
id="g2655"
|
||||||
|
style="stroke:#ffffff;stroke-width:2.70137;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1">
|
||||||
|
<path
|
||||||
|
d="m -791.20669,125.08343 c 0,-182.20545 97.20541,-350.57025 254.99997,-441.67298 m 0,883.34591 C -694.00128,475.65366 -791.20669,307.28885 -791.20669,125.08343"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:2.70137;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2649"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path2651"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:2.70137;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m -26.2067,566.75633 c -157.79455,91.1027 -352.20544,91.10274 -510.00002,0 M 228.79329,125.08339 c 4e-5,182.20546 -97.20547,350.57023 -254.99999,441.67294"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
d="m -26.20678,-316.58955 c 157.79454,91.10273 255.00003,259.46749 255.00003,441.67294 m -765,-441.67294 c 157.79454,-91.10276 352.20545,-91.1027 509.99997,0"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:2.70137;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
id="path2653"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<path
|
||||||
|
inkscape:path-effect="#path-effect3339"
|
||||||
|
inkscape:original-d="m 227.45879,166.16354 v 375.035"
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
id="path3337"
|
||||||
|
d="m 227.45879,166.16354 v 375.035"
|
||||||
|
style="fill:none;stroke:#536eb6;stroke-width:1.98456001;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:none;stroke:#a803a5;stroke-width:1.98456001;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="M 227.45879,166.16354 552.24863,-21.35396"
|
||||||
|
id="path3431"
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:original-d="M 227.45879,166.16354 552.24863,-21.35396"
|
||||||
|
inkscape:path-effect="#path-effect3433"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
inkscape:path-effect="#path-effect3437"
|
||||||
|
inkscape:original-d="M 227.7742,166.34581 -97.015638,-21.171687"
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
id="path3435"
|
||||||
|
d="M 227.7742,166.34581 -97.015638,-21.171687"
|
||||||
|
style="fill:none;stroke:#02ac02;stroke-width:1.98456001;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
style="fill:#ffffff;fill-opacity:1;stroke:#ffffff;stroke-width:1.98456001;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||||
|
d="m 227.7742,-208.68919 v 375.035"
|
||||||
|
id="path3337-1"
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:original-d="m 227.7742,-208.68919 v 375.035"
|
||||||
|
inkscape:path-effect="#path-effect3456"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3755"
|
||||||
|
d="m 227.45898,165.17188 v 1.98437 h 375.03516 v -1.98437 z"
|
||||||
|
style="color:#000000;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:medium;line-height:normal;font-family:sans-serif;font-variant-ligatures:normal;font-variant-position:normal;font-variant-caps:normal;font-variant-numeric:normal;font-variant-alternates:normal;font-feature-settings:normal;text-indent:0;text-align:start;text-decoration:none;text-decoration-line:none;text-decoration-style:solid;text-decoration-color:#000000;letter-spacing:normal;word-spacing:normal;text-transform:none;writing-mode:lr-tb;direction:ltr;text-orientation:mixed;dominant-baseline:auto;baseline-shift:baseline;text-anchor:start;white-space:normal;shape-padding:0;clip-rule:nonzero;display:inline;overflow:visible;visibility:visible;opacity:1;isolation:auto;mix-blend-mode:normal;color-interpolation:sRGB;color-interpolation-filters:linearRGB;solid-color:#000000;solid-opacity:1;vector-effect:none;fill:#ffffff;fill-opacity:1;fill-rule:nonzero;stroke:none;stroke-width:1.98456001;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;color-rendering:auto;image-rendering:auto;shape-rendering:auto;text-rendering:auto;enable-background:accumulate"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<g
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:37.67200089px;line-height:1.25;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
id="text3479"
|
||||||
|
aria-label="X+">
|
||||||
|
<path
|
||||||
|
id="path3671"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:37.67200089px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 554.4385,162.57318 -7.23303,-8.43853 -7.04466,8.43853 h -7.83578 l 10.73652,-12.77081 -9.87006,-11.71599 h 8.32551 l 6.21588,7.42138 6.25355,-7.42138 h 7.83578 l -9.90774,11.75366 10.84954,12.73314 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3673"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:37.67200089px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 574.64246,159.97381 v -7.45905 h -7.34604 v -4.78435 h 7.34604 v -7.42138 h 4.78434 v 7.42138 h 7.30837 v 4.78435 h -7.30837 v 7.45905 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:37.6719017px;line-height:1.25;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
id="text3479-7"
|
||||||
|
aria-label="Y+">
|
||||||
|
<path
|
||||||
|
id="path3748"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:37.6719017px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 208.83454,-177.54643 v -8.62687 l -11.22622,-15.85987 h 7.72274 l 6.93163,9.75702 6.9693,-9.75702 h 7.38369 l -11.18855,15.85987 v 8.62687 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3750"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:37.6719017px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 238.31045,-180.14579 v -7.45904 h -7.34602 v -4.78433 h 7.34602 v -7.42137 h 4.78434 v 7.42137 h 7.30834 v 4.78433 h -7.30834 v 7.45904 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06484985px;line-height:1.25;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
id="text3479-7-8"
|
||||||
|
aria-label="100">
|
||||||
|
<path
|
||||||
|
id="path3676"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06484985px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 246.13076,175.06329 v -3.73471 q 0,-0.29008 -0.1813,-0.46231 -0.17223,-0.17223 -0.4623,-0.17223 h -0.70706 v -1.5229 h 0.979 q 0.42605,0 0.77958,0.13597 0.36259,0.12691 0.62547,0.37166 0.26288,0.24475 0.40792,0.58922 0.14504,0.3354 0.14504,0.74332 v 4.05198 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3678"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06484985px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 254.60257,172.11722 q 0,0.65267 -0.23569,1.20562 -0.22662,0.55296 -0.63453,0.95181 -0.40792,0.39885 -0.97901,0.62548 -0.56202,0.22662 -1.22375,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22662,-0.55295 -0.22662,-1.20562 0,-0.65267 0.22662,-1.20563 0.22662,-0.55295 0.63454,-0.95181 0.40792,-0.39885 0.96994,-0.62547 0.56202,-0.22662 1.23282,-0.22662 0.66173,0 1.22375,0.22662 0.57109,0.22662 0.97901,0.62547 0.40791,0.39886 0.63453,0.95181 0.23569,0.55296 0.23569,1.20563 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58922 -0.10877,-0.28101 -0.3082,-0.48044 -0.19036,-0.19942 -0.46231,-0.3082 -0.27194,-0.11784 -0.59828,-0.11784 -0.3354,0 -0.61641,0.11784 -0.27194,0.10878 -0.47137,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27195 -0.10878,0.58922 0,0.31727 0.10878,0.58921 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47137,0.31727 0.28101,0.10878 0.61641,0.10878 0.32634,0 0.59828,-0.10878 0.27195,-0.11784 0.46231,-0.31727 0.19943,-0.19942 0.3082,-0.47137 0.10878,-0.27194 0.10878,-0.58921 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3680"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06484985px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 261.34809,172.11722 q 0,0.65267 -0.23568,1.20562 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.97901,0.62548 -0.56202,0.22662 -1.22375,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22662,-0.55295 -0.22662,-1.20562 0,-0.65267 0.22662,-1.20563 0.22662,-0.55295 0.63454,-0.95181 0.40792,-0.39885 0.96994,-0.62547 0.56202,-0.22662 1.23282,-0.22662 0.66173,0 1.22375,0.22662 0.57109,0.22662 0.97901,0.62547 0.40792,0.39886 0.63454,0.95181 0.23568,0.55296 0.23568,1.20563 z m -1.58634,0 q 0,-0.31727 -0.10878,-0.58922 -0.10878,-0.28101 -0.30821,-0.48044 -0.19036,-0.19942 -0.46231,-0.3082 -0.27194,-0.11784 -0.59828,-0.11784 -0.33539,0 -0.61641,0.11784 -0.27194,0.10878 -0.47137,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27195 -0.10878,0.58922 0,0.31727 0.10878,0.58921 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47137,0.31727 0.28102,0.10878 0.61641,0.10878 0.32634,0 0.59828,-0.10878 0.27195,-0.11784 0.46231,-0.31727 0.19943,-0.19942 0.30821,-0.47137 0.10878,-0.27194 0.10878,-0.58921 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;line-height:1.25;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
id="text3479-7-8-9"
|
||||||
|
aria-label="200">
|
||||||
|
<path
|
||||||
|
id="path3683"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 279.81518,175.06329 v -1.84016 q 0,-0.38979 0.13597,-0.70706 0.14504,-0.32634 0.39886,-0.55296 0.25381,-0.23569 0.59828,-0.36259 0.35353,-0.12691 0.76145,-0.12691 h 2.00333 q 0.16317,0 0.26288,-0.10878 0.0997,-0.10878 0.0997,-0.29008 0,-0.18129 -0.0997,-0.28101 -0.0997,-0.10877 -0.26288,-0.10877 h -3.60781 v -1.51384 h 3.67126 q 0.41699,0 0.76145,0.13598 0.34447,0.12691 0.59828,0.36259 0.25382,0.23569 0.38979,0.56202 0.14504,0.32634 0.14504,0.72519 0,0.39886 -0.14504,0.73426 -0.13597,0.32633 -0.38979,0.56202 -0.25381,0.22662 -0.60734,0.35353 -0.34447,0.1269 -0.75239,0.1269 h -2.01239 q -0.16317,0 -0.26289,0.0907 -0.0997,0.0906 -0.0997,0.27195 v 0.44418 h 4.1789 v 1.52289 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3685"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 292.52624,172.11721 q 0,0.65267 -0.23569,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.979,0.62548 -0.56202,0.22662 -1.22376,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22662,-0.55296 -0.22662,-1.20563 0,-0.65267 0.22662,-1.20562 0.22662,-0.55296 0.63454,-0.95181 0.40792,-0.39886 0.96994,-0.62548 0.56202,-0.22662 1.23282,-0.22662 0.66174,0 1.22376,0.22662 0.57108,0.22662 0.979,0.62548 0.40792,0.39885 0.63454,0.95181 0.23569,0.55295 0.23569,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58921 -0.10878,-0.28101 -0.30821,-0.48044 -0.19036,-0.19943 -0.4623,-0.3082 -0.27195,-0.11785 -0.59828,-0.11785 -0.3354,0 -0.61641,0.11785 -0.27195,0.10877 -0.47138,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27194 -0.10878,0.58921 0,0.31727 0.10878,0.58922 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47138,0.31727 0.28101,0.10878 0.61641,0.10878 0.32633,0 0.59828,-0.10878 0.27194,-0.11784 0.4623,-0.31727 0.19943,-0.19942 0.30821,-0.47137 0.10878,-0.27195 0.10878,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3687"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 299.27177,172.11721 q 0,0.65267 -0.23569,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.979,0.62548 -0.56202,0.22662 -1.22376,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22662,-0.55296 -0.22662,-1.20563 0,-0.65267 0.22662,-1.20562 0.22662,-0.55296 0.63454,-0.95181 0.40792,-0.39886 0.96994,-0.62548 0.56202,-0.22662 1.23282,-0.22662 0.66174,0 1.22376,0.22662 0.57108,0.22662 0.979,0.62548 0.40792,0.39885 0.63454,0.95181 0.23569,0.55295 0.23569,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58921 -0.10878,-0.28101 -0.3082,-0.48044 -0.19037,-0.19943 -0.46231,-0.3082 -0.27195,-0.11785 -0.59828,-0.11785 -0.3354,0 -0.61641,0.11785 -0.27195,0.10877 -0.47138,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10877,0.27194 -0.10877,0.58921 0,0.31727 0.10877,0.58922 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47138,0.31727 0.28101,0.10878 0.61641,0.10878 0.32633,0 0.59828,-0.10878 0.27194,-0.11784 0.46231,-0.31727 0.19942,-0.19942 0.3082,-0.47137 0.10878,-0.27195 0.10878,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;line-height:1.25;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
id="text3479-7-8-9-7"
|
||||||
|
aria-label="300">
|
||||||
|
<path
|
||||||
|
id="path3690"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 315.97357,175.06329 v -1.47757 h 4.18797 q 0.21756,0 0.3354,-0.10878 0.12691,-0.10878 0.12691,-0.31727 0,-0.21755 -0.12691,-0.3354 -0.11784,-0.12691 -0.3354,-0.12691 h -4.12451 v -1.21469 h 4.03386 q 0.42605,0 0.42605,-0.42604 0,-0.41699 -0.42605,-0.41699 h -4.09732 v -1.46851 h 4.30581 q 0.47138,0 0.80678,0.11785 0.3354,0.11784 0.54389,0.32633 0.20849,0.20849 0.3082,0.49857 0.0997,0.28101 0.0997,0.60735 0,0.4623 -0.17224,0.78864 -0.16316,0.31727 -0.48043,0.44418 0.35353,0.10877 0.58015,0.4623 0.23568,0.35353 0.23568,0.91556 0,0.7977 -0.50763,1.26908 -0.50763,0.4623 -1.45944,0.4623 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3692"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 328.90134,172.11721 q 0,0.65267 -0.23569,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.979,0.62548 -0.56202,0.22662 -1.22376,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22662,-0.55296 -0.22662,-1.20563 0,-0.65267 0.22662,-1.20562 0.22662,-0.55296 0.63454,-0.95181 0.40792,-0.39886 0.96994,-0.62548 0.56202,-0.22662 1.23282,-0.22662 0.66174,0 1.22376,0.22662 0.57108,0.22662 0.979,0.62548 0.40792,0.39885 0.63454,0.95181 0.23569,0.55295 0.23569,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58921 -0.10878,-0.28101 -0.3082,-0.48044 -0.19037,-0.19943 -0.46231,-0.3082 -0.27195,-0.11785 -0.59828,-0.11785 -0.3354,0 -0.61641,0.11785 -0.27195,0.10877 -0.47138,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27194 -0.10878,0.58921 0,0.31727 0.10878,0.58922 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47138,0.31727 0.28101,0.10878 0.61641,0.10878 0.32633,0 0.59828,-0.10878 0.27194,-0.11784 0.46231,-0.31727 0.19942,-0.19942 0.3082,-0.47137 0.10878,-0.27195 0.10878,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3694"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 335.64687,172.11721 q 0,0.65267 -0.23569,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.979,0.62548 -0.56202,0.22662 -1.22376,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22662,-0.55296 -0.22662,-1.20563 0,-0.65267 0.22662,-1.20562 0.22662,-0.55296 0.63454,-0.95181 0.40792,-0.39886 0.96994,-0.62548 0.56202,-0.22662 1.23282,-0.22662 0.66174,0 1.22376,0.22662 0.57108,0.22662 0.979,0.62548 0.40792,0.39885 0.63454,0.95181 0.23569,0.55295 0.23569,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58921 -0.10878,-0.28101 -0.3082,-0.48044 -0.19037,-0.19943 -0.46231,-0.3082 -0.27195,-0.11785 -0.59828,-0.11785 -0.3354,0 -0.61641,0.11785 -0.27195,0.10877 -0.47138,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10877,0.27194 -0.10877,0.58921 0,0.31727 0.10877,0.58922 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47138,0.31727 0.28101,0.10878 0.61641,0.10878 0.32633,0 0.59828,-0.10878 0.27194,-0.11784 0.46231,-0.31727 0.19942,-0.19942 0.3082,-0.47137 0.10878,-0.27195 0.10878,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;line-height:1.25;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
id="text3479-7-8-9-6"
|
||||||
|
aria-label="400">
|
||||||
|
<path
|
||||||
|
id="path3697"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 358.46701,175.06329 v -1.45037 h -2.03053 q -0.42605,0 -0.78864,-0.12691 -0.3626,-0.13598 -0.62548,-0.38073 -0.26288,-0.24475 -0.41698,-0.58015 -0.14504,-0.34446 -0.14504,-0.76145 v -2.59255 h 1.59542 v 2.3478 q 0,0.29914 0.18129,0.48044 0.1813,0.17223 0.46231,0.17223 h 1.76765 v -3.00047 h 1.58635 v 3.00047 h 0.61641 v 1.44132 h -0.61641 v 1.45037 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3699"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 367.28839,172.11721 q 0,0.65267 -0.23568,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.97901,0.62548 -0.56202,0.22662 -1.22375,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56203,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22663,-0.55296 -0.22663,-1.20563 0,-0.65267 0.22663,-1.20562 0.22662,-0.55296 0.63454,-0.95181 0.40791,-0.39886 0.96994,-0.62548 0.56202,-0.22662 1.23282,-0.22662 0.66173,0 1.22375,0.22662 0.57109,0.22662 0.97901,0.62548 0.40792,0.39885 0.63454,0.95181 0.23568,0.55295 0.23568,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10877,-0.58921 -0.10878,-0.28101 -0.30821,-0.48044 -0.19036,-0.19943 -0.46231,-0.3082 -0.27194,-0.11785 -0.59828,-0.11785 -0.3354,0 -0.61641,0.11785 -0.27194,0.10877 -0.47137,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27194 -0.10878,0.58921 0,0.31727 0.10878,0.58922 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47137,0.31727 0.28101,0.10878 0.61641,0.10878 0.32634,0 0.59828,-0.10878 0.27195,-0.11784 0.46231,-0.31727 0.19943,-0.19942 0.30821,-0.47137 0.10877,-0.27195 0.10877,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3701"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 374.03392,172.11721 q 0,0.65267 -0.23568,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.97901,0.62548 -0.56202,0.22662 -1.22375,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56203,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22663,-0.55296 -0.22663,-1.20563 0,-0.65267 0.22663,-1.20562 0.22662,-0.55296 0.63454,-0.95181 0.40791,-0.39886 0.96994,-0.62548 0.56202,-0.22662 1.23282,-0.22662 0.66173,0 1.22375,0.22662 0.57109,0.22662 0.97901,0.62548 0.40792,0.39885 0.63454,0.95181 0.23568,0.55295 0.23568,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10877,-0.58921 -0.10878,-0.28101 -0.30821,-0.48044 -0.19036,-0.19943 -0.46231,-0.3082 -0.27194,-0.11785 -0.59828,-0.11785 -0.3354,0 -0.61641,0.11785 -0.27194,0.10877 -0.47137,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27194 -0.10878,0.58921 0,0.31727 0.10878,0.58922 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47137,0.31727 0.28101,0.10878 0.61641,0.10878 0.32634,0 0.59828,-0.10878 0.27195,-0.11784 0.46231,-0.31727 0.19943,-0.19942 0.30821,-0.47137 0.10877,-0.27195 0.10877,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;line-height:1.25;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
id="text3479-7-8-9-1"
|
||||||
|
aria-label="500">
|
||||||
|
<path
|
||||||
|
id="path3704"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 391.84934,175.06329 v -1.52289 h 3.86163 q 0.19036,0 0.3082,-0.0997 0.11785,-0.10877 0.11785,-0.29914 0,-0.19036 -0.11785,-0.29914 -0.10878,-0.10878 -0.26288,-0.10878 h -3.90695 v -3.56249 h 5.62927 v 1.51384 h -4.11544 v 0.78864 h 2.45658 q 0.40791,0 0.75238,0.13597 0.35353,0.12691 0.60734,0.3626 0.26289,0.23568 0.40792,0.57108 0.14504,0.32634 0.14504,0.71613 0,0.40791 -0.14504,0.74331 -0.14503,0.32634 -0.40792,0.57109 -0.26288,0.23569 -0.62547,0.3626 -0.35353,0.1269 -0.77051,0.1269 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3706"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 404.50601,172.11721 q 0,0.65267 -0.23569,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.97901,0.62548 -0.56202,0.22662 -1.22375,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22662,-0.55296 -0.22662,-1.20563 0,-0.65267 0.22662,-1.20562 0.22662,-0.55296 0.63454,-0.95181 0.40792,-0.39886 0.96994,-0.62548 0.56202,-0.22662 1.23282,-0.22662 0.66173,0 1.22375,0.22662 0.57109,0.22662 0.97901,0.62548 0.40792,0.39885 0.63454,0.95181 0.23569,0.55295 0.23569,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58921 -0.10878,-0.28101 -0.30821,-0.48044 -0.19036,-0.19943 -0.46231,-0.3082 -0.27194,-0.11785 -0.59828,-0.11785 -0.3354,0 -0.61641,0.11785 -0.27194,0.10877 -0.47137,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27194 -0.10878,0.58921 0,0.31727 0.10878,0.58922 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47137,0.31727 0.28101,0.10878 0.61641,0.10878 0.32634,0 0.59828,-0.10878 0.27195,-0.11784 0.46231,-0.31727 0.19943,-0.19942 0.30821,-0.47137 0.10878,-0.27195 0.10878,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3708"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 411.25154,172.11721 q 0,0.65267 -0.23569,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.979,0.62548 -0.56203,0.22662 -1.22376,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22662,-0.55296 -0.22662,-1.20563 0,-0.65267 0.22662,-1.20562 0.22662,-0.55296 0.63454,-0.95181 0.40792,-0.39886 0.96994,-0.62548 0.56202,-0.22662 1.23282,-0.22662 0.66173,0 1.22376,0.22662 0.57108,0.22662 0.979,0.62548 0.40792,0.39885 0.63454,0.95181 0.23569,0.55295 0.23569,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58921 -0.10878,-0.28101 -0.30821,-0.48044 -0.19036,-0.19943 -0.46231,-0.3082 -0.27194,-0.11785 -0.59828,-0.11785 -0.3354,0 -0.61641,0.11785 -0.27194,0.10877 -0.47137,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27194 -0.10878,0.58921 0,0.31727 0.10878,0.58922 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47137,0.31727 0.28101,0.10878 0.61641,0.10878 0.32634,0 0.59828,-0.10878 0.27195,-0.11784 0.46231,-0.31727 0.19943,-0.19942 0.30821,-0.47137 0.10878,-0.27195 0.10878,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;line-height:1.25;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
id="text3479-7-8-9-17"
|
||||||
|
aria-label="600">
|
||||||
|
<path
|
||||||
|
id="path3711"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 432.04859,175.06329 q -0.67986,0 -1.22375,-0.19942 -0.53483,-0.19943 -0.91556,-0.57109 -0.37165,-0.37166 -0.57108,-0.89742 -0.19943,-0.52576 -0.19943,-1.17843 0,-0.70706 0.23569,-1.26908 0.23568,-0.57109 0.65267,-0.96088 0.41698,-0.39885 0.98807,-0.60734 0.57108,-0.2085 1.24188,-0.2085 h 2.75572 v 1.51384 h -2.86449 q -1.10592,0 -1.38693,0.80677 h 2.75572 q 0.90649,0 1.32347,0.45324 0.41698,0.45324 0.41698,1.21469 0,0.41699 -0.12691,0.77052 -0.11784,0.34446 -0.37165,0.59828 -0.24476,0.25381 -0.63455,0.39885 -0.38978,0.13597 -0.93368,0.13597 z m -1.32347,-2.41125 q 0.22662,0.88836 1.39599,0.88836 h 1.05152 q 0.44418,0 0.44418,-0.46231 0,-0.42605 -0.40792,-0.42605 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3713"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 442.02121,172.11721 q 0,0.65267 -0.23568,1.20563 -0.22663,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.97901,0.62548 -0.56202,0.22662 -1.22375,0.22662 -0.6708,0 -1.23283,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40791,-0.39885 -0.63454,-0.95181 -0.22662,-0.55296 -0.22662,-1.20563 0,-0.65267 0.22662,-1.20562 0.22663,-0.55296 0.63454,-0.95181 0.40792,-0.39886 0.96994,-0.62548 0.56203,-0.22662 1.23283,-0.22662 0.66173,0 1.22375,0.22662 0.57109,0.22662 0.97901,0.62548 0.40791,0.39885 0.63454,0.95181 0.23568,0.55295 0.23568,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58921 -0.10877,-0.28101 -0.3082,-0.48044 -0.19036,-0.19943 -0.46231,-0.3082 -0.27195,-0.11785 -0.59828,-0.11785 -0.3354,0 -0.61641,0.11785 -0.27195,0.10877 -0.47137,0.3082 -0.19037,0.19943 -0.29914,0.48044 -0.10878,0.27194 -0.10878,0.58921 0,0.31727 0.10878,0.58922 0.10877,0.27195 0.29914,0.47137 0.19942,0.19943 0.47137,0.31727 0.28101,0.10878 0.61641,0.10878 0.32633,0 0.59828,-0.10878 0.27195,-0.11784 0.46231,-0.31727 0.19943,-0.19942 0.3082,-0.47137 0.10878,-0.27195 0.10878,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3715"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 448.76674,172.11721 q 0,0.65267 -0.23568,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.97901,0.62548 -0.56202,0.22662 -1.22375,0.22662 -0.6708,0 -1.23283,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40791,-0.39885 -0.63454,-0.95181 -0.22662,-0.55296 -0.22662,-1.20563 0,-0.65267 0.22662,-1.20562 0.22663,-0.55296 0.63454,-0.95181 0.40792,-0.39886 0.96994,-0.62548 0.56203,-0.22662 1.23283,-0.22662 0.66173,0 1.22375,0.22662 0.57109,0.22662 0.97901,0.62548 0.40792,0.39885 0.63454,0.95181 0.23568,0.55295 0.23568,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58921 -0.10877,-0.28101 -0.3082,-0.48044 -0.19036,-0.19943 -0.46231,-0.3082 -0.27194,-0.11785 -0.59828,-0.11785 -0.3354,0 -0.61641,0.11785 -0.27195,0.10877 -0.47137,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27194 -0.10878,0.58921 0,0.31727 0.10878,0.58922 0.10878,0.27195 0.29914,0.47137 0.19942,0.19943 0.47137,0.31727 0.28101,0.10878 0.61641,0.10878 0.32634,0 0.59828,-0.10878 0.27195,-0.11784 0.46231,-0.31727 0.19943,-0.19942 0.3082,-0.47137 0.10878,-0.27195 0.10878,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<text
|
||||||
|
id="text3597"
|
||||||
|
y="196.26234"
|
||||||
|
x="396.47684"
|
||||||
|
style="font-style:normal;font-weight:normal;font-size:7.93824005px;line-height:1.25;font-family:sans-serif;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;stroke-width:0.198456"
|
||||||
|
xml:space="preserve"><tspan
|
||||||
|
style="stroke-width:0.198456"
|
||||||
|
y="203.28583"
|
||||||
|
x="396.47684"
|
||||||
|
id="tspan3595"
|
||||||
|
sodipodi:role="line" /></text>
|
||||||
|
<g
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;line-height:1.25;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
id="text3479-7-8-9-17-6"
|
||||||
|
aria-label="700">
|
||||||
|
<path
|
||||||
|
id="path3718"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 468.15605,175.06329 3.24522,-4.37832 h -4.1789 v -1.51384 h 5.77432 q 0.61641,0 0.61641,0.5167 v 0.31727 q 0,0.20849 -0.0725,0.37166 -0.0634,0.1541 -0.23568,0.38072 l -3.17271,4.30581 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3720"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 479.91304,172.11721 q 0,0.65267 -0.23569,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.97901,0.62548 -0.56202,0.22662 -1.22375,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22662,-0.55296 -0.22662,-1.20563 0,-0.65267 0.22662,-1.20562 0.22662,-0.55296 0.63454,-0.95181 0.40792,-0.39886 0.96994,-0.62548 0.56202,-0.22662 1.23282,-0.22662 0.66173,0 1.22375,0.22662 0.57109,0.22662 0.97901,0.62548 0.40792,0.39885 0.63454,0.95181 0.23569,0.55295 0.23569,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58921 -0.10878,-0.28101 -0.30821,-0.48044 -0.19036,-0.19943 -0.46231,-0.3082 -0.27194,-0.11785 -0.59828,-0.11785 -0.3354,0 -0.61641,0.11785 -0.27194,0.10877 -0.47137,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27194 -0.10878,0.58921 0,0.31727 0.10878,0.58922 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47137,0.31727 0.28101,0.10878 0.61641,0.10878 0.32634,0 0.59828,-0.10878 0.27195,-0.11784 0.46231,-0.31727 0.19943,-0.19942 0.30821,-0.47137 0.10878,-0.27195 0.10878,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3722"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 486.65857,172.11721 q 0,0.65267 -0.23569,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.979,0.62548 -0.56203,0.22662 -1.22376,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22662,-0.55296 -0.22662,-1.20563 0,-0.65267 0.22662,-1.20562 0.22662,-0.55296 0.63454,-0.95181 0.40792,-0.39886 0.96994,-0.62548 0.56202,-0.22662 1.23282,-0.22662 0.66173,0 1.22376,0.22662 0.57108,0.22662 0.979,0.62548 0.40792,0.39885 0.63454,0.95181 0.23569,0.55295 0.23569,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58921 -0.10878,-0.28101 -0.30821,-0.48044 -0.19036,-0.19943 -0.4623,-0.3082 -0.27195,-0.11785 -0.59829,-0.11785 -0.3354,0 -0.61641,0.11785 -0.27194,0.10877 -0.47137,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27194 -0.10878,0.58921 0,0.31727 0.10878,0.58922 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47137,0.31727 0.28101,0.10878 0.61641,0.10878 0.32634,0 0.59829,-0.10878 0.27194,-0.11784 0.4623,-0.31727 0.19943,-0.19942 0.30821,-0.47137 0.10878,-0.27195 0.10878,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;line-height:1.25;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
id="text3479-7-8-9-17-6-1"
|
||||||
|
aria-label="800">
|
||||||
|
<path
|
||||||
|
id="path3725"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 506.22745,175.06329 q -0.95181,0 -1.45944,-0.4623 -0.49857,-0.47138 -0.49857,-1.26908 0,-0.56203 0.22662,-0.90649 0.23569,-0.35353 0.58015,-0.47137 -0.31727,-0.12691 -0.4895,-0.44418 -0.16317,-0.32634 -0.16317,-0.78864 0,-0.32634 0.0997,-0.60735 0.0997,-0.29008 0.3082,-0.49857 0.2085,-0.20849 0.5439,-0.32633 0.3354,-0.11785 0.81583,-0.11785 h 2.38406 q 0.47137,0 0.80677,0.11785 0.3354,0.11784 0.5439,0.32633 0.21755,0.20849 0.3082,0.49857 0.0997,0.28101 0.0997,0.60735 0,0.4623 -0.16316,0.78864 -0.16317,0.31727 -0.48044,0.44418 0.34446,0.11784 0.57108,0.47137 0.23569,0.34446 0.23569,0.90649 0,0.7977 -0.50763,1.26908 -0.49857,0.4623 -1.45944,0.4623 z m 0.0544,-2.42938 q -0.21756,0 -0.34446,0.12691 -0.11785,0.11784 -0.11785,0.34446 0,0.21756 0.11785,0.3354 0.1269,0.11785 0.34446,0.11785 h 2.1937 q 0.21755,0 0.3354,-0.11785 0.12691,-0.11784 0.12691,-0.3354 0,-0.47137 -0.45325,-0.47137 z m 0.0907,-2.02146 q -0.20849,0 -0.32634,0.11784 -0.10877,0.10878 -0.10877,0.31727 0,0.20849 0.10877,0.32634 0.11785,0.11784 0.32634,0.11784 h 2.0124 q 0.20849,0 0.31727,-0.11784 0.11784,-0.11785 0.11784,-0.32634 0,-0.20849 -0.11784,-0.31727 -0.10878,-0.11784 -0.31727,-0.11784 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3727"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 517.19721,172.11721 q 0,0.65267 -0.23569,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.979,0.62548 -0.56203,0.22662 -1.22376,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22662,-0.55296 -0.22662,-1.20563 0,-0.65267 0.22662,-1.20562 0.22662,-0.55296 0.63454,-0.95181 0.40792,-0.39886 0.96994,-0.62548 0.56202,-0.22662 1.23282,-0.22662 0.66173,0 1.22376,0.22662 0.57108,0.22662 0.979,0.62548 0.40792,0.39885 0.63454,0.95181 0.23569,0.55295 0.23569,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58921 -0.10878,-0.28101 -0.30821,-0.48044 -0.19036,-0.19943 -0.4623,-0.3082 -0.27195,-0.11785 -0.59829,-0.11785 -0.3354,0 -0.61641,0.11785 -0.27194,0.10877 -0.47137,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27194 -0.10878,0.58921 0,0.31727 0.10878,0.58922 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47137,0.31727 0.28101,0.10878 0.61641,0.10878 0.32634,0 0.59829,-0.10878 0.27194,-0.11784 0.4623,-0.31727 0.19943,-0.19942 0.30821,-0.47137 0.10878,-0.27195 0.10878,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3729"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 523.94274,172.11721 q 0,0.65267 -0.23569,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.979,0.62548 -0.56202,0.22662 -1.22376,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22662,-0.55296 -0.22662,-1.20563 0,-0.65267 0.22662,-1.20562 0.22662,-0.55296 0.63454,-0.95181 0.40792,-0.39886 0.96994,-0.62548 0.56202,-0.22662 1.23282,-0.22662 0.66174,0 1.22376,0.22662 0.57108,0.22662 0.979,0.62548 0.40792,0.39885 0.63454,0.95181 0.23569,0.55295 0.23569,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58921 -0.10878,-0.28101 -0.30821,-0.48044 -0.19036,-0.19943 -0.4623,-0.3082 -0.27195,-0.11785 -0.59828,-0.11785 -0.3354,0 -0.61642,0.11785 -0.27194,0.10877 -0.47137,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27194 -0.10878,0.58921 0,0.31727 0.10878,0.58922 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47137,0.31727 0.28102,0.10878 0.61642,0.10878 0.32633,0 0.59828,-0.10878 0.27194,-0.11784 0.4623,-0.31727 0.19943,-0.19942 0.30821,-0.47137 0.10878,-0.27195 0.10878,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;line-height:1.25;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
id="text3479-7-8-9-17-6-1-6"
|
||||||
|
aria-label="900">
|
||||||
|
<path
|
||||||
|
id="path3732"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 544.55179,173.54946 q 1.12405,0 1.38693,-0.8521 h -2.77385 q -0.89742,0 -1.31441,-0.43511 -0.40791,-0.43511 -0.40791,-1.19656 0,-0.41698 0.11784,-0.76145 0.11784,-0.34446 0.36259,-0.59828 0.25382,-0.25382 0.64361,-0.38979 0.38979,-0.14504 0.93368,-0.14504 h 1.13311 q 0.68893,0 1.23282,0.19943 0.54389,0.19943 0.91555,0.57109 0.38072,0.37166 0.58015,0.89742 0.19943,0.52576 0.19943,1.17843 0,0.70706 -0.23569,1.27815 -0.23569,0.56202 -0.65267,0.96087 -0.41698,0.38979 -0.98807,0.59828 -0.57109,0.20849 -1.24189,0.20849 h -2.76478 v -1.51383 z m -1.44131,-2.44751 q 0,0.41698 0.38979,0.41698 h 2.43845 q -0.24475,-0.85209 -1.35973,-0.85209 h -1.01527 q -0.23568,0 -0.34446,0.11784 -0.10878,0.10878 -0.10878,0.31727 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3734"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 554.30686,172.11721 q 0,0.65267 -0.23569,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.979,0.62548 -0.56203,0.22662 -1.22376,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22662,-0.55296 -0.22662,-1.20563 0,-0.65267 0.22662,-1.20562 0.22662,-0.55296 0.63454,-0.95181 0.40792,-0.39886 0.96994,-0.62548 0.56202,-0.22662 1.23282,-0.22662 0.66173,0 1.22376,0.22662 0.57108,0.22662 0.979,0.62548 0.40792,0.39885 0.63454,0.95181 0.23569,0.55295 0.23569,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58921 -0.10878,-0.28101 -0.30821,-0.48044 -0.19036,-0.19943 -0.4623,-0.3082 -0.27195,-0.11785 -0.59829,-0.11785 -0.3354,0 -0.61641,0.11785 -0.27194,0.10877 -0.47137,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27194 -0.10878,0.58921 0,0.31727 0.10878,0.58922 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47137,0.31727 0.28101,0.10878 0.61641,0.10878 0.32634,0 0.59829,-0.10878 0.27194,-0.11784 0.4623,-0.31727 0.19943,-0.19942 0.30821,-0.47137 0.10878,-0.27195 0.10878,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3736"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 561.05239,172.11721 q 0,0.65267 -0.23569,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.979,0.62548 -0.56202,0.22662 -1.22376,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22662,-0.55296 -0.22662,-1.20563 0,-0.65267 0.22662,-1.20562 0.22662,-0.55296 0.63454,-0.95181 0.40792,-0.39886 0.96994,-0.62548 0.56202,-0.22662 1.23282,-0.22662 0.66174,0 1.22376,0.22662 0.57108,0.22662 0.979,0.62548 0.40792,0.39885 0.63454,0.95181 0.23569,0.55295 0.23569,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58921 -0.10878,-0.28101 -0.30821,-0.48044 -0.19036,-0.19943 -0.4623,-0.3082 -0.27195,-0.11785 -0.59828,-0.11785 -0.3354,0 -0.61642,0.11785 -0.27194,0.10877 -0.47137,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27194 -0.10878,0.58921 0,0.31727 0.10878,0.58922 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47137,0.31727 0.28102,0.10878 0.61642,0.10878 0.32633,0 0.59828,-0.10878 0.27194,-0.11784 0.4623,-0.31727 0.19943,-0.19942 0.30821,-0.47137 0.10878,-0.27195 0.10878,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<g
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;line-height:1.25;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
id="text3479-7-8-9-17-6-1-6-0"
|
||||||
|
aria-label="1000">
|
||||||
|
<path
|
||||||
|
id="path3739"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 577.14781,175.06329 v -3.73472 q 0,-0.29007 -0.1813,-0.46231 -0.17223,-0.17223 -0.46231,-0.17223 h -0.70706 v -1.5229 h 0.97901 q 0.42605,0 0.77957,0.13598 0.3626,0.12691 0.62548,0.37166 0.26288,0.24475 0.40792,0.58921 0.14504,0.3354 0.14504,0.74332 v 4.05199 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3741"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 585.61963,172.11721 q 0,0.65267 -0.23569,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.97901,0.62548 -0.56202,0.22662 -1.22375,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22662,-0.55296 -0.22662,-1.20563 0,-0.65267 0.22662,-1.20562 0.22662,-0.55296 0.63454,-0.95181 0.40792,-0.39886 0.96994,-0.62548 0.56202,-0.22662 1.23282,-0.22662 0.66173,0 1.22375,0.22662 0.57109,0.22662 0.97901,0.62548 0.40792,0.39885 0.63454,0.95181 0.23569,0.55295 0.23569,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58921 -0.10878,-0.28101 -0.30821,-0.48044 -0.19036,-0.19943 -0.46231,-0.3082 -0.27194,-0.11785 -0.59828,-0.11785 -0.3354,0 -0.61641,0.11785 -0.27194,0.10877 -0.47137,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27194 -0.10878,0.58921 0,0.31727 0.10878,0.58922 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47137,0.31727 0.28101,0.10878 0.61641,0.10878 0.32634,0 0.59828,-0.10878 0.27195,-0.11784 0.46231,-0.31727 0.19943,-0.19942 0.30821,-0.47137 0.10878,-0.27195 0.10878,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3743"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 592.36516,172.11721 q 0,0.65267 -0.23569,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.979,0.62548 -0.56203,0.22662 -1.22376,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22662,-0.55296 -0.22662,-1.20563 0,-0.65267 0.22662,-1.20562 0.22662,-0.55296 0.63454,-0.95181 0.40792,-0.39886 0.96994,-0.62548 0.56202,-0.22662 1.23282,-0.22662 0.66173,0 1.22376,0.22662 0.57108,0.22662 0.979,0.62548 0.40792,0.39885 0.63454,0.95181 0.23569,0.55295 0.23569,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58921 -0.10878,-0.28101 -0.30821,-0.48044 -0.19036,-0.19943 -0.46231,-0.3082 -0.27194,-0.11785 -0.59828,-0.11785 -0.3354,0 -0.61641,0.11785 -0.27194,0.10877 -0.47137,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27194 -0.10878,0.58921 0,0.31727 0.10878,0.58922 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47137,0.31727 0.28101,0.10878 0.61641,0.10878 0.32634,0 0.59828,-0.10878 0.27195,-0.11784 0.46231,-0.31727 0.19943,-0.19942 0.30821,-0.47137 0.10878,-0.27195 0.10878,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
id="path3745"
|
||||||
|
style="font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;font-size:9.06486034px;font-family:'Good Timing';-inkscape-font-specification:'Good Timing, Normal';font-variant-ligatures:normal;font-variant-caps:normal;font-variant-numeric:normal;fill:#ffffff;fill-opacity:1;stroke-width:0;stroke-miterlimit:4;stroke-dasharray:none"
|
||||||
|
d="m 599.11069,172.11721 q 0,0.65267 -0.23569,1.20563 -0.22662,0.55296 -0.63454,0.95181 -0.40792,0.39885 -0.979,0.62548 -0.56203,0.22662 -1.22376,0.22662 -0.6708,0 -1.23282,-0.22662 -0.56202,-0.22663 -0.96994,-0.62548 -0.40792,-0.39885 -0.63454,-0.95181 -0.22662,-0.55296 -0.22662,-1.20563 0,-0.65267 0.22662,-1.20562 0.22662,-0.55296 0.63454,-0.95181 0.40792,-0.39886 0.96994,-0.62548 0.56202,-0.22662 1.23282,-0.22662 0.66173,0 1.22376,0.22662 0.57108,0.22662 0.979,0.62548 0.40792,0.39885 0.63454,0.95181 0.23569,0.55295 0.23569,1.20562 z m -1.58635,0 q 0,-0.31727 -0.10878,-0.58921 -0.10878,-0.28101 -0.30821,-0.48044 -0.19036,-0.19943 -0.46231,-0.3082 -0.27194,-0.11785 -0.59828,-0.11785 -0.3354,0 -0.61641,0.11785 -0.27194,0.10877 -0.47137,0.3082 -0.19036,0.19943 -0.29914,0.48044 -0.10878,0.27194 -0.10878,0.58921 0,0.31727 0.10878,0.58922 0.10878,0.27195 0.29914,0.47137 0.19943,0.19943 0.47137,0.31727 0.28101,0.10878 0.61641,0.10878 0.32634,0 0.59828,-0.10878 0.27195,-0.11784 0.46231,-0.31727 0.19943,-0.19942 0.30821,-0.47137 0.10878,-0.27195 0.10878,-0.58922 z"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
</g>
|
||||||
|
<path
|
||||||
|
transform="translate(324.47462,186.34357)"
|
||||||
|
inkscape:path-effect="#path-effect3437-9"
|
||||||
|
inkscape:original-d="M 227.7742,166.34581 -97.015638,-21.171687"
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
id="path3435-4"
|
||||||
|
d="M 227.7742,166.34581 -97.015638,-21.171687"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:2.05969214;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:4.11938438, 2.05969219, 1.0298461, 2.05969219;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
inkscape:connector-curvature="0" />
|
||||||
|
<path
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
style="fill:none;stroke:#ffffff;stroke-width:2.05969214;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:4.11938438, 2.05969219, 1.0298461, 2.05969219;stroke-dashoffset:0;stroke-opacity:1"
|
||||||
|
d="M 227.7742,166.34581 -97.015638,-21.171687"
|
||||||
|
id="path939"
|
||||||
|
sodipodi:nodetypes="cc"
|
||||||
|
inkscape:original-d="M 227.7742,166.34581 -97.015638,-21.171687"
|
||||||
|
inkscape:path-effect="#path-effect941"
|
||||||
|
transform="matrix(-1,0,0,1,130.75858,187.15331)" />
|
||||||
|
<path
|
||||||
|
style="fill:none;fill-opacity:1;stroke:none;stroke-width:83.87161255;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:167.74322712, 83.87161360000000343, 41.93580680000000172, 83.87161360000000343;stroke-dashoffset:0;stroke-opacity:1;paint-order:markers fill stroke"
|
||||||
|
d="m 1753.8725,2623.1523 c -189.8008,-34.344 -372.2274,-153.5374 -480.0607,-313.6606 l -27.1485,-40.3132 30.0196,-18.4616 c 16.5107,-10.1539 34.5652,-18.5752 40.121,-18.7139 5.5559,-0.1387 10.1016,-3.6437 10.1016,-7.7888 0,-4.1452 8.0126,-10.0798 17.8058,-13.188 9.7932,-3.1083 22.7809,-10.6264 28.8615,-16.7071 16.3026,-16.3026 19.4707,-14.4014 49.3146,29.5936 34.9652,51.5446 114.8971,125.5745 172.6836,159.933 60.4219,35.9255 144.7256,64.384 223.8922,75.5796 l 65.0465,9.1988 v 83.5938 83.5939 l -34.3452,-0.7252 c -18.8899,-0.3988 -62.2212,-5.7693 -96.292,-11.9343 z"
|
||||||
|
id="path963"
|
||||||
|
inkscape:connector-curvature="0"
|
||||||
|
transform="matrix(0.19845602,0,0,0.19845602,-147.5762,-208.87145)" />
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
After Width: | Height: | Size: 78 KiB |