aboutsummaryrefslogtreecommitdiff
path: root/examples
diff options
context:
space:
mode:
authordatdenkikniet <jcdra1@gmail.com>2023-04-14 21:53:56 +0200
committerdatdenkikniet <jcdra1@gmail.com>2023-04-16 13:08:35 +0200
commit5a9135961f34505714e23f12e4cf4bacfa492dcd (patch)
tree14c986e17ee46a633ecce02d0f6b0c88ceb1c86b /examples
parentef8046b060a375fd5e6b23d62c3a9a303bbd6e11 (diff)
Split remove old examples
Diffstat (limited to 'examples')
-rw-r--r--examples/README.md42
-rw-r--r--examples/rp2040_local_i2c_init/.cargo/config.toml45
-rw-r--r--examples/rp2040_local_i2c_init/Cargo.toml32
-rw-r--r--examples/rp2040_local_i2c_init/Embed.toml39
-rw-r--r--examples/rp2040_local_i2c_init/build.rs31
-rw-r--r--examples/rp2040_local_i2c_init/memory.x15
-rw-r--r--examples/rp2040_local_i2c_init/src/main.rs114
-rw-r--r--examples/stm32f3_blinky/.cargo/config.toml45
-rw-r--r--examples/stm32f3_blinky/Cargo.toml35
-rw-r--r--examples/stm32f3_blinky/Embed.toml9
-rw-r--r--examples/stm32f3_blinky/README.md19
-rw-r--r--examples/stm32f3_blinky/memory.x5
-rw-r--r--examples/stm32f3_blinky/src/main.rs74
13 files changed, 505 insertions, 0 deletions
diff --git a/examples/README.md b/examples/README.md
new file mode 100644
index 0000000..929d3f2
--- /dev/null
+++ b/examples/README.md
@@ -0,0 +1,42 @@
+# `RTIC examples`
+
+> Here you can find examples on different aspects of the RTIC scheduler.
+
+## Structure
+
+This repo does have example applications based on RTIC framework for popular hardware platforms (for example nRF series and Bluepill).
+
+## Requirements
+
+To run these examples, you need to have working environment as described in [Installing the tools](https://rust-embedded.github.io/book/intro/install.html) chapter of **The Embedded Rust Book**.
+
+Short list:
+
+* Rust and cargo
+* Toolchain for your microcontroller
+* OpenOCD
+
+## Contributing
+New examples are always welcome!
+
+## External examples
+
+Some projects maintain RTIC examples in their own repository. Follow these links to find more RTIC examples.
+
+- The [`teensy4-rs` project](https://github.com/mciantyre/teensy4-rs) maintains `RTIC v1.0` examples that run on the Teensy 4.0 and 4.1.
+
+## License
+
+Licensed under either of
+
+* Apache License, Version 2.0 ([LICENSE-APACHE](LICENSE-APACHE) or
+ [http://www.apache.org/licenses/LICENSE-2.0](http://www.apache.org/licenses/LICENSE-2.0))
+* MIT license ([LICENSE-MIT](LICENSE-MIT) or [http://opensource.org/licenses/MIT](http://opensource.org/licenses/MIT))
+
+at your option.
+
+### Contribution
+
+Unless you explicitly state otherwise, any contribution intentionally submitted for inclusion in the
+work by you, as defined in the Apache-2.0 license, shall be dual licensed as above, without any
+additional terms or conditions.
diff --git a/examples/rp2040_local_i2c_init/.cargo/config.toml b/examples/rp2040_local_i2c_init/.cargo/config.toml
new file mode 100644
index 0000000..c6e086a
--- /dev/null
+++ b/examples/rp2040_local_i2c_init/.cargo/config.toml
@@ -0,0 +1,45 @@
+[target.thumbv6m-none-eabi]
+# uncomment this to make `cargo run` execute programs on QEMU
+# runner = "qemu-system-arm -cpu cortex-m3 -machine lm3s6965evb -nographic -semihosting-config enable=on,target=native -kernel"
+
+[target.'cfg(all(target_arch = "arm", target_os = "none"))']
+# uncomment ONE of these three option to make `cargo run` start a GDB session
+# which option to pick depends on your system
+# runner = "arm-none-eabi-gdb -q -x openocd.gdb"
+# runner = "gdb-multiarch -q -x openocd.gdb"
+# runner = "gdb -q -x openocd.gdb"
+
+rustflags = [
+ # This is needed if your flash or ram addresses are not aligned to 0x10000 in memory.x
+ # See https://github.com/rust-embedded/cortex-m-quickstart/pull/95
+ "-C", "link-arg=--nmagic",
+
+ # LLD (shipped with the Rust toolchain) is used as the default linker
+ "-C", "link-arg=-Tlink.x",
+
+ # if you run into problems with LLD switch to the GNU linker by commenting out
+ # this line
+ # "-C", "linker=arm-none-eabi-ld",
+
+ # if you need to link to pre-compiled C libraries provided by a C toolchain
+ # use GCC as the linker by commenting out both lines above and then
+ # uncommenting the three lines below
+ # "-C", "linker=arm-none-eabi-gcc",
+ # "-C", "link-arg=-Wl,-Tlink.x",
+ # "-C", "link-arg=-nostartfiles",
+]
+
+[build]
+# Pick ONE of these compilation targets
+target = "thumbv6m-none-eabi" # Cortex-M0 and Cortex-M0+
+# target = "thumbv7m-none-eabi" # Cortex-M3
+# target = "thumbv7em-none-eabi" # Cortex-M4 and Cortex-M7 (no FPU)
+# target = "thumbv7em-none-eabihf" # Cortex-M4F and Cortex-M7F (with FPU)
+# target = "thumbv8m.base-none-eabi" # Cortex-M23
+# target = "thumbv8m.main-none-eabi" # Cortex-M33 (no FPU)
+# target = "thumbv8m.main-none-eabihf" # Cortex-M33 (with FPU)
+
+# thumbv7m-none-eabi is not coming with core and alloc, compile myself
+[unstable]
+mtime-on-use = true
+build-std = ["core", "alloc"]
diff --git a/examples/rp2040_local_i2c_init/Cargo.toml b/examples/rp2040_local_i2c_init/Cargo.toml
new file mode 100644
index 0000000..4aed0b8
--- /dev/null
+++ b/examples/rp2040_local_i2c_init/Cargo.toml
@@ -0,0 +1,32 @@
+[package]
+name = "rp2040_local_i2c_init"
+categories = ["embedded", "no-std"]
+description = "Example task local initialized resources for Raspberry Pi Pico"
+license = "MIT OR Apache-2.0"
+version = "0.1.0"
+edition = "2021"
+
+[dependencies]
+cortex-m = "0.7"
+rtic = { git = "https://github.com/rtic-rs/rtic", features = [
+ "thumbv6-backend",
+] }
+rtic-monotonics = { git = "https://github.com/rtic-rs/rtic", features = [
+ "rp2040",
+] }
+embedded-hal = { version = "0.2.7", features = ["unproven"] }
+fugit = "0.3"
+rp-pico = "0.7.0"
+panic-probe = "0.3"
+
+[profile.dev]
+opt-level = 1
+codegen-units = 16
+debug = true
+lto = false
+
+[profile.release]
+opt-level = "s" # optimize for size
+codegen-units = 1 # better optimizations
+debug = true # symbols are nice and they don't increase the size on Flash
+lto = true # better optimzations
diff --git a/examples/rp2040_local_i2c_init/Embed.toml b/examples/rp2040_local_i2c_init/Embed.toml
new file mode 100644
index 0000000..0e6edc0
--- /dev/null
+++ b/examples/rp2040_local_i2c_init/Embed.toml
@@ -0,0 +1,39 @@
+[default.probe]
+protocol = "Swd"
+speed = 20000
+# If you only have one probe cargo embed will pick automatically
+# Otherwise: add your probe's VID/PID/serial to filter
+
+## rust-dap
+# usb_vid = "6666"
+# usb_pid = "4444"
+# serial = "test"
+
+
+[default.flashing]
+enabled = true
+
+[default.reset]
+enabled = true
+halt_afterwards = false
+
+[default.general]
+chip = "RP2040"
+log_level = "WARN"
+# RP2040 does not support connect_under_reset
+connect_under_reset = false
+
+[default.rtt]
+enabled = true
+up_mode = "NoBlockSkip"
+channels = [
+ { up = 0, down = 0, name = "name", up_mode = "NoBlockSkip", format = "Defmt" },
+]
+timeout = 3000
+show_timestamps = true
+log_enabled = false
+log_path = "./logs"
+
+[default.gdb]
+enabled = true
+gdb_connection_string = "127.0.0.1:2345"
diff --git a/examples/rp2040_local_i2c_init/build.rs b/examples/rp2040_local_i2c_init/build.rs
new file mode 100644
index 0000000..d534cc3
--- /dev/null
+++ b/examples/rp2040_local_i2c_init/build.rs
@@ -0,0 +1,31 @@
+//! This build script copies the `memory.x` file from the crate root into
+//! a directory where the linker can always find it at build time.
+//! For many projects this is optional, as the linker always searches the
+//! project root directory -- wherever `Cargo.toml` is. However, if you
+//! are using a workspace or have a more complicated build setup, this
+//! build script becomes required. Additionally, by requesting that
+//! Cargo re-run the build script whenever `memory.x` is changed,
+//! updating `memory.x` ensures a rebuild of the application with the
+//! new memory settings.
+
+use std::env;
+use std::fs::File;
+use std::io::Write;
+use std::path::PathBuf;
+
+fn main() {
+ // Put `memory.x` in our output directory and ensure it's
+ // on the linker search path.
+ let out = &PathBuf::from(env::var_os("OUT_DIR").unwrap());
+ File::create(out.join("memory.x"))
+ .unwrap()
+ .write_all(include_bytes!("memory.x"))
+ .unwrap();
+ println!("cargo:rustc-link-search={}", out.display());
+
+ // By default, Cargo will re-run a build script whenever
+ // any file in the project changes. By specifying `memory.x`
+ // here, we ensure the build script is only re-run when
+ // `memory.x` is changed.
+ println!("cargo:rerun-if-changed=memory.x");
+}
diff --git a/examples/rp2040_local_i2c_init/memory.x b/examples/rp2040_local_i2c_init/memory.x
new file mode 100644
index 0000000..4077aab
--- /dev/null
+++ b/examples/rp2040_local_i2c_init/memory.x
@@ -0,0 +1,15 @@
+MEMORY {
+ BOOT2 : ORIGIN = 0x10000000, LENGTH = 0x100
+ FLASH : ORIGIN = 0x10000100, LENGTH = 2048K - 0x100
+ RAM : ORIGIN = 0x20000000, LENGTH = 256K
+}
+
+EXTERN(BOOT2_FIRMWARE)
+
+SECTIONS {
+ /* ### Boot loader */
+ .boot2 ORIGIN(BOOT2) :
+ {
+ KEEP(*(.boot2));
+ } > BOOT2
+} INSERT BEFORE .text;
diff --git a/examples/rp2040_local_i2c_init/src/main.rs b/examples/rp2040_local_i2c_init/src/main.rs
new file mode 100644
index 0000000..3d881aa
--- /dev/null
+++ b/examples/rp2040_local_i2c_init/src/main.rs
@@ -0,0 +1,114 @@
+#![no_std]
+#![no_main]
+#![feature(type_alias_impl_trait)]
+
+#[rtic::app(
+ device = rp_pico::hal::pac,
+ dispatchers = [TIMER_IRQ_1]
+)]
+mod app {
+ use rp_pico::hal::{
+ clocks, gpio,
+ gpio::pin::bank0::{Gpio2, Gpio25, Gpio3},
+ gpio::pin::PushPullOutput,
+ pac,
+ sio::Sio,
+ watchdog::Watchdog,
+ I2C,
+ };
+ use rp_pico::XOSC_CRYSTAL_FREQ;
+
+ use core::mem::MaybeUninit;
+ use embedded_hal::digital::v2::{OutputPin, ToggleableOutputPin};
+ use fugit::RateExtU32;
+ use rtic_monotonics::rp2040::*;
+
+ use panic_probe as _;
+
+ rtic_monotonics::make_rp2040_monotonic_handler!();
+
+ type I2CBus = I2C<
+ pac::I2C1,
+ (
+ gpio::Pin<Gpio2, gpio::FunctionI2C>,
+ gpio::Pin<Gpio3, gpio::FunctionI2C>,
+ ),
+ >;
+
+ #[shared]
+ struct Shared {}
+
+ #[local]
+ struct Local {
+ led: gpio::Pin<Gpio25, PushPullOutput>,
+ i2c: &'static mut I2CBus,
+ }
+
+ #[init(local=[
+ // Task local initialized resources are static
+ // Here we use MaybeUninit to allow for initialization in init()
+ // This enables its usage in driver initialization
+ i2c_ctx: MaybeUninit<I2CBus> = MaybeUninit::uninit()
+ ])]
+ fn init(mut ctx: init::Context) -> (Shared, Local) {
+ // Configure the clocks, watchdog - The default is to generate a 125 MHz system clock
+ Timer::start(ctx.device.TIMER, &mut ctx.device.RESETS); // default rp2040 clock-rate is 125MHz
+ let mut watchdog = Watchdog::new(ctx.device.WATCHDOG);
+ let clocks = clocks::init_clocks_and_plls(
+ XOSC_CRYSTAL_FREQ,
+ ctx.device.XOSC,
+ ctx.device.CLOCKS,
+ ctx.device.PLL_SYS,
+ ctx.device.PLL_USB,
+ &mut ctx.device.RESETS,
+ &mut watchdog,
+ )
+ .ok()
+ .unwrap();
+
+ // Init LED pin
+ let sio = Sio::new(ctx.device.SIO);
+ let gpioa = rp_pico::Pins::new(
+ ctx.device.IO_BANK0,
+ ctx.device.PADS_BANK0,
+ sio.gpio_bank0,
+ &mut ctx.device.RESETS,
+ );
+ let mut led = gpioa.led.into_push_pull_output();
+ led.set_low().unwrap();
+
+ // Init I2C pins
+ let sda_pin = gpioa.gpio2.into_mode::<gpio::FunctionI2C>();
+ let scl_pin = gpioa.gpio3.into_mode::<gpio::FunctionI2C>();
+
+ // Init I2C itself, using MaybeUninit to overwrite the previously
+ // uninitialized i2c_ctx variable without dropping its value
+ // (i2c_ctx definined in init local resources above)
+ let i2c_tmp: &'static mut _ = ctx.local.i2c_ctx.write(I2C::i2c1(
+ ctx.device.I2C1,
+ sda_pin,
+ scl_pin,
+ 100.kHz(),
+ &mut ctx.device.RESETS,
+ &clocks.system_clock,
+ ));
+
+ // Spawn heartbeat task
+ heartbeat::spawn().ok();
+
+ // Return resources and timer
+ (Shared {}, Local { led, i2c: i2c_tmp })
+ }
+
+ #[task(local = [i2c, led])]
+ async fn heartbeat(ctx: heartbeat::Context) {
+ // Flicker the built-in LED
+ _ = ctx.local.led.toggle();
+
+ // Congrats, you can use your i2c and have access to it here,
+ // now to do something with it!
+
+ // Re-spawn this task after 1 second
+ Timer::delay(1000.millis()).await;
+ }
+}
diff --git a/examples/stm32f3_blinky/.cargo/config.toml b/examples/stm32f3_blinky/.cargo/config.toml
new file mode 100644
index 0000000..05a5069
--- /dev/null
+++ b/examples/stm32f3_blinky/.cargo/config.toml
@@ -0,0 +1,45 @@
+[target.thumbv7m-none-eabi]
+# uncomment this to make `cargo run` execute programs on QEMU
+# runner = "qemu-system-arm -cpu cortex-m3 -machine lm3s6965evb -nographic -semihosting-config enable=on,target=native -kernel"
+
+[target.'cfg(all(target_arch = "arm", target_os = "none"))']
+# uncomment ONE of these three option to make `cargo run` start a GDB session
+# which option to pick depends on your system
+# runner = "arm-none-eabi-gdb -q -x openocd.gdb"
+# runner = "gdb-multiarch -q -x openocd.gdb"
+# runner = "gdb -q -x openocd.gdb"
+
+rustflags = [
+ # This is needed if your flash or ram addresses are not aligned to 0x10000 in memory.x
+ # See https://github.com/rust-embedded/cortex-m-quickstart/pull/95
+ "-C", "link-arg=--nmagic",
+
+ # LLD (shipped with the Rust toolchain) is used as the default linker
+ "-C", "link-arg=-Tlink.x",
+
+ # if you run into problems with LLD switch to the GNU linker by commenting out
+ # this line
+ # "-C", "linker=arm-none-eabi-ld",
+
+ # if you need to link to pre-compiled C libraries provided by a C toolchain
+ # use GCC as the linker by commenting out both lines above and then
+ # uncommenting the three lines below
+ # "-C", "linker=arm-none-eabi-gcc",
+ # "-C", "link-arg=-Wl,-Tlink.x",
+ # "-C", "link-arg=-nostartfiles",
+]
+
+[build]
+# Pick ONE of these compilation targets
+# target = "thumbv6m-none-eabi" # Cortex-M0 and Cortex-M0+
+target = "thumbv7m-none-eabi" # Cortex-M3
+# target = "thumbv7em-none-eabi" # Cortex-M4 and Cortex-M7 (no FPU)
+# target = "thumbv7em-none-eabihf" # Cortex-M4F and Cortex-M7F (with FPU)
+# target = "thumbv8m.base-none-eabi" # Cortex-M23
+# target = "thumbv8m.main-none-eabi" # Cortex-M33 (no FPU)
+# target = "thumbv8m.main-none-eabihf" # Cortex-M33 (with FPU)
+
+# thumbv7m-none-eabi is not coming with core and alloc, compile myself
+[unstable]
+mtime-on-use = true
+build-std = ["core", "alloc"]
diff --git a/examples/stm32f3_blinky/Cargo.toml b/examples/stm32f3_blinky/Cargo.toml
new file mode 100644
index 0000000..4cd21fc
--- /dev/null
+++ b/examples/stm32f3_blinky/Cargo.toml
@@ -0,0 +1,35 @@
+[package]
+authors = ["Simsys <winfried.simon@gmail.com>"]
+edition = "2021"
+readme = "README.md"
+name = "stm32f3-blinky"
+version = "0.1.0"
+
+[dependencies]
+embedded-hal = "0.2.7"
+rtic = { git = "https://github.com/rtic-rs/rtic", features = ["thumbv7-backend"] }
+rtic-monotonics = { git = "https://github.com/rtic-rs/rtic", features = ["cortex-m-systick"] }
+panic-rtt-target = { version = "0.1.2", features = ["cortex-m"] }
+rtt-target = { version = "0.3.1", features = ["cortex-m"] }
+
+[dependencies.stm32f3xx-hal]
+features = ["stm32f303xc", "rt"]
+version = "0.9.2"
+
+# this lets you use `cargo fix`!
+[[bin]]
+name = "stm32f3-blinky"
+test = false
+bench = false
+
+[profile.dev]
+opt-level = 1
+codegen-units = 16
+debug = true
+lto = false
+
+[profile.release]
+opt-level = "s" # optimize for size
+codegen-units = 1 # better optimizations
+debug = true # symbols are nice and they don't increase the size on Flash
+lto = true # better optimizations
diff --git a/examples/stm32f3_blinky/Embed.toml b/examples/stm32f3_blinky/Embed.toml
new file mode 100644
index 0000000..6dffe3f
--- /dev/null
+++ b/examples/stm32f3_blinky/Embed.toml
@@ -0,0 +1,9 @@
+[default.general]
+chip = "stm32f303re"
+
+
+[default.rtt]
+enabled = true
+
+[default.gdb]
+enabled = false
diff --git a/examples/stm32f3_blinky/README.md b/examples/stm32f3_blinky/README.md
new file mode 100644
index 0000000..5152661
--- /dev/null
+++ b/examples/stm32f3_blinky/README.md
@@ -0,0 +1,19 @@
+# STM32F3 RTIC Blink example
+
+Working example of simple LED blinking application for STM32 F303 Nucleo-64 board based on the STM32F303RE chip. Example uses schedule API and peripherials access. This example is based on blue-pill blinky example.
+
+## How-to
+
+### Build
+
+Run `cargo +nightly build` to compile the code. If you run it for the first time, it will take some time to download and compile dependencies.
+
+After that, you can use for example the cargo-embed tool to flash and run it
+
+```bash
+$ cargo +nightly embed
+```
+
+### Setup environment, flash and run program
+
+In the [Discovery Book](https://rust-embedded.github.io/discovery) you find all needed informations to setup the environment, flash the controler and run the program.
diff --git a/examples/stm32f3_blinky/memory.x b/examples/stm32f3_blinky/memory.x
new file mode 100644
index 0000000..d369345
--- /dev/null
+++ b/examples/stm32f3_blinky/memory.x
@@ -0,0 +1,5 @@
+MEMORY
+{
+ FLASH : ORIGIN = 0x08000000, LENGTH = 256K
+ RAM : ORIGIN = 0x20000000, LENGTH = 40K
+}
diff --git a/examples/stm32f3_blinky/src/main.rs b/examples/stm32f3_blinky/src/main.rs
new file mode 100644
index 0000000..e208d09
--- /dev/null
+++ b/examples/stm32f3_blinky/src/main.rs
@@ -0,0 +1,74 @@
+#![deny(unsafe_code)]
+#![deny(warnings)]
+#![no_main]
+#![no_std]
+#![feature(type_alias_impl_trait)]
+
+use panic_rtt_target as _;
+use rtic::app;
+use rtic_monotonics::systick::*;
+use rtt_target::{rprintln, rtt_init_print};
+use stm32f3xx_hal::gpio::{Output, PushPull, PA5};
+use stm32f3xx_hal::prelude::*;
+
+#[app(device = stm32f3xx_hal::pac, peripherals = true, dispatchers = [SPI1])]
+mod app {
+ use super::*;
+
+ rtic_monotonics::make_systick_handler!();
+
+ #[shared]
+ struct Shared {}
+
+ #[local]
+ struct Local {
+ led: PA5<Output<PushPull>>,
+ state: bool,
+ }
+
+ #[init]
+ fn init(cx: init::Context) -> (Shared, Local) {
+ // Setup clocks
+ let mut flash = cx.device.FLASH.constrain();
+ let mut rcc = cx.device.RCC.constrain();
+
+ Systick::start(cx.core.SYST, 36_000_000); // default STM32F303 clock-rate is 36MHz
+
+ rtt_init_print!();
+ rprintln!("init");
+
+ let _clocks = rcc
+ .cfgr
+ .use_hse(8.MHz())
+ .sysclk(36.MHz())
+ .pclk1(36.MHz())
+ .freeze(&mut flash.acr);
+
+ // Setup LED
+ let mut gpioa = cx.device.GPIOA.split(&mut rcc.ahb);
+ let mut led = gpioa
+ .pa5
+ .into_push_pull_output(&mut gpioa.moder, &mut gpioa.otyper);
+ led.set_high().unwrap();
+
+ // Schedule the blinking task
+ blink::spawn().ok();
+
+ (Shared {}, Local { led, state: false })
+ }
+
+ #[task(local = [led, state])]
+ async fn blink(cx: blink::Context) {
+ loop {
+ rprintln!("blink");
+ if *cx.local.state {
+ cx.local.led.set_high().unwrap();
+ *cx.local.state = false;
+ } else {
+ cx.local.led.set_low().unwrap();
+ *cx.local.state = true;
+ }
+ Systick::delay(1000.millis()).await;
+ }
+ }
+}