Compare commits

...

77 Commits

Author SHA1 Message Date
Astro 2773ba47fe tec: init freq pins for 1 MHz switching 2019-11-14 01:59:57 +01:00
Astro 13771bf770 tec: fix wrong SHDN pins 2019-11-13 20:13:57 +01:00
Astro 02d2403547 tec: setup iset_width 2019-11-13 20:12:25 +01:00
Astro ecdebe76bc tec: keep shdn off until first use 2019-11-13 20:01:17 +01:00
Astro 6041e41716 Carto.toml: update dependencies 2019-11-13 19:50:14 +01:00
Astro 9b1a0696ab Cargo.toml: update smoltcp git 2019-11-13 19:23:49 +01:00
Astro d360ec6dce shell.nix: cd in shellHook 2019-11-10 23:01:22 +01:00
Astro 7efc95941b default.nix: update rust nightly 2019-11-10 23:01:10 +01:00
Astro 7efd42715e tec: enable GPIO pins for TEC SHDN 2019-11-10 22:27:20 +01:00
Astro aafb733209 default.nix: update cargoSha256 2019-10-30 21:06:42 +01:00
Astro bb35f91a57 build.rs: delint 2019-10-30 19:55:15 +01:00
Astro 225be7b911 upgrade to current rust + smoltcp 2019-10-30 19:53:35 +01:00
Astro c2aa0e2989 main: report pwm_width 2019-10-03 01:35:52 +02:00
Astro cc5c21e088 main: use temperature as PID input 2019-10-03 01:35:37 +02:00
Astro 420be00407 main: fix DEFAULT_PID_PARAMETERS 2019-10-03 01:34:53 +02:00
Astro 2010b4fe10 main: reset PID after parameter change 2019-10-03 01:33:49 +02:00
Astro c8d31c7b0d tec: add pwm default setup 2019-10-03 01:33:21 +02:00
Astro 4ac0f7b171 pid: add test 2019-10-03 00:44:36 +02:00
Astro 21615819f6 main: improve tcp output 2019-10-02 22:33:23 +02:00
Astro 59d3fde32e main: fix DEFAULT_SH_PARAMETERS 2019-10-02 22:21:50 +02:00
Astro 86b5841119 default.nix: run tests 2019-10-02 21:30:44 +02:00
Astro e1af02f77a Cargo.toml: bump libm dependency 2019-10-02 21:28:37 +02:00
Astro 53ff7e70ca main: use steinhart-hart equation for temperature conversion 2019-10-02 21:28:14 +02:00
Astro 83117db8c5 ad7172: perform data sign checks 2019-10-02 21:27:35 +02:00
Astro 12c2be0a03 command_parser: shorten to parallel_r, add tests 2019-10-02 21:25:06 +02:00
Astro 8611cc1c79 add configurable Steinhart-Hart equation 2019-10-02 19:55:33 +02:00
Astro 2992688184 Cargo.toml: update smoltcp to 0.5.0 2019-09-30 21:57:13 +02:00
Astro 7f32591441 default.nix: pin rust-nightly, build firmware 2019-09-30 21:54:44 +02:00
Astro 9486946d06 main: improve command resonses 2019-09-24 01:57:52 +02:00
Astro ef17e1c4ff README: describe all the commands 2019-09-24 01:55:19 +02:00
Astro b508129c37 tec: make more brief 2019-09-24 01:45:51 +02:00
Astro fca427cb5a show pwm config of each tec channel 2019-09-24 01:45:11 +02:00
Astro 18e3e95615 group 4 PWM channels into Tec, add commands to configure them 2019-09-24 01:33:23 +02:00
Astro a82ffadb35 add PWM abstraction for TEC control 2019-09-23 16:50:43 +02:00
Astro 8d01ca8d20 rm unused test dependency 2019-09-19 15:38:00 +02:00
Astro f3664f01be command_parser: fix float parsing 2019-09-19 15:28:11 +02:00
Astro 6f36c682cd command_parser: add tests
Run with: cargo test --target=x86_64-unknown-linux-gnu
2019-09-19 14:56:34 +02:00
Astro 35dfba99e1 style 2019-09-19 03:29:06 +02:00
Astro 63aa2347b7 add remote postfilter configuration 2019-09-19 03:28:47 +02:00
Astro 87de8b7859 style 2019-09-19 02:18:37 +02:00
Astro e126bc0fe1 command_parser: parameterize `pid`, `pwm` with channel `<0/1>` 2019-09-19 02:17:54 +02:00
Astro 1514131fa3 ad7172: fix doc
Closes Gitea issue #1
2019-09-19 01:00:49 +02:00
Astro 6d4676a72a command_parser: fix pid 2019-09-19 00:59:16 +02:00
Astro f64e4fe2f3 main: don't log expected failure, log MAC to semihosting 2019-09-19 00:49:41 +02:00
Astro 2d2e7e80e0 ad7172: rm unused FiltCon odc setting 2019-09-19 00:49:26 +02:00
Astro 2ca06e023b command_parser: use combinators, allow trailing whitespace 2019-09-19 00:46:50 +02:00
Astro 4e5de7831b command_parser: fix non-optional whitespace after `report` 2019-09-18 23:25:40 +02:00
Astro db1788bafb ad7172: fix bits in regs::setup_con 2019-09-18 22:45:29 +02:00
Astro ba485cab16 README: link rustup 2019-09-18 01:53:19 +02:00
Astro ee8f8e87c3 README: build instructions 2019-09-18 00:29:29 +02:00
Astro f048026d21 update dependency lexical-core 2019-09-17 19:22:23 +02:00
Astro 42a9b89db1 let pid control pwm 2019-09-17 19:09:47 +02:00
Astro 393c276bda document commands 2019-09-17 01:46:29 +02:00
Astro 4c00548646 main: revert resampling, report per-channel 2019-09-17 01:42:50 +02:00
Astro a7ee2107ea command_parser: rm outdated TODO note 2019-09-17 01:38:12 +02:00
Astro 4587406d44 ad7172: setup adc 2019-09-17 00:13:46 +02:00
Astro 7e51585aa9 command_parser: swap btoi for lexical-core to parse floats too 2019-09-16 23:41:22 +02:00
Astro d4428b7fdc ad7172: rename reg bit bi_unipolar to bipolar 2019-09-16 23:28:28 +02:00
Astro ee4d24de6a delint 2019-09-14 21:40:49 +02:00
Astro b969f5c057 command_parser: complete to all PidParameter tokens 2019-09-14 21:35:06 +02:00
Astro 700ab47f0e improve output formatting 2019-09-14 21:23:45 +02:00
Astro b6af43feda control the pid 2019-09-14 21:11:26 +02:00
Astro 426be0d5f1 main: remove allocator 2019-09-14 19:09:38 +02:00
Astro 5c58c4370d command_parser: switch from logos to nom 2019-09-14 19:03:52 +02:00
Astro 328f6921fa README: init 2019-09-14 16:59:21 +02:00
Astro 8163d083b9 main: print panic info with semihosting 2019-09-14 16:52:35 +02:00
Astro 1395e8b410 add support for manipulating pwm duty cycle 2019-09-14 03:09:07 +02:00
Astro 5e0f55647a command_parser: rm unused tokens 2019-09-14 02:35:12 +02:00
Astro 5ef8d6a747 main: rework reporting 2019-09-14 02:33:56 +02:00
Astro ff3a793c19 ad7172: restrict macro input to remove cast 2019-09-14 02:19:18 +02:00
Astro 07dcc608bc ad7172: setup_channel() fixes 2019-09-14 02:18:47 +02:00
Astro 957f92d177 main: fight jitter 2019-09-14 02:18:33 +02:00
Astro f8dd7d1912 main: setup thermostat v1 channels, report avgs at 10hz 2019-09-14 01:36:47 +02:00
Astro c50e1c7766 remove too detailed adc control 2019-09-14 00:48:26 +02:00
Astro 76e30c0f7c some too detailed adc config 2019-09-14 00:46:48 +02:00
Astro f2dcb8b08d command_parser: unnest the grammar definition 2019-09-13 01:14:14 +02:00
Astro 3fd1b2265d command_parser: channel setup 2019-09-13 01:04:59 +02:00
20 changed files with 16856 additions and 493 deletions

15156
channel-rust-nightly.toml Normal file

File diff suppressed because it is too large Load Diff

View File

@ -1,5 +1,6 @@
{ # Use master branch of the overlay by default
mozillaOverlay ? import (builtins.fetchTarball https://github.com/mozilla/nixpkgs-mozilla/archive/master.tar.gz),
rustManifest ? ./channel-rust-nightly.toml,
}:
let
@ -7,21 +8,55 @@ let
in
with pkgs;
let
rustcSrc = fetchgit {
rustcSrc = pkgs.fetchgit {
url = https://github.com/rust-lang/rust.git;
# master of 2019-08-31
rev = "b3146549abf25818fecfc7555f35358a948e27ad";
sha256 = "1db3g1iq6ba5pdasffay1bpywdibv83z5nwp2dzi0fxvz5bqx1gi";
# master of 2019-11-09
rev = "ac162c6abe34cdf965afc0389f6cefa79653c63b";
sha256 = "06c5gws1mrpr69z1gzs358zf7hcsg6ky8n4ha0vv2s9d9w93x1kj";
fetchSubmodules = true;
};
targets = [
];
target = "thumbv7em-none-eabihf";
targets = [ target ];
rustChannelOfTargets = _channel: _date: targets:
(pkgs.lib.rustLib.fromManifestFile rustManifest {
inherit (pkgs) stdenv fetchurl patchelf;
}).rust.override { inherit targets; };
rust =
rustChannelOfTargets "nightly" null targets;
rustPlatform = recurseIntoAttrs (makeRustPlatform {
rustc = rust // { src = rustcSrc; };
cargo = rust;
});
gcc = pkgsCross.armv7l-hf-multiplatform.buildPackages.gcc;
xbuildRustPackage = attrs:
let
buildPkg = rustPlatform.buildRustPackage attrs;
in
buildPkg.overrideAttrs ({ name, nativeBuildInputs, ... }: {
nativeBuildInputs =
nativeBuildInputs ++ [ cargo-xbuild ];
buildPhase = ''
cargo xbuild --release --frozen
'';
XARGO_RUST_SRC = "${rustcSrc}/src";
installPhase = ''
mkdir $out
cp target/${target}/release/${name} $out/${name}.elf
'';
});
firmware = xbuildRustPackage {
name = "firmware";
src = ./firmware;
cargoSha256 = "0lf8h5g8sas36cxzqy0p65qqivnihh4gn4mkc1k210xp7niaymc5";
nativeBuildInputs = [
gcc
];
"CC_${target}" = "${gcc}/bin/armv7l-unknown-linux-gnueabihf-gcc";
RUST_COMPILER_RT_ROOT = "${rustcSrc}/src/llvm-project/compiler-rt";
checkPhase = ''
cargo test --target=${hostPlatform.config}
'';
};
in {
inherit pkgs rustPlatform rustcSrc;
inherit pkgs rustPlatform rustcSrc gcc firmware;
}

278
firmware/Cargo.lock generated
View File

@ -1,10 +1,5 @@
# This file is automatically @generated by Cargo.
# It is not intended for manual editing.
[[package]]
name = "aligned"
version = "0.2.0"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "aligned"
version = "0.3.1"
@ -13,15 +8,6 @@ dependencies = [
"as-slice 0.1.0 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
name = "alloc-cortex-m"
version = "0.3.5"
source = "registry+https://github.com/rust-lang/crates.io-index"
dependencies = [
"cortex-m 0.1.8 (registry+https://github.com/rust-lang/crates.io-index)",
"linked_list_allocator 0.6.4 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
name = "as-slice"
version = "0.1.0"
@ -46,7 +32,7 @@ source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "bitflags"
version = "1.1.0"
version = "1.2.1"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
@ -60,22 +46,21 @@ version = "1.3.2"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "cortex-m"
version = "0.1.8"
name = "cc"
version = "1.0.47"
source = "registry+https://github.com/rust-lang/crates.io-index"
dependencies = [
"volatile-register 0.1.2 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
name = "cortex-m"
version = "0.5.10"
name = "cfg-if"
version = "0.1.10"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "compiler_builtins"
version = "0.1.21"
source = "registry+https://github.com/rust-lang/crates.io-index"
dependencies = [
"aligned 0.2.0 (registry+https://github.com/rust-lang/crates.io-index)",
"bare-metal 0.2.5 (registry+https://github.com/rust-lang/crates.io-index)",
"cortex-m 0.6.1 (registry+https://github.com/rust-lang/crates.io-index)",
"volatile-register 0.2.0 (registry+https://github.com/rust-lang/crates.io-index)",
"cc 1.0.47 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
@ -93,19 +78,19 @@ name = "cortex-m-rt"
version = "0.6.10"
source = "registry+https://github.com/rust-lang/crates.io-index"
dependencies = [
"cortex-m-rt-macros 0.1.5 (registry+https://github.com/rust-lang/crates.io-index)",
"cortex-m-rt-macros 0.1.6 (registry+https://github.com/rust-lang/crates.io-index)",
"r0 0.2.2 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
name = "cortex-m-rt-macros"
version = "0.1.5"
version = "0.1.6"
source = "registry+https://github.com/rust-lang/crates.io-index"
dependencies = [
"proc-macro2 0.4.30 (registry+https://github.com/rust-lang/crates.io-index)",
"quote 0.6.13 (registry+https://github.com/rust-lang/crates.io-index)",
"proc-macro2 1.0.6 (registry+https://github.com/rust-lang/crates.io-index)",
"quote 1.0.2 (registry+https://github.com/rust-lang/crates.io-index)",
"rand 0.5.6 (registry+https://github.com/rust-lang/crates.io-index)",
"syn 0.15.44 (registry+https://github.com/rust-lang/crates.io-index)",
"syn 1.0.8 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
@ -133,6 +118,28 @@ dependencies = [
"void 1.0.2 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
name = "firmware"
version = "1.0.0"
dependencies = [
"bare-metal 0.2.5 (registry+https://github.com/rust-lang/crates.io-index)",
"bit_field 0.10.0 (registry+https://github.com/rust-lang/crates.io-index)",
"byteorder 1.3.2 (registry+https://github.com/rust-lang/crates.io-index)",
"compiler_builtins 0.1.21 (registry+https://github.com/rust-lang/crates.io-index)",
"cortex-m 0.6.1 (registry+https://github.com/rust-lang/crates.io-index)",
"cortex-m-rt 0.6.10 (registry+https://github.com/rust-lang/crates.io-index)",
"cortex-m-semihosting 0.3.5 (registry+https://github.com/rust-lang/crates.io-index)",
"crc 1.8.1 (registry+https://github.com/rust-lang/crates.io-index)",
"embedded-hal 0.2.3 (registry+https://github.com/rust-lang/crates.io-index)",
"lexical-core 0.6.2 (registry+https://github.com/rust-lang/crates.io-index)",
"libm 0.1.4 (registry+https://github.com/rust-lang/crates.io-index)",
"nb 0.1.2 (registry+https://github.com/rust-lang/crates.io-index)",
"nom 5.0.1 (registry+https://github.com/rust-lang/crates.io-index)",
"smoltcp 0.5.0 (git+https://github.com/m-labs/smoltcp.git?rev=8eb01aca364aefe5f823d68d552d62c76c9be4a3)",
"tm4c129x 0.9.0 (registry+https://github.com/rust-lang/crates.io-index)",
"walkdir 2.2.9 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
name = "generic-array"
version = "0.12.3"
@ -142,33 +149,13 @@ dependencies = [
]
[[package]]
name = "ionpak-firmware"
version = "1.0.0"
dependencies = [
"alloc-cortex-m 0.3.5 (registry+https://github.com/rust-lang/crates.io-index)",
"bare-metal 0.2.5 (registry+https://github.com/rust-lang/crates.io-index)",
"bit_field 0.10.0 (registry+https://github.com/rust-lang/crates.io-index)",
"byteorder 1.3.2 (registry+https://github.com/rust-lang/crates.io-index)",
"cortex-m 0.5.10 (registry+https://github.com/rust-lang/crates.io-index)",
"cortex-m-rt 0.6.10 (registry+https://github.com/rust-lang/crates.io-index)",
"cortex-m-semihosting 0.3.5 (registry+https://github.com/rust-lang/crates.io-index)",
"crc 1.8.1 (registry+https://github.com/rust-lang/crates.io-index)",
"embedded-hal 0.2.3 (registry+https://github.com/rust-lang/crates.io-index)",
"libm 0.1.4 (registry+https://github.com/rust-lang/crates.io-index)",
"logos 0.9.7 (registry+https://github.com/rust-lang/crates.io-index)",
"nb 0.1.2 (registry+https://github.com/rust-lang/crates.io-index)",
"smoltcp 0.4.0 (git+https://github.com/m-labs/smoltcp?rev=cd893e6)",
"tm4c129x 0.8.0 (registry+https://github.com/rust-lang/crates.io-index)",
"walkdir 1.0.7 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
name = "kernel32-sys"
version = "0.2.2"
name = "lexical-core"
version = "0.6.2"
source = "registry+https://github.com/rust-lang/crates.io-index"
dependencies = [
"winapi 0.2.8 (registry+https://github.com/rust-lang/crates.io-index)",
"winapi-build 0.1.1 (registry+https://github.com/rust-lang/crates.io-index)",
"cfg-if 0.1.10 (registry+https://github.com/rust-lang/crates.io-index)",
"rustc_version 0.2.3 (registry+https://github.com/rust-lang/crates.io-index)",
"static_assertions 0.3.4 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
@ -176,34 +163,14 @@ name = "libm"
version = "0.1.4"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "linked_list_allocator"
version = "0.6.4"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "logos"
version = "0.9.7"
source = "registry+https://github.com/rust-lang/crates.io-index"
dependencies = [
"logos-derive 0.9.7 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
name = "logos-derive"
version = "0.9.7"
source = "registry+https://github.com/rust-lang/crates.io-index"
dependencies = [
"proc-macro2 0.4.30 (registry+https://github.com/rust-lang/crates.io-index)",
"quote 0.6.13 (registry+https://github.com/rust-lang/crates.io-index)",
"regex-syntax 0.6.12 (registry+https://github.com/rust-lang/crates.io-index)",
"syn 0.15.44 (registry+https://github.com/rust-lang/crates.io-index)",
"utf8-ranges 1.0.4 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
name = "managed"
version = "0.5.1"
version = "0.7.1"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "memchr"
version = "2.2.1"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
@ -212,19 +179,28 @@ version = "0.1.2"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "proc-macro2"
version = "0.4.30"
name = "nom"
version = "5.0.1"
source = "registry+https://github.com/rust-lang/crates.io-index"
dependencies = [
"unicode-xid 0.1.0 (registry+https://github.com/rust-lang/crates.io-index)",
"memchr 2.2.1 (registry+https://github.com/rust-lang/crates.io-index)",
"version_check 0.1.5 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
name = "proc-macro2"
version = "1.0.6"
source = "registry+https://github.com/rust-lang/crates.io-index"
dependencies = [
"unicode-xid 0.2.0 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
name = "quote"
version = "0.6.13"
version = "1.0.2"
source = "registry+https://github.com/rust-lang/crates.io-index"
dependencies = [
"proc-macro2 0.4.30 (registry+https://github.com/rust-lang/crates.io-index)",
"proc-macro2 1.0.6 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
@ -253,11 +229,6 @@ name = "rand_core"
version = "0.4.2"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "regex-syntax"
version = "0.6.12"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "rustc_version"
version = "0.2.3"
@ -268,11 +239,10 @@ dependencies = [
[[package]]
name = "same-file"
version = "0.1.3"
version = "1.0.5"
source = "registry+https://github.com/rust-lang/crates.io-index"
dependencies = [
"kernel32-sys 0.2.2 (registry+https://github.com/rust-lang/crates.io-index)",
"winapi 0.2.8 (registry+https://github.com/rust-lang/crates.io-index)",
"winapi-util 0.1.2 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
@ -290,12 +260,12 @@ source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "smoltcp"
version = "0.4.0"
source = "git+https://github.com/m-labs/smoltcp?rev=cd893e6#cd893e6ab60f094d684b37be7bc013bf79f0459d"
version = "0.5.0"
source = "git+https://github.com/m-labs/smoltcp.git?rev=8eb01aca364aefe5f823d68d552d62c76c9be4a3#8eb01aca364aefe5f823d68d552d62c76c9be4a3"
dependencies = [
"bitflags 1.1.0 (registry+https://github.com/rust-lang/crates.io-index)",
"bitflags 1.2.1 (registry+https://github.com/rust-lang/crates.io-index)",
"byteorder 1.3.2 (registry+https://github.com/rust-lang/crates.io-index)",
"managed 0.5.1 (registry+https://github.com/rust-lang/crates.io-index)",
"managed 0.7.1 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
@ -303,23 +273,28 @@ name = "stable_deref_trait"
version = "1.1.1"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "static_assertions"
version = "0.3.4"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "syn"
version = "0.15.44"
version = "1.0.8"
source = "registry+https://github.com/rust-lang/crates.io-index"
dependencies = [
"proc-macro2 0.4.30 (registry+https://github.com/rust-lang/crates.io-index)",
"quote 0.6.13 (registry+https://github.com/rust-lang/crates.io-index)",
"unicode-xid 0.1.0 (registry+https://github.com/rust-lang/crates.io-index)",
"proc-macro2 1.0.6 (registry+https://github.com/rust-lang/crates.io-index)",
"quote 1.0.2 (registry+https://github.com/rust-lang/crates.io-index)",
"unicode-xid 0.2.0 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
name = "tm4c129x"
version = "0.8.0"
version = "0.9.0"
source = "registry+https://github.com/rust-lang/crates.io-index"
dependencies = [
"bare-metal 0.2.5 (registry+https://github.com/rust-lang/crates.io-index)",
"cortex-m 0.5.10 (registry+https://github.com/rust-lang/crates.io-index)",
"cortex-m 0.6.1 (registry+https://github.com/rust-lang/crates.io-index)",
"cortex-m-rt 0.6.10 (registry+https://github.com/rust-lang/crates.io-index)",
"vcell 0.1.2 (registry+https://github.com/rust-lang/crates.io-index)",
]
@ -331,12 +306,7 @@ source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "unicode-xid"
version = "0.1.0"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "utf8-ranges"
version = "1.0.4"
version = "0.2.0"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
@ -345,13 +315,13 @@ version = "0.1.2"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "void"
version = "1.0.2"
name = "version_check"
version = "0.1.5"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "volatile-register"
version = "0.1.2"
name = "void"
version = "1.0.2"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
@ -364,72 +334,88 @@ dependencies = [
[[package]]
name = "walkdir"
version = "1.0.7"
version = "2.2.9"
source = "registry+https://github.com/rust-lang/crates.io-index"
dependencies = [
"kernel32-sys 0.2.2 (registry+https://github.com/rust-lang/crates.io-index)",
"same-file 0.1.3 (registry+https://github.com/rust-lang/crates.io-index)",
"winapi 0.2.8 (registry+https://github.com/rust-lang/crates.io-index)",
"same-file 1.0.5 (registry+https://github.com/rust-lang/crates.io-index)",
"winapi 0.3.8 (registry+https://github.com/rust-lang/crates.io-index)",
"winapi-util 0.1.2 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
name = "winapi"
version = "0.2.8"
version = "0.3.8"
source = "registry+https://github.com/rust-lang/crates.io-index"
dependencies = [
"winapi-i686-pc-windows-gnu 0.4.0 (registry+https://github.com/rust-lang/crates.io-index)",
"winapi-x86_64-pc-windows-gnu 0.4.0 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
name = "winapi-i686-pc-windows-gnu"
version = "0.4.0"
source = "registry+https://github.com/rust-lang/crates.io-index"
[[package]]
name = "winapi-build"
version = "0.1.1"
name = "winapi-util"
version = "0.1.2"
source = "registry+https://github.com/rust-lang/crates.io-index"
dependencies = [
"winapi 0.3.8 (registry+https://github.com/rust-lang/crates.io-index)",
]
[[package]]
name = "winapi-x86_64-pc-windows-gnu"
version = "0.4.0"
source = "registry+https://github.com/rust-lang/crates.io-index"
[metadata]
"checksum aligned 0.2.0 (registry+https://github.com/rust-lang/crates.io-index)" = "d39da9b88ae1a81c03c9c082b8db83f1d0e93914126041962af61034ab44c4a5"
"checksum aligned 0.3.1 (registry+https://github.com/rust-lang/crates.io-index)" = "d3a316c7ea8e1e9ece54862c992def5a7ac14de9f5832b69d71760680efeeefa"
"checksum alloc-cortex-m 0.3.5 (registry+https://github.com/rust-lang/crates.io-index)" = "6d5f7d01bc93ce089de636f946f7f1fdc5e5d751732367e019c9755440e7aef4"
"checksum as-slice 0.1.0 (registry+https://github.com/rust-lang/crates.io-index)" = "293dac66b274fab06f95e7efb05ec439a6b70136081ea522d270bc351ae5bb27"
"checksum bare-metal 0.2.5 (registry+https://github.com/rust-lang/crates.io-index)" = "5deb64efa5bd81e31fcd1938615a6d98c82eafcbcd787162b6f63b91d6bac5b3"
"checksum bit_field 0.10.0 (registry+https://github.com/rust-lang/crates.io-index)" = "a165d606cf084741d4ac3a28fb6e9b1eb0bd31f6cd999098cfddb0b2ab381dc0"
"checksum bitflags 1.1.0 (registry+https://github.com/rust-lang/crates.io-index)" = "3d155346769a6855b86399e9bc3814ab343cd3d62c7e985113d46a0ec3c281fd"
"checksum bitflags 1.2.1 (registry+https://github.com/rust-lang/crates.io-index)" = "cf1de2fe8c75bc145a2f577add951f8134889b4795d47466a54a5c846d691693"
"checksum build_const 0.2.1 (registry+https://github.com/rust-lang/crates.io-index)" = "39092a32794787acd8525ee150305ff051b0aa6cc2abaf193924f5ab05425f39"
"checksum byteorder 1.3.2 (registry+https://github.com/rust-lang/crates.io-index)" = "a7c3dd8985a7111efc5c80b44e23ecdd8c007de8ade3b96595387e812b957cf5"
"checksum cortex-m 0.1.8 (registry+https://github.com/rust-lang/crates.io-index)" = "3df5de9a9829f2ccb7defa8945fa020c6614cd2f6ba9b5f33db9241dcc01985e"
"checksum cortex-m 0.5.10 (registry+https://github.com/rust-lang/crates.io-index)" = "3c0b159a1e8306949579de3698c841dba58058197b65c60807194e4fa1e7a554"
"checksum cc 1.0.47 (registry+https://github.com/rust-lang/crates.io-index)" = "aa87058dce70a3ff5621797f1506cb837edd02ac4c0ae642b4542dce802908b8"
"checksum cfg-if 0.1.10 (registry+https://github.com/rust-lang/crates.io-index)" = "4785bdd1c96b2a846b2bd7cc02e86b6b3dbf14e7e53446c4f54c92a361040822"
"checksum compiler_builtins 0.1.21 (registry+https://github.com/rust-lang/crates.io-index)" = "d3c520d376a5b582ce93a7f881ba3fae1b72d9404aa9539af09d11e68b27e123"
"checksum cortex-m 0.6.1 (registry+https://github.com/rust-lang/crates.io-index)" = "145da2fc379bbd378ed425e75e1748214add9bbd800d4d5b77abb54ca423dbca"
"checksum cortex-m-rt 0.6.10 (registry+https://github.com/rust-lang/crates.io-index)" = "17805910e3ecf029bdbfcc42b7384d9e3d9e5626153fa810002c1ef9839338ac"
"checksum cortex-m-rt-macros 0.1.5 (registry+https://github.com/rust-lang/crates.io-index)" = "d7ae692573e0acccb1579fef1abf5a5bf1d2f3f0149a22b16870ec9309aee25f"
"checksum cortex-m-rt-macros 0.1.6 (registry+https://github.com/rust-lang/crates.io-index)" = "2a6dc359ebb215c4924bffacfe46a8f02ef80fe2071bba1635a2ded42b40f936"
"checksum cortex-m-semihosting 0.3.5 (registry+https://github.com/rust-lang/crates.io-index)" = "113ef0ecffee2b62b58f9380f4469099b30e9f9cbee2804771b4203ba1762cfa"
"checksum crc 1.8.1 (registry+https://github.com/rust-lang/crates.io-index)" = "d663548de7f5cca343f1e0a48d14dcfb0e9eb4e079ec58883b7251539fa10aeb"
"checksum embedded-hal 0.2.3 (registry+https://github.com/rust-lang/crates.io-index)" = "ee4908a155094da7723c2d60d617b820061e3b4efcc3d9e293d206a5a76c170b"
"checksum generic-array 0.12.3 (registry+https://github.com/rust-lang/crates.io-index)" = "c68f0274ae0e023facc3c97b2e00f076be70e254bc851d972503b328db79b2ec"
"checksum kernel32-sys 0.2.2 (registry+https://github.com/rust-lang/crates.io-index)" = "7507624b29483431c0ba2d82aece8ca6cdba9382bff4ddd0f7490560c056098d"
"checksum lexical-core 0.6.2 (registry+https://github.com/rust-lang/crates.io-index)" = "d7043aa5c05dd34fb73b47acb8c3708eac428de4545ea3682ed2f11293ebd890"
"checksum libm 0.1.4 (registry+https://github.com/rust-lang/crates.io-index)" = "7fc7aa29613bd6a620df431842069224d8bc9011086b1db4c0e0cd47fa03ec9a"
"checksum linked_list_allocator 0.6.4 (registry+https://github.com/rust-lang/crates.io-index)" = "47314ec1d29aa869ee7cb5a5be57be9b1055c56567d59c3fb6689926743e0bea"
"checksum logos 0.9.7 (registry+https://github.com/rust-lang/crates.io-index)" = "f494e22d293fa05db60b3fd95fb30e9409feb5672b56ce6f250f99d9fbae6b93"
"checksum logos-derive 0.9.7 (registry+https://github.com/rust-lang/crates.io-index)" = "13ff1b1068db09ee21d12baf55eccc0900a781a735273e0a606f6f4fbb32a322"
"checksum managed 0.5.1 (registry+https://github.com/rust-lang/crates.io-index)" = "43e2737ecabe4ae36a68061398bf27d2bfd0763f4c3c837a398478459494c4b7"
"checksum managed 0.7.1 (registry+https://github.com/rust-lang/crates.io-index)" = "fdcec5e97041c7f0f1c5b7d93f12e57293c831c646f4cc7a5db59460c7ea8de6"
"checksum memchr 2.2.1 (registry+https://github.com/rust-lang/crates.io-index)" = "88579771288728879b57485cc7d6b07d648c9f0141eb955f8ab7f9d45394468e"
"checksum nb 0.1.2 (registry+https://github.com/rust-lang/crates.io-index)" = "b1411551beb3c11dedfb0a90a0fa256b47d28b9ec2cdff34c25a2fa59e45dbdc"
"checksum proc-macro2 0.4.30 (registry+https://github.com/rust-lang/crates.io-index)" = "cf3d2011ab5c909338f7887f4fc896d35932e29146c12c8d01da6b22a80ba759"
"checksum quote 0.6.13 (registry+https://github.com/rust-lang/crates.io-index)" = "6ce23b6b870e8f94f81fb0a363d65d86675884b34a09043c81e5562f11c1f8e1"
"checksum nom 5.0.1 (registry+https://github.com/rust-lang/crates.io-index)" = "c618b63422da4401283884e6668d39f819a106ef51f5f59b81add00075da35ca"
"checksum proc-macro2 1.0.6 (registry+https://github.com/rust-lang/crates.io-index)" = "9c9e470a8dc4aeae2dee2f335e8f533e2d4b347e1434e5671afc49b054592f27"
"checksum quote 1.0.2 (registry+https://github.com/rust-lang/crates.io-index)" = "053a8c8bcc71fcce321828dc897a98ab9760bef03a4fc36693c231e5b3216cfe"
"checksum r0 0.2.2 (registry+https://github.com/rust-lang/crates.io-index)" = "e2a38df5b15c8d5c7e8654189744d8e396bddc18ad48041a500ce52d6948941f"
"checksum rand 0.5.6 (registry+https://github.com/rust-lang/crates.io-index)" = "c618c47cd3ebd209790115ab837de41425723956ad3ce2e6a7f09890947cacb9"
"checksum rand_core 0.3.1 (registry+https://github.com/rust-lang/crates.io-index)" = "7a6fdeb83b075e8266dcc8762c22776f6877a63111121f5f8c7411e5be7eed4b"
"checksum rand_core 0.4.2 (registry+https://github.com/rust-lang/crates.io-index)" = "9c33a3c44ca05fa6f1807d8e6743f3824e8509beca625669633be0acbdf509dc"
"checksum regex-syntax 0.6.12 (registry+https://github.com/rust-lang/crates.io-index)" = "11a7e20d1cce64ef2fed88b66d347f88bd9babb82845b2b858f3edbf59a4f716"
"checksum rustc_version 0.2.3 (registry+https://github.com/rust-lang/crates.io-index)" = "138e3e0acb6c9fb258b19b67cb8abd63c00679d2851805ea151465464fe9030a"
"checksum same-file 0.1.3 (registry+https://github.com/rust-lang/crates.io-index)" = "d931a44fdaa43b8637009e7632a02adc4f2b2e0733c08caa4cf00e8da4a117a7"
"checksum same-file 1.0.5 (registry+https://github.com/rust-lang/crates.io-index)" = "585e8ddcedc187886a30fa705c47985c3fa88d06624095856b36ca0b82ff4421"
"checksum semver 0.9.0 (registry+https://github.com/rust-lang/crates.io-index)" = "1d7eb9ef2c18661902cc47e535f9bc51b78acd254da71d375c2f6720d9a40403"
"checksum semver-parser 0.7.0 (registry+https://github.com/rust-lang/crates.io-index)" = "388a1df253eca08550bef6c72392cfe7c30914bf41df5269b68cbd6ff8f570a3"
"checksum smoltcp 0.4.0 (git+https://github.com/m-labs/smoltcp?rev=cd893e6)" = "<none>"
"checksum smoltcp 0.5.0 (git+https://github.com/m-labs/smoltcp.git?rev=8eb01aca364aefe5f823d68d552d62c76c9be4a3)" = "<none>"
"checksum stable_deref_trait 1.1.1 (registry+https://github.com/rust-lang/crates.io-index)" = "dba1a27d3efae4351c8051072d619e3ade2820635c3958d826bfea39d59b54c8"
"checksum syn 0.15.44 (registry+https://github.com/rust-lang/crates.io-index)" = "9ca4b3b69a77cbe1ffc9e198781b7acb0c7365a883670e8f1c1bc66fba79a5c5"
"checksum tm4c129x 0.8.0 (registry+https://github.com/rust-lang/crates.io-index)" = "7d430ed4ed06dd9fff3d4517a37343e1b53789218f2f608bf1e0432f67abf624"
"checksum static_assertions 0.3.4 (registry+https://github.com/rust-lang/crates.io-index)" = "7f3eb36b47e512f8f1c9e3d10c2c1965bc992bd9cdb024fa581e2194501c83d3"
"checksum syn 1.0.8 (registry+https://github.com/rust-lang/crates.io-index)" = "661641ea2aa15845cddeb97dad000d22070bb5c1fb456b96c1cba883ec691e92"
"checksum tm4c129x 0.9.0 (registry+https://github.com/rust-lang/crates.io-index)" = "41ef3b3b339fa51167fcbe5fca426906bf9e7ac83333c3c69e94311a8586231d"
"checksum typenum 1.11.2 (registry+https://github.com/rust-lang/crates.io-index)" = "6d2783fe2d6b8c1101136184eb41be8b1ad379e4657050b8aaff0c79ee7575f9"
"checksum unicode-xid 0.1.0 (registry+https://github.com/rust-lang/crates.io-index)" = "fc72304796d0818e357ead4e000d19c9c174ab23dc11093ac919054d20a6a7fc"
"checksum utf8-ranges 1.0.4 (registry+https://github.com/rust-lang/crates.io-index)" = "b4ae116fef2b7fea257ed6440d3cfcff7f190865f170cdad00bb6465bf18ecba"
"checksum unicode-xid 0.2.0 (registry+https://github.com/rust-lang/crates.io-index)" = "826e7639553986605ec5979c7dd957c7895e93eabed50ab2ffa7f6128a75097c"
"checksum vcell 0.1.2 (registry+https://github.com/rust-lang/crates.io-index)" = "876e32dcadfe563a4289e994f7cb391197f362b6315dc45e8ba4aa6f564a4b3c"
"checksum version_check 0.1.5 (registry+https://github.com/rust-lang/crates.io-index)" = "914b1a6776c4c929a602fafd8bc742e06365d4bcbe48c30f9cca5824f70dc9dd"
"checksum void 1.0.2 (registry+https://github.com/rust-lang/crates.io-index)" = "6a02e4885ed3bc0f2de90ea6dd45ebcbb66dacffe03547fadbb0eeae2770887d"
"checksum volatile-register 0.1.2 (registry+https://github.com/rust-lang/crates.io-index)" = "a470889aa8f2d3ad893bd43cd90c824e63e8ac0ee5fe64c5d81a932d184fd549"
"checksum volatile-register 0.2.0 (registry+https://github.com/rust-lang/crates.io-index)" = "0d67cb4616d99b940db1d6bd28844ff97108b498a6ca850e5b6191a532063286"
"checksum walkdir 1.0.7 (registry+https://github.com/rust-lang/crates.io-index)" = "bb08f9e670fab86099470b97cd2b252d6527f0b3cc1401acdb595ffc9dd288ff"
"checksum winapi 0.2.8 (registry+https://github.com/rust-lang/crates.io-index)" = "167dc9d6949a9b857f3451275e911c3f44255842c1f7a76f33c55103a909087a"
"checksum winapi-build 0.1.1 (registry+https://github.com/rust-lang/crates.io-index)" = "2d315eee3b34aca4797b2da6b13ed88266e6d612562a0c46390af8299fc699bc"
"checksum walkdir 2.2.9 (registry+https://github.com/rust-lang/crates.io-index)" = "9658c94fa8b940eab2250bd5a457f9c48b748420d71293b165c8cdbe2f55f71e"
"checksum winapi 0.3.8 (registry+https://github.com/rust-lang/crates.io-index)" = "8093091eeb260906a183e6ae1abdba2ef5ef2257a21801128899c3fc699229c6"
"checksum winapi-i686-pc-windows-gnu 0.4.0 (registry+https://github.com/rust-lang/crates.io-index)" = "ac3b87c63620426dd9b991e5ce0329eff545bccbbb34f3be09ff6fb6ab51b7b6"
"checksum winapi-util 0.1.2 (registry+https://github.com/rust-lang/crates.io-index)" = "7168bab6e1daee33b4557efd0e95d5ca70a03706d39fa5f3fe7a236f584b03c9"
"checksum winapi-x86_64-pc-windows-gnu 0.4.0 (registry+https://github.com/rust-lang/crates.io-index)" = "712e227841d057c1ee1cd2fb22fa7e5a5461ae8e48fa2ca79ec42cfc1931183f"

View File

@ -1,33 +1,38 @@
[package]
name = "ionpak-firmware"
name = "firmware"
version = "1.0.0"
authors = ["whitequark <whitequark@whitequark.org>"]
edition = "2018"
[build-dependencies]
walkdir = "1.0"
walkdir = "~2"
[dependencies]
libm = "0.1.2"
cortex-m = { version = "0.5", features = ["const-fn"] }
libm = "0.1.4"
cortex-m = { version = "0.6", features = ["const-fn"] }
cortex-m-rt = "0.6"
crc = { version = "1.7", default-features = false }
tm4c129x = { version = "0.8", features = ["rt"] }
crc = { version = "~1", default-features = false }
tm4c129x = { version = "0.9", features = ["rt"] }
embedded-hal = { version = "0.2", features = ["unproven"] }
nb = "0.1"
cortex-m-semihosting = "0.3"
byteorder = { version = "1.3", default-features = false }
bit_field = "0.10"
bare-metal = "0.2"
logos = { version = "~0.9", default-features = false, features = ["export_derive"] }
alloc-cortex-m = "0.3"
lexical-core = { version = "~0.6", default-features = false }
nom = { version = "~5", default-features = false }
[dependencies.smoltcp]
git = "https://github.com/m-labs/smoltcp"
rev = "cd893e6"
features = ["proto-ipv4", "socket-tcp"]
git = "https://github.com/m-labs/smoltcp.git"
rev = "8eb01aca364aefe5f823d68d552d62c76c9be4a3"
features = ["ethernet", "proto-ipv4", "socket-tcp"]
default-features = false
[dependencies.compiler_builtins]
version = "0.1"
default-features = false
features = ["mem", "no-lang-items", "c"]
[profile.release]
lto = true
debug = true

75
firmware/README.md Normal file
View File

@ -0,0 +1,75 @@
# Thermostat v1 prototype firmware
## Building
### On Debian-based systems
- install [rustup](https://rustup.rs/)
```shell
apt install gcc gcc-arm-none-eabi git-core
rustup toolchain install nightly
rustup update
rustup target add thumbv7em-none-eabihf --toolchain nightly
rustup default nightly
rustup component add rust-src
cargo install cargo-xbuild
git clone https://github.com/llvm/llvm-project.git
export RUST_COMPILER_RT_ROOT=`pwd`/llvm-project/compiler-rt
cd firmware && cargo xbuild --release
```
The built ELF file will be at `target/thumbv7em-none-eabihf/release/ionpak-firmware`
### Development build on NixOS
Requires NixOS 19.09 or later for cargo-xbuild.
```shell
nix-shell --run "cd firmware && cargo xbuild --release"
```
## Network
### Setup
Ethernet, IP: 192.168.1.26/24
Use telnet or netcat to connect to port 23/tcp (telnet)
### Reading ADC input
Set report mode to `once` to obtain the single next value. Report mode
will turn itself off after the next reading.
Set report mode to `continuous` for a continuous stream of input data.
The scope of this setting is per TCP session.
### Commands
| Syntax | Function |
| --- | --- |
| `report` | Show current input |
| `report mode` | Show current report mode |
| `report mode <off/on>` | Set report mode |
| `pwm <0/1> max_i_pos <width> <total>` | Set PWM duty cycle for **max_i_pos** to *width / total* |
| `pwm <0/1> max_i_neg <width> <total>` | Set PWM duty cycle for **max_i_neg** to *width / total* |
| `pwm <0/1> max_v <width> <total>` | Set PWM duty cycle for **max_v** to *width / total* |
| `pwm <0/1> <width> <total>` | Set PWM duty cycle for **i_set** to manual *width / total* |
| `pwm <0/1> pid` | Set PWM to be controlled by PID |
| `pid` | Show PID configuration |
| `pid <0/1> target <value>` | Set the PID controller target |
| `pid <0/1> kp <value>` | Set proportional gain |
| `pid <0/1> ki <value>` | Set integral gain |
| `pid <0/1> kd <value>` | Set differential gain |
| `pid <0/1> output_min <value>` | Set mininum output |
| `pid <0/1> output_max <value>` | Set maximum output |
| `pid <0/1> integral_min <value>` | Set integral lower bound |
| `pid <0/1> integral_max <value>` | Set integral upper bound |
| `s-h` | Show Steinhart-Hart equation parameters |
| `s-h <0/1> <a/b/c> <value>` | Set Steinhart-Hart parameter for a channel |
| `s-h <0/1> parallel_r <value>` | Set parallel resistance of the ADC |
| `postfilter <0/1> rate <rate>` | Set postfilter output data rate |

View File

@ -3,49 +3,7 @@ extern crate walkdir;
use std::env;
use std::io::Write;
use std::fs::File;
use std::path::{Path, PathBuf};
use std::process::Command;
use walkdir::WalkDir;
fn git_describe() {
let git_dir = Path::new("../.git");
println!("cargo:rerun-if-changed={}", git_dir.join("HEAD").display());
for entry in WalkDir::new(git_dir.join("refs")) {
let entry = entry.unwrap();
println!("cargo:rerun-if-changed={}", entry.path().display());
}
let version;
if git_dir.exists() {
let git_describe =
Command::new("git")
.arg("describe")
.arg("--tags")
.arg("--dirty")
.arg("--always")
.arg("--long")
.arg("--abbrev=8")
.output()
.ok()
.and_then(|o| String::from_utf8(o.stdout).ok())
.map(|mut s| {
let len = s.trim_end().len();
s.truncate(len);
s
})
.unwrap();
let parts = git_describe.split("-").collect::<Vec<_>>();
version = format!("{}+{}.{}", parts[0], parts[1], parts[2]);
} else {
version = "unknown".to_owned();
}
let out_dir = PathBuf::from(env::var("OUT_DIR").unwrap());
let mut f = File::create(out_dir.join("git-describe")).unwrap();
write!(f, "{}", version).unwrap();
}
use std::path::PathBuf;
fn linker_script() {
// Put the linker script somewhere the linker can find it
@ -61,5 +19,4 @@ fn linker_script() {
fn main() {
linker_script();
git_describe();
}

View File

@ -2,7 +2,10 @@ use embedded_hal::digital::v2::OutputPin;
use embedded_hal::blocking::spi::Transfer;
use super::checksum::{ChecksumMode, Checksum};
use super::AdcError;
use super::regs::*;
use super::{
regs, regs::RegisterData,
Input, RefSource, PostFilter, DigitalFilterOrder,
};
/// AD7172-2 implementation
///
@ -25,34 +28,82 @@ impl<SPI: Transfer<u8>, NSS: OutputPin> Adc<SPI, NSS> {
Ok(adc)
}
/// `0x00DX` for AD7271-2
/// `0x00DX` for AD7172-2
pub fn identify(&mut self) -> Result<u16, AdcError<SPI::Error>> {
self.read_reg(&Id)
self.read_reg(&regs::Id)
.map(|id| id.id())
}
pub fn set_checksum_mode(&mut self, mode: ChecksumMode) -> Result<(), AdcError<SPI::Error>> {
let mut ifmode = self.read_reg(&IfMode)?;
// Cannot use update_reg() here because checksum_mode is
// updated between read_reg() and write_reg().
let mut ifmode = self.read_reg(&regs::IfMode)?;
ifmode.set_crc(mode);
self.checksum_mode = mode;
self.write_reg(&IfMode, &mut ifmode)?;
self.write_reg(&regs::IfMode, &mut ifmode)?;
Ok(())
}
// pub fn setup(&mut self) -> Result<(), SPI::Error> {
// let mut buf = [0, 0, 0];
// adc.write_reg(Register::AdcMode, &mut buf)?;
// let mut buf = [0, 1, 0];
// adc.write_reg(Register::IfMode, &mut buf)?;
// let mut buf = [0, 0, 0];
// adc.write_reg(Register::GpioCon, &mut buf)?;
pub fn set_sync_enable(&mut self, enable: bool) -> Result<(), AdcError<SPI::Error>> {
self.update_reg(&regs::GpioCon, |data| {
data.set_sync_en(enable);
})
}
// Ok(())
// }
pub fn setup_channel(
&mut self, index: u8, in_pos: Input, in_neg: Input
) -> Result<(), AdcError<SPI::Error>> {
self.update_reg(&regs::SetupCon { index }, |data| {
data.set_bipolar(false);
data.set_refbuf_pos(true);
data.set_refbuf_neg(true);
data.set_ainbuf_pos(true);
data.set_ainbuf_neg(true);
data.set_ref_sel(RefSource::External);
})?;
self.update_reg(&regs::FiltCon { index }, |data| {
data.set_enh_filt_en(true);
data.set_enh_filt(PostFilter::F16SPS);
data.set_order(DigitalFilterOrder::Sinc5Sinc1);
})?;
// let mut offset = <regs::Offset as regs::Register>::Data::empty();
// offset.set_offset(0);
// self.write_reg(&regs::Offset { index }, &mut offset);
self.update_reg(&regs::Channel { index }, |data| {
data.set_setup(index);
data.set_enabled(true);
data.set_a_in_pos(in_pos);
data.set_a_in_neg(in_neg);
})?;
Ok(())
}
pub fn get_postfilter(&mut self, index: u8) -> Result<Option<PostFilter>, AdcError<SPI::Error>> {
self.read_reg(&regs::FiltCon { index })
.map(|data| {
if data.enh_filt_en() {
Some(data.enh_filt())
} else {
None
}
})
}
pub fn set_postfilter(&mut self, index: u8, filter: Option<PostFilter>) -> Result<(), AdcError<SPI::Error>> {
self.update_reg(&regs::FiltCon { index }, |data| {
match filter {
None => data.set_enh_filt_en(false),
Some(filter) => {
data.set_enh_filt_en(true);
data.set_enh_filt(filter);
}
}
})
}
/// Returns the channel the data is from
pub fn data_ready(&mut self) -> Result<Option<u8>, AdcError<SPI::Error>> {
self.read_reg(&Status)
self.read_reg(&regs::Status)
.map(|status| {
if status.ready() {
Some(status.channel())
@ -63,12 +114,12 @@ impl<SPI: Transfer<u8>, NSS: OutputPin> Adc<SPI, NSS> {
}
/// Get data
pub fn read_data(&mut self) -> Result<u32, AdcError<SPI::Error>> {
self.read_reg(&Data)
pub fn read_data(&mut self) -> Result<i32, AdcError<SPI::Error>> {
self.read_reg(&regs::Data)
.map(|data| data.data())
}
fn read_reg<R: Register>(&mut self, reg: &R) -> Result<R::Data, AdcError<SPI::Error>> {
fn read_reg<R: regs::Register>(&mut self, reg: &R) -> Result<R::Data, AdcError<SPI::Error>> {
let mut reg_data = R::Data::empty();
let address = 0x40 | reg.address();
let mut checksum = Checksum::new(self.checksum_mode);
@ -85,7 +136,7 @@ impl<SPI: Transfer<u8>, NSS: OutputPin> Adc<SPI, NSS> {
Ok(reg_data)
}
fn write_reg<R: Register>(&mut self, reg: &R, reg_data: &mut R::Data) -> Result<(), AdcError<SPI::Error>> {
fn write_reg<R: regs::Register>(&mut self, reg: &R, reg_data: &mut R::Data) -> Result<(), AdcError<SPI::Error>> {
let address = reg.address();
let mut checksum = Checksum::new(match self.checksum_mode {
ChecksumMode::Off => ChecksumMode::Off,
@ -104,7 +155,7 @@ impl<SPI: Transfer<u8>, NSS: OutputPin> Adc<SPI, NSS> {
fn update_reg<R, F, A>(&mut self, reg: &R, f: F) -> Result<A, AdcError<SPI::Error>>
where
R: Register,
R: regs::Register,
F: FnOnce(&mut R::Data) -> A,
{
let mut reg_data = self.read_reg(reg)?;

View File

@ -1,4 +1,6 @@
mod regs;
use core::fmt;
pub mod regs;
mod checksum;
pub use checksum::ChecksumMode;
mod adc;
@ -16,6 +18,7 @@ impl<SPI> From<SPI> for AdcError<SPI> {
}
}
#[derive(Clone, Copy, Debug)]
#[repr(u8)]
pub enum Input {
Ain0 = 0,
@ -51,6 +54,27 @@ impl From<u8> for Input {
}
}
impl fmt::Display for Input {
fn fmt(&self, fmt: &mut fmt::Formatter) -> Result<(), fmt::Error> {
use Input::*;
match self {
Ain0 => "ain0",
Ain1 => "ain1",
Ain2 => "ain2",
Ain3 => "ain3",
Ain4 => "ain4",
TemperaturePos => "temperature+",
TemperatureNeg => "temperature-",
AnalogSupplyPos => "analogsupply+",
AnalogSupplyNeg => "analogsupply-",
RefPos => "ref+",
RefNeg => "ref-",
_ => "<INVALID>",
}.fmt(fmt)
}
}
/// Reference source for ADC conversion
#[repr(u8)]
pub enum RefSource {
@ -74,15 +98,76 @@ impl From<u8> for RefSource {
}
}
impl fmt::Display for RefSource {
fn fmt(&self, fmt: &mut fmt::Formatter) -> Result<(), fmt::Error> {
use RefSource::*;
match self {
External => "external",
Internal => "internal",
Avdd1MinusAvss => "avdd1-avss",
_ => "<INVALID>",
}.fmt(fmt)
}
}
#[derive(Clone, Copy)]
#[repr(u8)]
pub enum PostFilter {
/// 27 SPS, 47 dB rejection, 36.7 ms settling
F27SPS = 0b010,
/// 21.25 SPS, 62 dB rejection, 40 ms settling
F21SPS = 0b011,
/// 20 SPS, 86 dB rejection, 50 ms settling
F20SPS = 0b101,
/// 16.67 SPS, 92 dB rejection, 60 ms settling
F16SPS = 0b110,
Invalid = 0b111,
}
impl PostFilter {
pub const VALID_VALUES: &'static [Self] = &[
PostFilter::F27SPS,
PostFilter::F21SPS,
PostFilter::F20SPS,
PostFilter::F16SPS,
];
pub fn closest(rate: f32) -> Option<Self> {
/// (x - y).abs()
fn d(x: f32, y: f32) -> f32 {
if x >= y {
x - y
} else {
y - x
}
}
let mut best: Option<(f32, Self)> = None;
for value in Self::VALID_VALUES {
let error = d(rate, value.output_rate().unwrap());
let better = best
.map(|(best_error, _)| error < best_error)
.unwrap_or(true);
if better {
best = Some((error, *value));
}
}
best.map(|(_, best)| best)
}
/// Samples per Second
pub fn output_rate(&self) -> Option<f32> {
match self {
PostFilter::F27SPS => Some(27.0),
PostFilter::F21SPS => Some(21.25),
PostFilter::F20SPS => Some(20.0),
PostFilter::F16SPS => Some(16.67),
PostFilter::Invalid => None,
}
}
}
impl From<u8> for PostFilter {
fn from(x: u8) -> Self {
match x {

View File

@ -39,12 +39,12 @@ macro_rules! def_reg {
}
}
};
($Reg: ident, $index: ty, $reg: ident, $addr: expr, $size: expr) => {
struct $Reg { pub index: $index, }
($Reg: ident, u8, $reg: ident, $addr: expr, $size: expr) => {
pub struct $Reg { pub index: u8, }
impl Register for $Reg {
type Data = $reg::Data;
fn address(&self) -> u8 {
$addr + (self.index as u8)
$addr + self.index
}
}
mod $reg {
@ -63,16 +63,19 @@ macro_rules! def_reg {
macro_rules! reg_bit {
($getter: ident, $byte: expr, $bit: expr, $doc: expr) => {
#[allow(unused)]
#[doc = $doc]
pub fn $getter(&self) -> bool {
self.0[$byte].get_bit($bit)
}
};
($getter: ident, $setter: ident, $byte: expr, $bit: expr, $doc: expr) => {
#[allow(unused)]
#[doc = $doc]
pub fn $getter(&self) -> bool {
self.0[$byte].get_bit($bit)
}
#[allow(unused)]
#[doc = $doc]
pub fn $setter(&mut self, value: bool) {
self.0[$byte].set_bit($bit, value);
@ -82,32 +85,38 @@ macro_rules! reg_bit {
macro_rules! reg_bits {
($getter: ident, $byte: expr, $bits: expr, $doc: expr) => {
#[allow(unused)]
#[doc = $doc]
pub fn $getter(&self) -> u8 {
self.0[$byte].get_bits($bits)
}
};
($getter: ident, $setter: ident, $byte: expr, $bits: expr, $doc: expr) => {
#[allow(unused)]
#[doc = $doc]
pub fn $getter(&self) -> u8 {
self.0[$byte].get_bits($bits)
}
#[allow(unused)]
#[doc = $doc]
pub fn $setter(&mut self, value: u8) {
self.0[$byte].set_bits($bits, value);
}
};
($getter: ident, $byte: expr, $bits: expr, $ty: ty, $doc: expr) => {
#[allow(unused)]
#[doc = $doc]
pub fn $getter(&self) -> $ty {
self.0[$byte].get_bits($bits) as $ty
}
};
($getter: ident, $setter: ident, $byte: expr, $bits: expr, $ty: ty, $doc: expr) => {
#[allow(unused)]
#[doc = $doc]
pub fn $getter(&self) -> $ty {
self.0[$byte].get_bits($bits).into()
}
#[allow(unused)]
#[doc = $doc]
pub fn $setter(&mut self, value: $ty) {
self.0[$byte].set_bits($bits, value as u8);
@ -136,13 +145,24 @@ impl if_mode::Data {
def_reg!(Data, data, 0x04, 3);
impl data::Data {
pub fn data(&self) -> u32 {
(u32::from(self.0[0]) << 16) |
(u32::from(self.0[1]) << 8) |
u32::from(self.0[2])
pub fn data(&self) -> i32 {
let raw =
(u32::from(self.0[0]) << 16) |
(u32::from(self.0[1]) << 8) |
u32::from(self.0[2]);
if raw & 0x80_0000 != 0 {
((raw & 0x7F_FFFF) | 0x8000_0000) as i32
} else {
raw as i32
}
}
}
def_reg!(GpioCon, gpio_con, 0x06, 2);
impl gpio_con::Data {
reg_bit!(sync_en, set_sync_en, 0, 3, "Enables the SYNC/ERROR pin as a sync input");
}
def_reg!(Id, id, 0x07, 2);
impl id::Data {
pub fn id(&self) -> u16 {
@ -156,11 +176,13 @@ impl channel::Data {
reg_bits!(setup, set_setup, 0, 4..=5, "Setup number");
/// Which input is connected to positive input of this channel
#[allow(unused)]
pub fn a_in_pos(&self) -> Input {
((self.0[0].get_bits(0..=1) << 3) |
self.0[1].get_bits(5..=7)).into()
}
/// Set which input is connected to positive input of this channel
#[allow(unused)]
pub fn set_a_in_pos(&mut self, value: Input) {
let value = value as u8;
self.0[0].set_bits(0..=1, value >> 3);
@ -187,11 +209,11 @@ impl channel::Data {
def_reg!(SetupCon, u8, setup_con, 0x20, 2);
impl setup_con::Data {
reg_bit!(bi_unipolar, set_bi_unipolar, 0, 6, "Unipolar (`false`) or bipolar (`true`) coded output");
reg_bit!(refbuf_pos, set_refbuf_pos, 0, 5, "Enable REF+ input buffer");
reg_bit!(refbuf_neg, set_refbuf_neg, 0, 5, "Enable REF- input buffer");
reg_bit!(ainbuf_pos, set_ainbuf_pos, 0, 3, "Enable AIN+ input buffer");
reg_bit!(ainbuf_neg, set_ainbuf_neg, 0, 2, "Enable AIN- input buffer");
reg_bit!(bipolar, set_bipolar, 0, 4, "Unipolar (`false`) or bipolar (`true`) coded output");
reg_bit!(refbuf_pos, set_refbuf_pos, 0, 3, "Enable REF+ input buffer");
reg_bit!(refbuf_neg, set_refbuf_neg, 0, 2, "Enable REF- input buffer");
reg_bit!(ainbuf_pos, set_ainbuf_pos, 0, 1, "Enable AIN+ input buffer");
reg_bit!(ainbuf_neg, set_ainbuf_neg, 0, 0, "Enable AIN- input buffer");
reg_bit!(burnout_en, 1, 7, "enables a 10 µA current source on the positive analog input selected and a 10 µA current sink on the negative analog input selected");
reg_bits!(ref_sel, set_ref_sel, 1, 4..=5, RefSource, "Select reference source for conversion");
}
@ -207,11 +229,13 @@ impl filt_con::Data {
def_reg!(Offset, u8, offset, 0x30, 3);
impl offset::Data {
#[allow(unused)]
pub fn offset(&self) -> u32 {
(u32::from(self.0[0]) << 16) |
(u32::from(self.0[1]) << 8) |
u32::from(self.0[2])
}
#[allow(unused)]
pub fn set_offset(&mut self, value: u32) {
self.0[0] = (value >> 16) as u8;
self.0[1] = (value >> 8) as u8;
@ -221,11 +245,13 @@ impl offset::Data {
def_reg!(Gain, u8, gain, 0x38, 3);
impl gain::Data {
#[allow(unused)]
pub fn gain(&self) -> u32 {
(u32::from(self.0[0]) << 16) |
(u32::from(self.0[1]) << 8) |
u32::from(self.0[2])
}
#[allow(unused)]
pub fn set_gain(&mut self, value: u32) {
self.0[0] = (value >> 16) as u8;
self.0[1] = (value >> 8) as u8;

View File

@ -72,3 +72,11 @@ pub struct PE4;
def_gpio!(GPIO_PORTE_AHB, PE4, 4);
pub struct PE5;
def_gpio!(GPIO_PORTE_AHB, PE5, 5);
pub struct PK1;
def_gpio!(GPIO_PORTK, PK1, 1);
pub struct PP2;
def_gpio!(GPIO_PORTP, PP2, 2);
pub struct PP3;
def_gpio!(GPIO_PORTP, PP3, 3);
pub struct PQ4;
def_gpio!(GPIO_PORTQ, PQ4, 4);

View File

@ -4,6 +4,7 @@ use tm4c129x;
pub mod gpio;
pub mod softspi;
pub mod systick;
pub mod pwm;
const UART_DIV: u32 = (((/*sysclk*/120_000_000 * 8) / /*baud*/115200) + 1) / 2;
@ -130,46 +131,6 @@ pub fn init() {
}
while !timers_ready(sysctl) {}
// Manual: 13.4.5 PWM Mode
macro_rules! setup_timer_pwm {
($T: tt) => (
let timer = unsafe { &*tm4c129x::$T::ptr() };
timer.cfg.write(|w| unsafe { w.bits(4) });
timer.tamr.modify(|_, w| unsafe {
w
.taams().bit(true)
.tacmr().bit(false)
.tamr().bits(2)
});
timer.tbmr.modify(|_, w| unsafe {
w
.tbams().bit(true)
.tbcmr().bit(false)
.tbmr().bits(2)
});
timer.ctl.modify(|_, w| {
w
.tapwml().bit(false)
.tbpwml().bit(false)
});
// no prescaler
// no interrupts
timer.tailr.write(|w| unsafe { w.bits(0xFFFF) });
timer.tbilr.write(|w| unsafe { w.bits(0xFFFF) });
timer.tamatchr.write(|w| unsafe { w.bits(0x8000) });
timer.tbmatchr.write(|w| unsafe { w.bits(0x8000) });
timer.ctl.modify(|_, w| {
w
.taen().bit(true)
.tben().bit(true)
});
)
}
setup_timer_pwm!(TIMER2);
setup_timer_pwm!(TIMER3);
setup_timer_pwm!(TIMER4);
setup_timer_pwm!(TIMER5);
systick::init(cs);
});
}

138
firmware/src/board/pwm.rs Normal file
View File

@ -0,0 +1,138 @@
use tm4c129x::{
TIMER2, TIMER3, TIMER4, TIMER5,
};
pub struct T2CCP0;
pub struct T2CCP1;
pub struct T3CCP0;
pub struct T3CCP1;
pub struct T4CCP0;
pub struct T4CCP1;
pub struct T5CCP0;
pub struct T5CCP1;
pub trait PwmPeripheral {
type ChannelA: PwmChannel;
type ChannelB: PwmChannel;
fn split() -> (Self::ChannelA, Self::ChannelB);
}
macro_rules! pwm_peripheral {
($TIMER: ty, $A: tt, $B: tt) => {
impl PwmPeripheral for $TIMER {
type ChannelA = $A;
type ChannelB = $B;
fn split() -> (Self::ChannelA, Self::ChannelB) {
let regs = unsafe { &*Self::ptr() };
regs.cfg.write(|w| unsafe { w.bits(4) });
let mut a = $A;
a.configure();
let mut b = $B;
b.configure();
(a, b)
}
}
};
}
pwm_peripheral!(TIMER2, T2CCP0, T2CCP1);
pwm_peripheral!(TIMER3, T3CCP0, T3CCP1);
pwm_peripheral!(TIMER4, T4CCP0, T4CCP1);
pwm_peripheral!(TIMER5, T5CCP0, T5CCP1);
pub trait PwmChannel {
fn configure(&mut self);
fn get(&mut self) -> (u16, u16);
fn set(&mut self, width: u16, total: u16);
}
macro_rules! pwm_channel_a {
($CHANNEL: ty, $TIMER: tt) => {
impl PwmChannel for $CHANNEL {
fn configure(&mut self) {
let timer = unsafe { &*tm4c129x::$TIMER::ptr() };
timer.tamr.modify(|_, w| unsafe {
w
.taams().bit(true)
.tacmr().bit(false)
.tamr().bits(2)
});
timer.ctl.modify(|_, w| {
w
.tapwml().bit(false)
});
// no prescaler
// no interrupts
timer.tailr.write(|w| unsafe { w.bits(0xFFFF) });
timer.tamatchr.write(|w| unsafe { w.bits(0x0) });
timer.ctl.modify(|_, w| {
w
.taen().bit(true)
});
}
fn get(&mut self) -> (u16, u16) {
let timer = unsafe { &*tm4c129x::$TIMER::ptr() };
(timer.tamatchr.read().bits() as u16,
timer.tailr.read().bits() as u16)
}
fn set(&mut self, width: u16, total: u16) {
let timer = unsafe { &*tm4c129x::$TIMER::ptr() };
timer.tamatchr.write(|w| unsafe { w.bits(width.into()) });
timer.tailr.write(|w| unsafe { w.bits(total.into()) });
}
}
};
}
macro_rules! pwm_channel_b {
($CHANNEL: ty, $TIMER: tt) => {
impl PwmChannel for $CHANNEL {
fn configure(&mut self) {
let timer = unsafe { &*tm4c129x::$TIMER::ptr() };
timer.tbmr.modify(|_, w| unsafe {
w
.tbams().bit(true)
.tbcmr().bit(false)
.tbmr().bits(2)
});
timer.ctl.modify(|_, w| {
w
.tbpwml().bit(false)
});
// no prescaler
// no interrupts
timer.tbilr.write(|w| unsafe { w.bits(0xFFFF) });
timer.tbmatchr.write(|w| unsafe { w.bits(0x0) });
timer.ctl.modify(|_, w| {
w
.tben().bit(true)
});
}
fn get(&mut self) -> (u16, u16) {
let timer = unsafe { &*tm4c129x::$TIMER::ptr() };
(timer.tbmatchr.read().bits() as u16,
timer.tbilr.read().bits() as u16)
}
fn set(&mut self, width: u16, total: u16) {
let timer = unsafe { &*tm4c129x::$TIMER::ptr() };
timer.tbmatchr.write(|w| unsafe { w.bits(width.into()) });
timer.tbilr.write(|w| unsafe { w.bits(total.into()) });
}
}
};
}
pwm_channel_a!(T2CCP0, TIMER2);
pwm_channel_b!(T2CCP1, TIMER2);
pwm_channel_a!(T3CCP0, TIMER3);
pwm_channel_b!(T3CCP1, TIMER3);
pwm_channel_a!(T4CCP0, TIMER4);
pwm_channel_b!(T4CCP1, TIMER4);
pwm_channel_a!(T5CCP0, TIMER5);
pwm_channel_b!(T5CCP1, TIMER5);

View File

@ -1,121 +1,533 @@
use logos::Logos;
use super::session::ReportMode;
use core::fmt;
use nom::{
IResult,
branch::alt,
bytes::complete::{is_a, tag, take_while1},
character::{is_digit, complete::{char, one_of}},
combinator::{complete, map, opt, value},
sequence::{preceded, separated_pair},
multi::{fold_many0, fold_many1},
error::ErrorKind,
};
use lexical_core as lexical;
#[derive(Logos, Debug, PartialEq)]
enum Token {
#[end]
End,
#[error]
Error,
#[token = "Quit"]
Quit,
#[token = "show"]
Show,
#[token = "channel"]
Channel,
#[token = "report"]
Report,
#[token = "mode"]
Mode,
#[token = "off"]
Off,
#[token = "once"]
Once,
#[token = "continuous"]
Continuous,
#[token = "enable"]
Enable,
#[token = "disable"]
Disable,
#[regex = "[0-9]+"]
Number,
}
#[derive(Debug)]
#[derive(Clone, Debug, PartialEq)]
pub enum Error {
Parser,
UnexpectedEnd,
UnexpectedToken(Token),
NoSuchChannel,
Parser(ErrorKind),
Incomplete,
UnexpectedInput(u8),
ParseNumber(lexical::Error)
}
#[derive(Debug)]
impl<'t> From<nom::Err<(&'t [u8], ErrorKind)>> for Error {
fn from(e: nom::Err<(&'t [u8], ErrorKind)>) -> Self {
match e {
nom::Err::Incomplete(_) =>
Error::Incomplete,
nom::Err::Error((_, e)) =>
Error::Parser(e),
nom::Err::Failure((_, e)) =>
Error::Parser(e),
}
}
}
impl From<lexical::Error> for Error {
fn from(e: lexical::Error) -> Self {
Error::ParseNumber(e)
}
}
impl fmt::Display for Error {
fn fmt(&self, fmt: &mut fmt::Formatter) -> Result<(), fmt::Error> {
match self {
Error::Incomplete =>
"incomplete input".fmt(fmt),
Error::UnexpectedInput(c) => {
"unexpected input: ".fmt(fmt)?;
c.fmt(fmt)
}
Error::Parser(e) => {
"parser: ".fmt(fmt)?;
(e as &dyn core::fmt::Debug).fmt(fmt)
}
Error::ParseNumber(e) => {
"parsing number: ".fmt(fmt)?;
(e as &dyn core::fmt::Debug).fmt(fmt)
}
}
}
}
#[derive(Debug, Clone, PartialEq)]
pub enum ShowCommand {
ReportMode,
Input,
Reporting,
Pwm,
Pid,
SteinhartHart,
PostFilter,
}
#[derive(Debug)]
pub enum ChannelCommand {
Enable,
Disable,
#[derive(Debug, Clone, PartialEq)]
pub enum PidParameter {
Target,
KP,
KI,
KD,
OutputMin,
OutputMax,
IntegralMin,
IntegralMax,
}
#[derive(Debug)]
/// Steinhart-Hart equation parameter
#[derive(Debug, Clone, PartialEq)]
pub enum ShParameter {
A,
B,
C,
ParallelR,
}
#[derive(Debug, Clone, PartialEq)]
pub struct PwmConfig {
pub width: u16,
pub total: u16,
}
#[derive(Debug, Clone, PartialEq)]
pub enum PwmMode {
Manual(PwmConfig),
Pid,
}
#[derive(Debug, Clone, PartialEq)]
pub enum PwmSetup {
ISet(PwmMode),
MaxIPos(PwmConfig),
MaxINeg(PwmConfig),
MaxV(PwmConfig),
}
#[derive(Debug, Clone, PartialEq)]
pub enum Command {
Quit,
Show(ShowCommand),
Report(ReportMode),
Channel(u8, ChannelCommand),
Reporting(bool),
Pwm {
channel: usize,
setup: PwmSetup,
},
Pid {
channel: usize,
parameter: PidParameter,
value: f32,
},
SteinhartHart {
channel: usize,
parameter: ShParameter,
value: f32,
},
PostFilter {
channel: usize,
rate: f32,
},
}
const CHANNEL_IDS: &'static [&'static str] = &[
"0", "1", "2", "3",
];
fn end(input: &[u8]) -> IResult<&[u8], ()> {
complete(
fold_many0(
one_of("\r\n\t "),
(), |(), _| ()
)
)(input)
}
fn whitespace(input: &[u8]) -> IResult<&[u8], ()> {
fold_many1(char(' '), (), |(), _| ())(input)
}
fn unsigned(input: &[u8]) -> IResult<&[u8], Result<u16, Error>> {
take_while1(is_digit)(input)
.map(|(input, digits)| {
let result = lexical::parse(digits)
.map_err(|e| e.into());
(input, result)
})
}
fn float(input: &[u8]) -> IResult<&[u8], Result<f32, Error>> {
let (input, sign) = opt(is_a("-"))(input)?;
let negative = sign.is_some();
let (input, digits) = take_while1(|c| is_digit(c) || c == '.' as u8)(input)?;
let result = lexical::parse(digits)
.map(|result: f32| if negative { -result } else { result })
.map_err(|e| e.into());
Ok((input, result))
}
fn off_on(input: &[u8]) -> IResult<&[u8], bool> {
alt((value(false, tag("off")),
value(true, tag("on"))
))(input)
}
fn channel(input: &[u8]) -> IResult<&[u8], usize> {
map(one_of("01"), |c| (c as usize) - ('0' as usize))(input)
}
fn report(input: &[u8]) -> IResult<&[u8], Command> {
preceded(
tag("report"),
alt((
preceded(
whitespace,
preceded(
tag("mode"),
alt((
preceded(
whitespace,
// `report mode <on | off>` - Switch repoting mode
map(off_on, Command::Reporting)
),
// `report mode` - Show current reporting state
value(Command::Show(ShowCommand::Reporting), end)
))
)),
// `report` - Report once
value(Command::Show(ShowCommand::Input), end)
))
)(input)
}
/// `pwm ... <width> <total>` - Set pwm duty cycle
fn pwm_config(input: &[u8]) -> IResult<&[u8], Result<PwmConfig, Error>> {
let (input, width) = unsigned(input)?;
let width = match width {
Ok(width) => width,
Err(e) => return Ok((input, Err(e.into()))),
};
let (input, _) = whitespace(input)?;
let (input, total) = unsigned(input)?;
let total = match total {
Ok(total) => total,
Err(e) => return Ok((input, Err(e.into()))),
};
Ok((input, Ok(PwmConfig { width, total })))
}
fn pwm_setup(input: &[u8]) -> IResult<&[u8], Result<PwmSetup, Error>> {
alt((
map(
preceded(
tag("max_i_pos"),
preceded(
whitespace,
pwm_config
)
),
|result| result.map(PwmSetup::MaxIPos)
),
map(
preceded(
tag("max_i_neg"),
preceded(
whitespace,
pwm_config
)
),
|result| result.map(PwmSetup::MaxINeg)
),
map(
preceded(
tag("max_v"),
preceded(
whitespace,
pwm_config
)
),
|result| result.map(PwmSetup::MaxV)
),
map(pwm_config, |result| result.map(|config| {
PwmSetup::ISet(PwmMode::Manual(config))
}))
))(input)
}
/// `pwm <0-1> pid` - Set PWM to be controlled by PID
fn pwm_pid(input: &[u8]) -> IResult<&[u8], Result<PwmSetup, Error>> {
value(Ok(PwmSetup::ISet(PwmMode::Pid)), tag("pid"))(input)
}
fn pwm(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
let (input, _) = tag("pwm")(input)?;
alt((
preceded(
whitespace,
map(
separated_pair(
channel,
whitespace,
alt((
pwm_pid,
pwm_setup
))
),
|(channel, setup)| setup.map(|setup| Command::Pwm { channel, setup })
)
),
value(Ok(Command::Show(ShowCommand::Pwm)), end)
))(input)
}
/// `pid <0-1> <parameter> <value>`
fn pid_parameter(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
let (input, channel) = channel(input)?;
let (input, _) = whitespace(input)?;
let (input, parameter) =
alt((value(PidParameter::Target, tag("target")),
value(PidParameter::KP, tag("kp")),
value(PidParameter::KI, tag("ki")),
value(PidParameter::KD, tag("kd")),
value(PidParameter::OutputMin, tag("output_min")),
value(PidParameter::OutputMax, tag("output_max")),
value(PidParameter::IntegralMin, tag("integral_min")),
value(PidParameter::IntegralMax, tag("integral_max"))
))(input)?;
let (input, _) = whitespace(input)?;
let (input, value) = float(input)?;
let result = value
.map(|value| Command::Pid { channel, parameter, value });
Ok((input, result))
}
/// `pid` | `pid <pid_parameter>`
fn pid(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
let (input, _) = tag("pid")(input)?;
alt((
preceded(
whitespace,
pid_parameter
),
value(Ok(Command::Show(ShowCommand::Pid)), end)
))(input)
}
/// `s-h <0-1> <parameter> <value>`
fn steinhart_hart_parameter(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
let (input, channel) = channel(input)?;
let (input, _) = whitespace(input)?;
let (input, parameter) =
alt((value(ShParameter::A, tag("a")),
value(ShParameter::B, tag("b")),
value(ShParameter::C, tag("c")),
value(ShParameter::ParallelR, tag("parallel_r"))
))(input)?;
let (input, _) = whitespace(input)?;
let (input, value) = float(input)?;
let result = value
.map(|value| Command::SteinhartHart { channel, parameter, value });
Ok((input, result))
}
/// `s-h` | `s-h <steinhart_hart_parameter>`
fn steinhart_hart(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
let (input, _) = tag("s-h")(input)?;
alt((
preceded(
whitespace,
steinhart_hart_parameter
),
value(Ok(Command::Show(ShowCommand::SteinhartHart)), end)
))(input)
}
fn postfilter(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
let (input, _) = tag("postfilter")(input)?;
alt((
preceded(
whitespace,
|input| {
let (input, channel) = channel(input)?;
let (input, _) = whitespace(input)?;
let (input, _) = tag("rate")(input)?;
let (input, _) = whitespace(input)?;
let (input, rate) = float(input)?;
let result = rate
.map(|rate| Command::PostFilter {
channel, rate,
});
Ok((input, result))
}
),
value(Ok(Command::Show(ShowCommand::PostFilter)), end)
))(input)
}
fn command(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
alt((value(Ok(Command::Quit), tag("quit")),
map(report, Ok),
pwm,
pid,
steinhart_hart,
postfilter,
))(input)
}
impl Command {
pub fn parse(input: &str) -> Result<Self, Error> {
let mut lexer = Token::lexer(input);
macro_rules! choice {
[$($token: tt => $block: stmt,)*] => {
match lexer.token {
$(
Token::$token => {
lexer.advance();
$block
}
)*
Token::End => Err(Error::UnexpectedEnd),
_ => Err(Error::UnexpectedToken(lexer.token))
}
}
pub fn parse(input: &[u8]) -> Result<Self, Error> {
match command(input) {
Ok((b"", result)) =>
result,
Ok((input_remain, _)) =>
Err(Error::UnexpectedInput(input_remain[0])),
Err(e) =>
Err(e.into()),
}
choice![
Quit => Ok(Command::Quit),
Report => choice![
Mode => choice![
End => Ok(Command::Show(ShowCommand::ReportMode)),
Off => Ok(Command::Report(ReportMode::Off)),
Once => Ok(Command::Report(ReportMode::Once)),
Continuous => Ok(Command::Report(ReportMode::Continuous)),
],
End => Ok(Command::Report(ReportMode::Once)),
],
Channel => choice![
Number => {
let channel = CHANNEL_IDS.iter()
.position(|id| *id == lexer.slice());
match channel {
Some(channel) => {
choice![
Enable => Ok(Command::Channel(
channel as u8,
ChannelCommand::Enable
)),
Disable => Ok(Command::Channel(
channel as u8,
ChannelCommand::Enable
)),
]
}
None => Err(Error::NoSuchChannel)
}
},
],
]
}
}
#[cfg(test)]
mod test {
use super::*;
#[test]
fn parse_quit() {
let command = Command::parse(b"quit");
assert_eq!(command, Ok(Command::Quit));
}
#[test]
fn parse_report() {
let command = Command::parse(b"report");
assert_eq!(command, Ok(Command::Show(ShowCommand::Input)));
}
#[test]
fn parse_report_mode() {
let command = Command::parse(b"report mode");
assert_eq!(command, Ok(Command::Show(ShowCommand::Reporting)));
}
#[test]
fn parse_report_mode_on() {
let command = Command::parse(b"report mode on");
assert_eq!(command, Ok(Command::Reporting(true)));
}
#[test]
fn parse_report_mode_off() {
let command = Command::parse(b"report mode off");
assert_eq!(command, Ok(Command::Reporting(false)));
}
#[test]
fn parse_pwm_manual() {
let command = Command::parse(b"pwm 1 16383 65535");
assert_eq!(command, Ok(Command::Pwm {
channel: 1,
setup: PwmSetup::ISet(PwmMode::Manual(PwmConfig {
width: 16383,
total: 65535,
})),
}));
}
#[test]
fn parse_pwm_pid() {
let command = Command::parse(b"pwm 0 pid");
assert_eq!(command, Ok(Command::Pwm {
channel: 0,
setup: PwmSetup::ISet(PwmMode::Pid),
}));
}
#[test]
fn parse_pwm_max_i_pos() {
let command = Command::parse(b"pwm 0 max_i_pos 7 13");
assert_eq!(command, Ok(Command::Pwm {
channel: 0,
setup: PwmSetup::MaxIPos(PwmConfig {
width: 7,
total: 13,
}),
}));
}
#[test]
fn parse_pwm_max_i_neg() {
let command = Command::parse(b"pwm 0 max_i_neg 128 65535");
assert_eq!(command, Ok(Command::Pwm {
channel: 0,
setup: PwmSetup::MaxINeg(PwmConfig {
width: 128,
total: 65535,
}),
}));
}
#[test]
fn parse_pwm_max_v() {
let command = Command::parse(b"pwm 0 max_v 32768 65535");
assert_eq!(command, Ok(Command::Pwm {
channel: 0,
setup: PwmSetup::MaxV(PwmConfig {
width: 32768,
total: 65535,
}),
}));
}
#[test]
fn parse_pid() {
let command = Command::parse(b"pid");
assert_eq!(command, Ok(Command::Show(ShowCommand::Pid)));
}
#[test]
fn parse_pid_target() {
let command = Command::parse(b"pid 0 target 36.5");
assert_eq!(command, Ok(Command::Pid {
channel: 0,
parameter: PidParameter::Target,
value: 36.5,
}));
}
#[test]
fn parse_pid_integral_max() {
let command = Command::parse(b"pid 1 integral_max 2000");
assert_eq!(command, Ok(Command::Pid {
channel: 1,
parameter: PidParameter::IntegralMax,
value: 2000.0,
}));
}
#[test]
fn parse_steinhart_hart() {
let command = Command::parse(b"s-h");
assert_eq!(command, Ok(Command::Show(ShowCommand::SteinhartHart)));
}
#[test]
fn parse_steinhart_hart_parallel_r() {
let command = Command::parse(b"s-h 1 parallel_r 23.05");
assert_eq!(command, Ok(Command::SteinhartHart {
channel: 1,
parameter: ShParameter::ParallelR,
value: 23.05,
}));
}
#[test]
fn parse_postfilter_rate() {
let command = Command::parse(b"postfilter 0 rate 21");
assert_eq!(command, Ok(Command::PostFilter {
channel: 0,
rate: 21.0,
}));
}
}

View File

@ -155,11 +155,11 @@ impl RxRing {
(EMAC_RDES0_FS | EMAC_RDES0_LS)
}
unsafe fn buf_as_slice<'a>(&self) -> &'a [u8] {
unsafe fn buf_as_slice<'a>(&self) -> &'a mut [u8] {
let len = (self.desc_buf[self.cur_desc + 0] & EMAC_RDES0_FL) >> 16;
let len = cmp::min(len as usize, ETH_RX_BUFFER_SIZE);
let addr = self.desc_buf[self.cur_desc + 2] as *const u8;
slice::from_raw_parts(addr, len)
let addr = self.desc_buf[self.cur_desc + 2] as *mut u8;
slice::from_raw_parts_mut(addr, len)
}
fn buf_release(&mut self) {
@ -428,7 +428,7 @@ pub struct RxToken<'a>(&'a mut RxRing);
impl<'a> phy::RxToken for RxToken<'a> {
fn consume<R, F>(self, _timestamp: Instant, f: F) -> Result<R>
where F: FnOnce(&[u8]) -> Result<R> {
where F: FnOnce(&mut [u8]) -> Result<R> {
let result = f(unsafe { self.0.buf_as_slice() });
self.0.buf_release();
result

View File

@ -1,17 +1,14 @@
#![feature(const_fn)]
#![feature(alloc_error_handler)]
#![no_std]
#![no_main]
#![feature(const_fn, proc_macro_hygiene)]
#![cfg_attr(not(test), no_std)]
#![cfg_attr(not(test), no_main)]
extern crate alloc;
use cortex_m_rt::{entry, heap_start};
use cortex_m_rt::entry;
use core::fmt::{self, Write};
use smoltcp::time::Instant;
use smoltcp::wire::{IpCidr, IpAddress, EthernetAddress};
use smoltcp::iface::{NeighborCache, EthernetInterfaceBuilder};
use smoltcp::socket::{SocketSet, TcpSocket, TcpSocketBuffer};
use cortex_m_semihosting::hio;
use alloc_cortex_m::CortexMHeap;
#[macro_export]
macro_rules! print {
@ -27,30 +24,32 @@ macro_rules! println {
($fmt:expr, $($arg:tt)*) => (print!(concat!($fmt, "\n"), $($arg)*));
}
#[cfg(not(test))]
#[no_mangle] // https://github.com/rust-lang/rust/issues/{38281,51647}
#[panic_handler]
pub fn panic_fmt(info: &core::panic::PanicInfo) -> ! {
println!("{}", info);
let mut stdout = hio::hstdout().unwrap();
let _ = writeln!(stdout, "{}", info);
loop {}
}
#[global_allocator]
static ALLOCATOR: CortexMHeap = CortexMHeap::empty();
const HEAP_SIZE: usize = 8192;
#[alloc_error_handler]
fn alloc_error_handler(layout: alloc::alloc::Layout) -> ! {
panic!("Allocation error for: {:?}", layout)
}
mod board;
use self::board::{gpio::Gpio, systick::get_time};
use self::board::{
gpio::Gpio,
systick::get_time,
};
mod ethmac;
mod command_parser;
use command_parser::{Command, ShowCommand};
use command_parser::{Command, ShowCommand, PwmSetup, PwmMode, PwmConfig};
mod session;
use self::session::{Session, SessionOutput};
mod ad7172;
mod pid;
mod tec;
use tec::{Tec, TecPin};
mod steinhart_hart;
use steinhart_hart as sh;
pub struct UART0;
@ -85,23 +84,62 @@ macro_rules! create_socket {
)
}
const VCC: f32 = 3.3;
const PWM_PID_WIDTH: u16 = 0xffff;
const PWM_MAX: f32 = PWM_PID_WIDTH as f32;
const DEFAULT_PID_PARAMETERS: pid::Parameters = pid::Parameters {
kp: 0.5 * PWM_MAX,
ki: 0.05 * PWM_MAX,
kd: 0.45 * PWM_MAX,
output_min: 0.0,
output_max: PWM_MAX,
integral_min: 0.0,
integral_max: PWM_MAX,
};
const DEFAULT_SH_PARAMETERS: sh::Parameters = sh::Parameters {
a: 0.001_4,
b: 0.000_237,
c: 0.000_000_099,
parallel_r: 5_110.0, // Ohm (TODO: verify)
};
// TODO: maybe rename to `TECS`?
/// Number of TEC channels with four PWM channels each
pub const CHANNELS: usize = 2;
// TODO: maybe rename to `TecState`?
/// State per TEC channel
#[derive(Clone)]
struct ControlState {
/// Report data (time, data, temperature)
report: Option<(u64, i32, f32, Option<u16>)>,
pid_enabled: bool,
pid: pid::Controller,
sh: sh::Parameters,
}
#[cfg(not(test))]
#[entry]
fn main() -> ! {
let mut stdout = hio::hstdout().unwrap();
writeln!(stdout, "ionpak boot").unwrap();
writeln!(stdout, "tecpak boot").unwrap();
board::init();
writeln!(stdout, "board initialized").unwrap();
unsafe { ALLOCATOR.init(heap_start() as usize, HEAP_SIZE) };
let mut tec0 = Tec::tec0().setup(PWM_PID_WIDTH / 2, PWM_PID_WIDTH);
let mut tec1 = Tec::tec1().setup(PWM_PID_WIDTH / 2, PWM_PID_WIDTH);
println!(r#"
_ _
(_) | |
_ ___ _ __ _ __ __ _| |
| |/ _ \| '_ \| '_ \ / _` | |/ /
| | (_) | | | | |_) | (_| | <
|_|\___/|_| |_| .__/ \__,_|_|\_\
| | | |
/ _/___ _ __ _ __ __ _| |
| |/ _ \ /'__\| '_ \ / _` | |/ /
| | (/_/| |___| |_) | (_| | <
|_|\___\ \___/| .__/ \__,_|_|\_\
| |
|_|
|_| v1
"#);
// CSn
let pb4 = board::gpio::PB4.into_output();
@ -127,8 +165,9 @@ fn main() -> ! {
writeln!(stdout, "ADC id: {:04X}", id).unwrap();
break;
}
Ok(id) =>
writeln!(stdout, "Corrupt ADC id: {:04X}", id).unwrap(),
Ok(_id) => {
// This always happens on the first attempt. So retry silently
}
};
}
writeln!(stdout, "AD7172: setting checksum mode").unwrap();
@ -146,10 +185,25 @@ fn main() -> ! {
writeln!(stdout, "Corrupt ADC id: {:04X}", id).unwrap(),
};
}
adc.set_sync_enable(false).unwrap();
// SENS0_{P,N}
adc.setup_channel(0, ad7172::Input::Ain0, ad7172::Input::Ain1).unwrap();
// SENS1_{P,N}
adc.setup_channel(1, ad7172::Input::Ain2, ad7172::Input::Ain3).unwrap();
let init_state = ControlState {
report: None,
// Start with disengaged PID to let user setup parameters first
pid_enabled: false,
pid: pid::Controller::new(DEFAULT_PID_PARAMETERS.clone()),
sh: DEFAULT_SH_PARAMETERS.clone(),
};
let mut states = [init_state.clone(), init_state.clone()];
let mut hardware_addr = EthernetAddress(board::get_mac_address());
writeln!(stdout, "MAC address: {}", hardware_addr).unwrap();
if hardware_addr.is_multicast() {
println!("programmed MAC address is invalid, using default");
writeln!(stdout, "programmed MAC address is invalid, using default").unwrap();
hardware_addr = EthernetAddress([0x10, 0xE2, 0xD5, 0x00, 0x03, 0x00]);
}
let mut ip_addrs = [IpCidr::new(IpAddress::v4(192, 168, 1, 26), 24)];
@ -195,31 +249,37 @@ fn main() -> ! {
(Session::new(), tcp_handle7),
];
let mut read_times = [0, 0];
let mut data = None;
// if a socket has sent the latest data
loop {
let _ = adc.data_ready()
.and_then(|channel|
channel.map(|channel|
adc.read_data().map(|new_data| {
let now = get_time();
read_times[0] = read_times[1];
read_times[1] = now;
data = Some((now, Ok((channel, new_data))));
for (session, _) in sessions_handles.iter_mut() {
session.set_report_pending();
}
})
).unwrap_or(Ok(()))
)
.map_err(|e| {
// ADC input
adc.data_ready()
.unwrap_or_else(|e| {
writeln!(stdout, "ADC error: {:?}", e).unwrap();
None
}).map(|channel| {
let now = get_time();
data = Some((now, Err(e)));
let data = adc.read_data().unwrap();
let state = &mut states[usize::from(channel)];
let voltage = VCC * (data as f32) / (0x7FFFFF as f32);
let temperature = state.sh.get_temperature(voltage);
let pwm_width = if state.pid_enabled {
let width = state.pid.update(temperature) as u16;
match channel {
0 => tec0.set(TecPin::ISet, width, PWM_PID_WIDTH),
1 => tec1.set(TecPin::ISet, width, PWM_PID_WIDTH),
_ => unreachable!(),
}
Some(width)
} else {
None
};
state.report = Some((now, data, temperature, pwm_width));
for (session, _) in sessions_handles.iter_mut() {
session.set_report_pending();
session.set_report_pending(channel.into());
}
});
for (session, tcp_handle) in sessions_handles.iter_mut() {
let socket = &mut *sockets.get::<TcpSocket>(*tcp_handle);
if !socket.is_open() {
@ -231,20 +291,197 @@ fn main() -> ! {
}
if socket.may_recv() && socket.may_send() {
let command = socket.recv(|buf| session.feed(buf));
let output = socket.recv(|buf| session.feed(buf));
match command {
// TODO: use "{}" to display pretty errors
match output {
Ok(SessionOutput::Nothing) => {}
Ok(SessionOutput::Command(Command::Quit)) =>
socket.close(),
Ok(SessionOutput::Command(Command::Report(mode))) => {
let _ = writeln!(socket, "Report mode: {:?}", mode);
}
Ok(SessionOutput::Command(Command::Show(ShowCommand::ReportMode))) => {
let _ = writeln!(socket, "Report mode: {:?}", session.report_mode());
}
Ok(SessionOutput::Command(command)) => {
let _ = writeln!(socket, "Not implemented: {:?}", command);
Ok(SessionOutput::Command(command)) => match command {
Command::Quit =>
socket.close(),
Command::Reporting(reporting) => {
let _ = writeln!(socket, "report={}", if reporting { "on" } else { "off" });
}
Command::Show(ShowCommand::Reporting) => {
let _ = writeln!(socket, "report={}", if session.reporting() { "on" } else { "off" });
}
Command::Show(ShowCommand::Input) => {
for (channel, state) in states.iter().enumerate() {
state.report.map(|(time, data, temp, pwm_width)| {
let _ = write!(
socket, "t={} temp{}={} raw{}=0x{:06X}",
time, channel, temp, channel, data
);
pwm_width.map(|width| {
let _ = write!(
socket, " pwm{}=0x{:04X}",
channel, width
);
});
let _ = writeln!(socket, "");
});
}
}
Command::Show(ShowCommand::Pid) => {
for (channel, state) in states.iter().enumerate() {
let _ = writeln!(socket, "PID settings for channel {}", channel);
let pid = &state.pid;
let _ = writeln!(socket, "- target={:.4}", pid.get_target());
let p = pid.get_parameters();
macro_rules! out {
($p: tt) => {
let _ = writeln!(socket, "- {}={:.4}", stringify!($p), p.$p);
};
}
out!(kp);
out!(ki);
out!(kd);
out!(output_min);
out!(output_max);
out!(integral_min);
out!(integral_max);
let _ = writeln!(socket, "");
}
}
Command::Show(ShowCommand::Pwm) => {
for (channel, state) in states.iter().enumerate() {
let _ = writeln!(
socket, "channel {}: PID={}",
channel,
if state.pid_enabled { "engaged" } else { "disengaged" }
);
for pin in TecPin::VALID_VALUES {
let (width, total) = match channel {
0 => tec0.get(*pin),
1 => tec1.get(*pin),
_ => unreachable!(),
};
let _ = writeln!(socket, "- {}={}/{}", pin, width, total);
}
let _ = writeln!(socket, "");
}
}
Command::Show(ShowCommand::SteinhartHart) => {
for (channel, state) in states.iter().enumerate() {
let _ = writeln!(
socket, "channel {}: Steinhart-Hart equation parameters",
channel,
);
let _ = writeln!(socket, "- a={}", state.sh.a);
let _ = writeln!(socket, "- b={}", state.sh.b);
let _ = writeln!(socket, "- c={}", state.sh.c);
let _ = writeln!(socket, "- parallel_r={}", state.sh.parallel_r);
let _ = writeln!(socket, "");
}
}
Command::Show(ShowCommand::PostFilter) => {
for (channel, _) in states.iter().enumerate() {
match adc.get_postfilter(channel as u8).unwrap() {
Some(filter) => {
let _ = writeln!(
socket, "channel {}: postfilter={:.2} SPS",
channel, filter.output_rate().unwrap()
);
}
None => {
let _ = writeln!(
socket, "channel {}: no postfilter",
channel
);
}
}
}
}
Command::Pwm { channel, setup: PwmSetup::ISet(PwmMode::Pid) } => {
states[channel].pid_enabled = true;
let _ = writeln!(socket, "channel {}: PID enabled to control PWM", channel);
}
Command::Pwm { channel, setup: PwmSetup::ISet(PwmMode::Manual(config))} => {
states[channel].pid_enabled = false;
let PwmConfig { width, total } = config;
match channel {
0 => tec0.set(TecPin::ISet, width, total),
1 => tec1.set(TecPin::ISet, width, total),
_ => unreachable!(),
}
let _ = writeln!(
socket, "channel {}: PWM duty cycle manually set to {}/{}",
channel, config.width, config.total
);
}
Command::Pwm { channel, setup } => {
let (pin, config) = match setup {
PwmSetup::ISet(_) =>
// Handled above
unreachable!(),
PwmSetup::MaxIPos(config) =>
(TecPin::MaxIPos, config),
PwmSetup::MaxINeg(config) =>
(TecPin::MaxINeg, config),
PwmSetup::MaxV(config) =>
(TecPin::MaxV, config),
};
let PwmConfig { width, total } = config;
match channel {
0 => tec0.set(pin, width, total),
1 => tec1.set(pin, width, total),
_ => unreachable!(),
}
let _ = writeln!(
socket, "channel {}: PWM {} reconfigured to {}/{}",
channel, pin, width, total
);
}
Command::Pid { channel, parameter, value } => {
let pid = &mut states[channel].pid;
use command_parser::PidParameter::*;
match parameter {
Target =>
pid.set_target(value),
KP =>
pid.update_parameters(|parameters| parameters.kp = value),
KI =>
pid.update_parameters(|parameters| parameters.ki = value),
KD =>
pid.update_parameters(|parameters| parameters.kd = value),
OutputMin =>
pid.update_parameters(|parameters| parameters.output_min = value),
OutputMax =>
pid.update_parameters(|parameters| parameters.output_max = value),
IntegralMin =>
pid.update_parameters(|parameters| parameters.integral_min = value),
IntegralMax =>
pid.update_parameters(|parameters| parameters.integral_max = value),
}
pid.reset();
let _ = writeln!(socket, "PID parameter updated");
}
Command::SteinhartHart { channel, parameter, value } => {
let sh = &mut states[channel].sh;
use command_parser::ShParameter::*;
match parameter {
A => sh.a = value,
B => sh.b = value,
C => sh.c = value,
ParallelR => sh.parallel_r = value,
}
let _ = writeln!(socket, "Steinhart-Hart equation parameter updated");
}
Command::PostFilter { channel, rate } => {
let filter = ad7172::PostFilter::closest(rate);
match filter {
Some(filter) => {
adc.set_postfilter(channel as u8, Some(filter)).unwrap();
let _ = writeln!(
socket, "channel {}: postfilter set to {:.2} SPS",
channel, filter.output_rate().unwrap()
);
}
None => {
let _ = writeln!(socket, "Unable to choose postfilter");
}
}
}
}
Ok(SessionOutput::Error(e)) => {
let _ = writeln!(socket, "Command error: {:?}", e);
@ -252,21 +489,23 @@ fn main() -> ! {
Err(_) => {}
}
}
if socket.may_send() && session.is_report_pending() {
match &data {
Some((time, Ok((channel, input)))) => {
let interval = read_times[1] - read_times[0];
let _ = writeln!(socket, "t={}-{} channel={} input={}\r", time, interval, channel, input);
}
Some((time, Err(ad7172::AdcError::ChecksumMismatch(Some(expected), Some(input))))) => {
let _ = writeln!(socket, "t={} checksum_expected={:02X} checksum_input={:02X}\r", time, expected, input);
}
Some((time, Err(e))) => {
let _ = writeln!(socket, "t={} adc_error={:?}\r", time, e);
}
None => {}
if socket.may_send() {
if let Some(channel) = session.is_report_pending() {
states[channel].report.map(|(time, data, temp, pwm_width)| {
let _ = write!(
socket, "t={} temp{}={} raw{}=0x{:06X}",
time, channel, temp, channel, data
);
pwm_width.map(|width| {
let _ = write!(
socket, " pwm{}=0x{:04X}",
channel, width
);
});
let _ = writeln!(socket, "");
});
session.mark_report_sent(channel);
}
session.mark_report_sent();
}
}
match iface.poll(&mut sockets, Instant::from_millis((get_time() / 1000) as i64)) {

View File

@ -9,6 +9,7 @@ pub struct Parameters {
pub integral_max: f32
}
#[derive(Clone)]
pub struct Controller {
parameters: Parameters,
target: f32,
@ -56,13 +57,66 @@ impl Controller {
output
}
pub fn get_target(&self) -> f32 {
self.target
}
pub fn set_target(&mut self, target: f32) {
self.target = target;
}
pub fn get_parameters(&self) -> &Parameters {
&self.parameters
}
pub fn update_parameters<F: FnOnce(&mut Parameters)>(&mut self, f: F) {
f(&mut self.parameters);
}
#[allow(dead_code)]
pub fn reset(&mut self) {
self.integral = 0.0;
self.last_input = None;
}
}
#[cfg(test)]
mod test {
use super::*;
const PARAMETERS: Parameters = Parameters {
kp: 0.055,
ki: 0.005,
kd: 0.04,
output_min: -10.0,
output_max: 10.0,
integral_min: -100.0,
integral_max: 100.0,
};
#[test]
fn test_controller() {
const DEFAULT: f32 = 0.0;
const TARGET: f32 = 1234.56;
const ERROR: f32 = 0.01;
const DELAY: usize = 10;
let mut pid = Controller::new(PARAMETERS.clone());
pid.set_target(TARGET);
let mut values = [DEFAULT; DELAY];
let mut t = 0;
let mut total_t = 0;
let target = (TARGET - ERROR)..=(TARGET + ERROR);
while !values.iter().all(|value| target.contains(value)) {
let next_t = (t + 1) % DELAY;
// Feed the oldest temperature
let output = pid.update(values[next_t]);
// Overwrite oldest with previous temperature + output
values[next_t] = values[t] + output;
t = next_t;
total_t += 1;
}
dbg!(values[t], total_t);
}
}

View File

@ -1,5 +1,6 @@
use core::ops::Deref;
use super::command_parser::{Command, Error as ParserError};
use super::CHANNELS;
const MAX_LINE_LEN: usize = 64;
@ -16,13 +17,16 @@ impl LineReader {
}
}
pub fn feed(&mut self, c: u8) -> Option<&str> {
pub fn feed(&mut self, c: u8) -> Option<LineResult> {
if c == 13 || c == 10 {
// Enter
if self.pos > 0 {
let len = self.pos;
self.pos = 0;
core::str::from_utf8(&self.buf[..len]).ok()
Some(LineResult {
buf: self.buf.clone(),
len,
})
} else {
None
}
@ -38,11 +42,16 @@ impl LineReader {
}
}
#[derive(Debug, Clone, Copy)]
pub enum ReportMode {
Off,
Once,
Continuous,
pub struct LineResult {
buf: [u8; MAX_LINE_LEN],
len: usize,
}
impl Deref for LineResult {
type Target = [u8];
fn deref(&self) -> &Self::Target {
&self.buf[..self.len]
}
}
pub enum SessionOutput {
@ -60,16 +69,16 @@ impl From<Result<Command, ParserError>> for SessionOutput {
pub struct Session {
reader: LineReader,
report_mode: ReportMode,
report_pending: bool,
reporting: bool,
report_pending: [bool; CHANNELS],
}
impl Session {
pub fn new() -> Self {
Session {
reader: LineReader::new(),
report_mode: ReportMode::Off,
report_pending: false,
reporting: false,
report_pending: [false; CHANNELS],
}
}
@ -77,40 +86,45 @@ impl Session {
self.reader.pos > 0
}
pub fn report_mode(&self) -> ReportMode {
self.report_mode
pub fn reporting(&self) -> bool {
self.reporting
}
pub fn set_report_pending(&mut self) {
self.report_pending = true;
}
pub fn is_report_pending(&self) -> bool {
match self.report_mode {
ReportMode::Off => false,
_ => self.report_pending,
pub fn set_report_pending(&mut self, channel: usize) {
if self.reporting {
self.report_pending[channel] = true;
}
}
pub fn mark_report_sent(&mut self) {
self.report_pending = false;
match self.report_mode {
ReportMode::Once =>
self.report_mode = ReportMode::Off,
_ => {}
pub fn is_report_pending(&self) -> Option<usize> {
if ! self.reporting {
None
} else {
self.report_pending.iter()
.enumerate()
.fold(None, |result, (channel, report_pending)| {
result.or_else(|| {
if *report_pending { Some(channel) } else { None }
})
})
}
}
pub fn mark_report_sent(&mut self, channel: usize) {
self.report_pending[channel] = false;
}
pub fn feed(&mut self, buf: &[u8]) -> (usize, SessionOutput) {
let mut buf_bytes = 0;
for (i, b) in buf.iter().enumerate() {
buf_bytes = i + 1;
match self.reader.feed(*b) {
let line = self.reader.feed(*b);
match line {
Some(line) => {
let command = Command::parse(line);
let command = Command::parse(&line);
match command {
Ok(Command::Report(mode)) => {
self.report_mode = mode;
Ok(Command::Reporting(reporting)) => {
self.reporting = reporting;
}
_ => {}
}

View File

@ -0,0 +1,30 @@
use libm::F32Ext;
/// Steinhart-Hart equation parameters
#[derive(Clone, Debug)]
pub struct Parameters {
pub a: f32,
pub b: f32,
pub c: f32,
/// Parallel resistance
///
/// Not truly part of the equation but required to calculate
/// resistance from voltage.
pub parallel_r: f32,
}
impl Parameters {
/// Perform the voltage to temperature conversion.
///
/// Result unit: Kelvin
///
/// TODO: verify
pub fn get_temperature(&self, voltage: f32) -> f32 {
let r = self.parallel_r * voltage;
let ln_r = r.abs().ln();
let inv_temp = self.a +
self.b * ln_r +
self.c * ln_r * ln_r * ln_r;
1.0 / inv_temp
}
}

128
firmware/src/tec.rs Normal file
View File

@ -0,0 +1,128 @@
use core::fmt;
use crate::board::pwm::{self, PwmChannel, PwmPeripheral};
use crate::board::gpio::{Gpio, GpioOutput, PP2, PP3, PK1, PQ4};
use embedded_hal::digital::v2::OutputPin;
#[derive(Clone, Copy, Debug)]
pub enum TecPin {
ISet,
MaxIPos,
MaxINeg,
MaxV,
}
impl TecPin {
pub const VALID_VALUES: &'static [TecPin] = &[
TecPin::ISet,
TecPin::MaxIPos,
TecPin::MaxINeg,
TecPin::MaxV,
];
}
impl fmt::Display for TecPin {
fn fmt(&self, fmt: &mut fmt::Formatter) -> Result<(), fmt::Error> {
match self {
TecPin::ISet =>
"i_set".fmt(fmt),
TecPin::MaxIPos =>
"max_i_pos".fmt(fmt),
TecPin::MaxINeg =>
"max_i_neg".fmt(fmt),
TecPin::MaxV =>
"max_v".fmt(fmt),
}
}
}
fn setup_shdn<G>(gpio: G) -> GpioOutput<G>
where
G: Gpio,
GpioOutput<G>: OutputPin,
{
let mut pin = gpio.into_output();
// keep off until first use
let _ = pin.set_low();
pin
}
fn setup_freq<G>(gpio: G)
where
G: Gpio,
GpioOutput<G>: OutputPin,
{
let mut pin = gpio.into_output();
// Switching Frequency Select
// high: 1 MHz, low: 500 kHz
let _ = pin.set_high();
}
/// Thermo-Electric Cooling device controlled through four PWM
/// channels
pub struct Tec<MaxIPos: PwmChannel, MaxINeg: PwmChannel, ISet: PwmChannel, MaxV: PwmChannel, SHDN: OutputPin> {
max_i_pos: MaxIPos,
max_i_neg: MaxINeg,
i_set: ISet,
max_v: MaxV,
shdn: SHDN,
}
impl Tec<pwm::T2CCP0, pwm::T2CCP1, pwm::T3CCP0, pwm::T3CCP1, GpioOutput<PP2>> {
pub fn tec0() -> Self {
let (max_i_pos, max_i_neg) = tm4c129x::TIMER2::split();
let (i_set, max_v) = tm4c129x::TIMER3::split();
let shdn = setup_shdn(PP2);
setup_freq(PK1);
Tec { max_i_pos, max_i_neg, i_set, max_v, shdn }
}
}
impl Tec<pwm::T4CCP0, pwm::T4CCP1, pwm::T5CCP0, pwm::T5CCP1, GpioOutput<PP3>> {
pub fn tec1() -> Self {
let (max_i_pos, max_i_neg) = tm4c129x::TIMER4::split();
let (i_set, max_v) = tm4c129x::TIMER5::split();
let shdn = setup_shdn(PP3);
setup_freq(PQ4);
Tec { max_i_pos, max_i_neg, i_set, max_v, shdn }
}
}
impl<MaxIPos: PwmChannel, MaxINeg: PwmChannel, ISet: PwmChannel, MaxV: PwmChannel, SHDN: OutputPin> Tec<MaxIPos, MaxINeg, ISet, MaxV, SHDN> {
pub fn setup(mut self, iset_width: u16, max: u16) -> Self {
self.max_i_pos.set(max, max);
self.max_i_neg.set(max, max);
self.max_v.set(max, max);
self.i_set.set(iset_width, max);
self
}
pub fn get(&mut self, pin: TecPin) -> (u16, u16) {
match pin {
TecPin::MaxIPos =>
self.max_i_pos.get(),
TecPin::MaxINeg =>
self.max_i_neg.get(),
TecPin::ISet =>
self.i_set.get(),
TecPin::MaxV =>
self.max_v.get(),
}
}
pub fn set(&mut self, pin: TecPin, width: u16, total: u16) {
match pin {
TecPin::MaxIPos =>
self.max_i_pos.set(width, total),
TecPin::MaxINeg =>
self.max_i_neg.set(width, total),
TecPin::ISet => {
self.i_set.set(width, total);
// enable on first use
let _ = self.shdn.set_high();
}
TecPin::MaxV =>
self.max_v.set(width, total),
}
}
}

View File

@ -12,14 +12,17 @@ stdenv.mkDerivation {
buildInputs = with rustPlatform.rust; [
rustc cargo cargo-xbuild
rustcSrc
pkgsCross.arm-embedded.stdenv.cc
openocd
];
# Set Environment Variables
RUST_BACKTRACE = 1;
XARGO_RUST_SRC = "${rustcSrc}/src";
RUST_COMPILER_RT_ROOT = "${rustcSrc}/src/llvm-project/compiler-rt";
shellHook = ''
cd firmware
echo "Run 'cargo xbuild --release' to build."
'';
}