aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--embassy-rp/Cargo.toml8
-rw-r--r--embassy-rp/src/pwm.rs41
-rw-r--r--examples/rp/src/bin/pwm.rs58
-rw-r--r--examples/rp23/Cargo.toml3
-rw-r--r--examples/rp23/src/bin/pwm.rs60
-rw-r--r--examples/rp23/src/bin/pwm_tb6612fng_motor_driver.rs107
6 files changed, 260 insertions, 17 deletions
diff --git a/embassy-rp/Cargo.toml b/embassy-rp/Cargo.toml
index 547d64e43..3e61641ff 100644
--- a/embassy-rp/Cargo.toml
+++ b/embassy-rp/Cargo.toml
@@ -118,18 +118,18 @@ embassy-usb-driver = {version = "0.1.0", path = "../embassy-usb-driver" }
118atomic-polyfill = "1.0.1" 118atomic-polyfill = "1.0.1"
119defmt = { version = "0.3", optional = true } 119defmt = { version = "0.3", optional = true }
120log = { version = "0.4.14", optional = true } 120log = { version = "0.4.14", optional = true }
121nb = "1.0.0" 121nb = "1.1.0"
122cfg-if = "1.0.0" 122cfg-if = "1.0.0"
123cortex-m-rt = ">=0.6.15,<0.8" 123cortex-m-rt = ">=0.6.15,<0.8"
124cortex-m = "0.7.6" 124cortex-m = "0.7.6"
125critical-section = "1.1" 125critical-section = "1.2.0"
126chrono = { version = "0.4", default-features = false, optional = true } 126chrono = { version = "0.4", default-features = false, optional = true }
127embedded-io = { version = "0.6.1" } 127embedded-io = { version = "0.6.1" }
128embedded-io-async = { version = "0.6.1" } 128embedded-io-async = { version = "0.6.1" }
129embedded-storage = { version = "0.3" } 129embedded-storage = { version = "0.3" }
130embedded-storage-async = { version = "0.4.1" } 130embedded-storage-async = { version = "0.4.1" }
131rand_core = "0.6.4" 131rand_core = "0.6.4"
132fixed = "1.23.1" 132fixed = "1.28.0"
133 133
134rp-pac = { git = "https://github.com/embassy-rs/rp-pac.git", rev = "a7f42d25517f7124ad3b4ed492dec8b0f50a0e6c", feature = ["rt"] } 134rp-pac = { git = "https://github.com/embassy-rs/rp-pac.git", rev = "a7f42d25517f7124ad3b4ed492dec8b0f50a0e6c", feature = ["rt"] }
135 135
@@ -141,7 +141,7 @@ embedded-hal-nb = { version = "1.0" }
141pio-proc = {version= "0.2" } 141pio-proc = {version= "0.2" }
142pio = {version= "0.2.1" } 142pio = {version= "0.2.1" }
143rp2040-boot2 = "0.3" 143rp2040-boot2 = "0.3"
144document-features = "0.2.7" 144document-features = "0.2.10"
145sha2-const-stable = "0.1" 145sha2-const-stable = "0.1"
146rp-binary-info = { version = "0.1.0", optional = true } 146rp-binary-info = { version = "0.1.0", optional = true }
147smart-leds = "0.4.0" 147smart-leds = "0.4.0"
diff --git a/embassy-rp/src/pwm.rs b/embassy-rp/src/pwm.rs
index 027f5504e..cfb99c569 100644
--- a/embassy-rp/src/pwm.rs
+++ b/embassy-rp/src/pwm.rs
@@ -1,6 +1,8 @@
1//! Pulse Width Modulation (PWM) 1//! Pulse Width Modulation (PWM)
2 2
3use embassy_hal_internal::{into_ref, Peripheral, PeripheralRef}; 3use embassy_hal_internal::{into_ref, Peripheral, PeripheralRef};
4pub use embedded_hal_1::pwm::SetDutyCycle;
5use embedded_hal_1::pwm::{Error, ErrorKind, ErrorType};
4use fixed::traits::ToFixed; 6use fixed::traits::ToFixed;
5use fixed::FixedU16; 7use fixed::FixedU16;
6use pac::pwm::regs::{ChDiv, Intr}; 8use pac::pwm::regs::{ChDiv, Intr};
@@ -80,6 +82,21 @@ impl From<InputMode> for Divmode {
80 } 82 }
81} 83}
82 84
85/// PWM error.
86#[derive(Debug)]
87pub enum PwmError {
88 /// Invalid Duty Cycle.
89 InvalidDutyCycle,
90}
91
92impl Error for PwmError {
93 fn kind(&self) -> ErrorKind {
94 match self {
95 PwmError::InvalidDutyCycle => ErrorKind::Other,
96 }
97 }
98}
99
83/// PWM driver. 100/// PWM driver.
84pub struct Pwm<'d> { 101pub struct Pwm<'d> {
85 pin_a: Option<PeripheralRef<'d, AnyPin>>, 102 pin_a: Option<PeripheralRef<'d, AnyPin>>,
@@ -87,6 +104,30 @@ pub struct Pwm<'d> {
87 slice: usize, 104 slice: usize,
88} 105}
89 106
107impl<'d> ErrorType for Pwm<'d> {
108 type Error = PwmError;
109}
110
111impl<'d> SetDutyCycle for Pwm<'d> {
112 fn max_duty_cycle(&self) -> u16 {
113 pac::PWM.ch(self.slice).top().read().top()
114 }
115
116 fn set_duty_cycle(&mut self, duty: u16) -> Result<(), Self::Error> {
117 let max_duty = self.max_duty_cycle();
118 if duty > max_duty {
119 return Err(PwmError::InvalidDutyCycle);
120 }
121
122 let p = pac::PWM.ch(self.slice);
123 p.cc().modify(|w| {
124 w.set_a(duty);
125 w.set_b(duty);
126 });
127 Ok(())
128 }
129}
130
90impl<'d> Pwm<'d> { 131impl<'d> Pwm<'d> {
91 fn new_inner( 132 fn new_inner(
92 slice: usize, 133 slice: usize,
diff --git a/examples/rp/src/bin/pwm.rs b/examples/rp/src/bin/pwm.rs
index 26e233260..791b88b5b 100644
--- a/examples/rp/src/bin/pwm.rs
+++ b/examples/rp/src/bin/pwm.rs
@@ -1,24 +1,36 @@
1//! This example shows how to use PWM (Pulse Width Modulation) in the RP2040 chip. 1//! This example shows how to use PWM (Pulse Width Modulation) in the RP2040 chip.
2//! 2//!
3//! The LED on the RP Pico W board is connected differently. Add a LED and resistor to another pin. 3//! We demonstrate two ways of using PWM:
4//! 1. Via config
5//! 2. Via setting a duty cycle
4 6
5#![no_std] 7#![no_std]
6#![no_main] 8#![no_main]
7 9
8use defmt::*; 10use defmt::*;
9use embassy_executor::Spawner; 11use embassy_executor::Spawner;
10use embassy_rp::pwm::{Config, Pwm}; 12use embassy_rp::peripherals::{PIN_25, PIN_4, PWM_SLICE2, PWM_SLICE4};
13use embassy_rp::pwm::{Config, Pwm, SetDutyCycle};
11use embassy_time::Timer; 14use embassy_time::Timer;
12use {defmt_rtt as _, panic_probe as _}; 15use {defmt_rtt as _, panic_probe as _};
13 16
14#[embassy_executor::main] 17#[embassy_executor::main]
15async fn main(_spawner: Spawner) { 18async fn main(spawner: Spawner) {
16 let p = embassy_rp::init(Default::default()); 19 let p = embassy_rp::init(Default::default());
20 spawner.spawn(pwm_set_config(p.PWM_SLICE4, p.PIN_25)).unwrap();
21 spawner.spawn(pwm_set_dutycycle(p.PWM_SLICE2, p.PIN_4)).unwrap();
22}
17 23
18 let mut c: Config = Default::default(); 24/// Demonstrate PWM by modifying & applying the config
19 c.top = 0x8000; 25///
26/// Using the onboard led, if You are using a different Board than plain Pico2 (i.e. W variant)
27/// you must use another slice & pin and an appropriate resistor.
28#[embassy_executor::task]
29async fn pwm_set_config(slice4: PWM_SLICE4, pin25: PIN_25) {
30 let mut c = Config::default();
31 c.top = 32_768;
20 c.compare_b = 8; 32 c.compare_b = 8;
21 let mut pwm = Pwm::new_output_b(p.PWM_SLICE4, p.PIN_25, c.clone()); 33 let mut pwm = Pwm::new_output_b(slice4, pin25, c.clone());
22 34
23 loop { 35 loop {
24 info!("current LED duty cycle: {}/32768", c.compare_b); 36 info!("current LED duty cycle: {}/32768", c.compare_b);
@@ -27,3 +39,37 @@ async fn main(_spawner: Spawner) {
27 pwm.set_config(&c); 39 pwm.set_config(&c);
28 } 40 }
29} 41}
42
43/// Demonstrate PWM by setting duty cycle
44///
45/// Using GP4 in Slice2, make sure to use an appropriate resistor.
46#[embassy_executor::task]
47async fn pwm_set_dutycycle(slice2: PWM_SLICE2, pin4: PIN_4) {
48 // If we aim for a specific frequency, here is how we can calculate the top value.
49 // The top value sets the period of the PWM cycle, so a counter goes from 0 to top and then wraps around to 0.
50 // Every such wraparound is one PWM cycle. So here is how we get 25KHz:
51 let mut c = Config::default();
52 let pwm_freq = 25_000; // Hz, our desired frequency
53 let clock_freq = embassy_rp::clocks::clk_sys_freq();
54 c.top = (clock_freq / pwm_freq) as u16 - 1;
55
56 let mut pwm = Pwm::new_output_a(slice2, pin4, c.clone());
57
58 loop {
59 // 100% duty cycle, fully on
60 pwm.set_duty_cycle_fully_on().unwrap();
61 Timer::after_secs(1).await;
62
63 // 66% duty cycle. Expressed as simple percentage.
64 pwm.set_duty_cycle_percent(66).unwrap();
65 Timer::after_secs(1).await;
66
67 // 25% duty cycle. Expressed as 32768/4 = 8192.
68 pwm.set_duty_cycle(c.top / 4).unwrap();
69 Timer::after_secs(1).await;
70
71 // 0% duty cycle, fully off.
72 pwm.set_duty_cycle_fully_off().unwrap();
73 Timer::after_secs(1).await;
74 }
75}
diff --git a/examples/rp23/Cargo.toml b/examples/rp23/Cargo.toml
index 9ae75e16c..5527a1e0a 100644
--- a/examples/rp23/Cargo.toml
+++ b/examples/rp23/Cargo.toml
@@ -30,6 +30,9 @@ serde-json-core = "0.5.1"
30# for assign resources example 30# for assign resources example
31assign-resources = { git = "https://github.com/adamgreig/assign-resources", rev = "94ad10e2729afdf0fd5a77cd12e68409a982f58a" } 31assign-resources = { git = "https://github.com/adamgreig/assign-resources", rev = "94ad10e2729afdf0fd5a77cd12e68409a982f58a" }
32 32
33# for TB6612FNG example
34tb6612fng = "1.0.0"
35
33#cortex-m = { version = "0.7.6", features = ["critical-section-single-core"] } 36#cortex-m = { version = "0.7.6", features = ["critical-section-single-core"] }
34cortex-m = { version = "0.7.6", features = ["inline-asm"] } 37cortex-m = { version = "0.7.6", features = ["inline-asm"] }
35cortex-m-rt = "0.7.0" 38cortex-m-rt = "0.7.0"
diff --git a/examples/rp23/src/bin/pwm.rs b/examples/rp23/src/bin/pwm.rs
index 15eae09ee..5a4457158 100644
--- a/examples/rp23/src/bin/pwm.rs
+++ b/examples/rp23/src/bin/pwm.rs
@@ -1,6 +1,8 @@
1//! This example shows how to use PWM (Pulse Width Modulation) in the RP2040 chip. 1//! This example shows how to use PWM (Pulse Width Modulation) in the RP235x chip.
2//! 2//!
3//! The LED on the RP Pico W board is connected differently. Add a LED and resistor to another pin. 3//! We demonstrate two ways of using PWM:
4//! 1. Via config
5//! 2. Via setting a duty cycle
4 6
5#![no_std] 7#![no_std]
6#![no_main] 8#![no_main]
@@ -8,7 +10,8 @@
8use defmt::*; 10use defmt::*;
9use embassy_executor::Spawner; 11use embassy_executor::Spawner;
10use embassy_rp::block::ImageDef; 12use embassy_rp::block::ImageDef;
11use embassy_rp::pwm::{Config, Pwm}; 13use embassy_rp::peripherals::{PIN_25, PIN_4, PWM_SLICE2, PWM_SLICE4};
14use embassy_rp::pwm::{Config, Pwm, SetDutyCycle};
12use embassy_time::Timer; 15use embassy_time::Timer;
13use {defmt_rtt as _, panic_probe as _}; 16use {defmt_rtt as _, panic_probe as _};
14 17
@@ -17,13 +20,22 @@ use {defmt_rtt as _, panic_probe as _};
17pub static IMAGE_DEF: ImageDef = ImageDef::secure_exe(); 20pub static IMAGE_DEF: ImageDef = ImageDef::secure_exe();
18 21
19#[embassy_executor::main] 22#[embassy_executor::main]
20async fn main(_spawner: Spawner) { 23async fn main(spawner: Spawner) {
21 let p = embassy_rp::init(Default::default()); 24 let p = embassy_rp::init(Default::default());
25 spawner.spawn(pwm_set_config(p.PWM_SLICE4, p.PIN_25)).unwrap();
26 spawner.spawn(pwm_set_dutycycle(p.PWM_SLICE2, p.PIN_4)).unwrap();
27}
22 28
23 let mut c: Config = Default::default(); 29/// Demonstrate PWM by modifying & applying the config
24 c.top = 0x8000; 30///
31/// Using the onboard led, if You are using a different Board than plain Pico2 (i.e. W variant)
32/// you must use another slice & pin and an appropriate resistor.
33#[embassy_executor::task]
34async fn pwm_set_config(slice4: PWM_SLICE4, pin25: PIN_25) {
35 let mut c = Config::default();
36 c.top = 32_768;
25 c.compare_b = 8; 37 c.compare_b = 8;
26 let mut pwm = Pwm::new_output_b(p.PWM_SLICE4, p.PIN_25, c.clone()); 38 let mut pwm = Pwm::new_output_b(slice4, pin25, c.clone());
27 39
28 loop { 40 loop {
29 info!("current LED duty cycle: {}/32768", c.compare_b); 41 info!("current LED duty cycle: {}/32768", c.compare_b);
@@ -32,3 +44,37 @@ async fn main(_spawner: Spawner) {
32 pwm.set_config(&c); 44 pwm.set_config(&c);
33 } 45 }
34} 46}
47
48/// Demonstrate PWM by setting duty cycle
49///
50/// Using GP4 in Slice2, make sure to use an appropriate resistor.
51#[embassy_executor::task]
52async fn pwm_set_dutycycle(slice2: PWM_SLICE2, pin4: PIN_4) {
53 // If we aim for a specific frequency, here is how we can calculate the top value.
54 // The top value sets the period of the PWM cycle, so a counter goes from 0 to top and then wraps around to 0.
55 // Every such wraparound is one PWM cycle. So here is how we get 25KHz:
56 let mut c = Config::default();
57 let pwm_freq = 25_000; // Hz, our desired frequency
58 let clock_freq = embassy_rp::clocks::clk_sys_freq();
59 c.top = (clock_freq / pwm_freq) as u16 - 1;
60
61 let mut pwm = Pwm::new_output_a(slice2, pin4, c.clone());
62
63 loop {
64 // 100% duty cycle, fully on
65 pwm.set_duty_cycle_fully_on().unwrap();
66 Timer::after_secs(1).await;
67
68 // 66% duty cycle. Expressed as simple percentage.
69 pwm.set_duty_cycle_percent(66).unwrap();
70 Timer::after_secs(1).await;
71
72 // 25% duty cycle. Expressed as 32768/4 = 8192.
73 pwm.set_duty_cycle(c.top / 4).unwrap();
74 Timer::after_secs(1).await;
75
76 // 0% duty cycle, fully off.
77 pwm.set_duty_cycle_fully_off().unwrap();
78 Timer::after_secs(1).await;
79 }
80}
diff --git a/examples/rp23/src/bin/pwm_tb6612fng_motor_driver.rs b/examples/rp23/src/bin/pwm_tb6612fng_motor_driver.rs
new file mode 100644
index 000000000..3fad2928c
--- /dev/null
+++ b/examples/rp23/src/bin/pwm_tb6612fng_motor_driver.rs
@@ -0,0 +1,107 @@
1//! # PWM TB6612FNG motor driver
2//!
3//! This example shows the use of a TB6612FNG motor driver. The driver is built on top of embedded_hal and the example demonstrates how embassy_rp can be used to interact with ist.
4
5#![no_std]
6#![no_main]
7
8use assign_resources::assign_resources;
9use defmt::*;
10use embassy_executor::Spawner;
11use embassy_rp::block::ImageDef;
12use embassy_rp::config::Config;
13use embassy_rp::gpio::Output;
14use embassy_rp::{gpio, peripherals, pwm};
15use embassy_time::{Duration, Timer};
16use tb6612fng::{DriveCommand, Motor, Tb6612fng};
17use {defmt_rtt as _, panic_probe as _};
18
19#[link_section = ".start_block"]
20#[used]
21pub static IMAGE_DEF: ImageDef = ImageDef::secure_exe();
22
23assign_resources! {
24 motor: MotorResources {
25 standby_pin: PIN_22,
26 left_slice: PWM_SLICE6,
27 left_pwm_pin: PIN_28,
28 left_forward_pin: PIN_21,
29 left_backward_pin: PIN_20,
30 right_slice: PWM_SLICE5,
31 right_pwm_pin: PIN_27,
32 right_forward_pin: PIN_19,
33 right_backward_pin: PIN_18,
34 },
35}
36
37#[embassy_executor::main]
38async fn main(_spawner: Spawner) {
39 let p = embassy_rp::init(Config::default());
40 let s = split_resources!(p);
41 let r = s.motor;
42
43 // we want a PWM frequency of 1KHz, especially cheaper motors do not respond well to higher frequencies
44 let pwm_freq = 1_000; // Hz, our desired frequency
45 let clock_freq = embassy_rp::clocks::clk_sys_freq();
46 let period = (clock_freq / pwm_freq) as u16 - 1;
47
48 // we need a standby output and two motors to construct a full TB6612FNG
49
50 // standby pin
51 let stby = Output::new(r.standby_pin, gpio::Level::Low);
52
53 // motor A, here defined to be the left motor
54 let left_fwd = gpio::Output::new(r.left_forward_pin, gpio::Level::Low);
55 let left_bckw = gpio::Output::new(r.left_backward_pin, gpio::Level::Low);
56 let mut left_speed = pwm::Config::default();
57 left_speed.top = period;
58 let left_pwm = pwm::Pwm::new_output_a(r.left_slice, r.left_pwm_pin, left_speed);
59 let left_motor = Motor::new(left_fwd, left_bckw, left_pwm).unwrap();
60
61 // motor B, here defined to be the right motor
62 let right_fwd = gpio::Output::new(r.right_forward_pin, gpio::Level::Low);
63 let right_bckw = gpio::Output::new(r.right_backward_pin, gpio::Level::Low);
64 let mut right_speed = pwm::Config::default();
65 right_speed.top = period;
66 let right_pwm = pwm::Pwm::new_output_b(r.right_slice, r.right_pwm_pin, right_speed);
67 let right_motor = Motor::new(right_fwd, right_bckw, right_pwm).unwrap();
68
69 // construct the motor driver
70 let mut control = Tb6612fng::new(left_motor, right_motor, stby).unwrap();
71
72 loop {
73 // wake up the motor driver
74 info!("end standby");
75 control.disable_standby().unwrap();
76 Timer::after(Duration::from_millis(100)).await;
77
78 // drive a straight line forward at 20% speed for 5s
79 info!("drive straight");
80 control.motor_a.drive(DriveCommand::Forward(80)).unwrap();
81 control.motor_b.drive(DriveCommand::Forward(80)).unwrap();
82 Timer::after(Duration::from_secs(5)).await;
83
84 // coast for 2s
85 info!("coast");
86 control.motor_a.drive(DriveCommand::Stop).unwrap();
87 control.motor_b.drive(DriveCommand::Stop).unwrap();
88 Timer::after(Duration::from_secs(2)).await;
89
90 // actively brake
91 info!("brake");
92 control.motor_a.drive(DriveCommand::Brake).unwrap();
93 control.motor_b.drive(DriveCommand::Brake).unwrap();
94 Timer::after(Duration::from_secs(1)).await;
95
96 // slowly turn for 3s
97 info!("turn");
98 control.motor_a.drive(DriveCommand::Backward(50)).unwrap();
99 control.motor_b.drive(DriveCommand::Forward(50)).unwrap();
100 Timer::after(Duration::from_secs(3)).await;
101
102 // and put the driver in standby mode and wait for 5s
103 info!("standby");
104 control.enable_standby().unwrap();
105 Timer::after(Duration::from_secs(5)).await;
106 }
107}