diff options
| author | rafael <[email protected]> | 2024-10-20 23:28:47 +0200 |
|---|---|---|
| committer | rafael <[email protected]> | 2024-10-20 23:28:47 +0200 |
| commit | 7fc09f89e8e4b611a868bc986104762b1c5ba81a (patch) | |
| tree | 727067bbaced3aa804eb9145dd21717e37bd95aa /examples | |
| parent | c9358e1f1e5d88aa0ad998c44eb2da6be73cf477 (diff) | |
embassy_rp: implement pwm traits from embedded_hal
• Update crate versions • Implement embedded-hal PWM traits • Add TB6612FNG motor driver example
Diffstat (limited to 'examples')
| -rw-r--r-- | examples/rp23/Cargo.toml | 3 | ||||
| -rw-r--r-- | examples/rp23/src/bin/pwm_tb6612fng_motor_driver.rs | 114 |
2 files changed, 117 insertions, 0 deletions
diff --git a/examples/rp23/Cargo.toml b/examples/rp23/Cargo.toml index 08646463c..f35e3a11d 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 |
| 31 | assign-resources = { git = "https://github.com/adamgreig/assign-resources", rev = "94ad10e2729afdf0fd5a77cd12e68409a982f58a" } | 31 | assign-resources = { git = "https://github.com/adamgreig/assign-resources", rev = "94ad10e2729afdf0fd5a77cd12e68409a982f58a" } |
| 32 | 32 | ||
| 33 | # for TB6612FNG example | ||
| 34 | tb6612fng = "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"] } |
| 34 | cortex-m = { version = "0.7.6", features = ["inline-asm"] } | 37 | cortex-m = { version = "0.7.6", features = ["inline-asm"] } |
| 35 | cortex-m-rt = "0.7.0" | 38 | cortex-m-rt = "0.7.0" |
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..92c1ff6ba --- /dev/null +++ b/examples/rp23/src/bin/pwm_tb6612fng_motor_driver.rs | |||
| @@ -0,0 +1,114 @@ | |||
| 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 | |||
| 8 | use defmt::*; | ||
| 9 | use embassy_executor::Spawner; | ||
| 10 | use embassy_rp::block::ImageDef; | ||
| 11 | use embassy_rp::config::Config; | ||
| 12 | use embassy_rp::gpio::Output; | ||
| 13 | use embassy_rp::peripherals; | ||
| 14 | use embassy_rp::gpio; | ||
| 15 | use embassy_rp::pwm; | ||
| 16 | use embassy_time::Duration; | ||
| 17 | use embassy_time::Timer; | ||
| 18 | use {defmt_rtt as _, panic_probe as _}; | ||
| 19 | use tb6612fng::{DriveCommand, Motor, Tb6612fng}; | ||
| 20 | use assign_resources::assign_resources; | ||
| 21 | |||
| 22 | /// Maximum PWM value (fully on) | ||
| 23 | const PWM_MAX: u16 = 50000; | ||
| 24 | |||
| 25 | /// Minimum PWM value (fully off) | ||
| 26 | const PWM_MIN: u16 = 0; | ||
| 27 | |||
| 28 | #[link_section = ".start_block"] | ||
| 29 | #[used] | ||
| 30 | pub static IMAGE_DEF: ImageDef = ImageDef::secure_exe(); | ||
| 31 | |||
| 32 | assign_resources! { | ||
| 33 | motor: MotorResources { | ||
| 34 | standby_pin: PIN_22, | ||
| 35 | left_slice: PWM_SLICE6, | ||
| 36 | left_pwm_pin: PIN_28, | ||
| 37 | left_forward_pin: PIN_21, | ||
| 38 | left_backward_pin: PIN_20, | ||
| 39 | right_slice: PWM_SLICE5, | ||
| 40 | right_pwm_pin: PIN_27, | ||
| 41 | right_forward_pin: PIN_19, | ||
| 42 | right_backward_pin: PIN_18, | ||
| 43 | }, | ||
| 44 | } | ||
| 45 | |||
| 46 | #[embassy_executor::main] | ||
| 47 | async fn main(_spawner: Spawner) { | ||
| 48 | let p = embassy_rp::init(Config::default()); | ||
| 49 | let s = split_resources!(p); | ||
| 50 | let r = s.motor; | ||
| 51 | |||
| 52 | // we need a standby output and two motors to construct a full TB6612FNG | ||
| 53 | |||
| 54 | // standby pin | ||
| 55 | let stby = Output::new(r.standby_pin, gpio::Level::Low); | ||
| 56 | |||
| 57 | // motor A, here defined to be the left motor | ||
| 58 | let left_fwd = gpio::Output::new(r.left_forward_pin, gpio::Level::Low); | ||
| 59 | let left_bckw = gpio::Output::new(r.left_backward_pin, gpio::Level::Low); | ||
| 60 | let mut left_speed = pwm::Config::default(); | ||
| 61 | left_speed.top = PWM_MAX; | ||
| 62 | left_speed.compare_a = PWM_MIN; | ||
| 63 | let left_pwm = pwm::Pwm::new_output_a(r.left_slice, r.left_pwm_pin, left_speed); | ||
| 64 | let left_motor = Motor::new(left_fwd, left_bckw, left_pwm).unwrap(); | ||
| 65 | |||
| 66 | // motor B, here defined to be the right motor | ||
| 67 | let right_fwd = gpio::Output::new(r.right_forward_pin, gpio::Level::Low); | ||
| 68 | let right_bckw = gpio::Output::new(r.right_backward_pin, gpio::Level::Low); | ||
| 69 | let mut right_speed = pwm::Config::default(); | ||
| 70 | right_speed.top = PWM_MAX; | ||
| 71 | right_speed.compare_b = PWM_MIN; | ||
| 72 | let right_pwm = pwm::Pwm::new_output_b(r.right_slice, r.right_pwm_pin, right_speed); | ||
| 73 | let right_motor = Motor::new(right_fwd, right_bckw, right_pwm).unwrap(); | ||
| 74 | |||
| 75 | // construct the motor driver | ||
| 76 | let mut control = Tb6612fng::new(left_motor, right_motor, stby).unwrap(); | ||
| 77 | |||
| 78 | loop { | ||
| 79 | // wake up the motor driver | ||
| 80 | info!("end standby"); | ||
| 81 | control.disable_standby().unwrap(); | ||
| 82 | Timer::after(Duration::from_millis(100)).await; | ||
| 83 | |||
| 84 | // drive a straight line forward at 20% speed for 5s | ||
| 85 | info!("drive straight"); | ||
| 86 | control.motor_a.drive(DriveCommand::Forward(20)).unwrap(); | ||
| 87 | control.motor_b.drive(DriveCommand::Forward(20)).unwrap(); | ||
| 88 | Timer::after(Duration::from_secs(5)).await; | ||
| 89 | |||
| 90 | // coast for 2s | ||
| 91 | info!("coast"); | ||
| 92 | control.motor_a.drive(DriveCommand::Stop).unwrap(); | ||
| 93 | control.motor_b.drive(DriveCommand::Stop).unwrap(); | ||
| 94 | Timer::after(Duration::from_secs(2)).await; | ||
| 95 | |||
| 96 | // actively brake | ||
| 97 | info!("brake"); | ||
| 98 | control.motor_a.drive(DriveCommand::Brake).unwrap(); | ||
| 99 | control.motor_b.drive(DriveCommand::Brake).unwrap(); | ||
| 100 | Timer::after(Duration::from_secs(1)).await; | ||
| 101 | |||
| 102 | // slowly turn for 3s | ||
| 103 | info!( "turn"); | ||
| 104 | control.motor_a.drive(DriveCommand::Backward(10)).unwrap(); | ||
| 105 | control.motor_b.drive(DriveCommand::Forward(10)).unwrap(); | ||
| 106 | Timer::after(Duration::from_secs(3)).await; | ||
| 107 | |||
| 108 | // and put the driver in standby mode and wait for 5s | ||
| 109 | info!( "standby"); | ||
| 110 | control.enable_standby().unwrap(); | ||
| 111 | Timer::after(Duration::from_secs(5)).await; | ||
| 112 | } | ||
| 113 | } | ||
| 114 | |||
