initial check-in

This commit is contained in:
Terje Io 2021-02-23 07:47:52 +01:00
commit 0381e830f1
40 changed files with 6028 additions and 0 deletions

18
.gitattributes vendored Normal file
View File

@ -0,0 +1,18 @@
# Auto detect text files and perform LF normalization
* text=auto eol=lf
# Custom for Visual Studio
*.cs diff=csharp
# Standard to msysgit
*.doc diff=astextplain
*.DOC diff=astextplain
*.docx diff=astextplain
*.DOCX diff=astextplain
*.dot diff=astextplain
*.DOT diff=astextplain
*.pdf diff=astextplain
*.PDF diff=astextplain
*.rtf diff=astextplain
*.RTF diff=astextplain

35
.gitignore vendored Normal file
View File

@ -0,0 +1,35 @@
# Windows thumbnail cache files
Thumbs.db
ehthumbs.db
ehthumbs_vista.db
# Folder config file
Desktop.ini
# Recycle Bin used on file shares
$RECYCLE.BIN/
# Windows Installer files
*.cab
*.msi
*.msm
*.msp
# Windows shortcuts
*.lnk
# Subversion folders
.svn
# Build folder
build
#
# =========================
# Operating System Files
# =========================
.vscode/settings.json
.vscode/c_cpp_properties.json

30
.gitmodules vendored Normal file
View File

@ -0,0 +1,30 @@
[submodule "src/grbl"]
path = src/grbl
url = https://github.com/grblHAL/core
[submodule "src/odometer"]
path = src/odometer
url = https://github.com/grblHAL/Plugin_odometer
[submodule "src/laser"]
path = src/laser
url = https://github.com/grblHAL/Plugins_laser
[submodule "src/encoder"]
path = src/encoder
url = https://github.com/grblHAL/Plugin_encoder
[submodule "src/keypad"]
path = src/keypad
url = https://github.com/grblHAL/Plugin_I2C_keypad
[submodule "src/networking"]
path = src/networking
url = https://github.com/grblHAL/Plugin_networking
[submodule "src/sdcard"]
path = src/sdcard
url = https://github.com/grblHAL/Plugin_SD_card
[submodule "src/spindle"]
path = src/spindle
url = https://github.com/grblHAL/Plugins_spindle
[submodule "src/plasma"]
path = src/plasma
url = https://github.com/grblHAL/Plugin_plasma
[submodule "src/eeprom"]
path = src/eeprom
url = https://github.com/grblHAL/Plugin_EEPROM

View File

@ -0,0 +1,26 @@
/*
grblHAL_Teensy4_Upload.ino - upload code for iMRXT1062 processor on a Teensy4.x board
Part of GrblHAL
Copyright (c) 2020 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl is distributed in the hope that it will be useful,ss
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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
// Double tap reset to enter bootloader mode - select bootloader port for programming
#include "grblHAL_Teensy4.h"

17
library.json Normal file
View File

@ -0,0 +1,17 @@
{
"name": "grblHAL for Teensy 4.x",
"frameworks": "Arduino",
"platforms": "Twensy 4.0 - 4.1",
"keywords": "grbl, CNC",
"description": "grblHAL for Teensy 4.x",
"version": "1.1.7",
"authors":
{ "name": "Terje Io",
"maintainer": true
},
"repository":
{ "type": "git",
"url": "https://github.com/terjeio/grblHAL"
},
"examples": "examples/*/*.ino"
}

9
library.properties Normal file
View File

@ -0,0 +1,9 @@
name=grblHAL for Teensy 4.x
version=1.1.7
author=Terje Io
maintainer=Terje Io
sentence=grblHAL for Teensy 4.x
paragraph=
category=Other
url=https://github.com/terjeio/grblHAL
architectures=*

115
src/.cproject Normal file
View File

@ -0,0 +1,115 @@
<?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.1548809601">
<storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.toolchain.gnu.cross.base.1548809601" moduleId="org.eclipse.cdt.core.settings" name="Default">
<macros>
<stringMacro name="ARDUINO_HARDWARE" type="VALUE_TEXT" value="C:\Program Files (x86)\Arduino\hardware"/>
<stringMacro name="COMPILER_LOC" type="VALUE_TEXT" value="C:\Program Files (x86)\Arduino\hardware\tools\arm"/>
<stringMacro name="ETHERNET_LIB" type="VALUE_TEXT" value="C:\users\terjeio\Documents\Arduino\libraries\teensy41_ethernet-master\src"/>
<stringMacro name="ARDUINOPATH" type="VALUE_TEXT" value="C:\Program Files (x86)\Arduino"/>
</macros>
<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 buildProperties="" description="" id="cdt.managedbuild.toolchain.gnu.cross.base.1548809601" name="Default" optionalBuildProperties="" parent="org.eclipse.cdt.build.core.emptycfg">
<folderInfo id="cdt.managedbuild.toolchain.gnu.cross.base.1548809601.612984045" name="/" resourcePath="">
<toolChain id="cdt.managedbuild.toolchain.gnu.cross.base.518815447" name="Cross GCC" superClass="cdt.managedbuild.toolchain.gnu.cross.base">
<option id="cdt.managedbuild.option.gnu.cross.prefix.2007152370" name="Prefix" superClass="cdt.managedbuild.option.gnu.cross.prefix"/>
<option id="cdt.managedbuild.option.gnu.cross.path.971492409" name="Path" superClass="cdt.managedbuild.option.gnu.cross.path"/>
<targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="cdt.managedbuild.targetPlatform.gnu.cross.939061726" isAbstract="false" osList="all" superClass="cdt.managedbuild.targetPlatform.gnu.cross"/>
<builder arguments="Teensy4\build.cmd" command="D:\Projects\Espressif\Driver" id="cdt.managedbuild.builder.gnu.cross.1161603698" keepEnvironmentInBuildfile="false" managedBuildOn="false" name="Gnu Make Builder" superClass="cdt.managedbuild.builder.gnu.cross">
<outputEntries>
<entry flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="outputPath" name=""/>
</outputEntries>
</builder>
<tool id="cdt.managedbuild.tool.gnu.cross.c.compiler.105586221" name="Cross GCC Compiler" superClass="cdt.managedbuild.tool.gnu.cross.c.compiler">
<option IS_BUILTIN_EMPTY="false" IS_VALUE_EMPTY="false" id="gnu.c.compiler.option.include.paths.1419568434" name="Include paths (-I)" superClass="gnu.c.compiler.option.include.paths" useByScannerDiscovery="false" valueType="includePath">
<listOptionValue builtIn="false" value="&quot;../${ETHERNET_LIB}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${COMPILER_LOC}\arm-none-eabi\include&quot;"/>
<listOptionValue builtIn="false" value="&quot;${COMPILER_LOC}\lib\gcc\arm-none-eabi\5.4.1\include&quot;"/>
<listOptionValue builtIn="false" value="&quot;${ARDUINO_HARDWARE}\teensy\avr\cores\teensy4&quot;"/>
</option>
<option IS_BUILTIN_EMPTY="false" IS_VALUE_EMPTY="false" id="gnu.c.compiler.option.include.files.897313686" name="Include files (-include)" superClass="gnu.c.compiler.option.include.files" useByScannerDiscovery="false" valueType="includeFiles">
<listOptionValue builtIn="false" value="&quot;C:\Program Files (x86)\Arduino\hardware\teensy\avr\cores\teensy4\imxrt.h&quot;"/>
</option>
<option IS_BUILTIN_EMPTY="false" IS_VALUE_EMPTY="false" id="gnu.c.compiler.option.preprocessor.def.symbols.823275224" name="Defined symbols (-D)" superClass="gnu.c.compiler.option.preprocessor.def.symbols" useByScannerDiscovery="false" valueType="definedSymbols">
<listOptionValue builtIn="false" value="&quot;ETHERNET_LIB=C:\users\terjeio\Documents\Arduino\libraries\teensy41_ethernet-master\src&quot;"/>
<listOptionValue builtIn="false" value="ARDUINO_TEENSY41"/>
<listOptionValue builtIn="false" value="ARDUINO"/>
<listOptionValue builtIn="false" value="__IMXRT1062__"/>
</option>
<inputType id="cdt.managedbuild.tool.gnu.c.compiler.input.1291096238" superClass="cdt.managedbuild.tool.gnu.c.compiler.input"/>
</tool>
<tool id="cdt.managedbuild.tool.gnu.cross.cpp.compiler.20257565" name="Cross G++ Compiler" superClass="cdt.managedbuild.tool.gnu.cross.cpp.compiler">
<option IS_BUILTIN_EMPTY="false" IS_VALUE_EMPTY="false" id="gnu.cpp.compiler.option.include.paths.1967174191" name="Include paths (-I)" superClass="gnu.cpp.compiler.option.include.paths" useByScannerDiscovery="false" valueType="includePath">
<listOptionValue builtIn="false" value="&quot;../${ETHERNET_LIB}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${COMPILER_LOC}\arm-none-eabi\include&quot;"/>
<listOptionValue builtIn="false" value="&quot;${COMPILER_LOC}\lib\gcc\arm-none-eabi\5.4.1\include&quot;"/>
<listOptionValue builtIn="false" value="&quot;${ARDUINO_HARDWARE}\teensy\avr\cores\teensy4&quot;"/>
</option>
<option IS_BUILTIN_EMPTY="false" IS_VALUE_EMPTY="false" id="gnu.cpp.compiler.option.preprocessor.def.1442240395" name="Defined symbols (-D)" superClass="gnu.cpp.compiler.option.preprocessor.def" useByScannerDiscovery="false" valueType="definedSymbols">
<listOptionValue builtIn="false" value="&quot;ETHERNET_LIB=C:\users\terjeio\Documents\Arduino\libraries\teensy41_ethernet-master\src&quot;"/>
<listOptionValue builtIn="false" value="ARDUINO_TEENSY41"/>
<listOptionValue builtIn="false" value="ARDUINO"/>
</option>
<inputType id="cdt.managedbuild.tool.gnu.cpp.compiler.input.839035704" superClass="cdt.managedbuild.tool.gnu.cpp.compiler.input"/>
</tool>
<tool id="cdt.managedbuild.tool.gnu.cross.c.linker.1045789806" name="Cross GCC Linker" superClass="cdt.managedbuild.tool.gnu.cross.c.linker"/>
<tool id="cdt.managedbuild.tool.gnu.cross.cpp.linker.2115955747" name="Cross G++ Linker" superClass="cdt.managedbuild.tool.gnu.cross.cpp.linker">
<option IS_BUILTIN_EMPTY="false" IS_VALUE_EMPTY="true" id="gnu.cpp.link.option.paths.1990632849" name="Library search path (-L)" superClass="gnu.cpp.link.option.paths" valueType="libPaths"/>
<inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.861340448" 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.434033752" name="Cross GCC Archiver" superClass="cdt.managedbuild.tool.gnu.cross.archiver"/>
<tool id="cdt.managedbuild.tool.gnu.cross.assembler.1111871985" name="Cross GCC Assembler" superClass="cdt.managedbuild.tool.gnu.cross.assembler">
<inputType id="cdt.managedbuild.tool.gnu.assembler.input.158666844" superClass="cdt.managedbuild.tool.gnu.assembler.input"/>
</tool>
</toolChain>
</folderInfo>
</configuration>
</storageModule>
<storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
</cconfiguration>
</storageModule>
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
<project id="Driver Teensy4.null.1834074800" name="Driver Teensy4"/>
</storageModule>
<storageModule moduleId="org.eclipse.cdt.core.LanguageSettingsProviders"/>
<storageModule moduleId="refreshScope" versionNumber="2">
<configuration configurationName="Default">
<resource resourceType="PROJECT" workspacePath="/Driver Teensy4"/>
</configuration>
</storageModule>
<storageModule moduleId="scannerConfiguration">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.cross.base.1548809601;cdt.managedbuild.toolchain.gnu.cross.base.1548809601.612984045;cdt.managedbuild.tool.gnu.cross.cpp.compiler.20257565;cdt.managedbuild.tool.gnu.cpp.compiler.input.839035704">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
</scannerConfigBuildInfo>
<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.cross.base.1548809601;cdt.managedbuild.toolchain.gnu.cross.base.1548809601.612984045;cdt.managedbuild.tool.gnu.cross.c.compiler.105586221;cdt.managedbuild.tool.gnu.c.compiler.input.1291096238">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
</scannerConfigBuildInfo>
</storageModule>
<storageModule moduleId="org.eclipse.cdt.make.core.buildtargets">
<buildTargets>
<target name="iMXRT1062" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments/>
<buildTarget>iMXRT1062</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
</buildTargets>
</storageModule>
</cproject>

45
src/.project Normal file
View File

@ -0,0 +1,45 @@
<?xml version="1.0" encoding="UTF-8"?>
<projectDescription>
<name>Driver Teensy4</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>
<variableList>
<variable>
<name>ARDUINOPATH</name>
<value>file:/C:/Program%20Files%20(x86)/Arduino</value>
</variable>
<variable>
<name>COMPILER_LOC</name>
<value>file:/C:/Program%20Files%20(x86)/Arduino/hardware/tools/arm/arm-none-eabi</value>
</variable>
<variable>
<name>ETHERNET_LIB</name>
<value>file:/C:/users/terjeio/Documents/Arduino/libraries/teensy41_ethernet-master/src</value>
</variable>
<variable>
<name>TEENSY4_CORE</name>
<value>file:/C:/Program%20Files%20(x86)/Arduino/hardware/teensy/avr/cores/teensy4</value>
</variable>
</variableList>
</projectDescription>

View File

@ -0,0 +1,15 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<project>
<configuration id="cdt.managedbuild.toolchain.gnu.cross.base.1548809601" name="Default">
<extension point="org.eclipse.cdt.core.LanguageSettingsProvider">
<provider class="org.eclipse.cdt.core.language.settings.providers.LanguageSettingsGenericProvider" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider" name="CDT User Setting Entries" prefer-non-shared="true"/>
<provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
<provider copy-of="extension" id="org.eclipse.cdt.managedbuilder.core.GCCBuildCommandParser"/>
<provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-354975797569" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
<language-scope id="org.eclipse.cdt.core.gcc"/>
<language-scope id="org.eclipse.cdt.core.g++"/>
</provider>
<provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
</extension>
</configuration>
</project>

View File

@ -0,0 +1,93 @@
eclipse.preferences.version=1
org.eclipse.cdt.codan.checkers.errnoreturn=Warning
org.eclipse.cdt.codan.checkers.errnoreturn.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"No return\\")",implicit\=>false}
org.eclipse.cdt.codan.checkers.errreturnvalue=Error
org.eclipse.cdt.codan.checkers.errreturnvalue.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Unused return value\\")"}
org.eclipse.cdt.codan.checkers.nocommentinside=-Error
org.eclipse.cdt.codan.checkers.nocommentinside.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Nesting comments\\")"}
org.eclipse.cdt.codan.checkers.nolinecomment=-Error
org.eclipse.cdt.codan.checkers.nolinecomment.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Line comments\\")"}
org.eclipse.cdt.codan.checkers.noreturn=Error
org.eclipse.cdt.codan.checkers.noreturn.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"No return value\\")",implicit\=>false}
org.eclipse.cdt.codan.internal.checkers.AbstractClassCreation=Error
org.eclipse.cdt.codan.internal.checkers.AbstractClassCreation.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Abstract class cannot be instantiated\\")"}
org.eclipse.cdt.codan.internal.checkers.AmbiguousProblem=Error
org.eclipse.cdt.codan.internal.checkers.AmbiguousProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Ambiguous problem\\")"}
org.eclipse.cdt.codan.internal.checkers.AssignmentInConditionProblem=Warning
org.eclipse.cdt.codan.internal.checkers.AssignmentInConditionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Assignment in condition\\")"}
org.eclipse.cdt.codan.internal.checkers.AssignmentToItselfProblem=Error
org.eclipse.cdt.codan.internal.checkers.AssignmentToItselfProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Assignment to itself\\")"}
org.eclipse.cdt.codan.internal.checkers.CStyleCastProblem=-Warning
org.eclipse.cdt.codan.internal.checkers.CStyleCastProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"C-Style cast instead of C++ cast\\")"}
org.eclipse.cdt.codan.internal.checkers.CaseBreakProblem=Warning
org.eclipse.cdt.codan.internal.checkers.CaseBreakProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"No break at end of case\\")",no_break_comment\=>"no break",last_case_param\=>false,empty_case_param\=>false,enable_fallthrough_quickfix_param\=>false}
org.eclipse.cdt.codan.internal.checkers.CatchByReference=Warning
org.eclipse.cdt.codan.internal.checkers.CatchByReference.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Catching by reference is recommended\\")",unknown\=>false,exceptions\=>()}
org.eclipse.cdt.codan.internal.checkers.CircularReferenceProblem=Error
org.eclipse.cdt.codan.internal.checkers.CircularReferenceProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Circular inheritance\\")"}
org.eclipse.cdt.codan.internal.checkers.ClassMembersInitialization=Warning
org.eclipse.cdt.codan.internal.checkers.ClassMembersInitialization.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Class members should be properly initialized\\")",skip\=>true}
org.eclipse.cdt.codan.internal.checkers.CopyrightProblem=-Warning
org.eclipse.cdt.codan.internal.checkers.CopyrightProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Lack of copyright information\\")",regex\=>".*Copyright.*"}
org.eclipse.cdt.codan.internal.checkers.DecltypeAutoProblem=Error
org.eclipse.cdt.codan.internal.checkers.DecltypeAutoProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Invalid 'decltype(auto)' specifier\\")"}
org.eclipse.cdt.codan.internal.checkers.FieldResolutionProblem=Error
org.eclipse.cdt.codan.internal.checkers.FieldResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Field cannot be resolved\\")"}
org.eclipse.cdt.codan.internal.checkers.FunctionResolutionProblem=Error
org.eclipse.cdt.codan.internal.checkers.FunctionResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Function cannot be resolved\\")"}
org.eclipse.cdt.codan.internal.checkers.GotoStatementProblem=-Warning
org.eclipse.cdt.codan.internal.checkers.GotoStatementProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Goto statement used\\")"}
org.eclipse.cdt.codan.internal.checkers.InvalidArguments=Error
org.eclipse.cdt.codan.internal.checkers.InvalidArguments.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Invalid arguments\\")"}
org.eclipse.cdt.codan.internal.checkers.InvalidTemplateArgumentsProblem=Error
org.eclipse.cdt.codan.internal.checkers.InvalidTemplateArgumentsProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Invalid template argument\\")"}
org.eclipse.cdt.codan.internal.checkers.LabelStatementNotFoundProblem=Error
org.eclipse.cdt.codan.internal.checkers.LabelStatementNotFoundProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Label statement not found\\")"}
org.eclipse.cdt.codan.internal.checkers.MemberDeclarationNotFoundProblem=Error
org.eclipse.cdt.codan.internal.checkers.MemberDeclarationNotFoundProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Member declaration not found\\")"}
org.eclipse.cdt.codan.internal.checkers.MethodResolutionProblem=Error
org.eclipse.cdt.codan.internal.checkers.MethodResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Method cannot be resolved\\")"}
org.eclipse.cdt.codan.internal.checkers.MissCaseProblem=-Warning
org.eclipse.cdt.codan.internal.checkers.MissCaseProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Missing cases in switch\\")"}
org.eclipse.cdt.codan.internal.checkers.MissDefaultProblem=-Warning
org.eclipse.cdt.codan.internal.checkers.MissDefaultProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Missing default in switch\\")",defaultWithAllEnums\=>false}
org.eclipse.cdt.codan.internal.checkers.MissReferenceProblem=-Warning
org.eclipse.cdt.codan.internal.checkers.MissReferenceProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Missing reference return value in assignment operator\\")"}
org.eclipse.cdt.codan.internal.checkers.MissSelfCheckProblem=-Warning
org.eclipse.cdt.codan.internal.checkers.MissSelfCheckProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Missing self check in assignment operator\\")"}
org.eclipse.cdt.codan.internal.checkers.NamingConventionFunctionChecker=-Info
org.eclipse.cdt.codan.internal.checkers.NamingConventionFunctionChecker.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Name convention for function\\")",pattern\=>"^[a-z]",macro\=>true,exceptions\=>()}
org.eclipse.cdt.codan.internal.checkers.NonVirtualDestructorProblem=Warning
org.eclipse.cdt.codan.internal.checkers.NonVirtualDestructorProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Class has a virtual method and non-virtual destructor\\")"}
org.eclipse.cdt.codan.internal.checkers.OverloadProblem=Error
org.eclipse.cdt.codan.internal.checkers.OverloadProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Invalid overload\\")"}
org.eclipse.cdt.codan.internal.checkers.RedeclarationProblem=Error
org.eclipse.cdt.codan.internal.checkers.RedeclarationProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Invalid redeclaration\\")"}
org.eclipse.cdt.codan.internal.checkers.RedefinitionProblem=Error
org.eclipse.cdt.codan.internal.checkers.RedefinitionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Invalid redefinition\\")"}
org.eclipse.cdt.codan.internal.checkers.ReturnStyleProblem=-Warning
org.eclipse.cdt.codan.internal.checkers.ReturnStyleProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Return with parenthesis\\")"}
org.eclipse.cdt.codan.internal.checkers.ScanfFormatStringSecurityProblem=-Warning
org.eclipse.cdt.codan.internal.checkers.ScanfFormatStringSecurityProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Format String Vulnerability\\")"}
org.eclipse.cdt.codan.internal.checkers.StatementHasNoEffectProblem=Warning
org.eclipse.cdt.codan.internal.checkers.StatementHasNoEffectProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Statement has no effect\\")",macro\=>true,exceptions\=>()}
org.eclipse.cdt.codan.internal.checkers.SuggestedParenthesisProblem=Warning
org.eclipse.cdt.codan.internal.checkers.SuggestedParenthesisProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Suggested parenthesis around expression\\")",paramNot\=>false}
org.eclipse.cdt.codan.internal.checkers.SuspiciousSemicolonProblem=Warning
org.eclipse.cdt.codan.internal.checkers.SuspiciousSemicolonProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Suspicious semicolon\\")",else\=>false,afterelse\=>false}
org.eclipse.cdt.codan.internal.checkers.TypeResolutionProblem=Error
org.eclipse.cdt.codan.internal.checkers.TypeResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Type cannot be resolved\\")"}
org.eclipse.cdt.codan.internal.checkers.UnusedFunctionDeclarationProblem=Warning
org.eclipse.cdt.codan.internal.checkers.UnusedFunctionDeclarationProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Unused function declaration\\")",macro\=>true}
org.eclipse.cdt.codan.internal.checkers.UnusedStaticFunctionProblem=Warning
org.eclipse.cdt.codan.internal.checkers.UnusedStaticFunctionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Unused static function\\")",macro\=>true}
org.eclipse.cdt.codan.internal.checkers.UnusedVariableDeclarationProblem=Warning
org.eclipse.cdt.codan.internal.checkers.UnusedVariableDeclarationProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Unused variable declaration in file scope\\")",macro\=>true,exceptions\=>("@(\#)","$Id")}
org.eclipse.cdt.codan.internal.checkers.UsingInHeaderProblem=-Warning
org.eclipse.cdt.codan.internal.checkers.UsingInHeaderProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Using directive in header\\")"}
org.eclipse.cdt.codan.internal.checkers.VariableResolutionProblem=Error
org.eclipse.cdt.codan.internal.checkers.VariableResolutionProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Symbol is not resolved\\")"}
org.eclipse.cdt.codan.internal.checkers.VirtualMethodCallProblem=-Error
org.eclipse.cdt.codan.internal.checkers.VirtualMethodCallProblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>true,RUN_ON_INC_BUILD\=>true,RUN_ON_FILE_OPEN\=>false,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>"@suppress(\\"Virtual method call in constructor/destructor\\")"}
org.eclipse.cdt.qt.core.qtproblem=Warning
org.eclipse.cdt.qt.core.qtproblem.params={launchModes\=>{RUN_ON_FULL_BUILD\=>false,RUN_ON_INC_BUILD\=>false,RUN_ON_FILE_OPEN\=>true,RUN_ON_FILE_SAVE\=>false,RUN_AS_YOU_TYPE\=>true,RUN_ON_DEMAND\=>true},suppression_comment\=>null}

118
src/T40X101_map.h Normal file
View File

@ -0,0 +1,118 @@
/*
T40X101_map.h - driver code for IMXRT1062 processor (on Teensy 4.0 board)
Part of grblHAL
Board by Phil Barrett: https://github.com/phil-barrett/grblHAL-teensy-4.x
Copyright (c) 2020 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#define BOARD_NAME "T40X101"
#if N_AXIS > 4
#error Max number of axes is 4 for T40X101
#endif
#if QEI_ENABLE
#error No pins available for encoder input!
#endif
// Default pin assignments allow only one axis to be ganged or auto squared.
// A axis pin numbers are used for the ganged/auto squared axis.
// If a second axis is to be ganged/auto squared pin assignments needs to be changed!
// Set to 1 to enable, 0 to disable.
#define X_GANGED 0
#define X_AUTO_SQUARE 0
#define Y_GANGED 0
#define Y_AUTO_SQUARE 0
#define Z_GANGED 0
#define Z_AUTO_SQUARE 0
//
#define X_STEP_PIN (2u)
#define X_DIRECTION_PIN (3u)
#define X_LIMIT_PIN (20u)
#if X_GANGED || X_AUTO_SQUARE
#define X2_STEP_PIN (8u)
#define X2_DIRECTION_PIN (9u)
#if X_AUTO_SQUARE
#define X2_LIMIT_PIN (23u)
#endif
#endif
#define Y_STEP_PIN (4u)
#define Y_DIRECTION_PIN (5u)
#define Y_LIMIT_PIN (21u)
#if Y_GANGED || Y_AUTO_SQUARE
#define Y2_STEP_PIN (8u)
#define Y2_DIRECTION_PIN (9u)
#if Y_AUTO_SQUARE
#define Y2_LIMIT_PIN (23u)
#endif
#endif
#define Z_STEP_PIN (6u)
#define Z_DIRECTION_PIN (7u)
#define Z_LIMIT_PIN (22u)
#if Z_GANGED || Z_AUTO_SQUARE
#define Z2_STEP_PIN (8u)
#define Z2_DIRECTION_PIN (9u)
#define Z2_LIMIT_PIN (23u)
#endif
#if N_AXIS > 3
#define A_STEP_PIN (8u)
#define A_DIRECTION_PIN (9u)
#define A_LIMIT_PIN (23u)
#endif
#if N_AXIS > 4
#define B_STEP_PIN (26u)
#define B_DIRECTION_PIN (27u)
#define B_ENABLE_PIN (37u)
#define B_LIMIT_PIN (28u)
#endif
// Define stepper driver enable/disable output pin(s).
#define STEPPERS_ENABLE_PIN (10u)
// Define spindle enable and spindle direction output pins.
#define SPINDLE_ENABLE_PIN (12u)
#define SPINDLE_DIRECTION_PIN (11u)
#define SPINDLEPWMPIN (13u) // NOTE: only pin 12 or pin 13 can be assigned!
// Define flood and mist coolant enable output pins.
#define COOLANT_FLOOD_PIN (19u)
#define COOLANT_MIST_PIN (18u)
// Define user-control CONTROLs (cycle start, reset, feed hold, door) input pins.
#define RESET_PIN (14u)
#define FEED_HOLD_PIN (16u)
#define CYCLE_START_PIN (17u)
#define SAFETY_DOOR_PIN (29u)
// Define probe switch input pin.
#define PROBE_PIN (15U)
#if EEPROM_ENABLE || KEYPAD_ENABLE
#define I2C_PORT 4
#define I2C_SCL4 (24u) // Not used, for info only
#define I2C_SDA4 (25u) // Not used, for info only
#endif

194
src/T41U5XBB.c Normal file
View File

@ -0,0 +1,194 @@
/*
T41U5XBB.c - driver code for IMXRT1062 processor (on Teensy 4.1 board)
Part of grblHAL
Board by Phil Barrett: https://github.com/phil-barrett/grblHAL-teensy-4.x
Copyright (c) 2020-2021 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#include "driver.h"
#ifdef BOARD_T41U5XBB
//#include "Arduino.h"
#include <math.h>
#include <string.h>
#include "grbl/protocol.h"
static gpio_t stx[AUX_N_IN];
static gpio_t aux_out[AUX_N_OUT];
static void aux_settings_load (void);
static status_code_t aux_set_invert_out (setting_id_t id, uint_fast16_t int_value);
static uint32_t aux_get_invert_out (setting_id_t setting);
static input_signal_t aux_in[] = {
{ .id = Input_Aux0, .port = &stx[0], .pin = AUXINPUT0_PIN, .group = 0 }
#if AUX_N_IN == 4
, { .id = Input_Aux1, .port = &stx[1], .pin = AUXINPUT1_PIN, .group = 0 },
{ .id = Input_Aux2, .port = &stx[2], .pin = AUXINPUT2_PIN, .group = 0 },
{ .id = Input_Aux3, .port = &stx[3], .pin = AUXINPUT3_PIN, .group = 0 }
#endif
};
static const setting_group_detail_t aux_groups[] = {
{ Group_Root, Group_AuxPorts, "Aux ports"}
};
static const setting_detail_t aux_settings[] = {
#if AUX_N_IN == 4
{ Settings_IoPort_InvertIn, Group_AuxPorts, "Invert I/O Port inputs", NULL, Format_Bitfield, "Port 0,Port 1,Port 2,Port 3", NULL, NULL, Setting_NonCore, &settings.ioport.invert_in.mask },
#else
{ Settings_IoPort_InvertIn, Group_AuxPorts, "Invert I/O Port inputs", NULL, Format_Bitfield, "Port 0", NULL, NULL, Setting_NonCore, &settings.ioport.invert_in.mask },
#endif
{ Settings_IoPort_InvertOut, Group_AuxPorts, "Invert I/O Port outputs", NULL, Format_Bitfield, "Port 0,Port 1,Port 2", NULL, NULL, Setting_NonCoreFn, aux_set_invert_out, aux_get_invert_out },
};
static setting_details_t details = {
.groups = aux_groups,
.n_groups = sizeof(aux_groups) / sizeof(setting_group_detail_t),
.settings = aux_settings,
.n_settings = sizeof(aux_settings) / sizeof(setting_detail_t),
.load = aux_settings_load,
.save = settings_write_global
};
static setting_details_t *on_get_settings (void)
{
return &details;
}
static void aux_settings_load (void)
{
uint_fast8_t idx = AUX_N_OUT;
do {
idx--;
DIGITAL_OUT(aux_out[idx], (settings.ioport.invert_out.mask >> idx) & 0x01);
} while(idx);
}
static status_code_t aux_set_invert_out (setting_id_t id, uint_fast16_t value)
{
ioport_bus_t invert;
invert.mask = (uint8_t)value & AUX_OUT_MASK;
if(invert.mask != settings.ioport.invert_out.mask) {
uint_fast8_t idx = AUX_N_OUT;
do {
idx--;
if(((settings.ioport.invert_out.mask >> idx) & 0x01) != ((invert.mask >> idx) & 0x01))
DIGITAL_OUT(aux_out[idx], !DIGITAL_IN(aux_out[idx]));
} while(idx);
settings.ioport.invert_out.mask = invert.mask;
}
return Status_OK;
}
static uint32_t aux_get_invert_out (setting_id_t setting)
{
return settings.ioport.invert_out.mask;
}
static void digital_out (uint8_t port, bool on)
{
if(port < AUX_N_OUT)
DIGITAL_OUT(aux_out[port], ((settings.ioport.invert_out.mask >> port) & 0x01) ? !on : on);
}
inline static __attribute__((always_inline)) int32_t get_input (gpio_t *gpio, bool invert, wait_mode_t wait_mode, float timeout)
{
if(wait_mode == WaitMode_Immediate)
return !!(gpio->reg->DR & gpio->bit) ^ invert;
uint_fast16_t delay = (uint_fast16_t)ceilf((1000.0f / 50.0f) * timeout) + 1;
bool wait_for = wait_mode != WaitMode_Low;
do {
if((!!(gpio->reg->DR & gpio->bit) ^ invert) == wait_for)
return !!(gpio->reg->DR & gpio->bit);
if(delay) {
protocol_execute_realtime();
hal.delay_ms(50, NULL);
} else
break;
} while(--delay && !sys.abort);
return -1;
}
static int32_t wait_on_input (bool digital, uint8_t port, wait_mode_t wait_mode, float timeout)
{
int32_t value = -1;
if(digital) {
if(port < AUX_N_IN)
value = get_input(aux_in[port].port, (settings.ioport.invert_in.mask << port) & 0x01, wait_mode, timeout);
}
// else if(port == 0)
// value = analogRead(41);
/*
hal.stream.write("[MSG:AUX");
hal.stream.write(uitoa(port));
hal.stream.write("=");
hal.stream.write(value == -1 ? "fail" : uitoa(value));
hal.stream.write("]" ASCII_EOL);
*/
return value;
}
void board_init (void)
{
hal.port.digital_out = digital_out;
hal.port.wait_on_input = wait_on_input;
// hal.port.num_analog_in = 1;
hal.port.num_digital_in = AUX_N_IN;
hal.port.num_digital_out = AUX_N_OUT;
details.on_get_settings = grbl.on_get_settings;
grbl.on_get_settings = on_get_settings;
bool pullup;
uint32_t i = AUX_N_IN;
input_signal_t *signal;
do {
pullup = true; //??
signal = &aux_in[--i];
signal->irq_mode = IRQ_Mode_None;
pinMode(signal->pin, pullup ? INPUT_PULLUP : INPUT_PULLDOWN);
signal->gpio.reg = (gpio_reg_t *)digital_pin_to_info_PGM[signal->pin].reg;
signal->gpio.bit = digital_pin_to_info_PGM[signal->pin].mask;
if(signal->port != NULL)
memcpy(signal->port, &signal->gpio, sizeof(gpio_t));
} while(i);
pinModeOutput(&aux_out[0], AUXOUTPUT0_PIN);
pinModeOutput(&aux_out[1], AUXOUTPUT1_PIN);
pinModeOutput(&aux_out[2], AUXOUTPUT2_PIN);
// analog_init();
}
#endif

150
src/T41U5XBB_map.h Normal file
View File

@ -0,0 +1,150 @@
/*
T41U5XBB_map.h - driver code for IMXRT1062 processor (on Teensy 4.1 board)
Part of grblHAL
Board by Phil Barrett: https://github.com/phil-barrett/grblHAL-teensy-4.x
Copyright (c) 2020 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#define BOARD_NAME "T41U5XBB"
#define HAS_BOARD_INIT
void board_init (void);
#if N_AXIS > 5
#error Max number of axes is 5 for T41U5XBB
#endif
// Default pin assignments allow only one axis to be ganged or auto squared.
// B axis pin numbers are used for the ganged/auto squared axis.
// If a second axis is to be ganged/auto squared pin assignments needs to be changed!
// Set to 1 to enable, 0 to disable.
#define X_GANGED 0
#define X_AUTO_SQUARE 0
#define Y_GANGED 0
#define Y_AUTO_SQUARE 0
#define Z_GANGED 0
#define Z_AUTO_SQUARE 0
//
#define X_STEP_PIN (2u)
#define X_DIRECTION_PIN (3u)
#define X_ENABLE_PIN (10u)
#define X_LIMIT_PIN (20u)
#if X_GANGED || X_AUTO_SQUARE
#define X2_STEP_PIN (26u)
#define X2_DIRECTION_PIN (27u)
#define X2_ENABLE_PIN (37u)
#if X_AUTO_SQUARE
#define X2_LIMIT_PIN (28u)
#endif
#endif
#define Y_STEP_PIN (4u)
#define Y_DIRECTION_PIN (5u)
#define Y_ENABLE_PIN (40u)
#define Y_LIMIT_PIN (21u)
#if Y_GANGED || Y_AUTO_SQUARE
#define Y2_STEP_PIN (26u)
#define Y2_DIRECTION_PIN (27u)
#define Y2_ENABLE_PIN (37u)
#if Y_AUTO_SQUARE
#define Y2_LIMIT_PIN (28u)
#endif
#endif
#define Z_STEP_PIN (6u)
#define Z_DIRECTION_PIN (7u)
#define Z_ENABLE_PIN (39u)
#define Z_LIMIT_PIN (22u)
#if Z_GANGED || Z_AUTO_SQUARE
#define Z2_STEP_PIN (26u)
#define Z2_DIRECTION_PIN (27u)
#define Z2_ENABLE_PIN (37u)
#define Z2_LIMIT_PIN (28u)
#endif
#if N_AXIS > 3
#define A_STEP_PIN (8u)
#define A_DIRECTION_PIN (9u)
#define A_ENABLE_PIN (38u)
#define A_LIMIT_PIN (23u)
#endif
#if N_AXIS > 4
#define B_STEP_PIN (26u)
#define B_DIRECTION_PIN (27u)
#define B_ENABLE_PIN (37u)
#define B_LIMIT_PIN (28u)
#endif
// Define spindle enable and spindle direction output pins.
#define SPINDLE_ENABLE_PIN (12u)
#define SPINDLE_DIRECTION_PIN (11u)
#define SPINDLEPWMPIN (13u) // NOTE: only pin 12 or pin 13 can be assigned!
// Define flood and mist coolant enable output pins.
#define COOLANT_FLOOD_PIN (19u)
#define COOLANT_MIST_PIN (18u)
// Define user-control CONTROLs (cycle start, reset, feed hold, door) input pins.
#define RESET_PIN (14u)
#define FEED_HOLD_PIN (16u)
#define CYCLE_START_PIN (17u)
#define SAFETY_DOOR_PIN (29u)
// Define probe switch input pin.
#define PROBE_PIN (15U)
// Define auxillary input pins
#define AUXINPUT0_PIN (36u) // ST0
#if !QEI_ENABLE
#define AUXINPUT1_PIN (30u) // ST1
#define AUXINPUT2_PIN (34u) // ST2
#define AUXINPUT3_PIN (35u) // ST3
#define AUX_N_IN 4
#define AUX_IN_MASK 0b1111
#else
#define AUX_N_IN 1
#define AUX_IN_MASK 0b1
#endif
#define AUXOUTPUT0_PIN (31u) // AUX0
#define AUXOUTPUT1_PIN (32u) // AUX1
#define AUXOUTPUT2_PIN (33u) // AUX2
#define AUX_N_OUT 3
#define AUX_OUT_MASK 0b111
#if KEYPAD_ENABLE
#define KEYPAD_STROBE_PIN (41u) // I2C ST
#endif
#if EEPROM_ENABLE || KEYPAD_ENABLE
#define I2C_PORT 4
#define I2C_SCL4 (24u) // Not used, for info only
#define I2C_SDA4 (25u) // Not used, for info only
#endif
#if QEI_ENABLE
#define QEI_A_PIN (30u) // ST1
#define QEI_B_PIN (34u) // ST2
#define QEI_SELECT_PIN (35u) // ST3
#endif

96
src/cnc_boosterpack_map.h Normal file
View File

@ -0,0 +1,96 @@
/*
cnc_boosterpack_map.h - driver code for IMXRT1062 processor (on Teensy 4.0 board)
Part of grblHAL
Copyright (c) 2020 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#define BOARD_NAME "CNC BoosterPack"
#if N_AXIS > 3
#error Max number of axes is 3 for CNC BoosterPack
#endif
#ifdef EEPROM_ENABLE
#undef EEPROM_ENABLE
#endif
#define EEPROM_ENABLE 1 // CNC BoosterPack has on-board EEPROM
// Define step pulse output pins.
#define X_STEP_PIN (32u)
#define Y_STEP_PIN (30u)
#define Z_STEP_PIN (26u)
// Define step direction output pins.
#define X_DIRECTION_PIN (5u)
#define Y_DIRECTION_PIN (33u)
#define Z_DIRECTION_PIN (13u)
// Define stepper driver enable/disable output pin(s).
#define STEPPERS_ENABLE_PIN (24u)
#define Z_ENABLE_PIN (8u)
// Define homing/hard limit switch input pins.
#define X_LIMIT_PIN (10u)
#define Y_LIMIT_PIN (1u)
#define Z_LIMIT_PIN (0u)
// Define spindle enable and spindle direction output pins.
#define SPINDLE_ENABLE_PIN (12u)
#define SPINDLE_DIRECTION_PIN (16u)
#define SPINDLEPWMPIN (12u)
// Define flood and mist coolant enable output pins.
#define COOLANT_FLOOD_PIN (4u)
#define COOLANT_MIST_PIN (31u)
// Define user-control CONTROLs (cycle start, reset, feed hold) input pins.
#define RESET_PIN (11u)
#define FEED_HOLD_PIN (7u)
#define CYCLE_START_PIN (6u)
#define SAFETY_DOOR_PIN (9u)
// Define probe switch input pin.
#define PROBE_PIN (15U)
#if KEYPAD_ENABLE
#define KEYPAD_STROBE_PIN (28U)
#endif
#if EEPROM_ENABLE || KEYPAD_ENABLE
#define I2C_PORT 0
#define I2C_SCL0 (19u) // Not used, for info only
#define I2C_SDA0 (18u) // Not used, for info only
#endif
#define UART_PORT 5
#define UART_RX5 (21u) // Not used, for info only
#define UART_TX5 (20u) // Not used, for info only
#define GPIO0_PIN (3u)
#define GPIO1_PIN (29u)
#define GPIO2_PIN (27u)
#define GPIO3_PIN (2u)
#if QEI_ENABLE
#define QEI_A_PIN GPIO0_PIN
#define QEI_B_PIN GPIO3_PIN
// #define QEI_INDEX_PIN GPIO2_PIN
#define QEI_SELECT_PIN GPIO1_PIN
#endif
/* EOF */

2536
src/driver.c Normal file

File diff suppressed because it is too large Load Diff

340
src/driver.h Normal file
View File

@ -0,0 +1,340 @@
/*
driver.h - driver code for IMXRT1062 processor (on Teensy 4.0 board)
Part of grblHAL
Copyright (c) 2020-2021 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
//
// NOTE: do NOT change configuration here - edit my_machine.h instead!
//
#ifndef __DRIVER_H__
#define __DRIVER_H__
#include "imxrt.h"
#include "core_pins.h"
#include "pins_arduino.h"
#ifndef OVERRIDE_MY_MACHINE
#include "my_machine.h"
#endif
#include "grbl/hal.h"
#include "grbl/nuts_bolts.h"
#define DIGITAL_IN(gpio) (!!(gpio.reg->DR & gpio.bit))
#define DIGITAL_OUT(gpio, on) { if(on) gpio.reg->DR_SET = gpio.bit; else gpio.reg->DR_CLEAR = gpio.bit; }
#if USB_SERIAL_CDC > 0
//#define UART_DEBUG // For development only - enable only with USB_SERIAL_CDC enabled and SPINDLE_HUANYANG disabled
#endif
#ifndef USB_SERIAL_CDC
#define USB_SERIAL_CDC 0 // for UART comms
#endif
#ifndef USB_SERIAL_WAIT
#define USB_SERIAL_WAIT 0
#endif
#ifndef PLASMA_ENABLE
#define PLASMA_ENABLE 0
#endif
#ifndef PPI_ENABLE
#define PPI_ENABLE 0
#endif
#ifndef SPINDLE_HUANYANG
#define SPINDLE_HUANYANG 0
#endif
#ifndef QEI_ENABLE
#define QEI_ENABLE 0
#endif
#ifndef ODOMETER_ENABLE
#define ODOMETER_ENABLE 0
#endif
#ifndef ETHERNET_ENABLE
#define ETHERNET_ENABLE 0
#endif
#ifndef TELNET_ENABLE
#define TELNET_ENABLE 0
#endif
#ifndef WEBSOCKET_ENABLE
#define WEBSOCKET_ENABLE 0
#endif
#ifndef SDCARD_ENABLE
#define SDCARD_ENABLE 0
#endif
#ifndef KEYPAD_ENABLE
#define KEYPAD_ENABLE 0
#endif
#ifndef EEPROM_ENABLE
#define EEPROM_ENABLE 0
#endif
#ifndef EEPROM_IS_FRAM
#define EEPROM_IS_FRAM 0
#endif
#ifndef TRINAMIC_ENABLE
#define TRINAMIC_ENABLE 0
#endif
#ifndef TRINAMIC_I2C
#define TRINAMIC_I2C 0
#endif
#ifndef TRINAMIC_DEV
#define TRINAMIC_DEV 0
#endif
#ifndef ESTOP_ENABLE
#if COMPATIBILITY_LEVEL <= 1
#define ESTOP_ENABLE 1
#else
#define ESTOP_ENABLE 0
#endif
#elif ESTOP_ENABLE && COMPATIBILITY_LEVEL > 1
#warning "Enabling ESTOP may not work with all senders!"
#endif
#if ETHERNET_ENABLE
#ifndef NETWORK_HOSTNAME
#define NETWORK_HOSTNAME "GRBL"
#endif
#ifndef NETWORK_IPMODE
#define NETWORK_IPMODE 1 // 0 = static, 1 = DHCP, 2 = AutoIP
#endif
#ifndef NETWORK_IP
#define NETWORK_IP "192.168.5.1"
#endif
#ifndef NETWORK_GATEWAY
#define NETWORK_GATEWAY "192.168.5.1"
#endif
#ifndef NETWORK_MASK
#define NETWORK_MASK "255.255.255.0"
#endif
#ifndef NETWORK_TELNET_PORT
#define NETWORK_TELNET_PORT 23
#endif
#ifndef NETWORK_WEBSOCKET_PORT
#define NETWORK_WEBSOCKET_PORT 80
#endif
#ifndef NETWORK_HTTP_PORT
#define NETWORK_HTTP_PORT 80
#endif
#if NETWORK_IPMODE < 0 || NETWORK_IPMODE > 2
#error "Invalid IP mode selected!"
#endif
#endif
// Timer assignments (for reference, Arduino libs does not follow the CMSIS style...)
//#define STEPPER_TIMER PIT0 (32 bit)
//#define PULSE_TIMER TMR4
//#define SPINDLE_PWM_TIMER TMR1 (pin 12) or TMR2 (pin 3)
//#define DEBOUNCE_TIMER TMR3
//#define PLASMA_TIMER TMR2
//#define PPI_TIMER inverse of SPINDLE_PWM_TIMER
// Timers used for spindle encoder if spindle sync is enabled:
//#define RPM_TIMER GPT1
//#define RPM_COUNTER GPT2
// End configuration
#ifdef BOARD_CNC_BOOSTERPACK
#include "cnc_boosterpack_map.h"
#elif defined(BOARD_T40X101)
#include "T40X101_map.h"
#elif defined(BOARD_T41U5XBB)
#include "T41U5XBB_map.h"
#elif defined(BOARD_T41U5XSS)
#include "T41U5XSS_map.h"
#elif defined(BOARD_T41PROBB)
#include "T41ProBB_map.h"
#elif defined(BOARD_MY_MACHINE)
#include "my_machine_map.h"
#else // default board
#include "generic_map.h"
#endif
#if SPINDLEPWMPIN == 12
#define PPI_TIMER (IMXRT_TMR2)
#define PPI_TIMERIRQ IRQ_QTIMER2
#else
#define PPI_TIMER (IMXRT_TMR1)
#define PPI_TIMERIRQ IRQ_QTIMER1
#endif
// Adjust STEP_PULSE_LATENCY to get accurate step pulse length when required, e.g if using high step rates.
// The default value is calibrated for 10 microseconds length.
// NOTE: step output mode, number of axes and compiler optimization settings may all affect this value.
#ifndef STEP_PULSE_LATENCY
#define STEP_PULSE_LATENCY 0.2f // microseconds
#endif
#ifndef IOPORTS_ENABLE
#define IOPORTS_ENABLE 0
#endif
#if EEPROM_ENABLE && !defined(EEPROM_IS_FRAM)
#define EEPROM_IS_FRAM 0
#endif
#if TRINAMIC_ENABLE
#include "tmc2130/trinamic.h"
#endif
#if QEI_ENABLE
#include "encoder/encoder.h"
#endif
#if SPINDLE_HUANYANG
#if USB_SERIAL_CDC == 0
#error "Huanyang VFD cannot be used with UART communications enabled!"
#endif
#include "spindle/huanyang.h"
#endif
#ifndef VFD_SPINDLE
#define VFD_SPINDLE 0
#endif
#if PLASMA_ENABLE
#include "plasma/thc.h"
#endif
#if ODOMETER_ENABLE
#include "odometer/odometer.h"
#endif
#if KEYPAD_ENABLE && !defined(KEYPAD_STROBE_PIN)
#error "KEYPAD_ENABLE requires KEYPAD_STROBE_PIN to be defined!"
#endif
#ifndef I2C_PORT
#if EEPROM_ENABLE
#error "EEPROM_ENABLE requires I2C_PORT to be defined!"
#endif
#if KEYPAD_ENABLE
#error "KEYPAD_ENABLE requires I2C_PORT to be defined!"
#endif
#endif
#if !(SPINDLEPWMPIN == 12 || SPINDLEPWMPIN == 13)
#error "SPINDLEPWMPIN can only be routed to pin 12 or 13!"
#endif
#if QEI_ENABLE > 1
#error "Max number of quadrature interfaces is 1!"
#endif
#if QEI_ENABLE > 0 && !(defined(QEI_A_PIN) && defined(QEI_B_PIN))
#error "QEI_ENABLE requires encoder input pins A and B to be defined!"
#endif
typedef enum {
Input_Probe = 0,
Input_Reset,
Input_FeedHold,
Input_CycleStart,
Input_SafetyDoor,
Input_LimitsOverride,
Input_EStop,
Input_ModeSelect,
Input_LimitX,
Input_LimitX_Max,
Input_LimitY,
Input_LimitY_Max,
Input_LimitZ,
Input_LimitZ_Max,
Input_LimitA,
Input_LimitA_Max,
Input_LimitB,
Input_LimitB_Max,
Input_LimitC,
Input_LimitC_Max,
Input_KeypadStrobe,
Input_QEI_A,
Input_QEI_B,
Input_QEI_Select,
Input_QEI_Index,
Input_SpindleIndex,
Input_Aux0,
Input_Aux1,
Input_Aux2,
Input_Aux3
} input_t;
typedef enum {
IRQ_Mode_None = 0b00,
IRQ_Mode_Change = 0b01,
IRQ_Mode_Rising = 0b10,
IRQ_Mode_Falling = 0b11
} irq_mode_t;
typedef struct {
volatile uint32_t DR;
volatile uint32_t GDIR;
volatile uint32_t PSR;
volatile uint32_t ICR1;
volatile uint32_t ICR2;
volatile uint32_t IMR;
volatile uint32_t ISR;
volatile uint32_t EDGE_SEL;
uint32_t unused[25];
volatile uint32_t DR_SET;
volatile uint32_t DR_CLEAR;
volatile uint32_t DR_TOGGLE;
} gpio_reg_t;
typedef struct {
gpio_reg_t *reg;
uint32_t bit;
} gpio_t;
typedef struct {
input_t id;
uint8_t group;
uint8_t pin;
gpio_t *port;
gpio_t gpio; // doubled up for now for speed...
irq_mode_t irq_mode;
uint8_t offset;
volatile bool active;
volatile bool debounce;
} input_signal_t;
// The following struct is pulled from the Teensy Library core, Copyright (c) 2019 PJRC.COM, LLC.
typedef struct {
const uint8_t pin; // The pin number
const uint32_t mux_val; // Value to set for mux;
volatile uint32_t *select_reg; // Which register controls the selection
const uint32_t select_val; // Value for that selection
} pin_info_t;
//
void selectStream (stream_type_t stream);
void pinModeOutput (gpio_t *gpio, uint8_t pin);
uint32_t xTaskGetTickCount();
#ifdef UART_DEBUG
void uart_debug_write (char *s);
#endif
#endif // __DRIVER_H__

1
src/eeprom Submodule

@ -0,0 +1 @@
Subproject commit 292df8b7cc2a7d9df7a647483eef6ba8c68c250d

1
src/encoder Submodule

@ -0,0 +1 @@
Subproject commit 8ee8eea4e4974ae54787b01aa4a17fa744580246

325
src/enet.c Normal file
View File

@ -0,0 +1,325 @@
/*
enet.c - lwIP driver glue code for IMXRT1062 processor (on Teensy 4.1 board)
Part of grblHAL
Copyright (c) 2020-2021 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#include "driver.h"
#if ETHERNET_ENABLE
#include <math.h>
#include <stdio.h>
#include <string.h>
#include <lwipopts.h>
#include <lwip_k6x.h>
#include <lwip_t41.h>
#include <lwip/netif.h>
#include "lwip/dhcp.h"
#include "grbl/report.h"
#include "grbl/nvs_buffer.h"
#include "networking/TCPStream.h"
#include "networking/WsStream.h"
static volatile bool linkUp = false;
static char IPAddress[IP4ADDR_STRLEN_MAX];
static network_services_t services = {0};
static nvs_address_t nvs_address;
static network_settings_t ethernet, network;
static on_report_options_ptr on_report_options;
static void report_options (bool newopt)
{
on_report_options(newopt);
if(newopt)
hal.stream.write(",ETH");
else {
hal.stream.write("[IP:");
hal.stream.write(IPAddress);
hal.stream.write("]" ASCII_EOL);
}
}
static void link_status_callback (struct netif *netif)
{
bool isLinkUp = netif_is_link_up(netif);
if(isLinkUp != linkUp) {
linkUp = isLinkUp;
TCPStreamNotifyLinkStatus(linkUp);
}
}
static void netif_status_callback (struct netif *netif)
{
ip4addr_ntoa_r(netif_ip_addr4(netif), IPAddress, IP4ADDR_STRLEN_MAX);
#if TELNET_ENABLE
if(network.services.telnet && !services.telnet) {
TCPStreamInit();
TCPStreamListen(network.telnet_port == 0 ? 23 : network.telnet_port);
services.telnet = On;
}
#endif
#if WEBSOCKET_ENABLE
if(network.services.websocket && !services.websocket) {
WsStreamInit();
WsStreamListen(network.websocket_port == 0 ? 80 : network.websocket_port);
services.websocket = On;
}
#endif
}
void grbl_enet_poll (void)
{
static uint32_t last_ms0, last_ms1;
uint32_t ms;
enet_proc_input();
ms = millis();
if(ms - last_ms0 > 1) {
last_ms0 = ms;
#if TELNET_ENABLE
if(services.telnet)
TCPStreamPoll();
#endif
#if WEBSOCKET_ENABLE
if(services.websocket)
WsStreamPoll();
#endif
}
if (ms - last_ms1 > 25)
{
last_ms1 = ms;
enet_poll();
}
}
bool grbl_enet_start (void)
{
if(nvs_address != 0) {
*IPAddress = '\0';
memcpy(&network, &ethernet, sizeof(network_settings_t));
if(network.ip_mode == IpMode_Static)
enet_init((ip_addr_t *)&network.ip, (ip_addr_t *)&network.mask, (ip_addr_t *)&network.gateway);
else
enet_init(NULL, NULL, NULL);
netif_set_status_callback(netif_default, netif_status_callback);
netif_set_link_callback(netif_default, link_status_callback);
netif_set_up(netif_default);
#if LWIP_NETIF_HOSTNAME
netif_set_hostname(netif_default, network.hostname);
#endif
if(network.ip_mode == IpMode_DHCP)
dhcp_start(netif_default);
}
return nvs_address != 0;
}
static inline void set_addr (char *ip, ip4_addr_t *addr)
{
memcpy(ip, addr, sizeof(ip4_addr_t));
}
static void ethernet_settings_load (void);
static void ethernet_settings_restore (void);
static status_code_t ethernet_set_ip (setting_id_t setting, char *value);
static char *ethernet_get_ip (setting_id_t setting);
static const setting_group_detail_t ethernet_groups [] = {
{ Group_Root, Group_Networking, "Networking" }
};
#if TELNET_ENABLE && WEBSOCKET_ENABLE && HTTP_ENABLE
static const char netservices[] = "Telnet,Websocket,HTTP";
#endif
#if TELNET_ENABLE && WEBSOCKET_ENABLE && !HTTP_ENABLE
static const char netservices[] = "Telnet,Websocket";
#endif
#if TELNET_ENABLE && !WEBSOCKET_ENABLE && !HTTP_ENABLE
static const char netservices[] = "Telnet";
#endif
PROGMEM static const setting_detail_t ethernet_settings[] = {
{ Setting_NetworkServices, Group_Networking, "Network Services", NULL, Format_Bitfield, netservices, NULL, NULL, Setting_NonCore, &ethernet.services.mask, NULL, NULL },
{ Setting_Hostname, Group_Networking, "Hostname", NULL, Format_String, "x(64)", NULL, "64", Setting_NonCore, ethernet.hostname, NULL, NULL },
{ Setting_IpMode, Group_Networking, "IP Mode", NULL, Format_RadioButtons, "Static,DHCP,AutoIP", NULL, NULL, Setting_NonCore, &ethernet.ip_mode, NULL, NULL },
{ Setting_IpAddress, Group_Networking, "IP Address", NULL, Format_IPv4, NULL, NULL, NULL, Setting_NonCoreFn, ethernet_set_ip, ethernet_get_ip, NULL },
{ Setting_Gateway, Group_Networking, "Gateway", NULL, Format_IPv4, NULL, NULL, NULL, Setting_NonCoreFn, ethernet_set_ip, ethernet_get_ip, NULL },
{ Setting_NetMask, Group_Networking, "Netmask", NULL, Format_IPv4, NULL, NULL, NULL, Setting_NonCoreFn, ethernet_set_ip, ethernet_get_ip, NULL },
{ Setting_TelnetPort, Group_Networking, "Telnet port", NULL, Format_Int16, "####0", "1", "65535", Setting_NonCore, &ethernet.telnet_port, NULL, NULL },
#if HTTP_ENABLE
{ Setting_HttpPort, Group_Networking, "HTTP port", NULL, Format_Int16, "####0", "1", "65535", Setting_NonCore, &ethernet.http_port, NULL, NULL },
#endif
{ Setting_WebSocketPort, Group_Networking, "Websocket port", NULL, Format_Int16, "####0", "1", "65535", Setting_NonCore, &ethernet.websocket_port, NULL, NULL }
};
static void ethernet_settings_save (void)
{
hal.nvs.memcpy_to_nvs(nvs_address, (uint8_t *)&ethernet, sizeof(network_settings_t), true);
}
static setting_details_t details = {
.groups = ethernet_groups,
.n_groups = sizeof(ethernet_groups) / sizeof(setting_group_detail_t),
.settings = ethernet_settings,
.n_settings = sizeof(ethernet_settings) / sizeof(setting_detail_t),
.save = ethernet_settings_save,
.load = ethernet_settings_load,
.restore = ethernet_settings_restore
};
static setting_details_t *on_get_settings (void)
{
return &details;
}
static status_code_t ethernet_set_ip (setting_id_t setting, char *value)
{
ip_addr_t addr;
if(ip4addr_aton(value, &addr) != 1)
return Status_InvalidStatement;
status_code_t status = Status_OK;
switch(setting) {
case Setting_IpAddress:
set_addr(ethernet.ip, &addr);
break;
case Setting_Gateway:
set_addr(ethernet.gateway, &addr);
break;
case Setting_NetMask:
set_addr(ethernet.mask, &addr);
break;
default:
status = Status_Unhandled;
break;
}
return status;
}
static char *ethernet_get_ip (setting_id_t setting)
{
static char ip[IPADDR_STRLEN_MAX];
switch(setting) {
case Setting_IpAddress:
ip4addr_ntoa_r((const ip_addr_t *)&ethernet.ip, ip, IPADDR_STRLEN_MAX);
break;
case Setting_Gateway:
ip4addr_ntoa_r((const ip_addr_t *)&ethernet.gateway, ip, IPADDR_STRLEN_MAX);
break;
case Setting_NetMask:
ip4addr_ntoa_r((const ip_addr_t *)&ethernet.mask, ip, IPADDR_STRLEN_MAX);
break;
default:
*ip = '\0';
break;
}
return ip;
}
void ethernet_settings_restore (void)
{
strcpy(ethernet.hostname, NETWORK_HOSTNAME);
ip4_addr_t addr;
ethernet.ip_mode = (ip_mode_t)NETWORK_IPMODE;
if(ip4addr_aton(NETWORK_IP, &addr) == 1)
set_addr(ethernet.ip, &addr);
if(ip4addr_aton(NETWORK_GATEWAY, &addr) == 1)
set_addr(ethernet.gateway, &addr);
#if NETWORK_IPMODE == 0
if(ip4addr_aton(NETWORK_MASK, &addr) == 1)
set_addr(ethernet.mask, &addr);
#else
if(ip4addr_aton("255.255.255.0", &addr) == 1)
set_addr(ethernet.mask, &addr);
#endif
ethernet.services.mask = 0;
ethernet.telnet_port = NETWORK_TELNET_PORT;
ethernet.http_port = NETWORK_HTTP_PORT;
ethernet.websocket_port = NETWORK_WEBSOCKET_PORT;
#if TELNET_ENABLE
ethernet.services.telnet = On;
#endif
#if HTTP_ENABLE
ethernet.services.http = On;
#endif
#if WEBSOCKET_ENABLE
ethernet.services.websocket = On;
#endif
hal.nvs.memcpy_to_nvs(nvs_address, (uint8_t *)&ethernet, sizeof(network_settings_t), true);
}
static void ethernet_settings_load (void)
{
if(hal.nvs.memcpy_from_nvs((uint8_t *)&ethernet, nvs_address, sizeof(network_settings_t), true) != NVS_TransferResult_OK)
ethernet_settings_restore();
}
bool grbl_enet_init (network_settings_t *settings)
{
if((nvs_address = nvs_alloc(sizeof(network_settings_t)))) {
on_report_options = grbl.on_report_options;
grbl.on_report_options = report_options;
details.on_get_settings = grbl.on_get_settings;
grbl.on_get_settings = on_get_settings;
}
return nvs_address != 0;
}
#endif

31
src/enet.h Normal file
View File

@ -0,0 +1,31 @@
/*
enet.h - lwIP driver glue code for IMXRT1062 processor (on Teensy 4.1 board)
Part of grblHAL
Copyright (c) 2020 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __ENET_H__
#define __ENET_H__
#include "driver.h"
bool grbl_enet_init (void);
bool grbl_enet_start (void);
void grbl_enet_poll (void);
#endif

82
src/generic_map.h Normal file
View File

@ -0,0 +1,82 @@
/*
generic_map.h - driver code for IMXRT1062 processor (on Teensy 4.0 board)
Part of grblHAL
Copyright (c) 2020 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
// Define step pulse output pins.
#define X_STEP_PIN (2u)
#define Y_STEP_PIN (4u)
#define Z_STEP_PIN (6u)
// Define step direction output pins.
#define X_DIRECTION_PIN (3u)
#define Y_DIRECTION_PIN (5u)
#define Z_DIRECTION_PIN (7u)
// Define stepper driver enable/disable output pin(s).
#define STEPPERS_ENABLE_PIN (10u)
// Define homing/hard limit switch input pins.
#define X_LIMIT_PIN (20u)
#define Y_LIMIT_PIN (21u)
#define Z_LIMIT_PIN (22u)
#if N_AXIS > 3
#define A_STEP_PIN (8u)
#define A_DIRECTION_PIN (9u)
#define A_LIMIT_PIN (23u)
#endif
#if N_AXIS > 4
#define B_STEP_PIN (26u)
#define B_DIRECTION_PIN (27u)
#define B_LIMIT_PIN (28u)
#endif
// Define spindle enable and spindle direction output pins.
#define SPINDLE_ENABLE_PIN (12u)
#define SPINDLE_DIRECTION_PIN (11u)
#define SPINDLEPWMPIN (13u) // NOTE: only pin 12 or pin 13 can be assigned!
// Define flood and mist coolant enable output pins.
#define COOLANT_FLOOD_PIN (19u)
#define COOLANT_MIST_PIN (18u)
// Define user-control CONTROLs (cycle start, reset, feed hold, door) input pins.
#define RESET_PIN (14u)
#define FEED_HOLD_PIN (16u)
#define CYCLE_START_PIN (17u)
#define SAFETY_DOOR_PIN (29u)
// Define probe switch input pin.
#define PROBE_PIN (15U)
#if EEPROM_ENABLE || KEYPAD_ENABLE
#define I2C_PORT 4
#define I2C_SCL4 (24u) // Not used, for info only
#define I2C_SDA4 (25u) // Not used, for info only
#endif
#if QEI_ENABLE
#define QEI_A_PIN (0)
#define QEI_B_PIN (3)
// #define QEI_INDEX_PIN GPIO2_PIN
#define QEI_SELECT_PIN (1)
#endif

1
src/grbl Submodule

@ -0,0 +1 @@
Subproject commit cdca5ad55cc9b6076401a841583bd53e3baf1481

22
src/grblHAL_Teensy4.h Normal file
View File

@ -0,0 +1,22 @@
/*
grblHAL_Teensy4.h - Arduino library wrapper (Teensy4.x version)
Part of grblHAL
Copyright (c) 2019-2020 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#include "grbl/grbllib.h"

511
src/i2c.c Normal file
View File

@ -0,0 +1,511 @@
/*
i2c.c - driver code for IMXRT1062 processor (on Teensy 4.0 board)
Part of grblHAL
Some parts of this code is Copyright (c) 2020 Terje Io
Some parts are derived/pulled from WireIMXRT.cpp in the Teensyduino Core Library (no copyright header)
*/
#include "driver.h"
#ifdef I2C_PORT
#include <string.h>
#include "i2c.h"
#if EEPROM_ENABLE
#include "eeprom/eeprom.h"
#endif
#define i2cIsBusy (!(i2c.state == I2CState_Idle || i2c.state == I2CState_Error) || (port->MSR & (LPI2C_MSR_BBF|LPI2C_MSR_MBF)))
// Timeout if a device stretches SCL this long, in microseconds
#define CLOCK_STRETCH_TIMEOUT 15000
#define PINCONFIG (IOMUXC_PAD_ODE | IOMUXC_PAD_SRE | IOMUXC_PAD_DSE(4) | IOMUXC_PAD_SPEED(1) | IOMUXC_PAD_PKE | IOMUXC_PAD_PUE | IOMUXC_PAD_PUS(3))
typedef struct {
volatile uint32_t *clock_gate_register;
uint32_t clock_gate_mask;
pin_info_t sda_pin;
pin_info_t scl_pin;
IMXRT_LPI2C_t *port;
enum IRQ_NUMBER_t irq;
} i2c_hardware_t;
static const i2c_hardware_t i2c1_hardware = {
.clock_gate_register = &CCM_CCGR2,
.clock_gate_mask = CCM_CCGR2_LPI2C1(CCM_CCGR_ON),
.port = &IMXRT_LPI2C1,
.irq = IRQ_LPI2C1,
.sda_pin = {
.pin = 18,
.mux_val = 3 | 0x10,
.select_reg = &IOMUXC_LPI2C1_SDA_SELECT_INPUT,
.select_val = 1
},
.scl_pin = {
.pin = 19,
.mux_val = 3 | 0x10,
.select_reg = &IOMUXC_LPI2C1_SCL_SELECT_INPUT,
.select_val = 1
}
};
// NOTE: port 3 has alternative mapping to pin 36 and 37
static const i2c_hardware_t i2c3_hardware = {
.clock_gate_register = &CCM_CCGR2,
.clock_gate_mask = CCM_CCGR2_LPI2C3(CCM_CCGR_ON),
.port = &IMXRT_LPI2C3,
.irq = IRQ_LPI2C3,
.sda_pin = {
.pin = 16,
.mux_val = 1 | 0x10,
.select_reg = &IOMUXC_LPI2C3_SDA_SELECT_INPUT,
.select_val = 1
},
.scl_pin = {
.pin = 17,
.mux_val = 1 | 0x10,
.select_reg = &IOMUXC_LPI2C3_SCL_SELECT_INPUT,
.select_val = 1
}
};
static const i2c_hardware_t i2c4_hardware = {
.clock_gate_register = &CCM_CCGR6,
.clock_gate_mask = CCM_CCGR6_LPI2C4_SERIAL(CCM_CCGR_ON),
.port = &IMXRT_LPI2C4,
.irq = IRQ_LPI2C4,
.sda_pin = {
.pin = 25,
.mux_val = 0 | 0x10,
.select_reg = &IOMUXC_LPI2C4_SDA_SELECT_INPUT,
.select_val = 1
},
.scl_pin = {
.pin = 24,
.mux_val = 0 | 0x10,
.select_reg = &IOMUXC_LPI2C4_SCL_SELECT_INPUT,
.select_val = 1
}
};
static bool force_clock (i2c_hardware_t *hardware)
{
bool ret = false;
uint32_t sda_pin = hardware->sda_pin.pin;
uint32_t scl_pin = hardware->scl_pin.pin;
uint32_t sda_mask = digitalPinToBitMask(sda_pin);
uint32_t scl_mask = digitalPinToBitMask(scl_pin);
// take control of pins with GPIO
*portConfigRegister(sda_pin) = 5 | 0x10;
*portSetRegister(sda_pin) = sda_mask;
*portModeRegister(sda_pin) |= sda_mask;
*portConfigRegister(scl_pin) = 5 | 0x10;
*portSetRegister(scl_pin) = scl_mask;
*portModeRegister(scl_pin) |= scl_mask;
delayMicroseconds(10);
for (int i=0; i < 9; i++) {
if ((*portInputRegister(sda_pin) & sda_mask) && (*portInputRegister(scl_pin) & scl_mask)) {
// success, both pins are high
ret = true;
break;
}
*portClearRegister(scl_pin) = scl_mask;
delayMicroseconds(5);
*portSetRegister(scl_pin) = scl_mask;
delayMicroseconds(5);
}
// return control of pins to I2C
*(portConfigRegister(sda_pin)) = hardware->sda_pin.mux_val;
*(portConfigRegister(scl_pin)) = hardware->scl_pin.mux_val;
return ret;
}
static void setClock (IMXRT_LPI2C_t *port, uint32_t frequency)
{
port->MCR = 0;
if (frequency < 400000) {
// 100 kHz
port->MCCR0 = LPI2C_MCCR0_CLKHI(55) | LPI2C_MCCR0_CLKLO(59) | LPI2C_MCCR0_DATAVD(25) | LPI2C_MCCR0_SETHOLD(40);
port->MCFGR1 = LPI2C_MCFGR1_PRESCALE(1);
port->MCFGR2 = LPI2C_MCFGR2_FILTSDA(5) | LPI2C_MCFGR2_FILTSCL(5) | LPI2C_MCFGR2_BUSIDLE(3000); // idle timeout 250 us
port->MCFGR3 = LPI2C_MCFGR3_PINLOW(CLOCK_STRETCH_TIMEOUT * 12 / 256 + 1);
} else if (frequency < 1000000) {
// 400 kHz
port->MCCR0 = LPI2C_MCCR0_CLKHI(26) | LPI2C_MCCR0_CLKLO(28) | LPI2C_MCCR0_DATAVD(12) | LPI2C_MCCR0_SETHOLD(18);
port->MCFGR1 = LPI2C_MCFGR1_PRESCALE(0);
port->MCFGR2 = LPI2C_MCFGR2_FILTSDA(2) | LPI2C_MCFGR2_FILTSCL(2) | LPI2C_MCFGR2_BUSIDLE(3600); // idle timeout 150 us
port->MCFGR3 = LPI2C_MCFGR3_PINLOW(CLOCK_STRETCH_TIMEOUT * 24 / 256 + 1);
} else {
// 1 MHz
port->MCCR0 = LPI2C_MCCR0_CLKHI(9) | LPI2C_MCCR0_CLKLO(10) | LPI2C_MCCR0_DATAVD(4) | LPI2C_MCCR0_SETHOLD(7);
port->MCFGR1 = LPI2C_MCFGR1_PRESCALE(0);
port->MCFGR2 = LPI2C_MCFGR2_FILTSDA(1) | LPI2C_MCFGR2_FILTSCL(1) | LPI2C_MCFGR2_BUSIDLE(2400); // idle timeout 100 us
port->MCFGR3 = LPI2C_MCFGR3_PINLOW(CLOCK_STRETCH_TIMEOUT * 24 / 256 + 1);
}
port->MCCR1 = port->MCCR0;
port->MCFGR0 = 0;
port->MFCR = LPI2C_MFCR_RXWATER(0) | LPI2C_MFCR_TXWATER(1);
port->MCR = LPI2C_MCR_MEN;
}
typedef enum {
I2CState_Idle = 0,
I2CState_Restart,
I2CState_SendAddr,
I2CState_SendNext,
I2CState_SendLast,
I2CState_AwaitCompletion,
I2CState_ReceiveNext,
I2CState_ReceiveNextToLast,
I2CState_ReceiveLast,
I2CState_Error
} i2c_state_t;
typedef struct {
volatile i2c_state_t state;
uint8_t addr;
volatile uint16_t count;
volatile uint16_t rcount;
volatile uint8_t acount;
uint8_t *data;
uint8_t regaddr[2];
#if KEYPAD_ENABLE
keycode_callback_ptr keycode_callback;
#endif
uint8_t buffer[8];
} i2c_trans_t;
static i2c_trans_t i2c;
static uint8_t tx_fifo_size;
static const i2c_hardware_t *hardware;
static IMXRT_LPI2C_t *port = NULL;
static void I2C_interrupt_handler (void);
void i2c_init (void)
{
static bool init_ok = false;
if(!init_ok) {
init_ok = true;
#ifndef I2C_PORT
#error "I2C port is undefined!"
#endif
#if I2C_PORT == 0
hardware = &i2c1_hardware;
#elif I2C_PORT == 3
hardware = &i2c3_hardware;
#elif I2C_PORT == 4
hardware = &i2c4_hardware;
#else
#error "No such I2C port!"
#endif
port = hardware->port;
tx_fifo_size = 1 << (port->PARAM & 0b1111);
CCM_CSCDR2 = (CCM_CSCDR2 & ~CCM_CSCDR2_LPI2C_CLK_PODF(63)) | CCM_CSCDR2_LPI2C_CLK_SEL;
*hardware->clock_gate_register |= hardware->clock_gate_mask;
port->MCR = LPI2C_MCR_RST;
setClock(port, 100000);
// Setup SDA register
*(portControlRegister(hardware->sda_pin.pin)) = PINCONFIG;
*(portConfigRegister(hardware->sda_pin.pin)) = hardware->sda_pin.mux_val;
*(hardware->sda_pin.select_reg) = hardware->sda_pin.select_val;
// setup SCL register
*(portControlRegister(hardware->scl_pin.pin)) = PINCONFIG;
*(portConfigRegister(hardware->scl_pin.pin)) = hardware->scl_pin.mux_val;
*(hardware->scl_pin.select_reg) = hardware->scl_pin.select_val;
attachInterruptVector(hardware->irq, I2C_interrupt_handler);
NVIC_SET_PRIORITY(hardware->irq, 1);
NVIC_ENABLE_IRQ(hardware->irq);
}
}
// get bytes (max 8 if local buffer, else max 255), waits for result
uint8_t *I2C_Receive (uint32_t i2cAddr, uint8_t *buf, uint16_t bytes, bool block)
{
i2c.data = buf ? buf : i2c.buffer;
i2c.count = bytes;
i2c.rcount = 0;
i2c.state = bytes == 1 ? I2CState_ReceiveLast : (bytes == 2 ? I2CState_ReceiveNextToLast : I2CState_ReceiveNext);
port->MSR = 0;
port->MTDR = LPI2C_MTDR_CMD_START | (i2cAddr << 1) | 1;
port->MTDR = LPI2C_MTDR_CMD_RECEIVE | ((uint32_t)i2c.count - 1);
port->MIER = LPI2C_MIER_NDIE|LPI2C_MIER_RDIE;
if(block)
while(i2cIsBusy);
return i2c.buffer;
}
void I2C_Send (uint32_t i2cAddr, uint8_t *buf, uint16_t bytes, bool block)
{
i2c.count = bytes;
i2c.data = buf ? buf : i2c.buffer;
port->MSR = 0;
port->MTDR = LPI2C_MTDR_CMD_START | (i2cAddr << 1);
while(i2c.count && (port->MFSR & 0b111) < tx_fifo_size) {
port->MTDR = LPI2C_MTDR_CMD_TRANSMIT | (uint32_t)(*i2c.data++);
i2c.count--;
}
port->MIER = LPI2C_MIER_NDIE|LPI2C_MIER_TDIE;
i2c.state = i2c.count == 0 ? I2CState_AwaitCompletion : (i2c.count == 1 ? I2CState_SendLast : I2CState_SendNext);
if(block)
while(i2cIsBusy);
}
uint8_t *I2C_ReadRegister (uint32_t i2cAddr, uint8_t *buf, uint8_t abytes, uint16_t bytes, bool block)
{
while(i2cIsBusy);
i2c.addr = i2cAddr;
i2c.count = bytes;
i2c.rcount = 0;
i2c.acount = abytes;
i2c.data = buf ? buf : i2c.buffer;
i2c.state = I2CState_SendAddr;
port->MSR = 0;
port->MTDR = LPI2C_MTDR_CMD_START | (i2cAddr << 1);
port->MIER = LPI2C_MIER_NDIE|LPI2C_MIER_TDIE;
if(block)
while(i2cIsBusy);
return i2c.buffer;
}
#if EEPROM_ENABLE
nvs_transfer_result_t i2c_nvs_transfer (nvs_transfer_t *transfer, bool read)
{
static uint8_t txbuf[NVS_SIZE + 2];
while(i2cIsBusy);
if(read) {
if(transfer->word_addr_bytes == 1)
i2c.regaddr[0] = transfer->word_addr;
else {
i2c.regaddr[0] = transfer->word_addr & 0xFF;
i2c.regaddr[1] = transfer->word_addr >> 8;
}
I2C_ReadRegister(transfer->address, transfer->data, transfer->word_addr_bytes, transfer->count, true);
} else {
memcpy(&txbuf[transfer->word_addr_bytes], transfer->data, transfer->count);
if(transfer->word_addr_bytes == 1)
txbuf[0] = transfer->word_addr;
else {
txbuf[0] = transfer->word_addr >> 8;
txbuf[1] = transfer->word_addr & 0xFF;
}
I2C_Send(transfer->address, txbuf, transfer->count + transfer->word_addr_bytes, true);
#if !EEPROM_IS_FRAM
hal.delay_ms(7, NULL);
#endif
}
return NVS_TransferResult_OK;
}
#endif
#if KEYPAD_ENABLE
void I2C_GetKeycode (uint32_t i2cAddr, keycode_callback_ptr callback)
{
while(i2cIsBusy);
i2c.keycode_callback = callback;
I2C_Receive(i2cAddr, NULL, 1, false);
}
#endif
#if TRINAMIC_ENABLE && TRINAMIC_I2C
static TMC2130_status_t I2C_TMC_ReadRegister (TMC2130_t *driver, TMC2130_datagram_t *reg)
{
uint8_t *res, i2creg;
TMC2130_status_t status = {0};
if((i2creg = TMCI2C_GetMapAddress((uint8_t)(driver ? (uint32_t)driver->cs_pin : 0), reg->addr).value) == 0xFF)
return status; // unsupported register
while(i2cIsBusy);
i2c.buffer[0] = i2creg;
i2c.buffer[1] = 0;
i2c.buffer[2] = 0;
i2c.buffer[3] = 0;
i2c.buffer[4] = 0;
res = I2C_ReadRegister(I2C_ADR_I2CBRIDGE, NULL, 5, true);
status.value = (uint8_t)*res++;
reg->payload.value = ((uint8_t)*res++ << 24);
reg->payload.value |= ((uint8_t)*res++ << 16);
reg->payload.value |= ((uint8_t)*res++ << 8);
reg->payload.value |= (uint8_t)*res++;
return status;
}
static TMC2130_status_t I2C_TMC_WriteRegister (TMC2130_t *driver, TMC2130_datagram_t *reg)
{
TMC2130_status_t status = {0};
while(i2cIsBusy);
reg->addr.write = 1;
i2c.buffer[0] = TMCI2C_GetMapAddress((uint8_t)(driver ? (uint32_t)driver->cs_pin : 0), reg->addr).value;
reg->addr.write = 0;
if(i2c.buffer[0] == 0xFF)
return status; // unsupported register
i2c.buffer[1] = (reg->payload.value >> 24) & 0xFF;
i2c.buffer[2] = (reg->payload.value >> 16) & 0xFF;
i2c.buffer[3] = (reg->payload.value >> 8) & 0xFF;
i2c.buffer[4] = reg->payload.value & 0xFF;
I2C_Send(I2C_ADR_I2CBRIDGE, NULL, 5, true);
return status;
}
void I2C_DriverInit (TMC_io_driver_t *driver)
{
i2c_init();
driver->WriteRegister = I2C_TMC_WriteRegister;
driver->ReadRegister = I2C_TMC_ReadRegister;
}
#endif
static void I2C_interrupt_handler (void)
{
uint32_t ifg = port->MSR & 0xFFFF;
port->MSR &= ~ifg;
if((ifg & port->MIER) == 0) return;
//if(port->MSR & LPI2C_MSR_MBF) return;
/*
hal.stream.write("I:");
hal.stream.write(uitoa(ifg));
hal.stream.write(" ");
hal.stream.write(uitoa(i2c.state));
hal.stream.write(ASCII_EOL);
*/
if(ifg & LPI2C_MSR_ALF) {
port->MTDR = LPI2C_MTDR_CMD_STOP;
i2c.state = I2CState_Error;
}
if(ifg & LPI2C_MSR_NDF)
i2c.state = I2CState_Error;
switch(i2c.state) {
case I2CState_Idle:
case I2CState_Error:
port->MIER = 0;
port->MCR |= (LPI2C_MCR_RTF|LPI2C_MCR_RRF);
break;
case I2CState_SendNext:
port->MTDR = LPI2C_MTDR_CMD_TRANSMIT | (uint32_t)(*i2c.data++);
if(--i2c.count == 1)
i2c.state = I2CState_SendLast;
break;
case I2CState_SendLast:
port->MTDR = LPI2C_MTDR_CMD_TRANSMIT | (uint32_t)(*i2c.data++);
i2c.state = I2CState_AwaitCompletion;
break;
case I2CState_AwaitCompletion:
port->MIER &= ~LPI2C_MIER_TDIE;
port->MTDR = LPI2C_MTDR_CMD_STOP;
i2c.count = 0;
i2c.state = I2CState_Idle;
break;
case I2CState_SendAddr:
port->MTDR = LPI2C_MTDR_CMD_TRANSMIT | (uint32_t)(i2c.regaddr[--i2c.acount]);
if(i2c.acount == 0)
i2c.state = I2CState_Restart;
break;
case I2CState_Restart:
if(port->MIER & LPI2C_MIER_TDIE) {
port->MIER &= ~LPI2C_MIER_TDIE;
port->MIER |= LPI2C_MIER_EPIE;
port->MTDR = LPI2C_MTDR_CMD_START | (i2c.addr << 1) | 1;
} else if(port->MIER & LPI2C_MIER_EPIE) {
port->MIER &= ~LPI2C_MIER_EPIE;
port->MIER |= LPI2C_MIER_RDIE;
port->MTDR = LPI2C_MTDR_CMD_RECEIVE | ((uint32_t)i2c.count - 1);
i2c.state = i2c.count == 1 ? I2CState_ReceiveLast : (i2c.count == 2 ? I2CState_ReceiveNextToLast : I2CState_ReceiveNext);
}
break;
case I2CState_ReceiveNext: // superfluous, to be removed...
*i2c.data++ = port->MRDR & 0xFF;
if(--i2c.count == 1) {
i2c.state = I2CState_ReceiveLast;
}
++i2c.rcount;
break;
case I2CState_ReceiveNextToLast:
*i2c.data++ = port->MRDR & 0xFF;
// port->MTDR = LPI2C_MTDR_CMD_STOP;
i2c.count--;
i2c.state = I2CState_ReceiveLast;
break;
case I2CState_ReceiveLast:
*i2c.data = port->MRDR & 0xFF;
i2c.count = 0;
i2c.state = I2CState_Idle;
port->MTDR = LPI2C_MTDR_CMD_STOP;
#if KEYPAD_ENABLE
if(i2c.keycode_callback) {
i2c.keycode_callback(*i2c.data);
i2c.keycode_callback = NULL;
}
#endif
break;
default: break;
}
}
#endif

54
src/i2c.h Normal file
View File

@ -0,0 +1,54 @@
/*
i2c.h - I2C interface
Driver code for IMXRT1062 processor (on Teensy 4.0 board)
Part of grblHAL
Copyright (c) 2020-2021 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __I2C_DRIVER_H__
#define __I2C_DRIVER_H__
#include "driver.h"
#include "grbl/plugins.h"
void i2c_init (void);
uint8_t *I2C_Receive (uint32_t i2cAddr, uint8_t *buf, uint16_t bytes, bool block);
void I2C_Send (uint32_t i2cAddr, uint8_t *buf, uint16_t bytes, bool block);
uint8_t *I2C_ReadRegister (uint32_t i2cAddr, uint8_t *buf, uint8_t abytes, uint16_t bytes, bool block);
#if TRINAMIC_ENABLE && TRINAMIC_I2C
#include "trinamic/trinamic2130.h"
#include "trinamic/TMC2130_I2C_map.h"
#define I2C_ADR_I2CBRIDGE 0x47
void I2C_DriverInit (TMC_io_driver_t *drv);
#endif
#if KEYPAD_ENABLE
#include "keypad/keypad.h"
void I2C_GetKeycode (uint32_t i2cAddr, keycode_callback_ptr callback);
#endif
#endif

1
src/keypad Submodule

@ -0,0 +1 @@
Subproject commit 0ae3a110b6064596022aa978a5d0a1f14abaa0d7

1
src/laser Submodule

@ -0,0 +1 @@
Subproject commit 942f5607ba4d6428d8a2f5b690e251d80d462c61

35
src/main.c Normal file
View File

@ -0,0 +1,35 @@
/*
main.ino - startup code for iMXRT1062 processor (on Teensy 4.0 board)
Part of Grbl
Copyright (c) 2020 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl is distributed in the hope that it will be useful,ss
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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
// Double tap reset to enter bootloader mode - select bootloader port for programming
#include "grbl/grbllib.h"
void setup ()
{
grbl_enter();
}
void loop ()
{
}

76
src/my_machine.h Normal file
View File

@ -0,0 +1,76 @@
/*
my_machine.h - configuration for IMXRT1062 processor (on Teensy 4.x board)
Part of grblHAL
Copyright (c) 2020 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
// BOARD_T40X101 and BOARD_T41U5XBB by Phil Barrett: https://github.com/phil-barrett/grblHAL-teensy-4.x
// NOTE: Only one board may be enabled!
// If none is enabled pin mappings from generic_map.h will be used
//#define BOARD_T40X101
#define BOARD_T41U5XBB
//#define BOARD_CNC_BOOSTERPACK
//#define BOARD_MY_MACHINE // Add my_machine_map.h before enabling this!
// Configuration
// Uncomment to enable, for some a value > 1 may be assigned, if so the default value is shown.
/*
Plugin: | ETHERNET¹ | SDCARD¹ | KEYPAD | EEPROM | N_AXIS |
----------------------|-----------|---------|--------|--------|--------|
BOARD_T40X101 | no | no | yes | yes³ | max 4 |
BOARD_T41U5XBB | yes | yes | yes | yes³ | max 5 |
BOARD_CNC_BOOSTERPACK | yes² | yes | yes | yes | max 3 |
¹ Teensy 4.1 only.
² External magjack.
³ EEPROM is optional and must be added to the board.
N_AXIS has a default value of 3, edit grbl\config.h to increase.
*/
#define USB_SERIAL_CDC 2 // 1 for Arduino class library and 2 for PJRC C library. Comment out to use UART communication.
//#define USB_SERIAL_WAIT 1 // Wait for USB connection before starting grblHAL.
//#define SPINDLE_HUANYANG 1 // Set to 1 or 2 for Huanyang VFD spindle. Requires spindle plugin.
//#define QEI_ENABLE 1 // Enable quadrature encoder interfaces. Max value is 1. Requires encoder plugin.
//#define ETHERNET_ENABLE 1 // Ethernet streaming. Requires networking plugin.
//#define SDCARD_ENABLE 1 // Run gcode programs from SD card, requires sdcard plugin.
//#define KEYPAD_ENABLE 1 // I2C keypad for jogging etc., requires keypad plugin.
//#define PLASMA_ENABLE 1 // Plasma/THC plugin. To be completed.
//#define PPI_ENABLE 1 // Laser PPI plugin. To be completed.
//#define ODOMETER_ENABLE 1 // Odometer plugin. To be completed.
//#define EEPROM_ENABLE 1 // I2C EEPROM support. Set to 1 for 24LC16(2K), 2 for larger sizes. Requires eeprom plugin.
//#define EEPROM_IS_FRAM 1 // Uncomment when EEPROM is enabled and chip is FRAM, this to remove write delay.
//#define ESTOP_ENABLE 0 // When enabled only real-time report requests will be executed when the reset pin is asserted.
// Note: if left commented out the default setting is determined from COMPATIBILITY_LEVEL.
#if ETHERNET_ENABLE > 0
#define TELNET_ENABLE 1 // Telnet daemon - requires Ethernet streaming enabled.
#define WEBSOCKET_ENABLE 1 // Websocket daemon - requires Ethernet streaming enabled.
#define NETWORK_HOSTNAME "GRBL"
#define NETWORK_IPMODE 1 // 0 = static, 1 = DHCP, 2 = AutoIP
#define NETWORK_IP "192.168.5.1"
#define NETWORK_GATEWAY "192.168.5.1"
#define NETWORK_MASK "255.255.255.0"
#define NETWORK_TELNET_PORT 23
#define NETWORK_WEBSOCKET_PORT 80
#define NETWORK_HTTP_PORT 80
#endif

1
src/networking Submodule

@ -0,0 +1 @@
Subproject commit 3652e142c228c7a168cfa929497f570d541511f5

1
src/odometer Submodule

@ -0,0 +1 @@
Subproject commit 3ba87d7450bb6c4f4ded4cce96a0c71cffc48fa5

1
src/plasma Submodule

@ -0,0 +1 @@
Subproject commit b6240a9f9d88b7ef8ac368474589495cf2f43d24

1
src/sdcard Submodule

@ -0,0 +1 @@
Subproject commit 1f5a0df4e0a58480ab7c4e80f0f018152aa2da01

1
src/spindle Submodule

@ -0,0 +1 @@
Subproject commit 2f81fc6ce340133a48bd5a8209c34220d269308a

431
src/uart.c Normal file
View File

@ -0,0 +1,431 @@
/*
uart.c - driver code for IMXRT1062 processor (on Teensy 4.0 board)
Part of grblHAL
Some parts of this code is Copyright (c) 2020 Terje Io
Some parts are derived from HardwareSerial.cpp in the Teensyduino Core Library
*/
/* Teensyduino Core Library
* http://www.pjrc.com/teensy/
* Copyright (c) 2019 PJRC.COM, LLC.
*
* Permission is hereby granted, free of charge, to any person obtaining
* a copy of this software and associated documentation files (the
* "Software"), to deal in the Software without restriction, including
* without limitation the rights to use, copy, modify, merge, publish,
* distribute, sublicense, and/or sell copies of the Software, and to
* permit persons to whom the Software is furnished to do so, subject to
* the following conditions:
*
* 1. The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* 2. If the Software is incorporated into a build system that allows
* selection among a list of target devices, then similar target
* devices manufactured by PJRC.COM must be included in the list of
* target devices and selectable in the same manner.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
#include <string.h>
#include "driver.h"
#define UART_CLOCK 24000000
#define CTRL_ENABLE (LPUART_CTRL_TE | LPUART_CTRL_RE | LPUART_CTRL_RIE | LPUART_CTRL_ILIE)
#define CTRL_TX_ACTIVE (CTRL_ENABLE | LPUART_CTRL_TIE)
#define CTRL_TX_COMPLETING (CTRL_ENABLE | LPUART_CTRL_TCIE)
#define CTRL_TX_INACTIVE CTRL_ENABLE
#ifndef UART_PORT
#define UART uart1_hardware
#elif UART_PORT == 5
#define UART uart5_hardware
#else
#error "UART port not available!"
#endif
typedef struct {
IMXRT_LPUART_t *port;
volatile uint32_t *ccm_register;
const uint32_t ccm_value;
enum IRQ_NUMBER_t irq;
void (*irq_handler)(void);
pin_info_t rx_pin;
pin_info_t tx_pin;
} uart_hardware_t;
static void uart_interrupt_handler (void);
static const uart_hardware_t uart1_hardware =
{
.port = &IMXRT_LPUART6,
.ccm_register = &CCM_CCGR3,
.ccm_value = CCM_CCGR3_LPUART6(CCM_CCGR_ON),
.irq = IRQ_LPUART6,
.irq_handler = uart_interrupt_handler,
.rx_pin = {
.pin = 0,
.mux_val = 2,
.select_reg = &IOMUXC_LPUART6_RX_SELECT_INPUT,
.select_val = 1
},
.tx_pin = {
.pin = 1,
.mux_val = 2,
.select_reg = NULL,
.select_val = 0
}
};
static const uart_hardware_t uart5_hardware =
{
.port = &IMXRT_LPUART8,
.ccm_register = &CCM_CCGR6,
.ccm_value = CCM_CCGR6_LPUART8(CCM_CCGR_ON),
.irq = IRQ_LPUART8,
.irq_handler = uart_interrupt_handler,
.rx_pin = {
.pin = 21,
.mux_val = 2,
.select_reg = &IOMUXC_LPUART8_RX_SELECT_INPUT,
.select_val = 1
},
.tx_pin = {
.pin = 20,
.mux_val = 2,
.select_reg = &IOMUXC_LPUART8_TX_SELECT_INPUT,
.select_val = 1
}
};
/*
#define PIN_TO_BASEREG(pin) (portOutputRegister(pin))
#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin))
#define IO_REG_TYPE uint32_t
#define IO_REG_BASE_ATTR
#define IO_REG_MASK_ATTR
#define DIRECT_READ(base, mask) ((*((base)+2) & (mask)) ? 1 : 0)
#define DIRECT_MODE_INPUT(base, mask) (*((base)+1) &= ~(mask))
#define DIRECT_MODE_OUTPUT(base, mask) (*((base)+1) |= (mask))
#define DIRECT_WRITE_LOW(base, mask) (*((base)+34) = (mask))
#define DIRECT_WRITE_HIGH(base, mask) (*((base)+33) = (mask))
static bool transmitting_ = 0;
volatile uint32_t *transmit_pin_baseReg_ = 0;
uint32_t transmit_pin_bitmask_ = 0;
void transmitterEnable(uint8_t pin)
{
while (transmitting_) ;
pinMode(pin, OUTPUT);
transmit_pin_baseReg_ = PIN_TO_BASEREG(pin);
transmit_pin_bitmask_ = PIN_TO_BITMASK(pin);
DIRECT_WRITE_LOW(transmit_pin_baseReg_, transmit_pin_bitmask_);
}
*/
static uint16_t tx_fifo_size;
static stream_tx_buffer_t txbuffer = {0};
static stream_rx_buffer_t rxbuffer = {0}, rxbackup;
void serialInit (uint32_t baud_rate)
{
// uart_hardware_t *hardware = &UART;
float base = (float)UART_CLOCK / (float)baud_rate;
float besterr = 1e20;
int bestdiv = 1;
int bestosr = 4;
for (int osr = 4; osr <= 32; osr++) {
float div = base / (float)osr;
int divint = (int)(div + 0.5f);
if (divint < 1)
divint = 1;
else if (divint > 8191)
divint = 8191;
float err = ((float)divint - div) / div;
if (err < 0.0f)
err = -err;
if (err <= besterr) {
besterr = err;
bestdiv = divint;
bestosr = osr;
}
}
*UART.ccm_register |= UART.ccm_value;
*(portControlRegister(UART.rx_pin.pin)) = IOMUXC_PAD_DSE(7) | IOMUXC_PAD_PKE | IOMUXC_PAD_PUE | IOMUXC_PAD_PUS(3) | IOMUXC_PAD_HYS;
*(portConfigRegister(UART.rx_pin.pin)) = UART.rx_pin.mux_val;
if (UART.rx_pin.select_reg)
*(UART.rx_pin.select_reg) = UART.rx_pin.select_val;
*(portControlRegister(UART.tx_pin.pin)) = IOMUXC_PAD_SRE | IOMUXC_PAD_DSE(3) | IOMUXC_PAD_SPEED(3);
*(portConfigRegister(UART.tx_pin.pin)) = UART.tx_pin.mux_val;
if (UART.tx_pin.select_reg)
*(UART.tx_pin.select_reg) = UART.tx_pin.select_val;
UART.port->BAUD = LPUART_BAUD_OSR(bestosr - 1) | LPUART_BAUD_SBR(bestdiv) | (bestosr <= 8 ? LPUART_BAUD_BOTHEDGE : 0);
UART.port->PINCFG = 0;
// Enable the transmitter, receiver and enable receiver interrupt
NVIC_DISABLE_IRQ(UART.irq);
attachInterruptVector(UART.irq, UART.irq_handler);
NVIC_SET_PRIORITY(UART.irq, 0);
NVIC_ENABLE_IRQ(UART.irq);
tx_fifo_size = (UART.port->FIFO >> 4) & 0x7;
tx_fifo_size = tx_fifo_size ? (2 << tx_fifo_size) : 1;
uint8_t tx_water = (tx_fifo_size < 16) ? tx_fifo_size >> 1 : 7;
uint16_t rx_fifo_size = (((UART.port->FIFO >> 0) & 0x7) << 2);
uint8_t rx_water = (rx_fifo_size < 16) ? rx_fifo_size >> 1 : 7;
/*
Serial.printf("SerialX::begin stat:%x ctrl:%x fifo:%x water:%x\n", UART.port->STAT, UART.port->CTRL, UART.port->FIFO, UART.port->WATER );
Serial.printf(" FIFO sizes: tx:%d rx:%d\n",tx_fifo_size, rx_fifo_size);
Serial.printf(" Watermark tx:%d, rx: %d\n", tx_water, rx_water);
*/
UART.port->WATER = LPUART_WATER_RXWATER(rx_water) | LPUART_WATER_TXWATER(tx_water);
UART.port->FIFO |= LPUART_FIFO_TXFE | LPUART_FIFO_RXFE;
// lets configure up our CTRL register value
uint32_t ctrl = CTRL_TX_INACTIVE;
uint16_t format = 0;
// Now process the bits in the Format value passed in
// Bits 0-2 - Parity plus 9 bit.
ctrl |= (format & (LPUART_CTRL_PT | LPUART_CTRL_PE) ); // configure parity - turn off PT, PE, M and configure PT, PE
if (format & 0x04) ctrl |= LPUART_CTRL_M; // 9 bits (might include parity)
if ((format & 0x0F) == 0x04) ctrl |= LPUART_CTRL_R9T8; // 8N2 is 9 bit with 9th bit always 1
// Bit 5 TXINVERT
if (format & 0x20) ctrl |= LPUART_CTRL_TXINV; // tx invert
// write out computed CTRL
UART.port->CTRL = ctrl;
// Bit 3 10 bit - Will assume that begin already cleared it.
// process some other bits which change other registers.
if (format & 0x08) UART.port->BAUD |= LPUART_BAUD_M10;
// Bit 4 RXINVERT
uint32_t c = UART.port->STAT & ~LPUART_STAT_RXINV;
if (format & 0x10) c |= LPUART_STAT_RXINV; // rx invert
UART.port->STAT = c;
// bit 8 can turn on 2 stop bit mote
if ( format & 0x100) UART.port->BAUD |= LPUART_BAUD_SBNS;
//transmitterEnable(1);
}
bool serialSetBaudRate (uint32_t baud_rate)
{
static bool init_ok = false;
if(!init_ok) {
serialInit(baud_rate);
init_ok = true;
}
return true;
}
//
// serialGetC - returns -1 if no data available
//
int16_t serialGetC (void)
{
int16_t data;
uint_fast16_t bptr = rxbuffer.tail;
if(bptr == rxbuffer.head)
return -1; // no data available else EOF
data = rxbuffer.data[bptr++]; // Get next character, increment tmp pointer
rxbuffer.tail = bptr & (RX_BUFFER_SIZE - 1); // and update pointer
return data;
}
void serialTxFlush (void)
{
txbuffer.tail = txbuffer.head;
}
uint16_t serialRxCount (void)
{
uint_fast16_t head = rxbuffer.head, tail = rxbuffer.tail;
return BUFCOUNT(head, tail, RX_BUFFER_SIZE);
}
uint16_t serialRxFree (void)
{
return (RX_BUFFER_SIZE - 1) - serialRxCount();
}
void serialRxFlush (void)
{
rxbuffer.tail = rxbuffer.head;
rxbuffer.overflow = false;
}
void serialRxCancel (void)
{
serialRxFlush();
rxbuffer.data[rxbuffer.head] = ASCII_CAN;
rxbuffer.head = (rxbuffer.tail + 1) & (RX_BUFFER_SIZE - 1);
}
bool serialPutC (const char c)
{
uint_fast16_t next_head;
// swr(c); return true;
// if (transmit_pin_baseReg_) DIRECT_WRITE_HIGH(transmit_pin_baseReg_, transmit_pin_bitmask_);
if(txbuffer.head == txbuffer.tail && ((UART.port->WATER >> 8) & 0x7) < tx_fifo_size) {
UART.port->DATA = c;
return true;
}
next_head = (txbuffer.head + 1) & (TX_BUFFER_SIZE - 1); // Get and update head pointer
while(txbuffer.tail == next_head) { // Buffer full, block until space is available...
if(!hal.stream_blocking_callback())
return false;
}
txbuffer.data[txbuffer.head] = c; // Add data to buffer
txbuffer.head = next_head; // and update head pointer
__disable_irq();
// transmitting_ = 1;
UART.port->CTRL |= LPUART_CTRL_TIE; // (may need to handle this issue)BITBAND_SET_BIT(LPUART0_CTRL, TIE_BIT); // Enable TX interrupts
__enable_irq();
return true;
}
void serialWriteS (const char *data)
{
char c, *ptr = (char *)data;
while((c = *ptr++) != '\0')
serialPutC(c);
}
void serialWrite(const char *s, uint16_t length)
{
char *ptr = (char *)s;
while(length--)
serialPutC(*ptr++);
}
// "dummy" version of serialGetC
static int16_t serialGetNull (void)
{
return -1;
}
bool serialSuspendInput (bool suspend)
{
if(suspend)
hal.stream.read = serialGetNull;
else if(rxbuffer.backup)
memcpy(&rxbuffer, &rxbackup, sizeof(stream_rx_buffer_t));
return rxbuffer.tail != rxbuffer.head;
}
uint16_t serialTxCount(void) {
uint_fast16_t head = txbuffer.head, tail = txbuffer.tail;
return BUFCOUNT(head, tail, TX_BUFFER_SIZE) + ((UART.port->WATER >> 8) & 0x7) + ((UART.port->STAT & LPUART_STAT_TC) ? 0 : 1);
}
static void uart_interrupt_handler (void)
{
uint_fast16_t bptr;
uint32_t data, ctrl = UART.port->CTRL;
if ((ctrl & LPUART_CTRL_TIE) && (UART.port->STAT & LPUART_STAT_TDRE))
{
bptr = txbuffer.tail;
do {
if(txbuffer.head != bptr) {
UART.port->DATA = txbuffer.data[bptr++]; // Put character in TXT register
bptr &= (TX_BUFFER_SIZE - 1); // and update tmp tail pointer
} else
break;
} while(((UART.port->WATER >> 8) & 0x7) < tx_fifo_size);
txbuffer.tail = bptr; // Update tail pinter
if(bptr == txbuffer.head) { // Disable TX interrups
UART.port->CTRL &= ~LPUART_CTRL_TIE;
// UART.port->CTRL |= LPUART_CTRL_TCIE; // Actually wondering if we can just leave this one on...
}
}
if ((ctrl & LPUART_CTRL_TCIE) && (UART.port->STAT & LPUART_STAT_TC))
{
// transmitting_ = 0;
// if (transmit_pin_baseReg_) DIRECT_WRITE_LOW(transmit_pin_baseReg_, transmit_pin_bitmask_);
UART.port->CTRL &= ~LPUART_CTRL_TCIE;
}
if (UART.port->STAT & (LPUART_STAT_RDRF | LPUART_STAT_IDLE)) {
while ((UART.port->WATER >> 24) & 0x7) {
bptr = (rxbuffer.head + 1) & (RX_BUFFER_SIZE - 1); // Get next head pointer
data = UART.port->DATA & 0xFF; // and read input (use only 8 bits of data)
if(bptr == rxbuffer.tail) { // If buffer full
rxbuffer.overflow = true; // flag overflow
} else {
#if MODBUS_ENABLE
rxbuffer.data[rxbuffer.head] = (char)data; // Add data to buffer
rxbuffer.head = bptr; // and update pointer
#else
if(data == CMD_TOOL_ACK && !rxbuffer.backup) {
memcpy(&rxbackup, &rxbuffer, sizeof(stream_rx_buffer_t));
rxbuffer.backup = true;
rxbuffer.tail = rxbuffer.head;
hal.stream.read = serialGetC; // restore normal input
} else if(!hal.stream.enqueue_realtime_command((char)data)) {
rxbuffer.data[rxbuffer.head] = (char)data; // Add data to buffer
rxbuffer.head = bptr; // and update pointer
}
#endif
}
}
if (UART.port->STAT & LPUART_STAT_IDLE)
UART.port->STAT |= LPUART_STAT_IDLE; // writing a 1 to idle should clear it.
}
}

43
src/uart.h Normal file
View File

@ -0,0 +1,43 @@
/*
uart.h - driver code for IMXRT1062 processor (on Teensy 4.0 board)
Part of grblHAL
Copyright (c) 2020 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef _HAL_SERIAL_H_
#define _HAL_SERIAL_H_
#include <stdbool.h>
#include <stdint.h>
void serialInit (uint32_t baud_rate);
bool serialSetBaudRate (uint32_t baud_rate);
int16_t serialGetC (void);
bool serialPutC (const char c);
void serialWrite(const char *s, uint16_t length);
void serialWriteS (const char *data);
bool serialSuspendInput (bool suspend);
uint16_t serialRxFree (void);
uint16_t serialRxCount (void);
uint16_t serialTxCount (void);
void serialRxFlush (void);
void serialTxFlush (void);
void serialRxCancel (void);
#endif

245
src/usb_serial_ard.cpp Normal file
View File

@ -0,0 +1,245 @@
/*
usb_serial_ard.cpp - driver code for IMXRT1062 processor (on Teensy 4.0 board) : USB serial port wrapper
Part of grblHAL
Copyright (c) 2018-2020 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#include <string.h>
#include "Arduino.h"
#include "driver.h"
#if USB_SERIAL_CDC == 1
#ifdef __cplusplus
extern "C" {
#endif
#define BLOCK_RX_BUFFER_SIZE 20
static stream_block_tx_buffer_t txbuf = {0};
static char rxbuf[BLOCK_RX_BUFFER_SIZE];
static stream_rx_buffer_t usb_rxbuffer, usb_rxbackup;
void usb_serialInit(void)
{
txbuf.s = txbuf.data;
SerialUSB.begin(BAUD_RATE);
#if USB_SERIAL_WAIT
while(!SerialUSB); // Wait for connection
#endif
txbuf.max_length = SerialUSB.availableForWrite(); // 6144 bytes
txbuf.max_length = (txbuf.max_length > BLOCK_TX_BUFFER_SIZE ? BLOCK_TX_BUFFER_SIZE : txbuf.max_length) - 20;
}
//
// Returns number of characters in serial input buffer
//
uint16_t usb_serialRxCount (void)
{
uint_fast16_t tail = usb_rxbuffer.tail, head = usb_rxbuffer.head;
return (uint16_t)BUFCOUNT(head, tail, RX_BUFFER_SIZE);
}
//
// Returns number of free characters in serial input buffer
//
uint16_t usb_serialRxFree (void)
{
uint_fast16_t tail = usb_rxbuffer.tail, head = usb_rxbuffer.head;
return (uint16_t)((RX_BUFFER_SIZE - 1) - BUFCOUNT(head, tail, RX_BUFFER_SIZE));
}
//
// Flushes the serial input buffer (including the USB buffer)
//
void usb_serialRxFlush (void)
{
SerialUSB.flush();
usb_rxbuffer.tail = usb_rxbuffer.head;
}
//
// Flushes and adds a CAN character to the serial input buffer
//
void usb_serialRxCancel (void)
{
usb_rxbuffer.data[usb_rxbuffer.head] = CMD_RESET;
usb_rxbuffer.tail = usb_rxbuffer.head;
usb_rxbuffer.head = (usb_rxbuffer.tail + 1) & (RX_BUFFER_SIZE - 1);
}
//
// Writes a character to the serial output stream
//
bool usb_serialPutC (const char c)
{
SerialUSB.write(c);
return true;
}
//
// Writes a null terminated string to the serial output stream, blocks if buffer full.
// Buffers locally up to 40 characters or until the string is terminated with a ASCII_LF character.
// NOTE: grbl always sends ASCII_LF terminated strings!
//
void usb_serialWriteS (const char *s)
{
if(*s == '\0')
return;
size_t length = strlen(s);
if((length + txbuf.length) < BLOCK_TX_BUFFER_SIZE) {
memcpy(txbuf.s, s, length);
txbuf.length += length;
txbuf.s += length;
if(s[length - 1] == ASCII_LF || txbuf.length > txbuf.max_length) {
size_t txfree;
txbuf.s = txbuf.data;
while(txbuf.length) {
if((txfree = SerialUSB.availableForWrite()) > 10) {
length = txfree < txbuf.length ? txfree : txbuf.length;
SerialUSB.write((uint8_t *)txbuf.s, length); // doc is wrong - does not return bytes sent!
txbuf.length -= length;
txbuf.s += length;
}
if(txbuf.length && !hal.stream_blocking_callback()) {
txbuf.length = 0;
txbuf.s = txbuf.data;
return;
}
}
txbuf.s = txbuf.data;
}
}
}
//
// Writes a null terminated string to the serial output stream followed by EOL, blocks if buffer full
//
void usb_serialWriteLn (const char *s)
{
usb_serialWriteS(s);
usb_serialWriteS(ASCII_EOL);
}
//
// Writes a number of characters from string to the serial output stream followed by EOL, blocks if buffer full
//
void usb_serialWrite (const char *s, uint16_t length)
{
char *ptr = (char *)s;
while(length--)
usb_serialPutC(*ptr++);
}
//
// serialGetC - returns -1 if no data available
//
int16_t usb_serialGetC (void)
{
uint16_t bptr = usb_rxbuffer.tail;
if(bptr == usb_rxbuffer.head)
return -1; // no data available else EOF
char data = usb_rxbuffer.data[bptr++]; // Get next character, increment tmp pointer
usb_rxbuffer.tail = bptr & (RX_BUFFER_SIZE - 1); // and update pointer
return (int16_t)data;
}
// "dummy" version of serialGetC
static int16_t serialGetNull (void)
{
return -1;
}
bool usb_serialSuspendInput (bool suspend)
{
if(suspend)
hal.stream.read = serialGetNull;
else if(usb_rxbuffer.backup)
memcpy(&usb_rxbuffer, &usb_rxbackup, sizeof(stream_rx_buffer_t));
return usb_rxbuffer.tail != usb_rxbuffer.head;
}
//
// This function get called from the systick interrupt handler,
// used here to get characters off the USB serial input stream and buffer
// them for processing by grbl. Real time command characters are stripped out
// and submitted for realtime processing.
//
void usb_execute_realtime (uint_fast16_t state)
{
char c, *dp;
int avail, free;
if((avail = SerialUSB.available())) {
dp = rxbuf;
free = usb_serialRxFree();
free = free > BLOCK_RX_BUFFER_SIZE ? BLOCK_RX_BUFFER_SIZE : free;
avail = SerialUSB.readBytes(rxbuf, avail > free ? free : avail);
while(avail--) {
c = *dp++;
if(c == CMD_TOOL_ACK && !usb_rxbuffer.backup) {
memcpy(&usb_rxbackup, &usb_rxbuffer, sizeof(stream_rx_buffer_t));
usb_rxbuffer.backup = true;
usb_rxbuffer.tail = usb_rxbuffer.head;
hal.stream.read = usb_serialGetC; // restore normal input
} else if(!hal.stream.enqueue_realtime_command(c)) {
uint32_t bptr = (usb_rxbuffer.head + 1) & (RX_BUFFER_SIZE - 1); // Get next head pointer
if(bptr == usb_rxbuffer.tail) // If buffer full
usb_rxbuffer.overflow = On; // flag overflow,
else {
usb_rxbuffer.data[usb_rxbuffer.head] = c; // else add character data to buffer
usb_rxbuffer.head = bptr; // and update pointer
}
}
}
}
}
#ifdef __cplusplus
}
#endif
#endif

48
src/usb_serial_ard.h Normal file
View File

@ -0,0 +1,48 @@
/*
usb_serial_ard.h - driver code for IMXRT1062 processor (on Teensy 4.0 board)
Part of grblHAL
Copyright (c) 2018-2020 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef _USB_SERIAL_H_
#define _USB_SERIAL_H_
#include <stdbool.h>
#include <stdint.h>
extern void usb_execute_realtime (uint_fast16_t state);
#define usb_serial_poll() usb_execute_realtime(0)
void usb_serialInit(void);
int16_t usb_serialGetC(void);
bool usb_serialPutC(const char c);
void usb_serialWriteS(const char *s);
void usb_serialWriteLn(const char *s);
void usb_serialWrite(const char *s, uint16_t length);
bool usb_serialSuspendInput (bool suspend);
uint16_t usb_serialTxCount(void);
uint16_t usb_serialRxCount(void);
uint16_t usb_serialRxFree(void);
void usb_serialRxFlush(void);
void usb_serialRxCancel(void);
#endif

230
src/usb_serial_pjrc.c Normal file
View File

@ -0,0 +1,230 @@
/*
usb_serial_pjrc.c - driver code for IMXRT1062 processor (on Teensy 4.0 board) : USB serial port wrapper, PJRC version
Part of grblHAL
Copyright (c) 2018-2020 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#include <string.h>
#include "usb_serial.h"
#include "driver.h"
#if USB_SERIAL_CDC == 2
#define BLOCK_RX_BUFFER_SIZE 20
static stream_block_tx_buffer_t txbuf = {0};
static char rxbuf[BLOCK_RX_BUFFER_SIZE];
static stream_rx_buffer_t usb_rxbuffer, usb_rxbackup;
void usb_serialInit(void)
{
// usb_serial_configure(); // Done somewhere already - do not call again
txbuf.s = txbuf.data;
txbuf.max_length = usb_serial_write_buffer_free(); // 6144
txbuf.max_length = (txbuf.max_length > BLOCK_TX_BUFFER_SIZE ? BLOCK_TX_BUFFER_SIZE : txbuf.max_length) - 20;
}
//
// Returns number of characters in serial input buffer
//
uint16_t usb_serialRxCount (void)
{
uint_fast16_t tail = usb_rxbuffer.tail, head = usb_rxbuffer.head;
return (uint16_t)BUFCOUNT(head, tail, RX_BUFFER_SIZE);
}
//
// Returns number of free characters in serial input buffer
//
uint16_t usb_serialRxFree (void)
{
uint_fast16_t tail = usb_rxbuffer.tail, head = usb_rxbuffer.head;
return (uint16_t)((RX_BUFFER_SIZE - 1) - BUFCOUNT(head, tail, RX_BUFFER_SIZE));
}
//
// Flushes the serial input buffer (including the USB buffer)
//
void usb_serialRxFlush (void)
{
usb_serial_flush_input();
usb_rxbuffer.tail = usb_rxbuffer.head;
}
//
// Flushes and adds a CAN character to the serial input buffer
//
void usb_serialRxCancel (void)
{
usb_rxbuffer.data[usb_rxbuffer.head] = CMD_RESET;
usb_rxbuffer.tail = usb_rxbuffer.head;
usb_rxbuffer.head = (usb_rxbuffer.tail + 1) & (RX_BUFFER_SIZE - 1);
}
//
// Writes a character to the serial output stream
//
bool usb_serialPutC (const char c)
{
usb_serial_putchar(c);
return true;
}
//
// Writes a null terminated string to the serial output stream, blocks if buffer full
//
void usb_serialWriteS (const char *s)
{
if(*s == '\0')
return;
size_t length = strlen(s);
if((length + txbuf.length) < BLOCK_TX_BUFFER_SIZE) {
memcpy(txbuf.s, s, length);
txbuf.length += length;
txbuf.s += length;
if(s[length - 1] == ASCII_LF || txbuf.length > txbuf.max_length) {
size_t txfree;
txbuf.s = txbuf.data;
while(txbuf.length) {
if((txfree = usb_serial_write_buffer_free()) > 10) {
length = txfree < txbuf.length ? txfree : txbuf.length;
usb_serial_write(txbuf.s, length); //
txbuf.length -= length;
txbuf.s += length;
}
if(txbuf.length && !hal.stream_blocking_callback()) {
txbuf.length = 0;
txbuf.s = txbuf.data;
return;
}
}
txbuf.s = txbuf.data;
}
}
}
//
// Writes a null terminated string to the serial output stream followed by EOL, blocks if buffer full
//
void usb_serialWriteLn (const char *s)
{
usb_serialWriteS(s);
usb_serialWriteS(ASCII_EOL);
}
//
// Writes a number of characters from string to the serial output stream followed by EOL, blocks if buffer full
//
void usb_serialWrite (const char *s, uint16_t length)
{
char *ptr = (char *)s;
while(length--)
usb_serialPutC(*ptr++);
}
//
// serialGetC - returns -1 if no data available
//
int16_t usb_serialGetC (void)
{
uint16_t bptr = usb_rxbuffer.tail;
if(bptr == usb_rxbuffer.head)
return -1; // no data available else EOF
char data = usb_rxbuffer.data[bptr++]; // Get next character, increment tmp pointer
usb_rxbuffer.tail = bptr & (RX_BUFFER_SIZE - 1); // and update pointer
return (int16_t)data;
}
// "dummy" version of serialGetC
static int16_t serialGetNull (void)
{
return -1;
}
bool usb_serialSuspendInput (bool suspend)
{
if(suspend)
hal.stream.read = serialGetNull;
else if(usb_rxbuffer.backup)
memcpy(&usb_rxbuffer, &usb_rxbackup, sizeof(stream_rx_buffer_t));
return usb_rxbuffer.tail != usb_rxbuffer.head;
}
//
// This function get called from the systick interrupt handler,
// used here to get characters off the USB serial input stream and buffer
// them for processing by grbl. Real time command characters are stripped out
// and submitted for realtime processing.
//
void usb_execute_realtime (uint_fast16_t state)
{
char c, *dp;
int avail, free;
if((avail = usb_serial_available())) {
dp = rxbuf;
free = usb_serialRxFree();
free = free > BLOCK_RX_BUFFER_SIZE ? BLOCK_RX_BUFFER_SIZE : free;
avail = usb_serial_read(rxbuf, avail > free ? free : avail);
while(avail--) {
c = *dp++;
if(c == CMD_TOOL_ACK && !usb_rxbuffer.backup) {
memcpy(&usb_rxbackup, &usb_rxbuffer, sizeof(stream_rx_buffer_t));
usb_rxbuffer.backup = true;
usb_rxbuffer.tail = usb_rxbuffer.head;
hal.stream.read = usb_serialGetC; // restore normal input
} else if(!hal.stream.enqueue_realtime_command(c)) {
uint32_t bptr = (usb_rxbuffer.head + 1) & (RX_BUFFER_SIZE - 1); // Get next head pointer
if(bptr == usb_rxbuffer.tail) // If buffer full
usb_rxbuffer.overflow = On; // flag overflow,
else {
usb_rxbuffer.data[usb_rxbuffer.head] = c; // else add character data to buffer
usb_rxbuffer.head = bptr; // and update pointer
}
}
}
}
}
#endif

48
src/usb_serial_pjrc.h Normal file
View File

@ -0,0 +1,48 @@
/*
usb_serial.h - driver code for IMXRT1062 processor (on Teensy 4.0 board)
Part of grblHAL
Copyright (c) 2018-2020 Terje Io
Grbl 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, or
(at your option) any later version.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef _USB_SERIAL_H_
#define _USB_SERIAL_H_
#include <stdbool.h>
#include <stdint.h>
extern void usb_execute_realtime (uint_fast16_t state);
#define usb_serial_poll() usb_execute_realtime(0)
void usb_serialInit(void);
int16_t usb_serialGetC(void);
bool usb_serialPutC(const char c);
void usb_serialWriteS(const char *s);
void usb_serialWriteLn(const char *s);
void usb_serialWrite(const char *s, uint16_t length);
bool usb_serialSuspendInput (bool suspend);
uint16_t usb_serialTxCount(void);
uint16_t usb_serialRxCount(void);
uint16_t usb_serialRxFree(void);
void usb_serialRxFlush(void);
void usb_serialRxCancel(void);
#endif