mirror of
https://github.com/eddyem/stm32samples.git
synced 2025-12-08 11:45:22 +03:00
3 servos management in development
This commit is contained in:
parent
39fd5b4912
commit
3d59c76f65
6
.gitignore
vendored
6
.gitignore
vendored
@ -16,3 +16,9 @@
|
|||||||
*.sublime-workspace
|
*.sublime-workspace
|
||||||
F1/client-term/client
|
F1/client-term/client
|
||||||
*.bk
|
*.bk
|
||||||
|
*.config
|
||||||
|
*.creator
|
||||||
|
*.creator.user*
|
||||||
|
*.files
|
||||||
|
*.includes
|
||||||
|
|
||||||
|
|||||||
@ -2,22 +2,13 @@ Servo motors SG-90 management
|
|||||||
=============================
|
=============================
|
||||||
|
|
||||||
## GPIO
|
## GPIO
|
||||||
|
- PA0..PA3 - 4 ADC inputs
|
||||||
- PA0 - (ADC_IN0) - Servo1 control,
|
|
||||||
- PA1 - (ADC_IN1) - Servo2 control,
|
|
||||||
- PA2 - (ADC_IN2) - Servo3 control,
|
|
||||||
- PA3 - (ADC_IN3) - external analogue signal,
|
|
||||||
- PA4 - (PullUp in) - ext. input 0,
|
|
||||||
- PA5 - (PullUp in) - ext. input 1,
|
|
||||||
- PA6 - (TIM3_CH1) - Servo1,
|
- PA6 - (TIM3_CH1) - Servo1,
|
||||||
- PA7 - (TIM3_CH2) - Servo2,
|
- PA7 - (TIM3_CH2) - Servo2,
|
||||||
- PA9 - (USART_Tx) - TX,
|
- PA9 - (USART_Tx) - TX,
|
||||||
- PA10 - (USART_Rx) - RX,
|
- PA10 - (USART_Rx) - RX,
|
||||||
- PA13 - (PullUp in) - Jumper 0,
|
|
||||||
- PA14 - (PullUp in) - Jumper 1,
|
|
||||||
- PB1 - (TIM3_CH4) - Servo3,
|
- PB1 - (TIM3_CH4) - Servo3,
|
||||||
- PF0 - (OpenDrain) - Buzzer,
|
- PF1 - (OpenDrain) - external LED or laser (0 - active)
|
||||||
- PF1 - (OpenDrain) - External LED (or weak laser module).
|
|
||||||
|
|
||||||
## UART
|
## UART
|
||||||
115200N1, not more than 100ms between data bytes in command.
|
115200N1, not more than 100ms between data bytes in command.
|
||||||
|
|||||||
@ -1,6 +1,6 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
<!DOCTYPE QtCreatorProject>
|
<!DOCTYPE QtCreatorProject>
|
||||||
<!-- Written by QtCreator 4.8.0, 2019-03-10T11:39:00. -->
|
<!-- Written by QtCreator 4.6.2, 2019-05-25T17:10:21. -->
|
||||||
<qtcreator>
|
<qtcreator>
|
||||||
<data>
|
<data>
|
||||||
<variable>EnvironmentId</variable>
|
<variable>EnvironmentId</variable>
|
||||||
@ -54,10 +54,7 @@
|
|||||||
</data>
|
</data>
|
||||||
<data>
|
<data>
|
||||||
<variable>ProjectExplorer.Project.PluginSettings</variable>
|
<variable>ProjectExplorer.Project.PluginSettings</variable>
|
||||||
<valuemap type="QVariantMap">
|
<valuemap type="QVariantMap"/>
|
||||||
<valuelist type="QVariantList" key="ClangCodeModel.CustomCommandLineKey"/>
|
|
||||||
<value type="bool" key="ClangCodeModel.UseGlobalConfig">true</value>
|
|
||||||
</valuemap>
|
|
||||||
</data>
|
</data>
|
||||||
<data>
|
<data>
|
||||||
<variable>ProjectExplorer.Project.Target.0</variable>
|
<variable>ProjectExplorer.Project.Target.0</variable>
|
||||||
@ -78,7 +75,6 @@
|
|||||||
<value type="bool" key="GenericProjectManager.GenericMakeStep.Clean">false</value>
|
<value type="bool" key="GenericProjectManager.GenericMakeStep.Clean">false</value>
|
||||||
<value type="QString" key="GenericProjectManager.GenericMakeStep.MakeArguments"></value>
|
<value type="QString" key="GenericProjectManager.GenericMakeStep.MakeArguments"></value>
|
||||||
<value type="QString" key="GenericProjectManager.GenericMakeStep.MakeCommand"></value>
|
<value type="QString" key="GenericProjectManager.GenericMakeStep.MakeCommand"></value>
|
||||||
<value type="bool" key="GenericProjectManager.GenericMakeStep.OverrideMakeflags">false</value>
|
|
||||||
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
|
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
|
||||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Сборка</value>
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Сборка</value>
|
||||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
|
||||||
@ -97,7 +93,6 @@
|
|||||||
<value type="bool" key="GenericProjectManager.GenericMakeStep.Clean">false</value>
|
<value type="bool" key="GenericProjectManager.GenericMakeStep.Clean">false</value>
|
||||||
<value type="QString" key="GenericProjectManager.GenericMakeStep.MakeArguments"></value>
|
<value type="QString" key="GenericProjectManager.GenericMakeStep.MakeArguments"></value>
|
||||||
<value type="QString" key="GenericProjectManager.GenericMakeStep.MakeCommand"></value>
|
<value type="QString" key="GenericProjectManager.GenericMakeStep.MakeCommand"></value>
|
||||||
<value type="bool" key="GenericProjectManager.GenericMakeStep.OverrideMakeflags">false</value>
|
|
||||||
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
|
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
|
||||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Сборка</value>
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Сборка</value>
|
||||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
|
||||||
@ -172,19 +167,18 @@
|
|||||||
</valuelist>
|
</valuelist>
|
||||||
<value type="int" key="PE.EnvironmentAspect.Base">2</value>
|
<value type="int" key="PE.EnvironmentAspect.Base">2</value>
|
||||||
<valuelist type="QVariantList" key="PE.EnvironmentAspect.Changes"/>
|
<valuelist type="QVariantList" key="PE.EnvironmentAspect.Changes"/>
|
||||||
|
<value type="QString" key="ProjectExplorer.CustomExecutableRunConfiguration.Arguments"></value>
|
||||||
<value type="QString" key="ProjectExplorer.CustomExecutableRunConfiguration.Executable"></value>
|
<value type="QString" key="ProjectExplorer.CustomExecutableRunConfiguration.Executable"></value>
|
||||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Особая программа</value>
|
<value type="QString" key="ProjectExplorer.CustomExecutableRunConfiguration.WorkingDirectory"></value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName"></value>
|
||||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
|
||||||
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.CustomExecutableRunConfiguration</value>
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.CustomExecutableRunConfiguration</value>
|
||||||
<value type="QString" key="RunConfiguration.Arguments"></value>
|
|
||||||
<value type="uint" key="RunConfiguration.QmlDebugServerPort">3768</value>
|
<value type="uint" key="RunConfiguration.QmlDebugServerPort">3768</value>
|
||||||
<value type="bool" key="RunConfiguration.UseCppDebugger">false</value>
|
<value type="bool" key="RunConfiguration.UseCppDebugger">false</value>
|
||||||
<value type="bool" key="RunConfiguration.UseCppDebuggerAuto">true</value>
|
<value type="bool" key="RunConfiguration.UseCppDebuggerAuto">true</value>
|
||||||
<value type="bool" key="RunConfiguration.UseMultiProcess">false</value>
|
<value type="bool" key="RunConfiguration.UseMultiProcess">false</value>
|
||||||
<value type="bool" key="RunConfiguration.UseQmlDebugger">false</value>
|
<value type="bool" key="RunConfiguration.UseQmlDebugger">false</value>
|
||||||
<value type="bool" key="RunConfiguration.UseQmlDebuggerAuto">true</value>
|
<value type="bool" key="RunConfiguration.UseQmlDebuggerAuto">true</value>
|
||||||
<value type="QString" key="RunConfiguration.WorkingDirectory"></value>
|
|
||||||
<value type="QString" key="RunConfiguration.WorkingDirectory.default"></value>
|
|
||||||
</valuemap>
|
</valuemap>
|
||||||
<value type="int" key="ProjectExplorer.Target.RunConfigurationCount">1</value>
|
<value type="int" key="ProjectExplorer.Target.RunConfigurationCount">1</value>
|
||||||
</valuemap>
|
</valuemap>
|
||||||
@ -195,10 +189,10 @@
|
|||||||
</data>
|
</data>
|
||||||
<data>
|
<data>
|
||||||
<variable>ProjectExplorer.Project.Updater.FileVersion</variable>
|
<variable>ProjectExplorer.Project.Updater.FileVersion</variable>
|
||||||
<value type="int">20</value>
|
<value type="int">18</value>
|
||||||
</data>
|
</data>
|
||||||
<data>
|
<data>
|
||||||
<variable>Version</variable>
|
<variable>Version</variable>
|
||||||
<value type="int">20</value>
|
<value type="int">18</value>
|
||||||
</data>
|
</data>
|
||||||
</qtcreator>
|
</qtcreator>
|
||||||
|
|||||||
204
F0-nolib/Servo/Servo.creator.user.20
Normal file
204
F0-nolib/Servo/Servo.creator.user.20
Normal file
@ -0,0 +1,204 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<!DOCTYPE QtCreatorProject>
|
||||||
|
<!-- Written by QtCreator 4.8.0, 2019-05-24T21:52:16. -->
|
||||||
|
<qtcreator>
|
||||||
|
<data>
|
||||||
|
<variable>EnvironmentId</variable>
|
||||||
|
<value type="QByteArray">{7bd84e39-ca37-46d3-be9d-99ebea85bc0d}</value>
|
||||||
|
</data>
|
||||||
|
<data>
|
||||||
|
<variable>ProjectExplorer.Project.ActiveTarget</variable>
|
||||||
|
<value type="int">0</value>
|
||||||
|
</data>
|
||||||
|
<data>
|
||||||
|
<variable>ProjectExplorer.Project.EditorSettings</variable>
|
||||||
|
<valuemap type="QVariantMap">
|
||||||
|
<value type="bool" key="EditorConfiguration.AutoIndent">true</value>
|
||||||
|
<value type="bool" key="EditorConfiguration.AutoSpacesForTabs">false</value>
|
||||||
|
<value type="bool" key="EditorConfiguration.CamelCaseNavigation">true</value>
|
||||||
|
<valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.0">
|
||||||
|
<value type="QString" key="language">Cpp</value>
|
||||||
|
<valuemap type="QVariantMap" key="value">
|
||||||
|
<value type="QByteArray" key="CurrentPreferences">CppGlobal</value>
|
||||||
|
</valuemap>
|
||||||
|
</valuemap>
|
||||||
|
<valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.1">
|
||||||
|
<value type="QString" key="language">QmlJS</value>
|
||||||
|
<valuemap type="QVariantMap" key="value">
|
||||||
|
<value type="QByteArray" key="CurrentPreferences">QmlJSGlobal</value>
|
||||||
|
</valuemap>
|
||||||
|
</valuemap>
|
||||||
|
<value type="int" key="EditorConfiguration.CodeStyle.Count">2</value>
|
||||||
|
<value type="QByteArray" key="EditorConfiguration.Codec">KOI8-R</value>
|
||||||
|
<value type="bool" key="EditorConfiguration.ConstrainTooltips">false</value>
|
||||||
|
<value type="int" key="EditorConfiguration.IndentSize">4</value>
|
||||||
|
<value type="bool" key="EditorConfiguration.KeyboardTooltips">false</value>
|
||||||
|
<value type="int" key="EditorConfiguration.MarginColumn">80</value>
|
||||||
|
<value type="bool" key="EditorConfiguration.MouseHiding">true</value>
|
||||||
|
<value type="bool" key="EditorConfiguration.MouseNavigation">true</value>
|
||||||
|
<value type="int" key="EditorConfiguration.PaddingMode">1</value>
|
||||||
|
<value type="bool" key="EditorConfiguration.ScrollWheelZooming">true</value>
|
||||||
|
<value type="bool" key="EditorConfiguration.ShowMargin">false</value>
|
||||||
|
<value type="int" key="EditorConfiguration.SmartBackspaceBehavior">0</value>
|
||||||
|
<value type="bool" key="EditorConfiguration.SmartSelectionChanging">true</value>
|
||||||
|
<value type="bool" key="EditorConfiguration.SpacesForTabs">true</value>
|
||||||
|
<value type="int" key="EditorConfiguration.TabKeyBehavior">0</value>
|
||||||
|
<value type="int" key="EditorConfiguration.TabSize">8</value>
|
||||||
|
<value type="bool" key="EditorConfiguration.UseGlobal">true</value>
|
||||||
|
<value type="int" key="EditorConfiguration.Utf8BomBehavior">1</value>
|
||||||
|
<value type="bool" key="EditorConfiguration.addFinalNewLine">true</value>
|
||||||
|
<value type="bool" key="EditorConfiguration.cleanIndentation">false</value>
|
||||||
|
<value type="bool" key="EditorConfiguration.cleanWhitespace">true</value>
|
||||||
|
<value type="bool" key="EditorConfiguration.inEntireDocument">false</value>
|
||||||
|
</valuemap>
|
||||||
|
</data>
|
||||||
|
<data>
|
||||||
|
<variable>ProjectExplorer.Project.PluginSettings</variable>
|
||||||
|
<valuemap type="QVariantMap">
|
||||||
|
<valuelist type="QVariantList" key="ClangCodeModel.CustomCommandLineKey"/>
|
||||||
|
<value type="bool" key="ClangCodeModel.UseGlobalConfig">true</value>
|
||||||
|
</valuemap>
|
||||||
|
</data>
|
||||||
|
<data>
|
||||||
|
<variable>ProjectExplorer.Project.Target.0</variable>
|
||||||
|
<valuemap type="QVariantMap">
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Desktop</value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Desktop</value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">{65a14f9e-e008-4c1b-89df-4eaa4774b6e3}</value>
|
||||||
|
<value type="int" key="ProjectExplorer.Target.ActiveBuildConfiguration">0</value>
|
||||||
|
<value type="int" key="ProjectExplorer.Target.ActiveDeployConfiguration">0</value>
|
||||||
|
<value type="int" key="ProjectExplorer.Target.ActiveRunConfiguration">0</value>
|
||||||
|
<valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.0">
|
||||||
|
<value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/Big/Data/00__Electronics/STM32/F0-nolib/Servo</value>
|
||||||
|
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
|
||||||
|
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
|
||||||
|
<valuelist type="QVariantList" key="GenericProjectManager.GenericMakeStep.BuildTargets">
|
||||||
|
<value type="QString">all</value>
|
||||||
|
</valuelist>
|
||||||
|
<value type="bool" key="GenericProjectManager.GenericMakeStep.Clean">false</value>
|
||||||
|
<value type="QString" key="GenericProjectManager.GenericMakeStep.MakeArguments"></value>
|
||||||
|
<value type="QString" key="GenericProjectManager.GenericMakeStep.MakeCommand"></value>
|
||||||
|
<value type="bool" key="GenericProjectManager.GenericMakeStep.OverrideMakeflags">false</value>
|
||||||
|
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Сборка</value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">GenericProjectManager.GenericMakeStep</value>
|
||||||
|
</valuemap>
|
||||||
|
<value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Сборка</value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
|
||||||
|
</valuemap>
|
||||||
|
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
|
||||||
|
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
|
||||||
|
<valuelist type="QVariantList" key="GenericProjectManager.GenericMakeStep.BuildTargets">
|
||||||
|
<value type="QString">clean</value>
|
||||||
|
</valuelist>
|
||||||
|
<value type="bool" key="GenericProjectManager.GenericMakeStep.Clean">false</value>
|
||||||
|
<value type="QString" key="GenericProjectManager.GenericMakeStep.MakeArguments"></value>
|
||||||
|
<value type="QString" key="GenericProjectManager.GenericMakeStep.MakeCommand"></value>
|
||||||
|
<value type="bool" key="GenericProjectManager.GenericMakeStep.OverrideMakeflags">false</value>
|
||||||
|
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Сборка</value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">GenericProjectManager.GenericMakeStep</value>
|
||||||
|
</valuemap>
|
||||||
|
<value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Очистка</value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
|
||||||
|
</valuemap>
|
||||||
|
<value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
|
||||||
|
<value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value>
|
||||||
|
<valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">По умолчанию</value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">По умолчанию</value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">GenericProjectManager.GenericBuildConfiguration</value>
|
||||||
|
</valuemap>
|
||||||
|
<value type="int" key="ProjectExplorer.Target.BuildConfigurationCount">1</value>
|
||||||
|
<valuemap type="QVariantMap" key="ProjectExplorer.Target.DeployConfiguration.0">
|
||||||
|
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
|
||||||
|
<value type="int" key="ProjectExplorer.BuildStepList.StepsCount">0</value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Установка</value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Deploy</value>
|
||||||
|
</valuemap>
|
||||||
|
<value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">1</value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Конфигурация установки</value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.DefaultDeployConfiguration</value>
|
||||||
|
</valuemap>
|
||||||
|
<value type="int" key="ProjectExplorer.Target.DeployConfigurationCount">1</value>
|
||||||
|
<valuemap type="QVariantMap" key="ProjectExplorer.Target.PluginSettings"/>
|
||||||
|
<valuemap type="QVariantMap" key="ProjectExplorer.Target.RunConfiguration.0">
|
||||||
|
<value type="bool" key="Analyzer.QmlProfiler.AggregateTraces">false</value>
|
||||||
|
<value type="bool" key="Analyzer.QmlProfiler.FlushEnabled">false</value>
|
||||||
|
<value type="uint" key="Analyzer.QmlProfiler.FlushInterval">1000</value>
|
||||||
|
<value type="QString" key="Analyzer.QmlProfiler.LastTraceFile"></value>
|
||||||
|
<value type="bool" key="Analyzer.QmlProfiler.Settings.UseGlobalSettings">true</value>
|
||||||
|
<valuelist type="QVariantList" key="Analyzer.Valgrind.AddedSuppressionFiles"/>
|
||||||
|
<value type="bool" key="Analyzer.Valgrind.Callgrind.CollectBusEvents">false</value>
|
||||||
|
<value type="bool" key="Analyzer.Valgrind.Callgrind.CollectSystime">false</value>
|
||||||
|
<value type="bool" key="Analyzer.Valgrind.Callgrind.EnableBranchSim">false</value>
|
||||||
|
<value type="bool" key="Analyzer.Valgrind.Callgrind.EnableCacheSim">false</value>
|
||||||
|
<value type="bool" key="Analyzer.Valgrind.Callgrind.EnableEventToolTips">true</value>
|
||||||
|
<value type="double" key="Analyzer.Valgrind.Callgrind.MinimumCostRatio">0.01</value>
|
||||||
|
<value type="double" key="Analyzer.Valgrind.Callgrind.VisualisationMinimumCostRatio">10</value>
|
||||||
|
<value type="bool" key="Analyzer.Valgrind.FilterExternalIssues">true</value>
|
||||||
|
<value type="int" key="Analyzer.Valgrind.LeakCheckOnFinish">1</value>
|
||||||
|
<value type="int" key="Analyzer.Valgrind.NumCallers">25</value>
|
||||||
|
<valuelist type="QVariantList" key="Analyzer.Valgrind.RemovedSuppressionFiles"/>
|
||||||
|
<value type="int" key="Analyzer.Valgrind.SelfModifyingCodeDetection">1</value>
|
||||||
|
<value type="bool" key="Analyzer.Valgrind.Settings.UseGlobalSettings">true</value>
|
||||||
|
<value type="bool" key="Analyzer.Valgrind.ShowReachable">false</value>
|
||||||
|
<value type="bool" key="Analyzer.Valgrind.TrackOrigins">true</value>
|
||||||
|
<value type="QString" key="Analyzer.Valgrind.ValgrindExecutable">valgrind</value>
|
||||||
|
<valuelist type="QVariantList" key="Analyzer.Valgrind.VisibleErrorKinds">
|
||||||
|
<value type="int">0</value>
|
||||||
|
<value type="int">1</value>
|
||||||
|
<value type="int">2</value>
|
||||||
|
<value type="int">3</value>
|
||||||
|
<value type="int">4</value>
|
||||||
|
<value type="int">5</value>
|
||||||
|
<value type="int">6</value>
|
||||||
|
<value type="int">7</value>
|
||||||
|
<value type="int">8</value>
|
||||||
|
<value type="int">9</value>
|
||||||
|
<value type="int">10</value>
|
||||||
|
<value type="int">11</value>
|
||||||
|
<value type="int">12</value>
|
||||||
|
<value type="int">13</value>
|
||||||
|
<value type="int">14</value>
|
||||||
|
</valuelist>
|
||||||
|
<value type="int" key="PE.EnvironmentAspect.Base">2</value>
|
||||||
|
<valuelist type="QVariantList" key="PE.EnvironmentAspect.Changes"/>
|
||||||
|
<value type="QString" key="ProjectExplorer.CustomExecutableRunConfiguration.Executable"></value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Особая программа</value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
|
||||||
|
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.CustomExecutableRunConfiguration</value>
|
||||||
|
<value type="QString" key="RunConfiguration.Arguments"></value>
|
||||||
|
<value type="uint" key="RunConfiguration.QmlDebugServerPort">3768</value>
|
||||||
|
<value type="bool" key="RunConfiguration.UseCppDebugger">false</value>
|
||||||
|
<value type="bool" key="RunConfiguration.UseCppDebuggerAuto">true</value>
|
||||||
|
<value type="bool" key="RunConfiguration.UseMultiProcess">false</value>
|
||||||
|
<value type="bool" key="RunConfiguration.UseQmlDebugger">false</value>
|
||||||
|
<value type="bool" key="RunConfiguration.UseQmlDebuggerAuto">true</value>
|
||||||
|
<value type="QString" key="RunConfiguration.WorkingDirectory"></value>
|
||||||
|
<value type="QString" key="RunConfiguration.WorkingDirectory.default"></value>
|
||||||
|
</valuemap>
|
||||||
|
<value type="int" key="ProjectExplorer.Target.RunConfigurationCount">1</value>
|
||||||
|
</valuemap>
|
||||||
|
</data>
|
||||||
|
<data>
|
||||||
|
<variable>ProjectExplorer.Project.TargetCount</variable>
|
||||||
|
<value type="int">1</value>
|
||||||
|
</data>
|
||||||
|
<data>
|
||||||
|
<variable>ProjectExplorer.Project.Updater.FileVersion</variable>
|
||||||
|
<value type="int">20</value>
|
||||||
|
</data>
|
||||||
|
<data>
|
||||||
|
<variable>Version</variable>
|
||||||
|
<value type="int">20</value>
|
||||||
|
</data>
|
||||||
|
</qtcreator>
|
||||||
@ -1,11 +1,11 @@
|
|||||||
Makefile
|
Makefile
|
||||||
adc.c
|
adc.c
|
||||||
adc.h
|
adc.h
|
||||||
|
effects.c
|
||||||
|
effects.h
|
||||||
hardware.c
|
hardware.c
|
||||||
hardware.h
|
hardware.h
|
||||||
main.c
|
main.c
|
||||||
mainloop.c
|
|
||||||
mainloop.h
|
|
||||||
protocol.c
|
protocol.c
|
||||||
protocol.h
|
protocol.h
|
||||||
usart.c
|
usart.c
|
||||||
|
|||||||
@ -20,7 +20,7 @@
|
|||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief ADC_array - array for ADC channels with median filtering:
|
* @brief ADC_array - array for ADC channels with median filtering:
|
||||||
* 0..3 - external NTC
|
* 0..3 - external channels
|
||||||
* 4 - internal Tsens
|
* 4 - internal Tsens
|
||||||
* 5 - Vref
|
* 5 - Vref
|
||||||
*/
|
*/
|
||||||
|
|||||||
111
F0-nolib/Servo/effects.c
Normal file
111
F0-nolib/Servo/effects.c
Normal file
@ -0,0 +1,111 @@
|
|||||||
|
/*
|
||||||
|
* This file is part of the Servo project.
|
||||||
|
* Copyright 2019 Edward Emelianov <eddy@sao.ru>.
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "effects.h"
|
||||||
|
#include "hardware.h"
|
||||||
|
#include "usart.h"
|
||||||
|
|
||||||
|
static effect_t current_ef[3] = {EFF_NONE, EFF_NONE, EFF_NONE};
|
||||||
|
|
||||||
|
#define SPD_STP (25)
|
||||||
|
|
||||||
|
static void eff_madwipe(int n){
|
||||||
|
static uint32_t speed[3] = {SPD_STP, SPD_STP, SPD_STP};
|
||||||
|
if(onposition(n)){ // move back
|
||||||
|
if((speed[n]+=SPD_STP) > SG90_STEP) speed[n] = SPD_STP;
|
||||||
|
int val = 0;
|
||||||
|
if(getPWM(n) < SG90_MIDPULSE) val = 1;
|
||||||
|
setPWM(n, val, speed[n]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void eff_wipe(int n){
|
||||||
|
static uint8_t cntr = 0;
|
||||||
|
if(onposition(n)){ // move back
|
||||||
|
int val = 0;
|
||||||
|
if(getPWM(n) < SG90_MIDPULSE) val = 1;
|
||||||
|
if(++cntr < 4){ // stay a little in outermost positions
|
||||||
|
setPWM(n, getPWM(n), SG90_STEP/2);
|
||||||
|
}else{
|
||||||
|
cntr = 0;
|
||||||
|
setPWM(n, val, SG90_STEP/2);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void eff_pendulum(int n){
|
||||||
|
const uint16_t steps[41] = {0, 10, 21, 33, 47, 62, 79, 97, 117, 140, 165, 193, 224, 258, 295, 337, 383, 434,
|
||||||
|
490, 552, 621, 697, 766, 828, 884, 935, 981, 1023, 1060, 1094, 1125, 1153, 1178,
|
||||||
|
1201, 1221, 1239, 1256, 1271, 1285, 1297, 1308};
|
||||||
|
static int8_t cntr = 0, dir = 1;
|
||||||
|
if(onposition(n)){
|
||||||
|
setPWM(n, SG90_MINPULSE + steps[cntr], SG90_STEP);
|
||||||
|
cntr += dir;
|
||||||
|
if(cntr == -1){ // min position
|
||||||
|
dir = 1;
|
||||||
|
cntr = 0; // repeat zero position one time
|
||||||
|
}else if(cntr == 41){ // max position
|
||||||
|
dir = -1;
|
||||||
|
cntr = 40; // and this position needs to repeat too
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void eff_pendsm(int n){
|
||||||
|
const uint16_t steps[19] = {0, 6, 10, 15, 22, 30, 40, 52, 66, 82, 101, 123, 148, 177, 210, 247, 289, 336, 389};
|
||||||
|
static int8_t cntr = 0, dir = 1;
|
||||||
|
if(onposition(n)){
|
||||||
|
setPWM(n, SG90_MINPULSE + steps[cntr], SG90_STEP);
|
||||||
|
cntr += dir;
|
||||||
|
if(cntr == -1){ // min position
|
||||||
|
dir = 1;
|
||||||
|
cntr = 1;
|
||||||
|
}else if(cntr == 19){ // max position
|
||||||
|
dir = -1;
|
||||||
|
cntr = 18;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void proc_effect(){
|
||||||
|
for(int i = 0; i < 3; ++i){
|
||||||
|
switch(current_ef[i]){
|
||||||
|
case EFF_WIPE:
|
||||||
|
eff_wipe(i);
|
||||||
|
break;
|
||||||
|
case EFF_MADWIPE:
|
||||||
|
eff_madwipe(i);
|
||||||
|
break;
|
||||||
|
case EFF_PENDULUM:
|
||||||
|
eff_pendulum(i);
|
||||||
|
break;
|
||||||
|
case EFF_SMPENDULUM:
|
||||||
|
eff_pendsm(i);
|
||||||
|
break;
|
||||||
|
case EFF_NONE:
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
effect_t set_effect(int n, effect_t eff){
|
||||||
|
if(n < 0 || n > 3) return EFF_NONE;
|
||||||
|
current_ef[n] = eff;
|
||||||
|
return eff;
|
||||||
|
}
|
||||||
36
F0-nolib/Servo/effects.h
Normal file
36
F0-nolib/Servo/effects.h
Normal file
@ -0,0 +1,36 @@
|
|||||||
|
/*
|
||||||
|
* This file is part of the Servo project.
|
||||||
|
* Copyright 2019 Edward Emelianov <eddy@sao.ru>.
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
#ifndef EFFECTS_H__
|
||||||
|
#define EFFECTS_H__
|
||||||
|
|
||||||
|
#include "stm32f0.h"
|
||||||
|
|
||||||
|
typedef enum{
|
||||||
|
EFF_NONE,
|
||||||
|
EFF_WIPE,
|
||||||
|
EFF_MADWIPE,
|
||||||
|
EFF_PENDULUM,
|
||||||
|
EFF_SMPENDULUM
|
||||||
|
} effect_t;
|
||||||
|
|
||||||
|
void proc_effect();
|
||||||
|
effect_t set_effect(int n, effect_t eff);
|
||||||
|
|
||||||
|
#endif // EFFECTS_H__
|
||||||
@ -15,9 +15,13 @@
|
|||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include "adc.h"
|
||||||
|
#include "effects.h"
|
||||||
#include "hardware.h"
|
#include "hardware.h"
|
||||||
#include "usart.h"
|
#include "usart.h"
|
||||||
#include "adc.h"
|
|
||||||
|
uint32_t sg90step = SG90DEFSTEP;
|
||||||
|
|
||||||
static inline void iwdg_setup(){
|
static inline void iwdg_setup(){
|
||||||
/* Enable the peripheral clock RTC */
|
/* Enable the peripheral clock RTC */
|
||||||
@ -99,13 +103,10 @@ static inline void adc_setup(){
|
|||||||
/**
|
/**
|
||||||
* @brief gpio_setup - setup GPIOs for external IO
|
* @brief gpio_setup - setup GPIOs for external IO
|
||||||
* GPIO pinout:
|
* GPIO pinout:
|
||||||
* PA5 - floating input - Ef of TLE5205
|
* PF1 - open drain - ext. LED/laser
|
||||||
* PA13 - open drain - IN1 of TLE5205
|
|
||||||
* PA14 - open drain - IN2 of TLE5205
|
|
||||||
* PF0 - floating input - water level alert
|
|
||||||
* PF1 - push-pull - external alarm
|
|
||||||
* PA0..PA3 - ADC_IN0..3
|
* PA0..PA3 - ADC_IN0..3
|
||||||
* PA4, PA6, PA7 - PWM outputs
|
* PA4 - open drain - onboard LED (always ON when board works)
|
||||||
|
* PB1, PA6, PA7 - Alt. F. - PWM outputs
|
||||||
* Registers
|
* Registers
|
||||||
* MODER - input/output/alternate/analog (2 bit)
|
* MODER - input/output/alternate/analog (2 bit)
|
||||||
* OTYPER - 0 pushpull, 1 opendrain
|
* OTYPER - 0 pushpull, 1 opendrain
|
||||||
@ -120,67 +121,54 @@ static inline void adc_setup(){
|
|||||||
static inline void gpio_setup(){
|
static inline void gpio_setup(){
|
||||||
// Enable clocks to the GPIO subsystems
|
// Enable clocks to the GPIO subsystems
|
||||||
RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN | RCC_AHBENR_GPIOFEN;
|
RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN | RCC_AHBENR_GPIOFEN;
|
||||||
GPIOA->MODER =
|
// PA6/7 - AF; PB1 - AF
|
||||||
GPIO_MODER_MODER13_O | GPIO_MODER_MODER14_O |
|
GPIOA->MODER = GPIO_MODER_MODER6_AF | GPIO_MODER_MODER7_AF |
|
||||||
GPIO_MODER_MODER4_AF | GPIO_MODER_MODER6_AF |
|
|
||||||
GPIO_MODER_MODER7_AF |
|
|
||||||
GPIO_MODER_MODER0_AI | GPIO_MODER_MODER1_AI |
|
GPIO_MODER_MODER0_AI | GPIO_MODER_MODER1_AI |
|
||||||
GPIO_MODER_MODER2_AI | GPIO_MODER_MODER3_AI;
|
GPIO_MODER_MODER2_AI | GPIO_MODER_MODER3_AI |
|
||||||
RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN; // enable syscfg clock for EXTI
|
GPIO_MODER_MODER4_O;
|
||||||
GPIOA->OTYPER = 3 << 13; // 13/14 opendrain
|
GPIOA->OTYPER = GPIO_OTYPER_OT_4;
|
||||||
|
GPIOB->MODER = GPIO_MODER_MODER1_AF;
|
||||||
|
//RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN; // enable syscfg clock for EXTI
|
||||||
|
GPIOF->ODR = 1<<1;
|
||||||
GPIOF->MODER = GPIO_MODER_MODER1_O;
|
GPIOF->MODER = GPIO_MODER_MODER1_O;
|
||||||
// PB1 - interrupt input
|
GPIOF->OTYPER = GPIO_OTYPER_OT_1;
|
||||||
/* (2) Select Port B for pin 1 external interrupt by writing 0001 in EXTI1*/
|
|
||||||
/* (3) Configure the corresponding mask bit in the EXTI_IMR register */
|
|
||||||
/* (4) Configure the Trigger Selection bits of the Interrupt line on rising edge*/
|
|
||||||
/* (5) Configure the Trigger Selection bits of the Interrupt line on falling edge*/
|
|
||||||
SYSCFG->EXTICR[0] = SYSCFG_EXTICR1_EXTI1_PB; /* (2) */
|
|
||||||
EXTI->IMR = EXTI_IMR_MR1; /* (3) */
|
|
||||||
//EXTI->RTSR = 0x0000; /* (4) */
|
|
||||||
EXTI->FTSR = EXTI_FTSR_TR1; /* (5) */
|
|
||||||
/* (6) Enable Interrupt on EXTI0_1 */
|
|
||||||
/* (7) Set priority for EXTI0_1 */
|
|
||||||
NVIC_EnableIRQ(EXTI0_1_IRQn); /* (6) */
|
|
||||||
NVIC_SetPriority(EXTI0_1_IRQn, 3); /* (7) */
|
|
||||||
// alternate functions:
|
// alternate functions:
|
||||||
// PA4 - TIM14_CH1 (AF4)
|
// PA6 - TIM3_CH1, PA7 - TIM3_CH2, PB1 - TIM3_CH4 (all - AF1)
|
||||||
// PA6 - TIM16_CH1 (AF5), PA7 - TIM17_CH1 (AF5)
|
GPIOA->AFR[0] = (GPIOA->AFR[0] &~ (GPIO_AFRL_AFRL6 | GPIO_AFRL_AFRL7)) \
|
||||||
GPIOA->AFR[0] = (GPIOA->AFR[0] &~ (GPIO_AFRL_AFRL4 | GPIO_AFRL_AFRL6 | GPIO_AFRL_AFRL7)) \
|
| (1 << (6 * 4)) | (1 << (7 * 4));
|
||||||
| (4 << (4 * 4)) | (5 << (6 * 4)) | (5 << (7 * 4));
|
GPIOB->AFR[0] = (GPIOB->AFR[0] &~ (GPIO_AFRL_AFRL1)) \
|
||||||
|
| (1 << (1 * 4)) ;
|
||||||
|
}
|
||||||
|
|
||||||
|
// change period of PWM
|
||||||
|
// MAX freq - 200Hz!!!
|
||||||
|
void setTIM3T(uint32_t T){
|
||||||
|
if(T < 1000 || T > 65536) return;
|
||||||
|
TIM3->ARR = T - 1;
|
||||||
|
// step = ampl / freq(Hz) * 3
|
||||||
|
sg90step = SG90_AMPL * T;
|
||||||
|
sg90step >>= 18; // /262144
|
||||||
}
|
}
|
||||||
|
|
||||||
static inline void timers_setup(){
|
static inline void timers_setup(){
|
||||||
// timer 14 ch1 - cooler PWM
|
// timer 3 ch1, 2, 4 PWM for three servos
|
||||||
// timer 16 ch1 - heater PWM
|
RCC->APB1ENR |= RCC_APB1ENR_TIM3EN;
|
||||||
// timer 17 ch1 - pump PWM
|
// PWM mode 1 (active -> inactive) on all three channels
|
||||||
RCC->APB1ENR |= RCC_APB1ENR_TIM3EN | RCC_APB1ENR_TIM14EN; // enable clocking for timers 3 and 14
|
TIM3->CCMR1 = TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 |
|
||||||
RCC->APB2ENR |= RCC_APB2ENR_TIM16EN | RCC_APB2ENR_TIM17EN; // & timers 16/17
|
TIM_CCMR1_OC2M_2 | TIM_CCMR1_OC2M_1;
|
||||||
// PWM mode 1 (active -> inactive)
|
TIM3->CCMR2 = TIM_CCMR2_OC4M_2 | TIM_CCMR2_OC4M_1;
|
||||||
TIM14->CCMR1 = TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1;
|
|
||||||
TIM16->CCMR1 = TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1;
|
|
||||||
TIM17->CCMR1 = TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1;
|
|
||||||
// frequency
|
// frequency
|
||||||
TIM14->PSC = 59; // 0.8MHz for 3kHz PWM
|
TIM3->PSC = 47; // 1MHz -> 1us per tick
|
||||||
TIM16->PSC = 18749; // 2.56kHz for 10Hz PWM
|
|
||||||
TIM17->PSC = 5; // 8MHz for 31kHz PWM
|
|
||||||
// ARR for 8-bit PWM
|
// ARR for 8-bit PWM
|
||||||
TIM14->ARR = 254;
|
TIM3->ARR = 19999; // 50Hz
|
||||||
TIM16->ARR = 254;
|
|
||||||
TIM17->ARR = 254;
|
|
||||||
// start in OFF state
|
|
||||||
// TIM14->CCR1 = 0; and so on
|
|
||||||
// enable main output
|
// enable main output
|
||||||
TIM14->BDTR |= TIM_BDTR_MOE;
|
TIM3->BDTR |= TIM_BDTR_MOE;
|
||||||
TIM16->BDTR |= TIM_BDTR_MOE;
|
|
||||||
TIM17->BDTR |= TIM_BDTR_MOE;
|
|
||||||
// enable PWM output
|
// enable PWM output
|
||||||
TIM14->CCER = TIM_CCER_CC1E;
|
TIM3->CCER = TIM_CCER_CC1E | TIM_CCER_CC2E | TIM_CCER_CC4E;
|
||||||
TIM16->CCER = TIM_CCER_CC1E;
|
TIM3->DIER = TIM_DIER_UIE; //TIM_DIER_CC1IE | TIM_DIER_CC2IE | TIM_DIER_CC4IE;
|
||||||
TIM17->CCER = TIM_CCER_CC1E;
|
// enable timer & ARR buffering
|
||||||
// enable timers
|
TIM3->CR1 |= TIM_CR1_CEN | TIM_CR1_ARPE;
|
||||||
TIM14->CR1 |= TIM_CR1_CEN;
|
NVIC_EnableIRQ(TIM3_IRQn);
|
||||||
TIM16->CR1 |= TIM_CR1_CEN;
|
|
||||||
TIM17->CR1 |= TIM_CR1_CEN;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void hw_setup(){
|
void hw_setup(){
|
||||||
@ -192,10 +180,79 @@ void hw_setup(){
|
|||||||
iwdg_setup();
|
iwdg_setup();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static uint32_t target_Val[3] = {SG90_MIDPULSE, SG90_MIDPULSE, SG90_MIDPULSE};
|
||||||
|
static uint32_t target_Speed[3] = {SG90DEFSTEP, SG90DEFSTEP, SG90DEFSTEP};
|
||||||
|
static uint8_t onpos[3] = {0,0,0};
|
||||||
|
volatile uint32_t *addr[3] = {&TIM3->CCR1, &TIM3->CCR2, &TIM3->CCR4};
|
||||||
|
|
||||||
|
int32_t getPWM(int nch){
|
||||||
|
return *addr[nch];
|
||||||
|
}
|
||||||
|
|
||||||
|
// return current value
|
||||||
|
int32_t setPWM(int nch, uint32_t val, uint32_t speed){
|
||||||
|
if(nch < 0 || nch > 2) return 0;
|
||||||
|
if(speed > 0){
|
||||||
|
if(speed > SG90_STEP) speed = SG90_STEP;
|
||||||
|
target_Speed[nch] = speed;
|
||||||
|
}
|
||||||
|
uint8_t ch = 1;
|
||||||
|
if(val >= SG90_MINPULSE && val <= SG90_MAXPULSE) target_Val[nch] = val;
|
||||||
|
else if(val == 0) target_Val[nch] = SG90_MINPULSE;
|
||||||
|
else if(val == 1) target_Val[nch] = SG90_MAXPULSE;
|
||||||
|
else if(val == 2) target_Val[nch] = SG90_MIDPULSE;
|
||||||
|
else ch = 0;
|
||||||
|
if(ch){
|
||||||
|
onpos[nch] = 0;
|
||||||
|
}
|
||||||
|
return *addr[nch];
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t onposition(int nch){
|
||||||
|
return onpos[nch];
|
||||||
|
}
|
||||||
|
|
||||||
|
static void chkPWM(int n){
|
||||||
|
if(n < 0 || n > 2) return;
|
||||||
|
uint32_t cur = *addr[n], tg = target_Val[n];
|
||||||
|
if(cur == tg){
|
||||||
|
onpos[n] = 1;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
uint32_t diff = tg - cur;
|
||||||
|
int sign = 1;
|
||||||
|
if(cur > tg){
|
||||||
|
diff = cur - tg;
|
||||||
|
sign = -1;
|
||||||
|
}
|
||||||
|
if(diff > target_Speed[n]) diff = target_Speed[n];
|
||||||
|
*addr[n] = cur + sign*diff;
|
||||||
|
}
|
||||||
|
|
||||||
|
void tim3_isr(){
|
||||||
|
/*
|
||||||
|
if(TIM3->SR & TIM_SR_CC1IF){ // 1st channel
|
||||||
|
chkPWM(0);
|
||||||
|
}
|
||||||
|
if(TIM3->SR & TIM_SR_CC2IF){ // 2nd channel
|
||||||
|
chkPWM(1);
|
||||||
|
}
|
||||||
|
if(TIM3->SR & TIM_SR_CC4IF){ // 3rd channel
|
||||||
|
chkPWM(2);
|
||||||
|
}*/
|
||||||
|
if(TIM3->SR & TIM_SR_UIF){
|
||||||
|
chkPWM(0);
|
||||||
|
chkPWM(1);
|
||||||
|
chkPWM(2);
|
||||||
|
}
|
||||||
|
TIM3->SR = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
void exti0_1_isr(){
|
void exti0_1_isr(){
|
||||||
if (EXTI->PR & EXTI_PR_PR1){
|
if (EXTI->PR & EXTI_PR_PR1){
|
||||||
EXTI->PR |= EXTI_PR_PR1; /* Clear the pending bit */
|
EXTI->PR |= EXTI_PR_PR1; // Clear the pending bit
|
||||||
;
|
;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
*/
|
||||||
|
|||||||
@ -20,59 +20,21 @@
|
|||||||
#define HARDWARE_H
|
#define HARDWARE_H
|
||||||
#include "stm32f0.h"
|
#include "stm32f0.h"
|
||||||
|
|
||||||
// measure flow sensor data each 1 second
|
// minimal and maximal pulse length for SG90
|
||||||
#define FLOW_RATE_MS (999)
|
#define SG90_MINPULSE (700)
|
||||||
// previous as string constant
|
#define SG90_MAXPULSE (2100)
|
||||||
#define FLOWRATESTR "1"
|
#define SG90_MIDPULSE ((SG90_MINPULSE+SG90_MAXPULSE)/2)
|
||||||
|
#define SG90_AMPL (SG90_MAXPULSE-SG90_MINPULSE)
|
||||||
// each TMEASURE_MS ms calculate temperatures & check them
|
#define SG90DEFSTEP (100)
|
||||||
#define TMEASURE_MS (1000)
|
#define SG90_STEP (sg90step)
|
||||||
// each TCHECK_MS ms check cooler state and regulate temperature
|
|
||||||
#define TCHECK_MS (10000)
|
|
||||||
|
|
||||||
/*
|
|
||||||
temperature limits and tolerances
|
|
||||||
*/
|
|
||||||
// tolerance: +-1.5degrC
|
|
||||||
#define TEMP_TOLERANCE (15)
|
|
||||||
// dT tolerance: +-0.5degrC
|
|
||||||
#define DT_TOLERANCE (5)
|
|
||||||
// maximal heater temperature - 80degrC; normal - <60
|
|
||||||
#define MAX_HEATER_T (800)
|
|
||||||
#define NORMAL_HEATER_T (600)
|
|
||||||
// maximal output temperature - 45degrC; minimal - 10
|
|
||||||
#define MAX_OUTPUT_T (450)
|
|
||||||
#define MIN_OUTPUT_T (100)
|
|
||||||
// temperature working values: from 15 to 30degrC
|
|
||||||
#define OUTPUT_T_H (300)
|
|
||||||
#define OUTPUT_T_L (150)
|
|
||||||
|
|
||||||
/*
|
|
||||||
other limits & tolerances
|
|
||||||
*/
|
|
||||||
// minimal flow rate - 0.2l per minute
|
|
||||||
#define MIN_FLOW_RATE (20)
|
|
||||||
// normal flow rate
|
|
||||||
#define NORMAL_FLOW_RATE (30)
|
|
||||||
// minimal PWM values when motors should work
|
|
||||||
#define MIN_PUMP_PWM (90)
|
|
||||||
#define MIN_COOLER_PWM (90)
|
|
||||||
|
|
||||||
// PWM setters and getters
|
|
||||||
#define SET_COOLER_PWM(N) do{TIM14->CCR1 = (uint32_t)N;}while(0)
|
|
||||||
#define GET_COOLER_PWM() (uint16_t)(TIM14->CCR1)
|
|
||||||
#define SET_HEATER_PWM(N) do{TIM16->CCR1 = (uint32_t)N;}while(0)
|
|
||||||
#define GET_HEATER_PWM() (uint16_t)(TIM16->CCR1)
|
|
||||||
#define SET_PUMP_PWM(N) do{TIM17->CCR1 = (uint32_t)N;}while(0)
|
|
||||||
#define GET_PUMP_PWM() (uint16_t)(TIM17->CCR1)
|
|
||||||
|
|
||||||
// ext. alarm states
|
|
||||||
#define ALARM_ON() pin_set(GPIOF, 2)
|
|
||||||
#define ALARM_OFF() pin_clear(GPIOF, 2)
|
|
||||||
#define ALARM_STATE() pin_read(GPIOF, 2)
|
|
||||||
|
|
||||||
extern volatile uint32_t Tms;
|
extern volatile uint32_t Tms;
|
||||||
|
extern uint32_t sg90step;
|
||||||
|
|
||||||
void hw_setup(void);
|
void hw_setup(void);
|
||||||
|
int32_t setPWM(int nch, uint32_t val, uint32_t speed);
|
||||||
|
int32_t getPWM(int nch);
|
||||||
|
uint8_t onposition(int nch);
|
||||||
|
void setTIM3T(uint32_t T);
|
||||||
|
|
||||||
#endif // HARDWARE_H
|
#endif // HARDWARE_H
|
||||||
|
|||||||
@ -19,8 +19,8 @@
|
|||||||
* MA 02110-1301, USA.
|
* MA 02110-1301, USA.
|
||||||
*/
|
*/
|
||||||
#include "adc.h"
|
#include "adc.h"
|
||||||
|
#include "effects.h"
|
||||||
#include "hardware.h"
|
#include "hardware.h"
|
||||||
#include "mainloop.h"
|
|
||||||
#include "protocol.h"
|
#include "protocol.h"
|
||||||
#include "usart.h"
|
#include "usart.h"
|
||||||
#include <string.h> // memcpy
|
#include <string.h> // memcpy
|
||||||
@ -38,12 +38,12 @@ int main(void){
|
|||||||
char *txt;
|
char *txt;
|
||||||
hw_setup();
|
hw_setup();
|
||||||
SysTick_Config(6000, 1);
|
SysTick_Config(6000, 1);
|
||||||
SEND_BLK("Servos controller v0.1\n");
|
SEND("Servos controller v0.1\n");
|
||||||
if(RCC->CSR & RCC_CSR_IWDGRSTF){ // watchdog reset occured
|
if(RCC->CSR & RCC_CSR_IWDGRSTF){ // watchdog reset occured
|
||||||
SEND_BLK("WDGRESET=1");
|
SEND("WDGRESET=1\n");
|
||||||
}
|
}
|
||||||
if(RCC->CSR & RCC_CSR_SFTRSTF){ // software reset occured
|
if(RCC->CSR & RCC_CSR_SFTRSTF){ // software reset occured
|
||||||
SEND_BLK("SOFTRESET=1");
|
SEND("SOFTRESET=1\n");
|
||||||
}
|
}
|
||||||
RCC->CSR |= RCC_CSR_RMVF; // remove reset flags
|
RCC->CSR |= RCC_CSR_RMVF; // remove reset flags
|
||||||
while (1){
|
while (1){
|
||||||
@ -56,7 +56,7 @@ int main(void){
|
|||||||
IWDG->KR = IWDG_REFRESH;
|
IWDG->KR = IWDG_REFRESH;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
mainloop();
|
proc_effect();
|
||||||
IWDG->KR = IWDG_REFRESH;
|
IWDG->KR = IWDG_REFRESH;
|
||||||
usart1_sendbuf();
|
usart1_sendbuf();
|
||||||
}
|
}
|
||||||
|
|||||||
@ -15,81 +15,170 @@
|
|||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
#include "adc.h"
|
||||||
|
#include "effects.h"
|
||||||
#include "hardware.h"
|
#include "hardware.h"
|
||||||
#include "protocol.h"
|
#include "protocol.h"
|
||||||
#include "usart.h"
|
#include "usart.h"
|
||||||
#include "adc.h"
|
|
||||||
#include "mainloop.h"
|
|
||||||
|
|
||||||
extern uint8_t crit_error;
|
extern uint8_t crit_error;
|
||||||
|
|
||||||
#ifdef EBUG
|
#ifdef EBUG
|
||||||
|
static void putADC(int n){
|
||||||
|
put_string("ADC");
|
||||||
|
put_char('0' + n);
|
||||||
|
put_string(" value: ");
|
||||||
|
put_uint(getADCval(n));
|
||||||
|
put_char('\n');
|
||||||
|
// while(LINE_BUSY == usart1_sendbuf());
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief debugging_proc - debugging functions
|
* @brief debugging_proc - debugging functions
|
||||||
* @param command - rest of cmd
|
* @param command - rest of cmd
|
||||||
*/
|
*/
|
||||||
static void debugging_proc(const char *command){
|
static void debugging_proc(const char *command){
|
||||||
const char *ptr = command;
|
char ch;
|
||||||
int i;
|
int i;
|
||||||
switch(*ptr++){
|
switch(*command++){
|
||||||
case 'w':
|
case 'w':
|
||||||
usart1_send("Test watchdog", 0);
|
SEND("Test watchdog\n");
|
||||||
while(1){nop();}
|
while(1){nop();}
|
||||||
break;
|
break;
|
||||||
case 'A': // raw ADC values depending on next symbol
|
case 'A': // raw ADC values depending on next symbol
|
||||||
i = *ptr++ - '0';
|
ch = *command;
|
||||||
if(i < 0 || i > NUMBER_OF_ADC_CHANNELS){
|
if(ch == 'A' || ch == 'B'){
|
||||||
usart1_send("Wrong channel nuber!", 0);
|
for(i = 0; i < NUMBER_OF_ADC_CHANNELS; ++i){
|
||||||
return;
|
putADC(i);
|
||||||
}
|
}
|
||||||
put_string("ADC value: ");
|
}else{
|
||||||
put_uint(getADCval(i));
|
i = ch - '0';
|
||||||
put_string(", ");
|
if(i < 0 || i >= NUMBER_OF_ADC_CHANNELS){
|
||||||
usart1_sendbuf();
|
SEND("Wrong channel nuber!\n");
|
||||||
|
}else putADC(i);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 'B':
|
||||||
|
SEND("B command\n");
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
|
SEND("wrong command\n");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
while(LINE_BUSY == usart1_sendbuf()){nop();};
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
static void chPWM(const char *command){
|
||||||
|
int n = *command++ - '1';
|
||||||
|
if(n < 0 || n > 2){
|
||||||
|
put_string("Wrong PWM channel number");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
int32_t CCR = getPWM(n);
|
||||||
|
if((command = getnum(command, &CCR))){
|
||||||
|
set_effect(n, EFF_NONE);
|
||||||
|
int32_t speed = SG90_STEP;
|
||||||
|
if(*command++ == ','){
|
||||||
|
getnum(command, &speed);
|
||||||
|
}
|
||||||
|
CCR = setPWM(n, CCR, speed);
|
||||||
|
}
|
||||||
|
put_string("pulse");
|
||||||
|
put_char('1' + n);
|
||||||
|
put_char('=');
|
||||||
|
put_int(CCR);
|
||||||
|
put_char('\n');
|
||||||
|
}
|
||||||
|
|
||||||
|
static void set_servoT(const char *buf){
|
||||||
|
int32_t T;
|
||||||
|
if(!getnum(buf, &T) || T < 1000 || T > 65535){
|
||||||
|
put_string("Bad period value\n");
|
||||||
|
usart1_sendbuf();
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
put_string("Set period to ");
|
||||||
|
put_int(T);
|
||||||
|
put_string(" us\n");
|
||||||
|
setTIM3T(T);
|
||||||
|
usart1_sendbuf();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void chk_effect(const char *cmd, effect_t eff, const char *name){
|
||||||
|
if(set_effect(*(++cmd)-'1', eff) == eff){
|
||||||
|
put_string("Turn on ");
|
||||||
|
put_string(name);
|
||||||
|
put_string(" effect\n");
|
||||||
|
}else put_string("err\n");
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief process_command - command parser
|
* @brief process_command - command parser
|
||||||
* @param command - command text (all inside [] without spaces)
|
* @param command - command text (all inside [] without spaces)
|
||||||
* @return text to send over terminal or NULL
|
* @return text to send over terminal or NULL
|
||||||
*/
|
*/
|
||||||
char *process_command(const char *command){
|
char *process_command(const char *command){
|
||||||
const char *ptr = command;
|
|
||||||
char *ret = NULL;
|
char *ret = NULL;
|
||||||
usart1_sendbuf(); // send buffer (if it is already filled)
|
usart1_sendbuf(); // send buffer (if it is already filled)
|
||||||
switch(*ptr++){
|
switch(*command){
|
||||||
case '?': // help
|
case '?': // help
|
||||||
SEND_BLK(
|
SEND_BLK(
|
||||||
|
"1-3[pos[,speed]]- set/get xth pulse length (us) (0,1,2 - min, max, mid)\n"
|
||||||
|
"fx - servo period (us)"
|
||||||
|
"Mn - set Mad Wipe effect\n"
|
||||||
|
"Pn - set Pendulum effect\n"
|
||||||
"R - reset\n"
|
"R - reset\n"
|
||||||
|
"Sn - set Small Pendulum effect\n"
|
||||||
"t - get MCU temperature (approx.)\n"
|
"t - get MCU temperature (approx.)\n"
|
||||||
"V - get Vdd"
|
"V - get Vdd\n"
|
||||||
|
"Wn - set Wipe effect\n"
|
||||||
);
|
);
|
||||||
#ifdef EBUG
|
#ifdef EBUG
|
||||||
SEND_BLK("d -> goto debug:\n"
|
SEND_BLK("d -> goto debug:\n"
|
||||||
"\tAx - get raw ADCx value\n"
|
"\tAx - get raw ADCx value (A for all)\n"
|
||||||
"\tw - test watchdog"
|
"\tw - test watchdog\n"
|
||||||
);
|
);
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
case '1':
|
||||||
|
case '2':
|
||||||
|
case '3':
|
||||||
|
chPWM(command);
|
||||||
|
break;
|
||||||
|
case 'f':
|
||||||
|
set_servoT(++command);
|
||||||
|
break;
|
||||||
|
case 'M':
|
||||||
|
chk_effect(command, EFF_MADWIPE, "mad wipe");
|
||||||
|
break;
|
||||||
|
case 'P':
|
||||||
|
chk_effect(command, EFF_PENDULUM, "pendulum");
|
||||||
|
break;
|
||||||
case 'R': // reset MCU
|
case 'R': // reset MCU
|
||||||
NVIC_SystemReset();
|
NVIC_SystemReset();
|
||||||
break;
|
break;
|
||||||
|
case 'S':
|
||||||
|
chk_effect(command, EFF_SMPENDULUM, "small pendulum");
|
||||||
|
break;
|
||||||
case 't': // get mcu T
|
case 't': // get mcu T
|
||||||
put_string("MCUTEMP10=");
|
put_string("MCUTEMP10=");
|
||||||
put_int(getMCUtemp());
|
put_int(getMCUtemp());
|
||||||
|
put_char('\n');
|
||||||
break;
|
break;
|
||||||
case 'V': // get Vdd
|
case 'V': // get Vdd
|
||||||
put_string("VDD100=");
|
put_string("VDD100=");
|
||||||
put_uint(getVdd());
|
put_uint(getVdd());
|
||||||
|
put_char('\n');
|
||||||
|
break;
|
||||||
|
case 'W':
|
||||||
|
chk_effect(command, EFF_WIPE, "wipe");
|
||||||
break;
|
break;
|
||||||
#ifdef EBUG
|
#ifdef EBUG
|
||||||
case 'd':
|
case 'd':
|
||||||
debugging_proc(ptr);
|
debugging_proc(++command);
|
||||||
return NULL;
|
return NULL;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|||||||
Binary file not shown.
@ -42,7 +42,8 @@ static int trbufidx = 0;
|
|||||||
|
|
||||||
int put_char(char c){
|
int put_char(char c){
|
||||||
if(trbufidx >= UARTBUFSZ - 1){
|
if(trbufidx >= UARTBUFSZ - 1){
|
||||||
if(ALL_OK != usart1_sendbuf()) return 1;
|
for(int i = 0; i < 72000000 && ALL_OK != usart1_sendbuf(); ++i)
|
||||||
|
if(i == 72000000) return 1;
|
||||||
}
|
}
|
||||||
trbuf[trbufidx++] = c;
|
trbuf[trbufidx++] = c;
|
||||||
return 0;
|
return 0;
|
||||||
@ -84,10 +85,11 @@ int put_uint(uint32_t N){
|
|||||||
*/
|
*/
|
||||||
TXstatus usart1_sendbuf(){
|
TXstatus usart1_sendbuf(){
|
||||||
int len = trbufidx;
|
int len = trbufidx;
|
||||||
trbufidx = 0;
|
|
||||||
if(len == 0) return ALL_OK;
|
if(len == 0) return ALL_OK;
|
||||||
else if(len > UARTBUFSZ) len = UARTBUFSZ;
|
else if(len > UARTBUFSZ) len = UARTBUFSZ;
|
||||||
return usart1_send(trbuf, len);
|
TXstatus s = usart1_send(trbuf, len);
|
||||||
|
if(s == ALL_OK) trbufidx = 0;
|
||||||
|
return s;
|
||||||
}
|
}
|
||||||
|
|
||||||
void USART1_config(){
|
void USART1_config(){
|
||||||
@ -125,8 +127,14 @@ void USART1_config(){
|
|||||||
NVIC_EnableIRQ(USART1_IRQn); /* (4) */
|
NVIC_EnableIRQ(USART1_IRQn); /* (4) */
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef EBUG
|
||||||
|
#define TMO 0
|
||||||
|
#else
|
||||||
|
#define TMO 1
|
||||||
|
#endif
|
||||||
|
|
||||||
void usart1_isr(){
|
void usart1_isr(){
|
||||||
static uint8_t timeout = 1 // == 0 for human interface without timeout
|
static uint8_t timeout = TMO // == 0 for human interface without timeout
|
||||||
,nctr = 0 // counter of '#' received
|
,nctr = 0 // counter of '#' received
|
||||||
,incmd = 0 // ==1 - inside command
|
,incmd = 0 // ==1 - inside command
|
||||||
;
|
;
|
||||||
@ -235,7 +243,7 @@ TXstatus usart1_send(const char *str, int len){
|
|||||||
if(len == 0) return ALL_OK;
|
if(len == 0) return ALL_OK;
|
||||||
DMA1_Channel2->CCR &= ~DMA_CCR_EN;
|
DMA1_Channel2->CCR &= ~DMA_CCR_EN;
|
||||||
memcpy(tbuf, str, len);
|
memcpy(tbuf, str, len);
|
||||||
tbuf[len++] = '\n';
|
// tbuf[len++] = '\n';
|
||||||
DMA1_Channel2->CNDTR = len;
|
DMA1_Channel2->CNDTR = len;
|
||||||
DMA1_Channel2->CCR |= DMA_CCR_EN; // start transmission
|
DMA1_Channel2->CCR |= DMA_CCR_EN; // start transmission
|
||||||
return ALL_OK;
|
return ALL_OK;
|
||||||
@ -252,7 +260,7 @@ TXstatus usart1_send_blocking(const char *str, int len){
|
|||||||
USART1->TDR = *str++;
|
USART1->TDR = *str++;
|
||||||
while(!(USART1->ISR & USART_ISR_TXE));
|
while(!(USART1->ISR & USART_ISR_TXE));
|
||||||
}
|
}
|
||||||
USART1->TDR = '\n';
|
// USART1->TDR = '\n';
|
||||||
while(!(USART1->ISR & USART_ISR_TC));
|
while(!(USART1->ISR & USART_ISR_TC));
|
||||||
txrdy = 1;
|
txrdy = 1;
|
||||||
return ALL_OK;
|
return ALL_OK;
|
||||||
|
|||||||
@ -38,8 +38,8 @@ typedef enum{
|
|||||||
#define usart1ovr() (bufovr)
|
#define usart1ovr() (bufovr)
|
||||||
|
|
||||||
// send constant string
|
// send constant string
|
||||||
#define SEND_BLK(x) do{while(LINE_BUSY == usart1_send_blocking(x, sizeof(x)-1));}while(0)
|
#define SEND_BLK(x) do{while(LINE_BUSY == usart1_send_blocking(x, sizeof(x)-1)) IWDG->KR = IWDG_REFRESH;}while(0)
|
||||||
#define SEND(x) do{while(LINE_BUSY == usart1_send(x, sizeof(x)-1));}while(0)
|
#define SEND(x) do{while(LINE_BUSY == usart1_send(x, sizeof(x)-1)) IWDG->KR = IWDG_REFRESH;}while(0)
|
||||||
|
|
||||||
extern uint8_t bufovr;
|
extern uint8_t bufovr;
|
||||||
|
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user