From 0fba15f32f14569156cf4285867d234f1fa4406d Mon Sep 17 00:00:00 2001 From: Andelf Date: Tue, 5 Dec 2023 12:35:07 +0800 Subject: [PATCH] fix: compile error --- examples/adc_pin.rs | 5 +- examples/adc_temp.rs | 11 +- examples/ble-peripheral-devinfo.rs | 555 ----------------------------- examples/ble-peripheral-simple.rs | 536 ---------------------------- examples/ble-peripheral.rs | 27 +- examples/blinky.rs | 3 - examples/empty.rs | 5 +- examples/flashisp.rs | 5 +- examples/gpio_int.rs | 102 ------ examples/hardfault.rs | 5 +- examples/i2c-mpu6050.rs | 8 +- examples/serial.rs | 8 +- examples/spi-ssd1306.rs | 9 +- examples/yd-ch582m.rs | 5 +- 14 files changed, 27 insertions(+), 1257 deletions(-) delete mode 100644 examples/ble-peripheral-devinfo.rs delete mode 100644 examples/ble-peripheral-simple.rs delete mode 100644 examples/gpio_int.rs diff --git a/examples/adc_pin.rs b/examples/adc_pin.rs index 5e6a4eb..6d88068 100644 --- a/examples/adc_pin.rs +++ b/examples/adc_pin.rs @@ -13,7 +13,6 @@ use hal::interrupt::Interrupt; use hal::isp::EEPROM_BLOCK_SIZE; use hal::rtc::{DateTime, Rtc}; use hal::sysctl::Config; -use hal::systick::SysTick; use hal::uart::UartTx; use hal::{pac, peripherals, Peripherals}; use {ch58x_hal as hal, panic_halt as _}; @@ -25,8 +24,6 @@ fn main() -> ! { let p = hal::init(config); - let mut delay = SysTick::new(p.SYSTICK); - // LED PA8 let mut blue_led = Output::new(p.PA8, Level::Low, OutputDrive::_5mA); @@ -80,6 +77,6 @@ fn main() -> ! { ) .unwrap(); - delay.delay_ms(1000); + hal::delay_ms(1000); } } diff --git a/examples/adc_temp.rs b/examples/adc_temp.rs index 94c5b95..7a9d594 100644 --- a/examples/adc_temp.rs +++ b/examples/adc_temp.rs @@ -13,7 +13,6 @@ use hal::interrupt::Interrupt; use hal::isp::EEPROM_BLOCK_SIZE; use hal::rtc::{DateTime, Rtc}; use hal::sysctl::Config; -use hal::systick::SysTick; use hal::uart::UartTx; use hal::{pac, peripherals, Peripherals}; use {ch58x_hal as hal, panic_halt as _}; @@ -25,8 +24,6 @@ fn main() -> ! { let p = hal::init(config); - let mut delay = SysTick::new(p.SYSTICK); - // LED PA8 let mut blue_led = Output::new(p.PA8, Level::Low, OutputDrive::_5mA); @@ -36,7 +33,7 @@ fn main() -> ! { let mut reset_button = Input::new(p.PB23, Pull::Up); let mut rtc = Rtc {}; - serial.blocking_flush(); + serial.blocking_flush().unwrap(); // rtc.set_datatime(DateTime { // year: 2023, // month: 10, @@ -48,7 +45,7 @@ fn main() -> ! { writeln!(serial, "\n\n\nHello World!").unwrap(); writeln!(serial, "Clocks: {}", hal::sysctl::clocks().hclk).unwrap(); - writeln!(serial, "ChipID: {:02x}", hal::signature::get_chip_id()); + writeln!(serial, "ChipID: {:02x}", hal::signature::get_chip_id()).unwrap(); let now = rtc.now(); writeln!(serial, "Boot time: {} weekday={}", now, now.isoweekday()).unwrap(); @@ -59,7 +56,7 @@ fn main() -> ! { // writeln!(serial, "mias: 0x{:08x?}", mias.bits()); // ADC part - let mut adc_config = hal::adc::Config::for_temperature(); + let adc_config = hal::adc::Config::for_temperature(); let mut adc = Adc::new(p.ADC, adc_config); let mut temp_sensor = adc.enable_temperature(); @@ -87,6 +84,6 @@ fn main() -> ! { ) .unwrap(); - delay.delay_ms(1000); + hal::delay_ms(1000); } } diff --git a/examples/ble-peripheral-devinfo.rs b/examples/ble-peripheral-devinfo.rs deleted file mode 100644 index 4490c49..0000000 --- a/examples/ble-peripheral-devinfo.rs +++ /dev/null @@ -1,555 +0,0 @@ -//! Device Info Peripheral - -#![no_std] -#![no_main] -#![feature(type_alias_impl_trait)] - -use core::mem::size_of_val; -use core::sync::atomic::AtomicBool; -use core::{ptr, slice}; - -use ch32v_rt::highcode; -use ch58x_hal as hal; -use embassy_executor::Spawner; -use embassy_futures::select::{select, Either}; -use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex; -use embassy_sync::channel::Channel; -use embassy_time::{Duration, Ticker, Timer}; -use hal::ble::ffi::*; -use hal::ble::gap::*; -use hal::ble::gatt::*; -use hal::ble::gattservapp::{gattServiceCBs_t, GATTServApp}; -use hal::ble::{gatt_uuid, TmosEvent}; -use hal::gpio::{AnyPin, Level, Output, OutputDrive, Pin}; -use hal::rtc::Rtc; -use hal::uart::UartTx; -use hal::{ble, peripherals, println}; - -const fn lo_u16(x: u16) -> u8 { - (x & 0xff) as u8 -} -const fn hi_u16(x: u16) -> u8 { - (x >> 8) as u8 -} - -// GAP - SCAN RSP data (max size = 31 bytes) -static mut SCAN_RSP_DATA: &[u8] = &[ - // complete name - 0x12, // length of this data - GAP_ADTYPE_LOCAL_NAME_COMPLETE, - b'S', - b'i', - b'm', - b'p', - b'l', - b'e', - b' ', - b'P', - b'e', - b'r', - b'i', - b'p', - b'h', - b'e', - b'r', - b'a', - b'l', - // Connection interval range - 0x05, - GAP_ADTYPE_SLAVE_CONN_INTERVAL_RANGE, - lo_u16(80), // units of 1.25ms, 80=100ms - hi_u16(80), - lo_u16(800), // units of 1.25ms, 800=1000ms - hi_u16(800), - // Tx power level - 0x02, // length of this data - GAP_ADTYPE_POWER_LEVEL, - 0, // 0dBm -]; - -// const SIMPLEPROFILE_SERV_UUID: u16 = 0xFFE0; - -// GAP - Advertisement data (max size = 31 bytes, though this is -// best kept short to conserve power while advertisting) -#[rustfmt::skip] -static mut ADVERT_DATA: &[u8] = &[ - 0x02, // length of this data - GAP_ADTYPE_FLAGS, - GAP_ADTYPE_FLAGS_BREDR_NOT_SUPPORTED, - // https://www.bluetooth.com/specifications/assigned-numbers/ - 0x04, // length of this data including the data type byte - GAP_ADTYPE_MANUFACTURER_SPECIFIC, // manufacturer specific advertisement data type - lo_u16(0x07D7), // 0x07D7, Nanjing Qinheng Microelectronics Co., Ltd. - hi_u16(0x07D7), - 0x01, // remains manufacturer specific data - - // service UUID, to notify central devices what services are included - // in this peripheral - // 0x03, // length of this data - // GAP_ADTYPE_16BIT_MORE, // some of the UUID's, but not all - // lo_u16(SIMPLEPROFILE_SERV_UUID), - // hi_u16(SIMPLEPROFILE_SERV_UUID), -]; - -// GAP GATT Attributes -// len = 21 GAP_DEVICE_NAME_LEN -// max_len = 248 -static ATT_DEVICE_NAME: &[u8] = b"ch58x-hal peripheral"; - -// System ID characteristic -const DEVINFO_SYSTEM_ID_LEN: usize = 8; - -static mut SYSTEM_ID: [u8; 8] = [0u8; 8]; -// The list must start with a Service attribute followed by -// all attributes associated with this Service attribute. -// Must use static mut fixed sized array, as it will be changed by Service to assign handles. -static mut DEVICE_INFO_TABLE: [GattAttribute; 7] = - [ - // Device Information Service - GattAttribute { - type_: GattAttrType { - len: ATT_BT_UUID_SIZE, - uuid: unsafe { gatt_uuid::primaryServiceUUID.as_ptr() }, - }, - permissions: GATT_PERMIT_READ, - handle: 0, - // The first must be a Service attribute - value: &GattAttrType { - len: ATT_BT_UUID_SIZE, - uuid: &gatt_uuid::DEVINFO_SERV_UUID as *const _ as _, - } as *const _ as _, - }, - // System ID Declaration - GattAttribute { - type_: GattAttrType { - len: ATT_BT_UUID_SIZE, - uuid: unsafe { gatt_uuid::characterUUID.as_ptr() }, - }, - permissions: GATT_PERMIT_READ, - handle: 0, - value: &GATT_PROP_READ as *const _ as _, - }, - // System ID Value - GattAttribute { - type_: GattAttrType { - len: ATT_BT_UUID_SIZE, - uuid: &gatt_uuid::SYSTEM_ID_UUID as *const _ as _, - }, - permissions: GATT_PERMIT_READ, - handle: 0, - value: unsafe { SYSTEM_ID.as_ptr() }, - }, - // Serial Number String Declaration - GattAttribute { - type_: GattAttrType { - len: ATT_BT_UUID_SIZE, - uuid: unsafe { gatt_uuid::characterUUID.as_ptr() }, - }, - permissions: GATT_PERMIT_READ, - handle: 0, - value: &GATT_PROP_READ as *const _ as _, - }, - // Serial Number Value - GattAttribute { - type_: GattAttrType { - len: ATT_BT_UUID_SIZE, - uuid: &gatt_uuid::SERIAL_NUMBER_UUID as *const _ as _, - }, - permissions: GATT_PERMIT_READ, - handle: 0, - value: ptr::null(), - }, - // Temperature - GattAttribute { - type_: GattAttrType { - len: ATT_BT_UUID_SIZE, - uuid: unsafe { gatt_uuid::characterUUID.as_ptr() }, - }, - permissions: GATT_PERMIT_READ, - handle: 0, - value: &GATT_PROP_READ as *const _ as _, - }, - // Serial Number Value - GattAttribute { - type_: GattAttrType { - len: ATT_BT_UUID_SIZE, - uuid: &gatt_uuid::TEMP_UUID as *const _ as _, - }, - permissions: GATT_PERMIT_READ, - handle: 0, - value: ptr::null(), - }, - ]; - -#[inline] -unsafe fn devinfo_init() { - // Setup the GAP Peripheral Role Profile - { - // Set the GAP Role Parameters - let _ = GAPRole_SetParameter(GAPROLE_ADVERT_ENABLED, 1, &true as *const _ as _); - let _ = GAPRole_SetParameter( - GAPROLE_SCAN_RSP_DATA, - SCAN_RSP_DATA.len() as _, - SCAN_RSP_DATA.as_ptr() as _, - ); - let _ = GAPRole_SetParameter(GAPROLE_ADVERT_DATA, ADVERT_DATA.len() as _, ADVERT_DATA.as_ptr() as _); - } - - // Set the GAP Characteristics - let _ = GGS_SetParameter( - GGS_DEVICE_NAME_ATT, - ATT_DEVICE_NAME.len() as _, - ATT_DEVICE_NAME.as_ptr() as _, - ); - - // Setup the GAP Bond Manager - { - let passkey: u32 = 0; // passkey "000000" - let pair_mode = GAPBOND_PAIRING_MODE_WAIT_FOR_REQ; - let mitm = false; - let bonding = true; - let io_cap = GAPBOND_IO_CAP_DISPLAY_ONLY; // display only device - let _ = GAPBondMgr_SetParameter( - GAPBOND_PERI_DEFAULT_PASSCODE, - size_of_val(&passkey) as _, - &passkey as *const _ as _, - ); - let _ = GAPBondMgr_SetParameter(GAPBOND_PERI_PAIRING_MODE, 1, &pair_mode as *const _ as _); - let _ = GAPBondMgr_SetParameter(GAPBOND_PERI_MITM_PROTECTION, 1, &mitm as *const _ as _); - let _ = GAPBondMgr_SetParameter(GAPBOND_PERI_IO_CAPABILITIES, 1, &io_cap as *const _ as _); - let _ = GAPBondMgr_SetParameter(GAPBOND_PERI_BONDING_ENABLED, 1, &bonding as *const _ as _); - } - - // Initialize GATT attributes - { - let _ = GGS_AddService(GATT_ALL_SERVICES).unwrap(); // GAP - let _ = GATTServApp::add_service(GATT_ALL_SERVICES).unwrap(); // GATT attributes - } - // DevInfo_AddService - unsafe { - unsafe extern "C" fn dev_info_on_read_attr( - _conn_handle: u16, - attr: *mut GattAttribute, - value: *mut u8, - plen: *mut u16, - _offset: u16, - max_len: u16, - _method: u8, - ) -> u8 { - let raw_uuid = slice::from_raw_parts((*attr).type_.uuid, 2); - let uuid = u16::from_le_bytes([raw_uuid[0], raw_uuid[1]]); - println!("! on_read_attr UUID: 0x{:04x}", uuid); - - match uuid { - gatt_uuid::SYSTEM_ID_UUID => { - *plen = DEVINFO_SYSTEM_ID_LEN as _; - ptr::copy(SYSTEM_ID.as_ptr(), value, DEVINFO_SYSTEM_ID_LEN); - } - gatt_uuid::SERIAL_NUMBER_UUID => { - let out = b"No. 9527"; - *plen = out.len() as _; - core::ptr::copy(out.as_ptr(), value, out.len()); - } - gatt_uuid::TEMP_UUID => { - println!("temp uuid {:04x} {:p} {}", uuid, value, max_len); - let val: i16 = 32_00; // 0.01 degC - *plen = size_of_val(&val) as _; - core::ptr::copy(&val as *const _ as _, value, *plen as _); - } - _ => { - return ATT_ERR_ATTR_NOT_FOUND; - } - } - - return 0; - } - static DEV_INFO_SERVICE_CB: gattServiceCBs_t = gattServiceCBs_t { - pfnReadAttrCB: Some(dev_info_on_read_attr), - pfnWriteAttrCB: None, - pfnAuthorizeAttrCB: None, - }; - - // DevInfo_AddService(); // Device Information Service - // might fail, must check - GATTServApp::register_service( - &mut DEVICE_INFO_TABLE[..], - GATT_MAX_ENCRYPT_KEY_SIZE, - &DEV_INFO_SERVICE_CB, - ) - .unwrap(); - } -} - -pub enum AppEvent { - Connected(u16), -} - -static APP_CHANNEL: Channel = Channel::new(); - -/// Default desired minimum connection interval (units of 1.25ms) -const DEFAULT_DESIRED_MIN_CONN_INTERVAL: u16 = 20; -/// Default desired maximum connection interval (units of 1.25ms) -const DEFAULT_DESIRED_MAX_CONN_INTERVAL: u16 = 160; -/// Default desired slave latency to use if parameter update request -const DEFAULT_DESIRED_SLAVE_LATENCY: u16 = 1; -/// Default supervision timeout value (units of 10ms) -const DEFAULT_DESIRED_CONN_TIMEOUT: u16 = 1000; - -async fn peripheral(spawner: Spawner, task_id: u8, mut subscriber: ble::EventSubscriber) -> ! { - // Profile State Change Callbacks - unsafe extern "C" fn on_gap_state_change(new_state: gapRole_States_t, event: *mut gapRoleEvent_t) { - println!("in on_gap_state_change: {}", new_state); - let event = &*event; - - // state machine, requires last state - static mut LAST_STATE: gapRole_States_t = GAPROLE_INIT; - - // time units 625us - const DEFAULT_FAST_ADV_INTERVAL: u16 = 32; - const DEFAULT_FAST_ADV_DURATION: u16 = 30000; - - const DEFAULT_SLOW_ADV_INTERVAL: u16 = 1600; - const DEFAULT_SLOW_ADV_DURATION: u16 = 0; // continuous - - match new_state { - GAPROLE_CONNECTED => { - // Peripheral_LinkEstablished - if event.gap.opcode == GAP_LINK_ESTABLISHED_EVENT { - println!("connected.. !!"); - let conn_handle = event.linkCmpl.connectionHandle; - - let _ = APP_CHANNEL.try_send(AppEvent::Connected(conn_handle)); - } - } - // if disconnected - _ if LAST_STATE == GAPROLE_CONNECTED && new_state != GAPROLE_CONNECTED => { - // link loss -- use fast advertising - let _ = GAP_SetParamValue(TGAP_DISC_ADV_INT_MIN, DEFAULT_FAST_ADV_INTERVAL); - let _ = GAP_SetParamValue(TGAP_DISC_ADV_INT_MAX, DEFAULT_FAST_ADV_INTERVAL); - let _ = GAP_SetParamValue(TGAP_GEN_DISC_ADV_MIN, DEFAULT_FAST_ADV_DURATION); - - // Enable advertising - let _ = GAPRole_SetParameter(GAPROLE_ADVERT_ENABLED, 1, &true as *const _ as _); - } - // if advertising stopped - GAPROLE_WAITING if LAST_STATE == GAPROLE_ADVERTISING => { - // if fast advertising switch to slow - if GAP_GetParamValue(TGAP_DISC_ADV_INT_MIN) == DEFAULT_FAST_ADV_INTERVAL { - let _ = GAP_SetParamValue(TGAP_DISC_ADV_INT_MIN, DEFAULT_SLOW_ADV_INTERVAL); - let _ = GAP_SetParamValue(TGAP_DISC_ADV_INT_MAX, DEFAULT_SLOW_ADV_INTERVAL); - let _ = GAP_SetParamValue(TGAP_GEN_DISC_ADV_MIN, DEFAULT_SLOW_ADV_DURATION); - let _ = GAPRole_SetParameter(GAPROLE_ADVERT_ENABLED, 1, &true as *const _ as _); - } - } - // if started - GAPROLE_STARTED => { - println!("initialized.."); - let mut system_id = [0u8; 8]; // DEVINFO_SYSTEM_ID_LEN - GAPRole_GetParameter(GAPROLE_BD_ADDR, system_id.as_mut_ptr() as _).unwrap(); - - // shift three bytes up - system_id[7] = system_id[5]; - system_id[6] = system_id[4]; - system_id[5] = system_id[3]; - - // set middle bytes to zero - system_id[4] = 0; - system_id[3] = 0; - - ptr::copy(system_id.as_ptr(), SYSTEM_ID.as_mut_ptr(), 8); - } - _ => { - println!("!!! on_state_change unhandled state: {}", new_state); - } - } - - LAST_STATE = new_state; - } - - // Deivce start - unsafe { - static BOND_CB: gapBondCBs_t = gapBondCBs_t { - passcodeCB: None, - pairStateCB: None, - oobCB: None, - }; - // peripheralStateNotificationCB - static APP_CB: gapRolesCBs_t = gapRolesCBs_t { - pfnStateChange: Some(on_gap_state_change), - pfnRssiRead: None, - pfnParamUpdate: None, - }; - // Start the Device - let r = GAPRole_PeripheralStartDevice(task_id, &BOND_CB, &APP_CB); - println!("Start device {:?}", r); - } - - loop { - match select(subscriber.next_message_pure(), APP_CHANNEL.receive()).await { - Either::First(event) => { - handle_tmos_event(&event).await; - } - Either::Second(event) => match event { - AppEvent::Connected(conn_handle) => unsafe { - // 1600 * 625 us - Timer::after(Duration::from_secs(1)).await; // FIXME: spawn handler - - GAPRole_PeripheralConnParamUpdateReq( - conn_handle, - DEFAULT_DESIRED_MIN_CONN_INTERVAL, - DEFAULT_DESIRED_MAX_CONN_INTERVAL, - DEFAULT_DESIRED_SLAVE_LATENCY, - DEFAULT_DESIRED_CONN_TIMEOUT, - task_id, - ) - .unwrap(); - }, - }, - } - } -} - -async fn handle_tmos_event(event: &TmosEvent) { - match event.message_id() { - TmosEvent::GAP_MSG_EVENT => { - // Peripheral_ProcessGAPMsg - let msg = event.0 as *const gapRoleEvent_t; - - let opcode = unsafe { (*msg).gap.opcode }; - match opcode { - GAP_SCAN_REQUEST_EVENT => { - println!( - "GAP scan request from {:02x}:{:02x}:{:02x}:{:02x}:{:02x}:{:02x} ...", - (*msg).scanReqEvt.scannerAddr[0], - (*msg).scanReqEvt.scannerAddr[1], - (*msg).scanReqEvt.scannerAddr[2], - (*msg).scanReqEvt.scannerAddr[3], - (*msg).scanReqEvt.scannerAddr[4], - (*msg).scanReqEvt.scannerAddr[5], - ); - } - GAP_PHY_UPDATE_EVENT => { - println!( - "GAP phy update Rx:{:x} Tx:{:x}", - (*msg).linkPhyUpdate.connRxPHYS, - (*msg).linkPhyUpdate.connTxPHYS, - ); - } - GAP_LINK_PARAM_UPDATE_EVENT => { - println!( - "GAP link param update status: {:x} interval: {:x} latency: {:x} timeout: {:x}", - (*msg).linkUpdate.status, - (*msg).linkUpdate.connInterval, - (*msg).linkUpdate.connLatency, - (*msg).linkUpdate.connTimeout, - ); - } - _ => { - println!("GAP MSG EVENT: {:p} {:x}", msg, opcode); - } - } - } - TmosEvent::GATT_MSG_EVENT => { - let msg = event.0 as *const gattMsgEvent_t; - let method = unsafe { (*msg).method }; - println!("GATT_MSG_EVENT: {:p} {:x}", msg, method); - } - _ => { - println!("peripheral got event: {:?} id=0x{:02x}", event, event.message_id()); - } - } -} - -#[embassy_executor::main(entry = "ch32v_rt::entry")] -async fn main(spawner: Spawner) -> ! { - use hal::ble::ffi::*; - - let mut config = hal::Config::default(); - config.clock.use_pll_60mhz().enable_lse(); - let p = hal::init(config); - hal::embassy::init(); - - let uart = UartTx::new(p.UART1, p.PA9, Default::default()).unwrap(); - unsafe { - hal::set_default_serial(uart); - } - - let rtc = Rtc::new(p.RTC); - - println!(); - println!("Hello World from ch58x-hal!"); - println!( - r#" - ______ __ - / ____/___ ___ / /_ ____ _____________ __ - / __/ / __ `__ \/ __ \/ __ `/ ___/ ___/ / / / - / /___/ / / / / / /_/ / /_/ (__ |__ ) /_/ / -/_____/_/ /_/ /_/_.___/\__,_/____/____/\__, / - /____/ on CH582"# - ); - println!("System Clocks: {}", hal::sysctl::clocks().hclk); - println!("ChipID: 0x{:02x}", hal::signature::get_chip_id()); - println!("RTC datetime: {}", rtc.now()); - println!("MemFree: {}K", hal::stack_free() / 1024); - - spawner.spawn(blink(p.PA8.degrade())).unwrap(); - - // BLE part - println!("BLE Lib Version: {}", ble::lib_version()); - - let mut ble_config = ble::Config::default(); - ble_config.pa_config = None; - let (task_id, sub) = hal::ble::init(ble_config).unwrap(); - println!("BLE hal task id: {}", task_id); - - unsafe { - let _ = GAPRole_PeripheralInit().unwrap(); - } - - unsafe { - devinfo_init(); - } - - // Main_Circulation - spawner.spawn(tmos_mainloop()).unwrap(); - - // Application code - peripheral(spawner, task_id, sub).await -} - -#[highcode] -#[embassy_executor::task] -async fn tmos_mainloop() { - let mut ticker = Ticker::every(Duration::from_micros(300)); - loop { - ticker.next().await; - unsafe { - TMOS_SystemProcess(); - } - } -} - -#[embassy_executor::task] -async fn blink(pin: AnyPin) { - let mut led = Output::new(pin, Level::Low, OutputDrive::_5mA); - - loop { - led.set_high(); - Timer::after(Duration::from_millis(150)).await; - led.set_low(); - Timer::after(Duration::from_millis(150)).await; - } -} - -#[panic_handler] -fn panic(info: &core::panic::PanicInfo) -> ! { - use core::fmt::Write; - - let pa9 = unsafe { peripherals::PA9::steal() }; - let uart1 = unsafe { peripherals::UART1::steal() }; - let mut serial = UartTx::new(uart1, pa9, Default::default()).unwrap(); - - let _ = writeln!(&mut serial, "\n\n\n{}", info); - - loop {} -} diff --git a/examples/ble-peripheral-simple.rs b/examples/ble-peripheral-simple.rs deleted file mode 100644 index 367c7d8..0000000 --- a/examples/ble-peripheral-simple.rs +++ /dev/null @@ -1,536 +0,0 @@ -#![no_std] -#![no_main] -#![feature(type_alias_impl_trait)] - -use core::ffi::c_void; -use core::mem::size_of_val; -use core::slice; - -use ch32v_rt::highcode; -use ch58x_hal as hal; -use embassy_executor::Spawner; -use embassy_futures::select::{select, Either}; -use embassy_sync::blocking_mutex::raw::{CriticalSectionRawMutex, NoopRawMutex}; -use embassy_sync::channel::Channel; -use embassy_time::{Delay, Duration, Instant, Ticker, Timer}; -use embedded_hal_02::timer::Periodic; -use hal::ble::ffi::*; -use hal::ble::gap::*; -use hal::ble::gatt::gattMsgEvent_t; -use hal::ble::TmosEvent; -use hal::gpio::{AnyPin, Input, Level, Output, OutputDrive, Pin, Pull}; -use hal::interrupt::Interrupt; -use hal::prelude::*; -use hal::rtc::Rtc; -use hal::uart::UartTx; -use hal::{ble, peripherals, println}; - -const fn lo_u16(x: u16) -> u8 { - (x & 0xff) as u8 -} -const fn hi_u16(x: u16) -> u8 { - (x >> 8) as u8 -} - -// GAP - SCAN RSP data (max size = 31 bytes) -static mut SCAN_RSP_DATA: &[u8] = &[ - // complete name - 0x12, // length of this data - GAP_ADTYPE_LOCAL_NAME_COMPLETE, - b'S', - b'i', - b'm', - b'p', - b'l', - b'e', - b' ', - b'P', - b'e', - b'r', - b'i', - b'p', - b'h', - b'e', - b'r', - b'a', - b'l', - // Connection interval range - 0x05, - GAP_ADTYPE_SLAVE_CONN_INTERVAL_RANGE, - lo_u16(80), // units of 1.25ms, 80=100ms - hi_u16(80), - lo_u16(800), // units of 1.25ms, 800=1000ms - hi_u16(800), - // Tx power level - 0x02, // length of this data - GAP_ADTYPE_POWER_LEVEL, - 0, // 0dBm -]; - -const SIMPLEPROFILE_SERV_UUID: u16 = 0xFFE0; - -// GAP - Advertisement data (max size = 31 bytes, though this is -// best kept short to conserve power while advertisting) -static mut ADVERT_DATA: &[u8] = &[ - 0x02, // length of this data - GAP_ADTYPE_FLAGS, - GAP_ADTYPE_FLAGS_BREDR_NOT_SUPPORTED, - // https://www.bluetooth.com/specifications/assigned-numbers/ - 0x04, // length of this data including the data type byte - GAP_ADTYPE_MANUFACTURER_SPECIFIC, // manufacturer specific advertisement data type - lo_u16(0x07D7), // 0x07D7, Nanjing Qinheng Microelectronics Co., Ltd. - hi_u16(0x07D7), - 0x01, // remains manufacturer specific data - // service UUID, to notify central devices what services are included - // in this peripheral - 0x03, // length of this data - GAP_ADTYPE_16BIT_MORE, // some of the UUID's, but not all - lo_u16(SIMPLEPROFILE_SERV_UUID), - hi_u16(SIMPLEPROFILE_SERV_UUID), -]; - -// GAP GATT Attributes -// len = 21 GAP_DEVICE_NAME_LEN -// max_len = 248 -static ATT_DEVICE_NAME: &[u8] = b"ch58x-hal peripheral"; - -// device info service - -static DEV_INFO_SERVICE: gattAttrType_t = gattAttrType_t { - len: ATT_BT_UUID_SIZE, - uuid: unsafe { primaryServiceUUID.as_ptr() }, -}; - -// System ID characteristic -const DEVINFO_SYSTEM_ID_LEN: usize = 8; - -// The list must start with a Service attribute followed by -// all attributes associated with this Service attribute. -static DEVICE_INFO_TABLE: &[GattAttribute] = &[ - // Device Information Service - GattAttribute { - type_: gattAttrType_t { - len: ATT_BT_UUID_SIZE, - uuid: unsafe { primaryServiceUUID.as_ptr() }, - }, - permissions: GATT_PERMIT_READ, - handle: 0, - value: &DEV_INFO_SERVICE as *const _ as _, - }, - // System ID Declaration - GattAttribute { - type_: gattAttrType_t { - len: ATT_BT_UUID_SIZE, - uuid: unsafe { characterUUID.as_ptr() }, - }, - permissions: GATT_PERMIT_READ, - handle: 0, - value: &GATT_PROP_READ as *const _ as _, - }, - // System ID Value - GattAttribute { - type_: gattAttrType_t { - len: ATT_BT_UUID_SIZE, - uuid: &hal::ble::gatt_uuid::SYSTEM_ID_UUID as *const _ as _, - }, - permissions: GATT_PERMIT_READ, - handle: 0, - value: [0, 0, 0, 0, 0, 0, 0, 0].as_ptr() as *const _ as _, // 8 bytes - }, - // Serial Number String Declaration - GattAttribute { - type_: gattAttrType_t { - len: ATT_BT_UUID_SIZE, - uuid: unsafe { characterUUID.as_ptr() }, - }, - permissions: GATT_PERMIT_READ, - handle: 0, - value: &GATT_PROP_READ as *const _ as _, - }, - // Serial Number Value - GattAttribute { - type_: gattAttrType_t { - len: ATT_BT_UUID_SIZE, - uuid: &hal::ble::gatt_uuid::SERIAL_NUMBER_UUID as *const _ as _, - }, - permissions: GATT_PERMIT_READ, - handle: 0, - value: b"Serial Number xxxx\0".as_ptr() as *const _ as _, - }, -]; - -fn peripheral_init() { - // Setup the GAP Peripheral Role Profile - unsafe { - // interval unit 1.25ms - const MIN_INTERVAL: u16 = 6; // 6*1.25 = 7.5ms - const MAX_INTERVAL: u16 = 100; // 100*1.25 = 125ms - - // Set the GAP Role Parameters - GAPRole_SetParameter(GAPROLE_ADVERT_ENABLED, 1, &true as *const _ as _); - GAPRole_SetParameter( - GAPROLE_SCAN_RSP_DATA, - SCAN_RSP_DATA.len() as _, - SCAN_RSP_DATA.as_ptr() as _, - ); - GAPRole_SetParameter(GAPROLE_ADVERT_DATA, ADVERT_DATA.len() as _, ADVERT_DATA.as_ptr() as _); - GAPRole_SetParameter(GAPROLE_MIN_CONN_INTERVAL, 2, &MIN_INTERVAL as *const _ as _); - GAPRole_SetParameter(GAPROLE_MAX_CONN_INTERVAL, 2, &MAX_INTERVAL as *const _ as _); - } - - // Set the GAP Characteristics - unsafe { - GGS_SetParameter( - GGS_DEVICE_NAME_ATT, - ATT_DEVICE_NAME.len() as _, - ATT_DEVICE_NAME.as_ptr() as _, - ); - } - - unsafe { - // units of 625us, 80=50ms - const ADVERTISING_INTERVAL: u16 = 80; - - // Set advertising interval - GAP_SetParamValue(TGAP_DISC_ADV_INT_MIN, ADVERTISING_INTERVAL); - GAP_SetParamValue(TGAP_DISC_ADV_INT_MAX, ADVERTISING_INTERVAL); - - // Enable scan req notify - GAP_SetParamValue(TGAP_ADV_SCAN_REQ_NOTIFY, 1); - } - - // Setup the GAP Bond Manager - unsafe { - let passkey: u32 = 0; // passkey "000000" - let pair_mode = GAPBOND_PAIRING_MODE_WAIT_FOR_REQ; - let mitm = true; - let bonding = true; - let io_cap = GAPBOND_IO_CAP_DISPLAY_ONLY; // display only device - GAPBondMgr_SetParameter( - GAPBOND_PERI_DEFAULT_PASSCODE, - size_of_val(&passkey) as _, - &passkey as *const _ as _, - ); - GAPBondMgr_SetParameter(GAPBOND_PERI_PAIRING_MODE, 1, &pair_mode as *const _ as _); - GAPBondMgr_SetParameter(GAPBOND_PERI_MITM_PROTECTION, 1, &mitm as *const _ as _); - GAPBondMgr_SetParameter(GAPBOND_PERI_IO_CAPABILITIES, 1, &io_cap as *const _ as _); - GAPBondMgr_SetParameter(GAPBOND_PERI_BONDING_ENABLED, 1, &bonding as *const _ as _); - } - - // Initialize GATT attributes - unsafe { - GGS_AddService(GATT_ALL_SERVICES); // GAP - GATTServApp_AddService(GATT_ALL_SERVICES); // GATT attributes - } - - unsafe { - unsafe extern "C" fn on_read_attr( - connHandle: u16, - pAttr: *mut GattAttribute, - pValue: *mut u8, - pLen: *mut u16, - offset: u16, - maxLen: u16, - method: u8, - ) -> u8 { - println!("on_read_attr: {:x}", connHandle); - - let raw_uuid = slice::from_raw_parts((*pAttr).type_.uuid, 2); - let uuid = u16::from_le_bytes([raw_uuid[0], raw_uuid[1]]); - - println!("UUID: 0x{:04x}", uuid); - - return 0; - } - static DEV_INFO_CB: gattServiceCBs_t = gattServiceCBs_t { - pfnReadAttrCB: Some(on_read_attr), - pfnWriteAttrCB: None, - pfnAuthorizeAttrCB: None, - }; - - //DevInfo_AddService(); // Device Information Service - GATTServApp::register_service( - DEVICE_INFO_TABLE.as_ptr() as *const _ as _, - DEVICE_INFO_TABLE.len() as _, - GATT_MAX_ENCRYPT_KEY_SIZE, - &DEV_INFO_CB, - ); - - //SimpleProfile_AddService(GATT_ALL_SERVICES); // Simple GATT Profile - } - - // Setup the SimpleProfile Characteristic Values - // SimpleProfile_SetParameter - - // Register receive scan request callback - unsafe { - static CB: gapRolesBroadcasterCBs_t = gapRolesBroadcasterCBs_t { - pfnScanRecv: None, - pfnStateChange: None, - }; - GAPRole_BroadcasterSetCB(&CB); - } -} - -#[embassy_executor::task] -async fn read_rssi(conn_handle: u16) { - let mut ticker = Ticker::every(Duration::from_millis(1000)); - loop { - ticker.next().await; - unsafe { - let r = GAPRole_ReadRssiCmd(conn_handle); - if r.is_err() { - // normally it's already disconnected, quit - // println!("!! GAPRole_ReadRssiCmd error: {:?}", r); - return; - } - } - } -} - -pub enum AppEvent { - Connected(u16), -} - -static APP_CHANNEL: Channel = Channel::new(); - -async fn peripheral(spawner: Spawner, task_id: u8, mut subscriber: ble::EventSubscriber) { - unsafe extern "C" fn on_state_change(new_state: gapRole_States_t, pEvent: *mut gapRoleEvent_t) { - println!("in on_state_change: {}", new_state); - let event = &*pEvent; - - match new_state { - GAPROLE_STARTED => { - println!("initialized.."); - } - GAPROLE_ADVERTISING => { - println!("advertising.."); - } - GAPROLE_WAITING => { - if event.gap.opcode == GAP_END_DISCOVERABLE_DONE_EVENT { - println!("waiting for advertising.."); - } else if event.gap.opcode == GAP_LINK_TERMINATED_EVENT { - // Peripheral_LinkTerminated - println!(" disconnected .. reason {:x}", event.linkTerminate.reason); - // restart advertising here - let mut ret: u32 = 0; - GAPRole_GetParameter(GAPROLE_ADVERT_ENABLED, &mut ret as *mut _ as *mut c_void); - println!(" GAPROLE_ADVERT_ENABLED: {}", ret); - - GAPRole_SetParameter(GAPROLE_ADVERT_ENABLED, 1, &true as *const _ as _); - } else { - println!("unknown event: {}", event.gap.opcode); - } - } - GAPROLE_CONNECTED => { - // Peripheral_LinkEstablished - if event.gap.opcode == GAP_LINK_ESTABLISHED_EVENT { - println!("connected.. !!"); - // logic - // - SBP_PERIODIC_EVT, period = 1600 - // - performPeriodicTask - // - SBP_PARAM_UPDATE_EVT, after = 6400 - // - GAPRole_PeripheralConnParamUpdateReq - // - SBP_READ_RSSI_EVT, period = 3200 - //GAPRole_ReadRssiCmd(event.linkCmpl.connectionHandle); - let _ = APP_CHANNEL.try_send(AppEvent::Connected(event.linkCmpl.connectionHandle)); - } - } - GAPROLE_ERROR => { - println!("error.."); - } - _ => { - println!("!!! on_state_change unknown state: {}", new_state); - } - } - } - unsafe extern "C" fn on_rssi_read(conn_handle: u16, rssi: i8) { - println!("RSSI -{} dB Conn {:x}", -rssi, conn_handle); - } - unsafe extern "C" fn on_param_update(conn_handle: u16, interval: u16, slave_latency: u16, timeout: u16) { - println!( - "on_param_update Conn handle: {} inverval: {} timeout: {}", - conn_handle, interval, timeout - ); - } - - unsafe { - static BOND_MGR_CB: gapBondCBs_t = gapBondCBs_t { - passcodeCB: None, - pairStateCB: None, - oobCB: None, - }; - - // peripheralStateNotificationCB - - static APP_CB: gapRolesCBs_t = gapRolesCBs_t { - pfnStateChange: Some(on_state_change), - pfnRssiRead: Some(on_rssi_read), - pfnParamUpdate: Some(on_param_update), - }; - // Start the Device - GAPRole_PeripheralStartDevice(task_id, &BOND_MGR_CB, &APP_CB); - } - - loop { - match select(subscriber.next_message_pure(), APP_CHANNEL.receive()).await { - Either::First(event) => { - handle_tmos_event(&event).await; - } - Either::Second(event) => match event { - AppEvent::Connected(conn_handle) => { - spawner.spawn(read_rssi(conn_handle)).unwrap(); - } - }, - } - - // spawner.spawn(read_rssi(event.linkCmpl.connectionHandle)).unwrap(); - } -} - -async fn handle_tmos_event(event: &TmosEvent) { - match event.message_id() { - TmosEvent::GAP_MSG_EVENT => { - // Peripheral_ProcessGAPMsg - let msg = event.0 as *const gapRoleEvent_t; - - let opcode = unsafe { (*msg).gap.opcode }; - match opcode { - GAP_SCAN_REQUEST_EVENT => { - println!( - "GAP scan request from {:02x}:{:02x}:{:02x}:{:02x}:{:02x}:{:02x} ...", - (*msg).scanReqEvt.scannerAddr[0], - (*msg).scanReqEvt.scannerAddr[1], - (*msg).scanReqEvt.scannerAddr[2], - (*msg).scanReqEvt.scannerAddr[3], - (*msg).scanReqEvt.scannerAddr[4], - (*msg).scanReqEvt.scannerAddr[5], - ); - } - GAP_PHY_UPDATE_EVENT => { - println!( - "GAP phy update Rx:{:x} Tx:{:x}", - (*msg).linkPhyUpdate.connRxPHYS, - (*msg).linkPhyUpdate.connTxPHYS, - ); - } - GAP_LINK_PARAM_UPDATE_EVENT => { - println!( - "GAP link param update status: {:x} interval: {:x} latency: {:x} timeout: {:x}", - (*msg).linkUpdate.status, - (*msg).linkUpdate.connInterval, - (*msg).linkUpdate.connLatency, - (*msg).linkUpdate.connTimeout, - ); - } - _ => { - println!("GAP MSG EVENT: {:p} {:x}", msg, opcode); - } - } - } - TmosEvent::GATT_MSG_EVENT => { - let msg = event.0 as *const gattMsgEvent_t; - let method = unsafe { (*msg).method }; - println!("GATT_MSG_EVENT: {:p} {:x}", msg, method); - } - _ => { - println!("peripheral got event: {:?} id=0x{:02x}", event, event.message_id()); - } - } -} - -#[embassy_executor::main(entry = "ch32v_rt::entry")] -async fn main(spawner: Spawner) -> ! { - use hal::ble::ffi::*; - - let mut config = hal::Config::default(); - config.clock.use_pll_60mhz().enable_lse(); - let p = hal::init(config); - hal::embassy::init(); - - let uart = UartTx::new(p.UART1, p.PA9, Default::default()).unwrap(); - unsafe { - hal::set_default_serial(uart); - } - - let boot_btn = Input::new(p.PB22, Pull::Up); - - let rtc = Rtc::new(p.RTC); - - println!(); - println!("Hello World from ch58x-hal!"); - println!( - r#" - ______ __ - / ____/___ ___ / /_ ____ _____________ __ - / __/ / __ `__ \/ __ \/ __ `/ ___/ ___/ / / / - / /___/ / / / / / /_/ / /_/ (__ |__ ) /_/ / -/_____/_/ /_/ /_/_.___/\__,_/____/____/\__, / - /____/ on CH582"# - ); - println!("System Clocks: {}", hal::sysctl::clocks().hclk); - println!("ChipID: 0x{:02x}", hal::signature::get_chip_id()); - println!("RTC datetime: {}", rtc.now()); - println!("MemFree: {}K", hal::stack_free() / 1024); - - spawner.spawn(blink(p.PA8.degrade())).unwrap(); - - // BLE part - println!("BLE Lib Version: {}", ble::lib_version()); - - let mut ble_config = ble::Config::default(); - let (task_id, sub) = hal::ble::init(ble_config).unwrap(); - println!("BLE task id: {}", task_id); - - unsafe { - let r = GAPRole_PeripheralInit(); - println!("GAPRole_PeripheralInit: {:?}", r); - } - - peripheral_init(); - - // Main_Circulation - spawner.spawn(tmos_mainloop()).unwrap(); - - // jump to app code - peripheral(spawner, task_id, sub).await; - - loop {} -} - -#[highcode] -#[embassy_executor::task] -async fn tmos_mainloop() { - let mut ticker = Ticker::every(Duration::from_micros(300)); - loop { - ticker.next().await; - unsafe { - TMOS_SystemProcess(); - } - } -} - -#[embassy_executor::task] -async fn blink(pin: AnyPin) { - let mut led = Output::new(pin, Level::Low, OutputDrive::_5mA); - - loop { - led.set_high(); - Timer::after(Duration::from_millis(150)).await; - led.set_low(); - Timer::after(Duration::from_millis(150)).await; - } -} - -#[panic_handler] -fn panic(info: &core::panic::PanicInfo) -> ! { - use core::fmt::Write; - - let pa9 = unsafe { peripherals::PA9::steal() }; - let uart1 = unsafe { peripherals::UART1::steal() }; - let mut serial = UartTx::new(uart1, pa9, Default::default()).unwrap(); - - let _ = writeln!(&mut serial, "\n\n\n{}", info); - - loop {} -} diff --git a/examples/ble-peripheral.rs b/examples/ble-peripheral.rs index 57143d7..fd72b58 100644 --- a/examples/ble-peripheral.rs +++ b/examples/ble-peripheral.rs @@ -10,7 +10,8 @@ use ch58x_hal as hal; use embassy_executor::Spawner; use embassy_time::{Delay, Duration, Instant, Timer}; use hal::ble::ffi::*; -use hal::ble::get_raw_temperature; +use hal::ble::gap::*; +use hal::ble::gattservapp::*; use hal::gpio::{AnyPin, Input, Level, Output, OutputDrive, Pin, Pull}; use hal::interrupt::Interrupt; use hal::prelude::*; @@ -134,8 +135,8 @@ fn peripheral_init() { // Initialize GATT attributes unsafe { - GGS_AddService(GATT_ALL_SERVICES); // GAP - GATTServApp::add_service(GATT_ALL_SERVICES); // GATT attributes + GGS_AddService(GATT_ALL_SERVICES).unwrap(); // GAP + GATTServApp::add_service(GATT_ALL_SERVICES).unwrap(); // GATT attributes } // Setup the SimpleProfile Characteristic Values @@ -153,9 +154,9 @@ fn peripheral_init() { #[embassy_executor::task] async fn peripheral(task_id: u8, subscriber: ble::EventSubscriber) { - unsafe extern "C" fn on_state_change(new_state: gapRole_States_t, pEvent: *mut gapRoleEvent_t) { + unsafe extern "C" fn on_state_change(new_state: gapRole_States_t, event: *mut gapRoleEvent_t) { println!("in on_state_change: {}", new_state); - let event = &*pEvent; + let event = &*event; match new_state { GAPROLE_STARTED => { @@ -171,10 +172,10 @@ async fn peripheral(task_id: u8, subscriber: ble::EventSubscriber) { println!(" disconnected .. reason {:x}", event.linkTerminate.reason); // restart advertising here let mut ret: u32 = 0; - GAPRole_GetParameter(GAPROLE_ADVERT_ENABLED, &mut ret as *mut _ as *mut c_void); + GAPRole_GetParameter(GAPROLE_ADVERT_ENABLED, &mut ret as *mut _ as *mut c_void).unwrap(); println!("GAPROLE_ADVERT_ENABLED: {}", ret); - GAPRole_SetParameter(GAPROLE_ADVERT_ENABLED, 1, &true as *const _ as _); + GAPRole_SetParameter(GAPROLE_ADVERT_ENABLED, 1, &true as *const _ as _).unwrap(); } else { println!("unknown event: {}", event.gap.opcode); } @@ -193,15 +194,15 @@ async fn peripheral(task_id: u8, subscriber: ble::EventSubscriber) { unsafe extern "C" fn on_rssi_read(conn_handle: u16, rssi: i8) { println!("RSSI -{} dB Conn {:x}", -rssi, conn_handle); } - unsafe extern "C" fn on_param_update(connHandle: u16, connInterval: u16, connSlaveLatency: u16, connTimeout: u16) { + unsafe extern "C" fn on_param_update(conn_handle: u16, interval: u16, slave_latency: u16, timeout: u16) { println!( "on_param_update Conn handle: {} inverval: {} timeout: {}", - connHandle, connInterval, connTimeout + conn_handle, interval, timeout ); } unsafe { - static bond_mgr_cb: gapBondCBs_t = gapBondCBs_t { + static BOND_MGR_CB: gapBondCBs_t = gapBondCBs_t { passcodeCB: None, pairStateCB: None, oobCB: None, @@ -209,13 +210,13 @@ async fn peripheral(task_id: u8, subscriber: ble::EventSubscriber) { // peripheralStateNotificationCB - static app_cb: gapRolesCBs_t = gapRolesCBs_t { + static APP_CB: gapRolesCBs_t = gapRolesCBs_t { pfnStateChange: Some(on_state_change), pfnRssiRead: Some(on_rssi_read), pfnParamUpdate: Some(on_param_update), }; // Start the Device - GAPRole_PeripheralStartDevice(task_id, &bond_mgr_cb, &app_cb); + GAPRole_PeripheralStartDevice(task_id, &BOND_MGR_CB, &APP_CB).unwrap(); } } @@ -278,9 +279,7 @@ async fn mainloop() -> ! { loop { Timer::after(Duration::from_micros(300)).await; unsafe { - hal::interrupt::SysTick::pend(); TMOS_SystemProcess(); - hal::interrupt::SysTick::unpend(); } } } diff --git a/examples/blinky.rs b/examples/blinky.rs index 31472de..7be706b 100644 --- a/examples/blinky.rs +++ b/examples/blinky.rs @@ -11,7 +11,6 @@ use hal::interrupt::Interrupt; use hal::isp::EEPROM_BLOCK_SIZE; use hal::rtc::{DateTime, Rtc}; use hal::sysctl::Config; -use hal::systick::SysTick; use hal::uart::UartTx; use hal::{pac, peripherals, Peripherals}; use {ch58x_hal as hal, panic_halt as _}; @@ -30,8 +29,6 @@ fn main() -> ! { //let p = Peripherals::take(); let p = hal::init(config); - let mut delay = SysTick::new(p.SYSTICK); - let mut pa8 = Output::new(p.PA8, Level::Low, OutputDrive::_5mA); let mut download_button = Input::new(p.PB22, Pull::Up); diff --git a/examples/empty.rs b/examples/empty.rs index 155625a..b333a41 100644 --- a/examples/empty.rs +++ b/examples/empty.rs @@ -4,7 +4,6 @@ use embedded_hal_1::delay::DelayUs; use hal::gpio::{Input, Level, Output, OutputDrive, Pull}; use hal::peripherals; -use hal::systick::SysTick; use hal::uart::UartTx; use {ch58x_hal as hal, panic_halt as _}; // use hal::interrupt::Interrupt; @@ -33,8 +32,6 @@ fn main() -> ! { config.clock.use_pll_80mhz(); let p = hal::init(config); - let mut delay = SysTick::new(p.SYSTICK); - let mut led = Output::new(p.PA8, Level::Low, OutputDrive::_5mA); let download_button = Input::new(p.PB22, Pull::Up); @@ -53,7 +50,7 @@ fn main() -> ! { println!("tick"); led.toggle(); - delay.delay_ms(1000); + hal::delay_ms(1000); while download_button.is_low() {} diff --git a/examples/flashisp.rs b/examples/flashisp.rs index 4745496..a179cde 100644 --- a/examples/flashisp.rs +++ b/examples/flashisp.rs @@ -6,7 +6,6 @@ use embedded_hal_1::delay::DelayUs; use hal::gpio::{Input, Level, Output, OutputDrive, Pull}; // use hal::interrupt::Interrupt; use hal::rtc::{DateTime, Rtc}; -use hal::systick::SysTick; use hal::uart::UartTx; use hal::{peripherals, with_safe_access}; use {ch58x_hal as hal, panic_halt as _}; @@ -35,8 +34,6 @@ fn main() -> ! { config.clock.use_pll_60mhz(); let p = hal::init(config); - let mut delay = SysTick::new(p.SYSTICK); - // GPIO let mut led = Output::new(p.PA8, Level::Low, OutputDrive::_5mA); let download_button = Input::new(p.PB22, Pull::Up); @@ -72,7 +69,7 @@ fn main() -> ! { led.toggle(); println!("tick"); - delay.delay_ms(1000); + hal::delay_ms(1000); /* while download_button.is_low() {} diff --git a/examples/gpio_int.rs b/examples/gpio_int.rs deleted file mode 100644 index 759eb5a..0000000 --- a/examples/gpio_int.rs +++ /dev/null @@ -1,102 +0,0 @@ -#![no_std] -#![no_main] - -use core::arch::{asm, global_asm}; -use core::fmt::Write; -use core::writeln; - -use embedded_hal_1::delay::DelayUs; -use hal::dma::NoDma; -use hal::gpio::{AnyPin, Flex, Input, Level, Output, OutputDrive, Pull}; -use hal::interrupt::Interrupt; -use hal::isp::EEPROM_BLOCK_SIZE; -use hal::rtc::{DateTime, Rtc}; -use hal::sysctl::Config; -use hal::systick::SysTick; -use hal::uart::UartTx; -use hal::{pac, peripherals, Peripherals}; -use {ch58x_hal as hal, panic_halt as _}; - -static mut SERIAL: Option> = None; - -static mut BUTTON: Option> = None; - -#[ch32v_rt::interrupt] -unsafe fn GPIOB() { - if let Some(button) = BUTTON.as_mut() { - button.disable_interrupt(); - - let serial = unsafe { SERIAL.as_mut().unwrap() }; - - writeln!(serial, "in irq handler").unwrap(); - if button.is_low() { - writeln!(serial, "button pressed").unwrap(); - } - button.clear_interrupt(); - button.enable_interrupt(); - } -} - -#[ch32v_rt::entry] -fn main() -> ! { - let mut config = hal::Config::default(); - config.clock.use_pll_60mhz().enable_lse(); - - let p = hal::init(config); - - let mut delay = SysTick::new(p.SYSTICK); - - // LED PA8 - let mut blue_led = Output::new(p.PA8, Level::Low, OutputDrive::_5mA); - - let mut serial = UartTx::new(p.UART1, p.PA9, Default::default()).unwrap(); - unsafe { - SERIAL = Some(serial); - } - //let mut serial = UartTx::new(p.UART3, p.PA5, Default::default()).unwrap(); - //let mut serial = UartTx::new(p.UART0, p.PA14, Default::default()).unwrap(); - - //let mut serial = UartTx::new(p.UART0, p.PB7, Default::default()).unwrap(); - - let mut button = Input::new(p.PB22, Pull::Up); - // let mut reset_button = Input::new(p.PB23, Pull::Up); - - button.set_trigger(hal::gpio::InterruptTrigger::FallingEdge); - button.enable_interrupt(); - unsafe { - BUTTON = Some(button); - } - unsafe { hal::interrupt::GPIOB::enable() }; - - let mut rtc = Rtc {}; - - let serial = unsafe { SERIAL.as_mut().unwrap() }; - - writeln!(serial, "\n\n\nHello World!").unwrap(); - writeln!(serial, "Clocks: {}", hal::sysctl::clocks().hclk).unwrap(); - writeln!(serial, "ChipID: {:02x}", hal::signature::get_chip_id()); - let now = rtc.now(); - writeln!(serial, "Boot time: {} weekday={}", now, now.isoweekday()).unwrap(); - - loop { - blue_led.toggle(); - - // writeln!(uart, "day {:?}", rtc.counter_day()).unwrap(); - // writeln!(uart, "2s {:?}", rtc.counter_2s()).unwrap(); - - // writeln!(uart, "tick! {}", SysTick::now()).unwrap(); - delay.delay_ms(1000); - - let now = rtc.now(); - writeln!( - serial, - "{}: tick", - now, - // now.isoweekday(), - ) - .unwrap(); - // serial.blocking_flush(); - //writeln!(serial, "Current time: {} weekday={}", now, now.isoweekday()).unwrap(); - //writeln!(serial, "button: {} {}", ).unwrap(); - } -} diff --git a/examples/hardfault.rs b/examples/hardfault.rs index da3e63c..94ae107 100644 --- a/examples/hardfault.rs +++ b/examples/hardfault.rs @@ -10,7 +10,6 @@ use hal::gpio::{AnyPin, Input, Level, Output, OutputDrive, Pull}; use hal::isp::EEPROM_BLOCK_SIZE; use hal::rtc::{DateTime, Rtc}; use hal::sysctl::Config; -use hal::systick::SysTick; use hal::uart::UartTx; use hal::{pac, peripherals, Peripherals}; use {ch58x_hal as hal, panic_halt as _}; @@ -74,8 +73,6 @@ fn main() -> ! { config.clock.use_pll_60mhz(); let p = hal::init(config); - let mut delay = SysTick::new(p.SYSTICK); - let mut pa8 = Output::new(p.PA8, Level::Low, OutputDrive::_5mA); let mut download_button = Input::new(p.PB22, Pull::Up); @@ -97,7 +94,7 @@ fn main() -> ! { unsafe { pa8.toggle(); - delay.delay_ms(100); + hal::delay_ms(100); while download_button.is_low() {} diff --git a/examples/i2c-mpu6050.rs b/examples/i2c-mpu6050.rs index 130d976..4e8549b 100644 --- a/examples/i2c-mpu6050.rs +++ b/examples/i2c-mpu6050.rs @@ -6,9 +6,7 @@ use hal::gpio::{Input, Level, Output, OutputDrive, Pull}; use hal::i2c::{self, I2c}; use hal::peripherals; use hal::prelude::*; -// use hal::interrupt::Interrupt; use hal::rtc::Rtc; -use hal::systick::SysTick; use hal::uart::UartTx; use {ch58x_hal as hal, panic_halt as _}; @@ -316,14 +314,10 @@ impl<'d> MPU6050<'d> { #[ch32v_rt::entry] fn main() -> ! { - // LED PA8 - let mut config = hal::Config::default(); config.clock.use_pll_60mhz(); let p = hal::init(config); - let mut delay = SysTick::new(p.SYSTICK); - // GPIO let mut led = Output::new(p.PA8, Level::Low, OutputDrive::_5mA); let download_button = Input::new(p.PB22, Pull::Up); @@ -363,6 +357,6 @@ fn main() -> ! { let gyro = mpu6050.read_gyro().unwrap(); println!("gyro: {:?}", gyro); - delay.delay_ms(500); + hal::delay_ms(500); } } diff --git a/examples/serial.rs b/examples/serial.rs index 78b6964..6e0eb5b 100644 --- a/examples/serial.rs +++ b/examples/serial.rs @@ -12,22 +12,16 @@ use hal::interrupt::Interrupt; use hal::isp::EEPROM_BLOCK_SIZE; use hal::rtc::{DateTime, Rtc}; use hal::sysctl::Config; -use hal::systick::SysTick; use hal::uart::UartTx; use hal::{pac, peripherals, Peripherals}; use {ch58x_hal as hal, panic_halt as _}; #[ch32v_rt::entry] fn main() -> ! { - // hal::sysctl::Config::pll_60mhz().freeze(); - //hal::sysctl::Config::pll_60mhz().enable_lse().freeze(); - //hal::sysctl::Config::with_lsi_32k().freeze(); let mut config = hal::Config::default(); config.clock.use_pll_60mhz().enable_lse(); let p = hal::init(config); - let mut delay = SysTick::new(p.SYSTICK); - // LED PA8 let mut blue_led = Output::new(p.PA8, Level::Low, OutputDrive::_5mA); @@ -69,7 +63,7 @@ fn main() -> ! { // writeln!(uart, "2s {:?}", rtc.counter_2s()).unwrap(); // writeln!(uart, "tick! {}", SysTick::now()).unwrap(); - delay.delay_ms(1000); + hal::delay_ms(1000); let now = rtc.now(); writeln!( diff --git a/examples/spi-ssd1306.rs b/examples/spi-ssd1306.rs index 27e14cb..37f3a8c 100644 --- a/examples/spi-ssd1306.rs +++ b/examples/spi-ssd1306.rs @@ -19,7 +19,6 @@ use hal::gpio::{Input, Level, Output, OutputDrive, Pull}; use hal::prelude::*; use hal::rtc::Rtc; use hal::spi::{BitOrder, Spi}; -use hal::systick::SysTick; use hal::uart::UartTx; use hal::{delay_ms, pac, peripherals, with_safe_access}; use ssd1306::prelude::*; @@ -62,8 +61,6 @@ fn main() -> ! { config.clock.use_pll_60mhz(); let p = hal::init(config); - let mut delay = SysTick::new(p.SYSTICK); - // GPIO let mut led = Output::new(p.PA8, Level::Low, OutputDrive::_5mA); let download_button = Input::new(p.PB22, Pull::Up); @@ -119,7 +116,7 @@ fn main() -> ! { .unwrap(); display.flush().unwrap(); - delay.delay_ms(5); + hal::delay_ms(5); } for i in 0..32 { // display.clear(BinaryColor::Off).unwrap(); @@ -133,7 +130,7 @@ fn main() -> ! { .unwrap(); display.flush().unwrap(); - delay.delay_ms(5); + hal::delay_ms(5); } display.clear(BinaryColor::Off).unwrap(); @@ -153,7 +150,7 @@ fn main() -> ! { .unwrap(); display.flush().unwrap(); - delay.delay_ms(1000); + hal::delay_ms(1000); display.clear(BinaryColor::Off).unwrap(); display.flush().unwrap(); diff --git a/examples/yd-ch582m.rs b/examples/yd-ch582m.rs index 256bada..fe20bd1 100644 --- a/examples/yd-ch582m.rs +++ b/examples/yd-ch582m.rs @@ -9,7 +9,6 @@ use embedded_hal_1::delay::DelayUs; use hal::gpio::{Input, Level, Output, OutputDrive, Pull}; use hal::peripherals; use hal::rtc::{DateTime, Rtc}; -use hal::systick::SysTick; use hal::uart::UartTx; static mut SERIAL: Option> = None; @@ -47,8 +46,6 @@ fn main() -> ! { config.clock.use_pll_60mhz().enable_lse(); let p = hal::init(config); - let mut delay = SysTick::new(p.SYSTICK); - // GPIO let mut led = Output::new(p.PB4, Level::Low, OutputDrive::_5mA); let boot_btn = Input::new(p.PB22, Pull::Up); @@ -70,7 +67,7 @@ fn main() -> ! { led.toggle(); println!("tick"); - delay.delay_ms(1000); + hal::delay_ms(1000); println!("button: {} {}", boot_btn.is_low(), rst_btn.is_low());