Initial Release

This commit is contained in:
graham sanderson 2021-01-20 10:49:34 -06:00
commit 46078742c7
245 changed files with 21157 additions and 0 deletions

7
.gitignore vendored Normal file
View File

@ -0,0 +1,7 @@
.idea
.vscode
_deps
cmake-*
build
.DS_Store
*.pdf

43
CMakeLists.txt Normal file
View File

@ -0,0 +1,43 @@
cmake_minimum_required(VERSION 3.12)
# Pull in PICO SDK (must be before project)
include(pico_sdk_import.cmake)
project(pico_examples C CXX ASM)
set(CMAKE_C_STANDARD 11)
set(CMAKE_CXX_STANDARD 17)
set(PICO_EXAMPLES_PATH ${PROJECT_SOURCE_DIR})
# Initialize the SDK
pico_sdk_init()
include(example_auto_set_url.cmake)
# Add blink example
add_subdirectory(blink)
# Add hello world example
add_subdirectory(hello_world)
# Hardware-specific examples in subdirectories:
add_subdirectory(adc)
add_subdirectory(clocks)
add_subdirectory(cmake)
add_subdirectory(divider)
add_subdirectory(dma)
add_subdirectory(flash)
add_subdirectory(gpio)
add_subdirectory(i2c)
add_subdirectory(interp)
add_subdirectory(multicore)
add_subdirectory(picoboard)
add_subdirectory(pio)
add_subdirectory(pwm)
add_subdirectory(reset)
add_subdirectory(rtc)
add_subdirectory(spi)
add_subdirectory(system)
add_subdirectory(timer)
add_subdirectory(uart)
add_subdirectory(usb)
add_subdirectory(watchdog)

21
LICENSE.TXT Normal file
View File

@ -0,0 +1,21 @@
Copyright 2020 (c) 2020 Raspberry Pi (Trading) Ltd.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the
following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following
disclaimer.
2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following
disclaimer in the documentation and/or other materials provided with the distribution.
3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products
derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

196
README.md Normal file
View File

@ -0,0 +1,196 @@
# PICO SDK Examples
## Getting started
See [Getting Started with the Raspberry Pi Pico](https://rptl.io/pico-get-started) and the README in the [pico-sdk](https://github.com/raspberrypi/pico-sdk) for information
on getting up and running.
### First Examples
App | Description | Link to prebuilt UF2
---|---|---
[hello_serial](hello_world/serial) | The obligatory Hello World program for Pico (Output over serial version) | https://rptl.io/pico-hello-serial
[hello_usb](hello_world/usb) | The obligatory Hello World program for Pico (Output over USB version) | https://rptl.io/pico-hello-usb
[blink](blink) | Blink an LED on and off. | https://rptl.io/pico-blink
### ADC
App|Description
---|---
[hello_adc](adc/hello_adc)|Display the voltage from an ADC input.
[joystick_display](adc/joystick_display)|Display a Joystick X/Y input based on two ADC inputs.
[adc_console](adc/adc_console)|An interactive shell for playing with the ADC. Includes example of free-running capture mode.
### Clocks
App|Description
---|---
[hello_48MHz](clocks/hello_48MHz)| Change the system clock frequency to 48 MHz while running.
[hello_gpout](clocks/hello_gpout)| Use the general purpose clock outputs (GPOUT) to drive divisions of internal clocks onto GPIO outputs.
[hello_resus](clocks/hello_resus)| Enable the clock resuscitate feature, "accidentally" stop the system clock, and show how we recover.
### CMake
App|Description
---|---
[build_variants](cmake/build_variants)| Builds two version of the same app with different configurations
### DMA
App|Description
---|---
[hello_dma](dma/hello_dma)| Use the DMA to copy data in memory.
[control_blocks](dma/control_blocks)| Build a control block list, to program a longer sequence of DMA transfers to the UART.
[channel_irq](dma/channel_irq)| Use an IRQ handler to reconfigure a DMA channel, in order to continuously drive data through a PIO state machine.
### Flash
App|Description
---|---
[cache_perfctr](flash/cache_perfctr)| Read and clear the cache performance counters. Show how they are affected by different types of flash reads.
[nuke](flash/nuke)| Obliterate the contents of flash. An example of a NO_FLASH binary (UF2 loaded directly into SRAM and runs in-place there). A useful utility to drag and drop onto your Pico if the need arises.
[program](flash/program)| Erase a flash sector, program one flash page, and read back the data.
[xip_stream](flash/xip_stream)| Stream data using the XIP stream hardware, which allows data to be DMA'd in the background whilst executing code from flash.
[ssi_dma](flash/ssi_dma)| DMA directly from the flash interface (continuous SCK clocking) for maximum bulk read performance.
### GPIO
App|Description
---|---
[hello_7segment](gpio/hello_7segment) | Use the GPIOs to drive a seven segment LED display.
[hello_gpio_irq](gpio/hello_gpio_irq) | Register an interrupt handler to run when a GPIO is toggled.
[dht_sensor](gpio/dht_sensor) | Use GPIO to bitbang the serial protocol for a DHT temperature/humidity sensor.
See also: [blink](blink), blinking an LED attached to a GPIO.
### HW divider
App|Description
---|---
[hello_divider](divider) | Show how to directly access the hardware integer dividers, in case AEABI injection is disabled.
### I2C
App|Description
---|---
[bus_scan](i2c/bus_scan) | Scan the I2C bus for devices and display results.
[lcd_1602_i2c](i2c/lcd_1602_i2c) | Display some text on a generic 16x2 character LCD display, via I2C.
[mpu6050_i2c](i2c/mpu6050_i2c) | Read acceleration and angular rate values from a MPU6050 accelerometer/gyro, attached to an I2C bus.
### Interpolator
App|Description
---|---
[hello_interp](interp/hello_interp) | A bundle of small examples, showing how to access the core-local interpolator hardware, and use most of its features.
### Multicore
App|Description
---|---
[hello_multicore](multicore/hello_multicore) | Launch a function on the second core, printf some messages on each core, and pass data back and forth through the mailbox FIFOs.
[multicore_fifo_irqs](multicore/multicore_fifo_irqs) | On each core, register and interrupt handler for the mailbox FIFOs. Show how the interrupt fires when that core receives a message.
[multicore_runner](multicore/multicore_runner) | Set up the second core to accept, and run, any function pointer pushed into its mailbox FIFO. Push in a few pieces of code and get answers back.
### Pico Board
App|Description
---|---
[blinky](picoboard/blinky)| Blink "hello, world" in Morse code on Pico's LED
[button](picoboard/button)| Use Pico's BOOTSEL button as a regular button input, by temporarily suspending flash access.
### PIO
App|Description
---|---
[hello_pio](pio/hello_pio)| Absolutely minimal example showing how to control an LED by pushing values into a PIO FIFO.
[apa102](pio/apa102)| Rainbow pattern on on a string of APA102 addressable RGB LEDs.
[differential_manchester](pio/differential_manchester)| Send and receive differential Manchester-encoded serial (BMC).
[hub75](pio/hub75)| Display an image on a 128x64 HUB75 RGB LED matrix.
[i2c](pio/i2c)| Scan an I2C bus.
[logic_analyser](pio/logic_analyser)| Use PIO and DMA to capture a logic trace of some GPIOs, whilst a PWM unit is driving them.
[manchester_encoding](pio/manchester_encoding)| Send and receive Manchester-encoded serial.
[pio_blink](pio/pio_blink)| Set up some PIO state machines to blink LEDs at different frequencies, according to delay counts pushed into their FIFOs.
[pwm](pio/pwm)| Pulse width modulation on PIO. Use it to gradually fade the brightness of an LED.
[spi](pio/spi)| Use PIO to erase, program and read an external SPI flash chip. A second example runs a loopback test with all four CPHA/CPOL combinations.
[squarewave](pio/squarewave)| Drive a fast square wave onto a GPIO. This example accesses low-level PIO registers directly, instead of using the SDK functions.
[st7789_lcd](pio/st7789_lcd)| Set up PIO for 62.5 Mbps serial output, and use this to display a spinning image on a ST7789 serial LCD.
[uart_rx](pio/uart_rx)| Implement the receive component of a UART serial port. Attach it to the spare Arm UART to see it receive characters.
[uart_tx](pio/uart_tx)| Implement the transmit component of a UART serial port, and print hello world.
[ws2812](pio/ws2812)| Examples of driving WS2812 addressable RGB LEDs.
[addition](pio/addition)| Add two integers together using PIO. Only around 8 billion times slower than Cortex-M0+.
### PWM
App|Description
---|---
[hello_pwm](pwm/hello_pwm) | Minimal example of driving PWM output on GPIOs.
[led_fade](pwm/led_fade) | Fade an LED between low and high brightness. An interrupt handler updates the PWM slice's output level each time the counter wraps.
[measure_duty_cycle](pwm/measure_duty_cycle) | Drives a PWM output at a range of duty cycles, and uses another PWM slice in input mode to measure the duty cycle.
### Reset
App|Description
---|---
[hello_reset](reset/hello_reset) | Perform a hard reset on some peripherals, then bring them back up.
### RTC
App|Description
---|---
[hello_rtc](rtc/hello_rtc) | Set a date/time on the RTC, then repeatedly print the current time, 10 times per second, to show it updating.
[rtc_alarm](rtc/rtc_alarm) | Set an alarm on the RTC to trigger an interrupt at a date/time 5 seconds into the future.
[rtc_alarm_repeat](rtc/rtc_alarm_repeat) | Trigger an RTC interrupt once per minute.
### SPI
App|Description
---|---
[bme280_spi](spi/bme280_spi) | Attach a BME280 temperature/humidity/pressure sensor via SPI.
[mpu9250_spi](spi/mpu9250_spi) | Attach a MPU9250 accelerometer/gyoscope via SPI.
[spi_dma](spi/spi_dma) | Use DMA to transfer data both to and from the SPI simultaneously. The SPI is configured for loopback.
[spi_flash](spi/spi_flash) | Erase, program and read a serial flash device attached to one of the SPI controllers.
### System
App|Description
---|---
[hello_double_tap](system/hello_double_tap) | On dev boards with a reset button (but no BOOTSEL), a magic number in RAM can be used to enter the USB bootloader, when the reset button is pressed twice quickly.
[narrow_io_write](system/narrow_io_write) | Demonstrate the effects of 8-bit and 16-bit writes on a 32-bit IO register.
### Timer
App|Description
---|---
[hello_timer](timer/hello_timer) | Set callbacks on the system timer, which repeat at regular intervals. Cancel the timer when we're done.
[periodic_sampler](timer/periodic_sampler) | Sample GPIOs in a timer callback, and push the samples into a concurrency-safe queue. Pop data from the queue in code running in the foreground.
[timer_lowlevel](timer/timer_lowlevel) | Example of direct access to the timer hardware. Not generally recommended, as the SDK may use the timer for IO timeouts.
### UART
App|Description
---|---
[hello_uart](uart/hello_uart) | Print some text from one of the UART serial ports, without going through `stdio`.
[uart_advanced](uart/uart_advanced) | Use some other UART features like RX interrupts, hardware control flow, and data formats other than 8n1.
### USB Device
App|Description
---|---
[dev_audio_headset](usb/device/dev_audio_headset) | Audio headset example from TinyUSB
[dev_hid_composite](usb/device/dev_hid_composite) | Composite HID (mouse + keyboard) example from TinyUSB
[dev_hid_generic_inout](usb/device/dev_hid_generic_inout) | Generic HID device example from TinyUSB
[dev_lowlevel](usb/device/dev_lowlevel) | A USB Bulk loopback implemented with direct access to the USB hardware (no TinyUSB)
### USB Host
App|Description
---|---
[host_hid](usb/host/host_hid) | Use USB in host mode to poll an attached HID keyboard (TinyUSB example)
### Watchdog
App|Description
---|---
[hello_watchdog](watchdog/hello_watchdog) | Set the watchdog timer, and let it expire. Detect the reboot, and halt.

5
adc/CMakeLists.txt Normal file
View File

@ -0,0 +1,5 @@
if (NOT PICO_NO_HARDWARE)
add_subdirectory(adc_console)
add_subdirectory(hello_adc)
add_subdirectory(joystick_display)
endif ()

View File

@ -0,0 +1,12 @@
add_executable(adc_console
adc_console.c
)
target_link_libraries(adc_console pico_stdlib hardware_adc)
# create map/bin/hex file etc.
pico_add_extra_outputs(adc_console)
# add url via pico_set_program_url
example_auto_set_url(adc_console)

View File

@ -0,0 +1,100 @@
#include <stdio.h>
#include "pico/stdlib.h"
#include "hardware/gpio.h"
#include "hardware/adc.h"
#define N_SAMPLES 1000
uint16_t sample_buf[N_SAMPLES];
void printhelp() {
puts("\nCommands:");
puts("c0, ...\t: Select ADC channel n");
puts("s\t: Sample once");
puts("S\t: Sample many");
puts("w\t: Wiggle pins");
}
void __not_in_flash_func(adc_capture)(uint16_t *buf, size_t count) {
adc_fifo_setup(true, false, 0, false, false);
adc_run(true);
for (int i = 0; i < count; i = i + 1)
buf[i] = adc_fifo_get_blocking();
adc_run(false);
adc_fifo_drain();
}
int main(void) {
stdio_init_all();
adc_init();
adc_set_temp_sensor_enabled(true);
// Set all pins to input (as far as SIO is concerned)
gpio_set_dir_all_bits(0);
for (int i = 2; i < 30; ++i) {
gpio_set_function(i, GPIO_FUNC_SIO);
if (i >= 26) {
gpio_disable_pulls(i);
gpio_set_input_enabled(i, false);
}
}
printf("\n===========================\n");
printf("RP2040 ADC and Test Console\n");
printf("===========================\n");
printhelp();
while (1) {
char c = getchar();
printf("%c", c);
switch (c) {
case 'c':
c = getchar();
printf("%c\n", c);
if (c < '0' || c > '7') {
printf("Unknown input channel\n");
printhelp();
} else {
adc_select_input(c - '0');
printf("Switched to channel %c\n", c);
}
break;
case 's': {
uint32_t result = adc_read();
const float conversion_factor = 3.3f / (1 << 12);
printf("\n0x%03x -> %f V\n", result, result * conversion_factor);
break;
}
case 'S': {
printf("\nStarting capture\n");
adc_capture(sample_buf, N_SAMPLES);
printf("Done\n");
for (int i = 0; i < N_SAMPLES; i = i + 1)
printf("%03x\n", sample_buf[i]);
break;
}
case 'w':
printf("\nPress any key to stop wiggling\n");
int i = 1;
gpio_set_dir_all_bits(-1);
while (getchar_timeout_us(0) == PICO_ERROR_TIMEOUT) {
// Pattern: Flash all pins for a cycle,
// Then scan along pins for one cycle each
i = i ? i << 1 : 1;
gpio_put_all(i ? i : ~0);
}
gpio_set_dir_all_bits(0);
printf("Wiggling halted.\n");
break;
case '\n':
case '\r':
break;
case 'h':
printhelp();
break;
default:
printf("\nUnrecognised command: %c\n", c);
printhelp();
break;
}
}
}

View File

@ -0,0 +1,11 @@
add_executable(hello_adc
hello_adc.c
)
target_link_libraries(hello_adc pico_stdlib hardware_adc)
# create map/bin/hex file etc.
pico_add_extra_outputs(hello_adc)
# add url via pico_set_program_url
example_auto_set_url(hello_adc)

30
adc/hello_adc/hello_adc.c Normal file
View File

@ -0,0 +1,30 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
#include "hardware/gpio.h"
#include "hardware/adc.h"
int main() {
stdio_init_all();
printf("ADC Example, measuring GPIO26\n");
adc_init();
// Make sure GPIO is high-impedance, no pullups etc
adc_gpio_init(26);
// Select ADC input 0 (GPIO26)
adc_select_input(0);
while (1) {
// 12-bit conversion, assume max value == ADC_VREF == 3.3 V
const float conversion_factor = 3.3f / (1 << 12);
uint16_t result = adc_read();
printf("Raw value: 0x%03x, voltage: %f V\n", result, result * conversion_factor);
sleep_ms(500);
}
}

View File

@ -0,0 +1,11 @@
add_executable(joystick_display
joystick_display.c
)
target_link_libraries(joystick_display pico_stdlib hardware_adc)
# create map/bin/hex file etc.
pico_add_extra_outputs(joystick_display)
# add url via pico_set_program_url
example_auto_set_url(joystick_display)

View File

@ -0,0 +1,40 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
#include "hardware/adc.h"
int main() {
stdio_init_all();
adc_init();
// Make sure GPIO is high-impedance, no pullups etc
adc_gpio_init(26);
adc_gpio_init(27);
while (1) {
adc_select_input(0);
uint adc_x_raw = adc_read();
adc_select_input(1);
uint adc_y_raw = adc_read();
// Display the joystick position something like this:
// X: [ o ] Y: [ o ]
const uint bar_width = 40;
const uint adc_max = (1 << 12) - 1;
uint bar_x_pos = adc_x_raw * bar_width / adc_max;
uint bar_y_pos = adc_y_raw * bar_width / adc_max;
printf("\rX: [");
for (int i = 0; i < bar_width; ++i)
putchar( i == bar_x_pos ? 'o' : ' ');
printf("] Y: [");
for (int i = 0; i < bar_width; ++i)
putchar( i == bar_y_pos ? 'o' : ' ');
printf("]");
sleep_ms(50);
}
}

12
blink/CMakeLists.txt Normal file
View File

@ -0,0 +1,12 @@
add_executable(blink
blink.c
)
# Pull in our pico_stdlib which pulls in commonly used features
target_link_libraries(blink pico_stdlib)
# create map/bin/hex file etc.
pico_add_extra_outputs(blink)
# add url via pico_set_program_url
example_auto_set_url(blink)

19
blink/blink.c Normal file
View File

@ -0,0 +1,19 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "pico/stdlib.h"
int main() {
const uint LED_PIN = 25;
gpio_init(LED_PIN);
gpio_set_dir(LED_PIN, GPIO_OUT);
while (true) {
gpio_put(LED_PIN, 1);
sleep_ms(250);
gpio_put(LED_PIN, 0);
sleep_ms(250);
}
}

5
clocks/CMakeLists.txt Normal file
View File

@ -0,0 +1,5 @@
if (NOT PICO_NO_HARDWARE)
add_subdirectory(hello_48MHz)
add_subdirectory(hello_gpout)
add_subdirectory(hello_resus)
endif ()

View File

@ -0,0 +1,12 @@
add_executable(hello_48MHz
hello_48MHz.c
)
# Pull in our pico_stdlib which pulls in commonly used features
target_link_libraries(hello_48MHz pico_stdlib hardware_clocks)
# create map/bin/hex file etc.
pico_add_extra_outputs(hello_48MHz)
# add url via pico_set_program_url
example_auto_set_url(hello_48MHz)

View File

@ -0,0 +1,68 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
#include "hardware/pll.h"
#include "hardware/clocks.h"
#include "hardware/structs/pll.h"
#include "hardware/structs/clocks.h"
void measure_freqs(void) {
uint f_pll_sys = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_PLL_SYS_CLKSRC_PRIMARY);
uint f_pll_usb = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_PLL_USB_CLKSRC_PRIMARY);
uint f_rosc = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_ROSC_CLKSRC);
uint f_clk_sys = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_CLK_SYS);
uint f_clk_peri = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_CLK_PERI);
uint f_clk_usb = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_CLK_USB);
uint f_clk_adc = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_CLK_ADC);
uint f_clk_rtc = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_CLK_RTC);
printf("pll_sys = %dkHz\n", f_pll_sys);
printf("pll_usb = %dkHz\n", f_pll_usb);
printf("rosc = %dkHz\n", f_rosc);
printf("clk_sys = %dkHz\n", f_clk_sys);
printf("clk_peri = %dkHz\n", f_clk_peri);
printf("clk_usb = %dkHz\n", f_clk_usb);
printf("clk_adc = %dkHz\n", f_clk_adc);
printf("clk_rtc = %dkHz\n", f_clk_rtc);
// Can't measure clk_ref / xosc as it is the ref
}
int main() {
stdio_init_all();
printf("Hello, world!\n");
measure_freqs();
// Change clk_sys to be 48MHz. The simplest way is to take this from PLL_USB
// which has a source frequency of 48MHz
clock_configure(clk_sys,
CLOCKS_CLK_SYS_CTRL_SRC_VALUE_CLKSRC_CLK_SYS_AUX,
CLOCKS_CLK_SYS_CTRL_AUXSRC_VALUE_CLKSRC_PLL_USB,
48 * MHZ,
48 * MHZ);
// Turn off PLL sys for good measure
pll_deinit(pll_sys);
// CLK peri is clocked from clk_sys so need to change clk_peri's freq
clock_configure(clk_peri,
0,
CLOCKS_CLK_PERI_CTRL_AUXSRC_VALUE_CLK_SYS,
48 * MHZ,
48 * MHZ);
// Re init uart now that clk_peri has changed
stdio_init_all();
measure_freqs();
printf("Hello, 48MHz");
return 0;
}

View File

@ -0,0 +1,12 @@
add_executable(hello_gpout
hello_gpout.c
)
# Pull in our pico_stdlib which pulls in commonly used features
target_link_libraries(hello_gpout pico_stdlib)
# create map/bin/hex file etc.
pico_add_extra_outputs(hello_gpout)
# add url via pico_set_program_url
example_auto_set_url(hello_gpout)

View File

@ -0,0 +1,23 @@
/**
* Copyright (c) 2021 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
#include "hardware/clocks.h"
int main() {
stdio_init_all();
printf("Hello gpout\n");
// Output clk_sys / 10 to gpio 21, etc...
clock_gpio_init(21, CLOCKS_CLK_GPOUT0_CTRL_AUXSRC_VALUE_CLK_SYS, 10);
clock_gpio_init(23, CLOCKS_CLK_GPOUT0_CTRL_AUXSRC_VALUE_CLK_USB, 10);
clock_gpio_init(24, CLOCKS_CLK_GPOUT0_CTRL_AUXSRC_VALUE_CLK_ADC, 10);
clock_gpio_init(26, CLOCKS_CLK_GPOUT0_CTRL_AUXSRC_VALUE_CLK_RTC, 10);
return 0;
}

View File

@ -0,0 +1,12 @@
add_executable(hello_resus
hello_resus.c
)
# Pull in our pico_stdlib which pulls in commonly used features
target_link_libraries(hello_resus pico_stdlib)
# create map/bin/hex file etc.
pico_add_extra_outputs(hello_resus)
# add url via pico_set_program_url
example_auto_set_url(hello_resus)

View File

@ -0,0 +1,48 @@
/**
* Copyright (c) 2021 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
#include "hardware/clocks.h"
#include "hardware/pll.h"
volatile bool seen_resus;
void resus_callback(void) {
// Reconfigure PLL sys back to the default state of 1500 / 6 / 2 = 125MHz
pll_init(pll_sys, 1, 1500 * MHZ, 6, 2);
// CLK SYS = PLL SYS (125MHz) / 1 = 125MHz
clock_configure(clk_sys,
CLOCKS_CLK_SYS_CTRL_SRC_VALUE_CLKSRC_CLK_SYS_AUX,
CLOCKS_CLK_SYS_CTRL_AUXSRC_VALUE_CLKSRC_PLL_SYS,
125 * MHZ,
125 * MHZ);
// Reconfigure uart as clocks have changed
stdio_init_all();
printf("Resus event fired\n");
// Wait for uart output to finish
uart_default_tx_wait_blocking();
seen_resus = true;
}
int main() {
stdio_init_all();
printf("Hello resus\n");
seen_resus = false;
clocks_enable_resus(&resus_callback);
// Break PLL sys
pll_deinit(pll_sys);
while(!seen_resus);
return 0;
}

1
cmake/CMakeLists.txt Normal file
View File

@ -0,0 +1 @@
add_subdirectory(build_variants)

View File

@ -0,0 +1,37 @@
# 1 Create an INTERFACE library aggregating all the common parts of the application
add_library(common_stuff INTERFACE)
# note cmake policy is to use absolute paths for interface libraries.
target_sources(common_stuff INTERFACE
${CMAKE_CURRENT_LIST_DIR}/main.c
${CMAKE_CURRENT_LIST_DIR}/other.c
)
target_compile_definitions(common_stuff INTERFACE
A_DEFINE_THAT_IS_SHARED=123
)
# can include library dependencies here
target_link_libraries(common_stuff INTERFACE
pico_stdlib
)
# 2 Create the first executable including all the common stuff...
# we can set compile definitions for this executable here too. Because
# we depend on an INTERFACE library (common_stuff) we
# will pick up all of its definitions/dependencies too
add_executable(build_variant1)
target_link_libraries(build_variant1 common_stuff)
target_compile_definitions(build_variant1 PRIVATE
A_DEFINE_THAT_IS_NOT_SHARED=456)
pico_add_extra_outputs(build_variant1)
# 3 Create a second executable including all the common stuff
# this version also sets the DO_EXTRA define
add_executable(build_variant2)
target_link_libraries(build_variant2 common_stuff)
target_compile_definitions(build_variant2 PRIVATE
A_DEFINE_THAT_IS_NOT_SHARED=789
DO_EXTRA)
pico_add_extra_outputs(build_variant2)

View File

@ -0,0 +1,18 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
#include "other.h"
int main() {
stdio_init_all();
do_other();
#ifdef DO_EXTRA
printf("A little extra\n");
#endif
return 0;
}

View File

@ -0,0 +1,15 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "other.h"
void do_other() {
printf("The common thing is %d\n",
A_DEFINE_THAT_IS_SHARED);
printf("The binary local thing is %d\n",
A_DEFINE_THAT_IS_NOT_SHARED);
}

View File

@ -0,0 +1,7 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
void do_other();

12
divider/CMakeLists.txt Normal file
View File

@ -0,0 +1,12 @@
add_executable(hello_divider
hello_divider.c
)
# Pull in our pico_stdlib which pulls in commonly used features
target_link_libraries(hello_divider pico_stdlib)
# create map/bin/hex file etc.
pico_add_extra_outputs(hello_divider)
# add url via pico_set_program_url
example_auto_set_url(hello_divider)

75
divider/hello_divider.c Normal file
View File

@ -0,0 +1,75 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
#include "hardware/divider.h"
// tag::hello_divider[]
int main() {
stdio_init_all();
printf("Hello, divider!\n");
// This is the basic hardware divider function
int32_t dividend = 123456;
int32_t divisor = -321;
divmod_result_t result = hw_divider_divmod_s32(dividend, divisor);
printf("%d/%d = %d remainder %d\n", dividend, divisor, to_quotient_s32(result), to_remainder_s32(result));
// Is it right?
printf("Working backwards! Result %d should equal %d!\n\n",
to_quotient_s32(result) * divisor + to_remainder_s32(result), dividend);
// This is the recommended unsigned fast divider for general use.
int32_t udividend = 123456;
int32_t udivisor = 321;
divmod_result_t uresult = hw_divider_divmod_u32(udividend, udivisor);
printf("%d/%d = %d remainder %d\n", udividend, udivisor, to_quotient_u32(uresult), to_remainder_u32(uresult));
// Is it right?
printf("Working backwards! Result %d should equal %d!\n\n",
to_quotient_u32(result) * divisor + to_remainder_u32(result), dividend);
// You can also do divides asynchronously. Divides will be complete after 8 cyles.
hw_divider_divmod_s32_start(dividend, divisor);
// Do something for 8 cycles!
// In this example, our results function will wait for completion.
// Use hw_divider_result_nowait() if you don't want to wait, but are sure you have delayed at least 8 cycles
result = hw_divider_result_wait();
printf("Async result %d/%d = %d remainder %d\n", dividend, divisor, to_quotient_s32(result),
to_remainder_s32(result));
// For a really fast divide, you can use the inlined versions... the / involves a function call as / always does
// when using the ARM AEABI, so if you really want the best performance use the inlined versions.
// Note that the / operator function DOES use the hardware divider by default, although you can change
// that behavior by calling pico_set_divider_implementation in the cmake build for your target.
printf("%d / %d = (by operator %d) (inlined %d)\n", dividend, divisor,
dividend / divisor, hw_divider_s32_quotient_inlined(dividend, divisor));
// Note however you must manually save/restore the divider state if you call the inlined methods from within an IRQ
// handler.
hw_divider_state_t state;
hw_divider_divmod_s32_start(dividend, divisor);
hw_divider_save_state(&state);
hw_divider_divmod_s32_start(123, 7);
printf("inner %d / %d = %d\n", 123, 7, hw_divider_s32_quotient_wait());
hw_divider_restore_state(&state);
int32_t tmp = hw_divider_s32_quotient_wait();
printf("outer divide %d / %d = %d\n", dividend, divisor, tmp);
return 0;
}
// end::hello_divider[]

5
dma/CMakeLists.txt Normal file
View File

@ -0,0 +1,5 @@
if (NOT PICO_NO_HARDWARE)
add_subdirectory(channel_irq)
add_subdirectory(control_blocks)
add_subdirectory(hello_dma)
endif ()

View File

@ -0,0 +1,18 @@
add_executable(dma_channel_irq
channel_irq.c
)
pico_generate_pio_header(dma_channel_irq ${CMAKE_CURRENT_LIST_DIR}/pio_serialiser.pio)
target_link_libraries(dma_channel_irq
pico_stdlib
hardware_dma
hardware_irq
hardware_pio
)
# create map/bin/hex file etc.
pico_add_extra_outputs(dma_channel_irq)
# add url via pico_set_program_url
example_auto_set_url(dma_channel_irq)

View File

@ -0,0 +1,91 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
// Show how to reconfigure and restart a channel in a channel completion
// interrupt handler.
//
// Our DMA channel will transfer data to a PIO state machine, which is
// configured to serialise the raw bits that we push, one by one. We're going
// to use this to do some crude LED PWM by repeatedly sending values with the
// right balance of 1s and 0s. (note there are better ways to do PWM with PIO
// -- see the PIO PWM example).
//
// Once the channel has sent a predetermined amount of data, it will halt, and
// raise an interrupt flag. The processor will enter the interrupt handler in
// response to this, where it will reconfigure and restart the channel. This
// repeats.
#include <stdio.h>
#include "hardware/dma.h"
#include "hardware/irq.h"
#include "pio_serialiser.pio.h"
// PIO sends one bit per 10 system clock cycles. DMA sends the same 32-bit
// value 10 000 times before halting. This means we cycle through the 32 PWM
// levels roughly once per second.
#define PIO_SERIAL_CLKDIV 10.f
#define PWM_REPEAT_COUNT 10000
#define N_PWM_LEVELS 32
int dma_chan;
void dma_handler() {
static int pwm_level = 0;
static uint32_t wavetable[N_PWM_LEVELS];
static bool first_run = true;
// Entry number `i` has `i` one bits and `(32 - i)` zero bits.
if (first_run) {
first_run = false;
for (int i = 0; i < N_PWM_LEVELS; ++i)
wavetable[i] = ~(~0u << i);
}
// Clear the interrupt request.
dma_hw->ints0 = 1u << dma_chan;
// Give the channel a new wave table entry to read from, and re-trigger it
dma_channel_set_read_addr(dma_chan, &wavetable[pwm_level], true);
pwm_level = (pwm_level + 1) % N_PWM_LEVELS;
}
int main() {
// Set up a PIO state machine to serialise our bits
uint offset = pio_add_program(pio0, &pio_serialiser_program);
pio_serialiser_program_init(pio0, 0, offset, PICO_DEFAULT_LED_PIN, PIO_SERIAL_CLKDIV);
// Configure a channel to write the same word (32 bits) repeatedly to PIO0
// SM0's TX FIFO, paced by the data request signal from that peripheral.
dma_chan = dma_claim_unused_channel(true);
dma_channel_config c = dma_channel_get_default_config(dma_chan);
channel_config_set_transfer_data_size(&c, DMA_SIZE_32);
channel_config_set_read_increment(&c, false);
channel_config_set_dreq(&c, DREQ_PIO0_TX0);
dma_channel_configure(
dma_chan,
&c,
&pio0_hw->txf[0], // Write address (only need to set this once)
NULL, // Don't provide a read address yet
PWM_REPEAT_COUNT, // Write the same value many times, then halt and interrupt
false // Don't start yet
);
// Tell the DMA to raise IRQ line 0 when the channel finishes a block
dma_channel_set_irq0_enabled(dma_chan, true);
// Configure the processor to run dma_handler() when DMA IRQ 0 is asserted
irq_set_exclusive_handler(DMA_IRQ_0, dma_handler);
irq_set_enabled(DMA_IRQ_0, true);
// Manually call the handler once, to trigger the first transfer
dma_handler();
// Everything else from this point is interrupt-driven. The processor has
// time to sit and think about its early retirement -- maybe open a bakery?
while (true)
tight_loop_contents();
}

View File

@ -0,0 +1,27 @@
;
; Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
;
; SPDX-License-Identifier: BSD-3-Clause
;
.program pio_serialiser
; Just serialise a stream of bits. Take 32 bits from each FIFO record. LSB-first.
.wrap_target
out pins, 1
.wrap
% c-sdk {
static inline void pio_serialiser_program_init(PIO pio, uint sm, uint offset, uint data_pin, float clk_div) {
pio_gpio_init(pio, data_pin);
pio_sm_set_consecutive_pindirs(pio, sm, data_pin, 1, true);
pio_sm_config c = pio_serialiser_program_get_default_config(offset);
sm_config_set_out_pins(&c, data_pin, 1);
sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_TX);
sm_config_set_clkdiv(&c, clk_div);
sm_config_set_out_shift(&c, true, true, 32);
pio_sm_init(pio, sm, offset, &c);
pio_sm_set_enabled(pio, sm, true);
}
%}

View File

@ -0,0 +1,11 @@
add_executable(dma_control_blocks
control_blocks.c
)
target_link_libraries(dma_control_blocks pico_stdlib hardware_dma)
# create map/bin/hex file etc.
pico_add_extra_outputs(dma_control_blocks)
# add url via pico_set_program_url
example_auto_set_url(dma_control_blocks)

View File

@ -0,0 +1,111 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
// Use two DMA channels to make a programmed sequence of data transfers to the
// UART (a data gather operation). One channel is responsible for transferring
// the actual data, the other repeatedly reprograms that channel.
#include <stdio.h>
#include "pico/stdlib.h"
#include "hardware/dma.h"
#include "hardware/structs/uart.h"
// These buffers will be DMA'd to the UART, one after the other.
const char word0[] = "Transferring ";
const char word1[] = "one ";
const char word2[] = "word ";
const char word3[] = "at ";
const char word4[] = "a ";
const char word5[] = "time.\n";
// Note the order of the fields here: it's important that the length is before
// the read address, because the control channel is going to write to the last
// two registers in alias 3 on the data channel:
// +0x0 +0x4 +0x8 +0xC (Trigger)
// Alias 0: READ_ADDR WRITE_ADDR TRANS_COUNT CTRL
// Alias 1: CTRL READ_ADDR WRITE_ADDR TRANS_COUNT
// Alias 2: CTRL TRANS_COUNT READ_ADDR WRITE_ADDR
// Alias 3: CTRL WRITE_ADDR TRANS_COUNT READ_ADDR
//
// This will program the transfer count and read address of the data channel,
// and trigger it. Once the data channel completes, it will restart the
// control channel (via CHAIN_TO) to load the next two words into its control
// registers.
const struct {uint32_t len; const char *data;} control_blocks[] = {
{count_of(word0) - 1, word0}, // Skip null terminator
{count_of(word1) - 1, word1},
{count_of(word2) - 1, word2},
{count_of(word3) - 1, word3},
{count_of(word4) - 1, word4},
{count_of(word5) - 1, word5},
{0, NULL} // Null trigger to end chain.
};
int main() {
stdio_init_all();
puts("DMA control block example:");
// ctrl_chan loads control blocks into data_chan, which executes them.
int ctrl_chan = dma_claim_unused_channel(true);
int data_chan = dma_claim_unused_channel(true);
// The control channel transfers two words into the data channel's control
// registers, then halts. The write address wraps on a two-word
// (eight-byte) boundary, so that the control channel writes the same two
// registers when it is next triggered.
dma_channel_config c = dma_channel_get_default_config(ctrl_chan);
channel_config_set_transfer_data_size(&c, DMA_SIZE_32);
channel_config_set_read_increment(&c, true);
channel_config_set_write_increment(&c, true);
channel_config_set_ring(&c, true, 3); // 1 << 3 byte boundary on write ptr
dma_channel_configure(
ctrl_chan,
&c,
&dma_hw->ch[data_chan].al3_transfer_count, // Initial write address
&control_blocks[0], // Initial read address
2, // Halt after each control block
false // Don't start yet
);
// The data channel is set up to write to the UART FIFO (paced by the
// UART's TX data request signal) and then chain to the control channel
// once it completes. The control channel programs a new read address and
// data length, and retriggers the data channel.
c = dma_channel_get_default_config(data_chan);
channel_config_set_transfer_data_size(&c, DMA_SIZE_8);
channel_config_set_dreq(&c, DREQ_UART0_TX + 2 * PICO_DEFAULT_UART);
// Trigger ctrl_chan when data_chan completes
channel_config_set_chain_to(&c, ctrl_chan);
// Raise the IRQ flag when 0 is written to a trigger register (end of chain):
channel_config_set_irq_quiet(&c, true);
dma_channel_configure(
data_chan,
&c,
&(PICO_DEFAULT_UART ? uart1_hw : uart0_hw)->dr,
NULL, // Initial read address and transfer count are unimportant;
0, // the control channel will reprogram them each time.
false // Don't start yet.
);
// Everything is ready to go. Tell the control channel to load the first
// control block. Everything is automatic from here.
dma_start_channel_mask(1u << ctrl_chan);
// The data channel will assert its IRQ flag when it gets a null trigger,
// indicating the end of the control block list. We're just going to wait
// for the IRQ flag instead of setting up an interrupt handler.
while (!(dma_hw->intr & 1u << data_chan))
tight_loop_contents();
dma_hw->ints0 = 1u << data_chan;
puts("DMA finished.");
}

View File

@ -0,0 +1,11 @@
add_executable(hello_dma
hello_dma.c
)
target_link_libraries(hello_dma pico_stdlib hardware_dma)
# create map/bin/hex file etc.
pico_add_extra_outputs(hello_dma)
# add url via pico_set_program_url
example_auto_set_url(hello_dma)

49
dma/hello_dma/hello_dma.c Normal file
View File

@ -0,0 +1,49 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
// Use the DMA to copy data between two buffers in memory.
#include <stdio.h>
#include "pico/stdlib.h"
#include "hardware/dma.h"
// Data will be copied from src to dst
const char src[] = "Hello, world! (from DMA)";
char dst[count_of(src)];
int main() {
stdio_init_all();
// Get a free channel, panic() if there are none
int chan = dma_claim_unused_channel(true);
// 8 bit transfers. Both read and write address increment after each
// transfer (each pointing to a location in src or dst respectively).
// No DREQ is selected, so the DMA transfers as fast as it can.
dma_channel_config c = dma_channel_get_default_config(chan);
channel_config_set_transfer_data_size(&c, DMA_SIZE_8);
channel_config_set_read_increment(&c, true);
channel_config_set_write_increment(&c, true);
dma_channel_configure(
chan, // Channel to be configured
&c, // The configuration we just created
dst, // The initial write address
src, // The initial read address
count_of(src), // Number of transfers; in this case each is 1 byte.
true // Start immediately.
);
// We could choose to go and do something else whilst the DMA is doing its
// thing. In this case the processor has nothing else to do, so we just
// wait for the DMA to finish.
dma_channel_wait_for_finish_blocking(chan);
// The DMA has now copied our text from the transmit buffer (src) to the
// receive buffer (dst), so we can print it out from there.
puts(dst);
}

View File

@ -0,0 +1,5 @@
set(PICO_EXAMPLE_URL_BASE "https://github.com/raspberrypi/pico-examples/tree/HEAD")
macro(example_auto_set_url TARGET)
file(RELATIVE_PATH URL_REL_PATH "${PICO_EXAMPLES_PATH}" "${CMAKE_CURRENT_LIST_DIR}")
pico_set_program_url(${TARGET} "${PICO_EXAMPLE_URL_BASE}/${URL_REL_PATH}")
endmacro()

7
flash/CMakeLists.txt Normal file
View File

@ -0,0 +1,7 @@
if (NOT PICO_NO_HARDWARE)
add_subdirectory(cache_perfctr)
add_subdirectory(nuke)
add_subdirectory(program)
add_subdirectory(ssi_dma)
add_subdirectory(xip_stream)
endif ()

View File

@ -0,0 +1,13 @@
add_executable(flash_cache_perfctr
flash_cache_perfctr.c
)
target_link_libraries(flash_cache_perfctr
pico_stdlib
)
# create map/bin/hex file etc.
pico_add_extra_outputs(flash_cache_perfctr)
# add url via pico_set_program_url
example_auto_set_url(flash_cache_perfctr)

View File

@ -0,0 +1,88 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include <stdlib.h>
#include "pico/stdlib.h"
#include "hardware/structs/xip_ctrl.h"
// Example of using cache hit/access counters, and showing the effect of
// invalidate on cache miss/hit.
const uint32_t test_data[8] = {0, 1, 2, 3, 4, 5, 6, 7};
void __no_inline_not_in_flash_func(check)(bool cond, const char *msg) {
if (!cond) {
puts(msg);
exit(-1);
}
}
void __no_inline_not_in_flash_func(check_hit_miss_invalidate)() {
io_rw_32 *test_data_ptr = (io_rw_32 *) test_data;
//tag::check_hit_miss_invalidate[]
// Flush cache to make sure we miss the first time we access test_data
xip_ctrl_hw->flush = 1;
while (!(xip_ctrl_hw->stat & XIP_STAT_FLUSH_READY_BITS))
tight_loop_contents();
// Clear counters (write any value to clear)
xip_ctrl_hw->ctr_acc = 1;
xip_ctrl_hw->ctr_hit = 1;
(void) *test_data_ptr;
check(xip_ctrl_hw->ctr_hit == 0 && xip_ctrl_hw->ctr_acc == 1,
"First access to data should miss");
(void) *test_data_ptr;
check(xip_ctrl_hw->ctr_hit == 1 && xip_ctrl_hw->ctr_acc == 2,
"Second access to data should hit");
// Write to invalidate individual cache lines (64 bits)
// Writes must be directed to the cacheable, allocatable alias (address 0x10.._....)
*test_data_ptr = 0;
(void) *test_data_ptr;
check(xip_ctrl_hw->ctr_hit == 1 && xip_ctrl_hw->ctr_acc == 3,
"Should miss after invalidation");
(void) *test_data_ptr;
check(xip_ctrl_hw->ctr_hit == 2 && xip_ctrl_hw->ctr_acc == 4,
"Second access after invalidation should hit again");
//end::check_hit_miss_invalidate[]
}
// Some code which achieves a very high cache hit rate:
int recursive_fibonacci(int n) {
if (n <= 1)
return 1;
else
return recursive_fibonacci(n - 1) + recursive_fibonacci(n - 2);
}
int main() {
stdio_init_all();
uint hit = xip_ctrl_hw->ctr_hit;
uint access = xip_ctrl_hw->ctr_acc;
if (access == 0)
printf("It looks like you're running this example from SRAM. This probably won't go well!\n");
// Note the hit rate will appear quite low at boot, as the .data,
// .time_critical init in crt0 read a lot of read-once data from flash
printf("At boot: %d hits, %d accesses\n", hit, access);
printf("Hit rate so far: %.1f%%\n", hit * 100.f / access);
printf("Calculate 25th fibonacci number: %d\n", recursive_fibonacci(25));
printf("New hit rate after printf and fibonacci: %.1f%%\n", xip_ctrl_hw->ctr_hit * 100.f / xip_ctrl_hw->ctr_acc);
check_hit_miss_invalidate();
printf("Hit/miss check passed\n");
return 0;
}

18
flash/nuke/CMakeLists.txt Normal file
View File

@ -0,0 +1,18 @@
add_executable(flash_nuke
nuke.c
)
target_link_libraries(flash_nuke
pico_stdlib
hardware_flash
)
# It doesn't make sense to run this program from flash. Always build a
# RAM-only binary.
pico_set_binary_type(flash_nuke no_flash)
pico_add_extra_outputs(flash_nuke)
# add url via pico_set_program_url
example_auto_set_url(flash_nuke)

47
flash/nuke/nuke.c Normal file
View File

@ -0,0 +1,47 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
// Obliterate the contents of flash. This is a silly thing to do if you are
// trying to run this program from flash, so you should really load and run
// directly from SRAM. You can enable RAM-only builds for all targets by doing:
//
// cmake -DPICO_NO_FLASH=1 ..
//
// in your build directory. We've also forced no-flash builds for this app in
// particular by adding:
//
// pico_set_binary_type(flash_nuke no_flash)
//
// To the CMakeLists.txt app for this file. Just to be sure, we can check the
// define:
#if !PICO_NO_FLASH
#error "This example must be built to run from SRAM!"
#endif
#include "pico/stdlib.h"
#include "hardware/flash.h"
#include "pico/bootrom.h"
int main() {
flash_range_erase(0, PICO_FLASH_SIZE_BYTES);
// Leave an eyecatcher pattern in the first page of flash so picotool can
// more easily check the size:
static const uint8_t eyecatcher[FLASH_PAGE_SIZE] = "NUKE";
flash_range_program(0, eyecatcher, FLASH_PAGE_SIZE);
// Flash LED for success
gpio_init(PICO_DEFAULT_LED_PIN);
gpio_set_dir(PICO_DEFAULT_LED_PIN, GPIO_OUT);
for (int i = 0; i < 3; ++i) {
gpio_put(PICO_DEFAULT_LED_PIN, 1);
sleep_ms(100);
gpio_put(PICO_DEFAULT_LED_PIN, 0);
sleep_ms(100);
}
// Pop back up as an MSD drive
reset_usb_boot(0, 0);
}

View File

@ -0,0 +1,14 @@
add_executable(flash_program
flash_program.c
)
target_link_libraries(flash_program
pico_stdlib
hardware_flash
)
# create map/bin/hex file etc.
pico_add_extra_outputs(flash_program)
# add url via pico_set_program_url
example_auto_set_url(flash_program)

View File

@ -0,0 +1,58 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include <stdlib.h>
#include "pico/stdlib.h"
#include "hardware/flash.h"
// We're going to erase and reprogram a region 256k from the start of flash.
// Once done, we can access this at XIP_BASE + 256k.
#define FLASH_TARGET_OFFSET (256 * 1024)
const uint8_t *flash_target_contents = (const uint8_t *) (XIP_BASE + FLASH_TARGET_OFFSET);
void print_buf(const uint8_t *buf, size_t len) {
for (size_t i = 0; i < len; ++i) {
printf("%02x", buf[i]);
if (i % 16 == 15)
printf("\n");
else
printf(" ");
}
}
int main() {
stdio_init_all();
uint8_t random_data[FLASH_PAGE_SIZE];
for (int i = 0; i < FLASH_PAGE_SIZE; ++i)
random_data[i] = rand() >> 16;
printf("Generated random data:\n");
print_buf(random_data, FLASH_PAGE_SIZE);
// Note that a whole number of sectors must be erased at a time.
printf("\nErasing target region...\n");
flash_range_erase(FLASH_TARGET_OFFSET, FLASH_SECTOR_SIZE);
printf("Done. Read back target region:\n");
print_buf(flash_target_contents, FLASH_PAGE_SIZE);
printf("\nProgramming target region...\n");
flash_range_program(FLASH_TARGET_OFFSET, random_data, FLASH_PAGE_SIZE);
printf("Done. Read back target region:\n");
print_buf(flash_target_contents, FLASH_PAGE_SIZE);
bool mismatch = false;
for (int i = 0; i < FLASH_PAGE_SIZE; ++i) {
if (random_data[i] != flash_target_contents[i])
mismatch = true;
}
if (mismatch)
printf("Programming failed!\n");
else
printf("Programming successful!\n");
}

View File

@ -0,0 +1,14 @@
add_executable(flash_ssi_dma
flash_ssi_dma.c
)
target_link_libraries(flash_ssi_dma
pico_stdlib
hardware_dma
)
# create map/bin/hex file etc.
pico_add_extra_outputs(flash_ssi_dma)
# add url via pico_set_program_url
example_auto_set_url(flash_ssi_dma)

View File

@ -0,0 +1,90 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include <string.h>
#include "pico/stdlib.h"
#include "pico/time.h"
#include "hardware/dma.h"
#include "hardware/structs/ssi.h"
// This example DMAs 16kB of data from the start of flash to SRAM, and
// measures the transfer speed.
//
// The SSI (flash interface) inside the XIP block has DREQ logic, so we can
// DMA directly from its FIFOs. Unlike the XIP stream hardware (see
// flash_xip_stream.c) this can *not* be done whilst code is running from
// flash, without careful footwork like we do here. The tradeoff is that it's
// ~2.5x as fast in QSPI mode, ~2x as fast in SPI mode.
void __no_inline_not_in_flash_func(flash_bulk_read)(uint32_t *rxbuf, uint32_t flash_offs, size_t len,
uint dma_chan) {
// SSI must be disabled to set transfer size. If software is executing
// from flash right now then it's about to have a bad time
ssi_hw->ssienr = 0;
ssi_hw->ctrlr1 = len - 1; // NDF, number of data frames
ssi_hw->dmacr = SSI_DMACR_TDMAE_BITS | SSI_DMACR_RDMAE_BITS;
ssi_hw->ssienr = 1;
// Other than NDF, the SSI configuration used for XIP is suitable for a bulk read too.
// Configure and start the DMA. Note we are avoiding the dma_*() functions
// as we can't guarantee they'll be inlined
dma_hw->ch[dma_chan].read_addr = (uint32_t) &ssi_hw->dr0;
dma_hw->ch[dma_chan].write_addr = (uint32_t) rxbuf;
dma_hw->ch[dma_chan].transfer_count = len;
// Must enable DMA byteswap because non-XIP 32-bit flash transfers are
// big-endian on SSI (we added a hardware tweak to make XIP sensible)
dma_hw->ch[dma_chan].ctrl_trig =
DMA_CH0_CTRL_TRIG_BSWAP_BITS |
DREQ_XIP_SSIRX << DMA_CH0_CTRL_TRIG_TREQ_SEL_LSB |
dma_chan << DMA_CH0_CTRL_TRIG_CHAIN_TO_LSB |
DMA_CH0_CTRL_TRIG_INCR_WRITE_BITS |
DMA_CH0_CTRL_TRIG_DATA_SIZE_VALUE_SIZE_WORD << DMA_CH0_CTRL_TRIG_DATA_SIZE_LSB |
DMA_CH0_CTRL_TRIG_EN_BITS;
// Now DMA is waiting, kick off the SSI transfer (mode continuation bits in LSBs)
ssi_hw->dr0 = (flash_offs << 8u) | 0xa0u;
// Wait for DMA finish
while (dma_hw->ch[dma_chan].ctrl_trig & DMA_CH0_CTRL_TRIG_BUSY_BITS);
// Reconfigure SSI before we jump back into flash!
ssi_hw->ssienr = 0;
ssi_hw->ctrlr1 = 0; // Single 32-bit data frame per transfer
ssi_hw->dmacr = 0;
ssi_hw->ssienr = 1;
}
#define DATA_SIZE_WORDS 4096
uint32_t rxdata[DATA_SIZE_WORDS];
uint32_t *expect = (uint32_t *) XIP_NOCACHE_NOALLOC_BASE;
int main() {
stdio_init_all();
memset(rxdata, 0, DATA_SIZE_WORDS * sizeof(uint32_t));
printf("Starting DMA\n");
uint32_t start_time = time_us_32();
flash_bulk_read(rxdata, 0, DATA_SIZE_WORDS, 0);
uint32_t finish_time = time_us_32();
printf("DMA finished\n");
float elapsed_time_s = 1e-6f * (finish_time - start_time);
printf("Transfer speed: %.3f MB/s\n", (sizeof(uint32_t) * DATA_SIZE_WORDS / 1e6f) / elapsed_time_s);
bool mismatch = false;
for (int i = 0; i < DATA_SIZE_WORDS; ++i) {
if (rxdata[i] != expect[i]) {
printf("Mismatch at %d: expected %08x, got %08x\n", i, expect[i], rxdata[i]);
mismatch = true;
break;
}
}
if (!mismatch)
printf("Data check ok\n");
}

View File

@ -0,0 +1,14 @@
add_executable(flash_xip_stream
flash_xip_stream.c
)
target_link_libraries(flash_xip_stream
pico_stdlib
hardware_dma
)
# create map/bin/hex file etc.
pico_add_extra_outputs(flash_xip_stream)
# add url via pico_set_program_url
example_auto_set_url(flash_xip_stream)

View File

@ -0,0 +1,88 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include <stdlib.h>
#include "pico/stdlib.h"
#include "hardware/dma.h"
#include "hardware/regs/addressmap.h"
#include "hardware/structs/xip_ctrl.h"
#include "random_test_data.h"
// The XIP has some internal hardware that can stream a linear access sequence
// to a DMAable FIFO, while the system is still doing random accesses on flash
// code + data.
uint32_t buf[count_of(random_test_data)];
int main() {
stdio_init_all();
for (int i = 0; i < count_of(random_test_data); ++i)
buf[i] = 0;
// This example won't work with PICO_NO_FLASH builds. Note that XIP stream
// can be made to work in these cases, if you enable some XIP mode first
// (e.g. via calling flash_enter_cmd_xip() in ROM). However, you will get
// much better performance by DMAing directly from the SSI's FIFOs, as in
// this way you can clock data continuously on the QSPI bus, rather than a
// series of short transfers.
if ((uint32_t) &random_test_data[0] >= SRAM_BASE) {
printf("You need to run this example from flash!\n");
exit(-1);
}
// Transfer started by writing nonzero value to stream_ctr. stream_ctr
// will count down as the transfer progresses. Can terminate early by
// writing 0 to stream_ctr.
// It's a good idea to drain the FIFO first!
printf("Starting stream from %p\n", random_test_data);
//tag::start_stream[]
while (!(xip_ctrl_hw->stat & XIP_STAT_FIFO_EMPTY))
(void) xip_ctrl_hw->stream_fifo;
xip_ctrl_hw->stream_addr = (uint32_t) &random_test_data[0];
xip_ctrl_hw->stream_ctr = count_of(random_test_data);
//end::start_stream[]
// Start DMA transfer from XIP stream FIFO to our buffer in memory. Use
// the auxiliary bus slave for the DMA<-FIFO accesses, to avoid stalling
// the DMA against general XIP traffic. Doesn't really matter for this
// example, but it can have a huge effect on DMA throughput.
printf("Starting DMA\n");
//tag::start_dma[]
const uint dma_chan = 0;
dma_channel_config cfg = dma_channel_get_default_config(dma_chan);
channel_config_set_read_increment(&cfg, false);
channel_config_set_write_increment(&cfg, true);
channel_config_set_dreq(&cfg, DREQ_XIP_STREAM);
dma_channel_configure(
dma_chan,
&cfg,
(void *) buf, // Write addr
(const void *) XIP_AUX_BASE, // Read addr
count_of(random_test_data), // Transfer count
true // Start immediately!
);
//end::start_dma[]
dma_channel_wait_for_finish_blocking(dma_chan);
printf("DMA complete\n");
bool mismatch = false;
for (int i = 0; i < count_of(random_test_data); ++i) {
if (random_test_data[i] != buf[i]) {
printf("Data mismatch: %08x (actual) != %08x (expected)\n", buf[i], random_test_data[i]);
mismatch = true;
break;
}
printf("%08x%c", buf[i], i % 8 == 7 ? '\n' : ' ');
}
if (!mismatch)
printf("Data check OK\n");
}

View File

@ -0,0 +1,160 @@
const uint32_t random_test_data[] = {
0x76654e22, 0x47207265, 0x616e6e6f,
0x76694720, 0x6f592065, 0x70552075,
0x570a0a22, 0x65722765, 0x206f6e20,
0x61727473, 0x7265676e, 0x6f742073,
0x766f6c20, 0x6f590a65, 0x6e6b2075,
0x7420776f, 0x72206568, 0x73656c75,
0x646e6120, 0x206f7320, 0x49206f64,
0x6620410a, 0x206c6c75, 0x6d6d6f63,
0x656d7469, 0x7327746e, 0x61687720,
0x27492074, 0x6874206d, 0x696b6e69,
0x6f20676e, 0x6f590a66, 0x6f772075,
0x6e646c75, 0x67207427, 0x74207465,
0x20736968, 0x6d6f7266, 0x796e6120,
0x68746f20, 0x67207265, 0x0a0a7975,
0x756a2049, 0x77207473, 0x616e6e61,
0x6c657420, 0x6f79206c, 0x6f682075,
0x27492077, 0x6566206d, 0x6e696c65,
0x6f470a67, 0x20617474, 0x656b616d,
0x756f7920, 0x646e7520, 0x74737265,
0x0a646e61, 0x76654e0a, 0x67207265,
0x616e6e6f, 0x76696720, 0x6f792065,
0x70752075, 0x76654e0a, 0x67207265,
0x616e6e6f, 0x74656c20, 0x756f7920,
0x776f6420, 0x654e0a6e, 0x20726576,
0x6e6e6f67, 0x75722061, 0x7261206e,
0x646e756f, 0x646e6120, 0x73656420,
0x20747265, 0x0a756f79, 0x6576654e,
0x6f672072, 0x20616e6e, 0x656b616d,
0x756f7920, 0x79726320, 0x76654e0a,
0x67207265, 0x616e6e6f, 0x79617320,
0x6f6f6720, 0x65796264, 0x76654e0a,
0x67207265, 0x616e6e6f, 0x6c657420,
0x2061206c, 0x2065696c, 0x20646e61,
0x74727568, 0x756f7920, 0x65570a0a,
0x20657627, 0x776f6e6b, 0x6165206e,
0x6f206863, 0x72656874, 0x726f6620,
0x206f7320, 0x676e6f6c, 0x756f590a,
0x65682072, 0x27747261, 0x65622073,
0x61206e65, 0x6e696863, 0x62202c67,
0x590a7475, 0x7227756f, 0x6f742065,
0x6873206f, 0x6f742079, 0x79617320,
0x0a746920, 0x69736e49, 0x202c6564,
0x62206577, 0x2068746f, 0x776f6e6b,
0x61687720, 0x20732774, 0x6e656562,
0x696f6720, 0x6f20676e, 0x65570a6e,
0x6f6e6b20, 0x68742077, 0x61672065,
0x6120656d, 0x7720646e, 0x65722765,
0x6e6f6720, 0x7020616e, 0x2079616c,
0x0a0a7469, 0x20646e41, 0x79206669,
0x6120756f, 0x6d206b73, 0x6f682065,
0x27492077, 0x6566206d, 0x6e696c65,
0x6f440a67, 0x2074276e, 0x6c6c6574,
0x20656d20, 0x27756f79, 0x74206572,
0x62206f6f, 0x646e696c, 0x206f7420,
0x0a656573, 0x76654e0a, 0x67207265,
0x616e6e6f, 0x76696720, 0x6f792065,
0x70752075, 0x76654e0a, 0x67207265,
0x616e6e6f, 0x74656c20, 0x756f7920,
0x776f6420, 0x654e0a6e, 0x20726576,
0x6e6e6f67, 0x75722061, 0x7261206e,
0x646e756f, 0x646e6120, 0x73656420,
0x20747265, 0x0a756f79, 0x6576654e,
0x6f672072, 0x20616e6e, 0x656b616d,
0x756f7920, 0x79726320, 0x76654e0a,
0x67207265, 0x616e6e6f, 0x79617320,
0x6f6f6720, 0x65796264, 0x76654e0a,
0x67207265, 0x616e6e6f, 0x6c657420,
0x2061206c, 0x2065696c, 0x20646e61,
0x74727568, 0x756f7920, 0x654e0a0a,
0x20726576, 0x6e6e6f67, 0x69672061,
0x79206576, 0x7520756f, 0x654e0a70,
0x20726576, 0x6e6e6f67, 0x656c2061,
0x6f792074, 0x6f642075, 0x4e0a6e77,
0x72657665, 0x6e6f6720, 0x7220616e,
0x61206e75, 0x6e756f72, 0x6e612064,
0x65642064, 0x74726573, 0x756f7920,
0x76654e0a, 0x67207265, 0x616e6e6f,
0x6b616d20, 0x6f792065, 0x72632075,
0x654e0a79, 0x20726576, 0x6e6e6f67,
0x61732061, 0x6f672079, 0x7962646f,
0x654e0a65, 0x20726576, 0x6e6e6f67,
0x65742061, 0x61206c6c, 0x65696c20,
0x646e6120, 0x72756820, 0x6f792074,
0x280a0a75, 0x2c686f4f, 0x76696720,
0x6f792065, 0x70752075, 0x4f280a29,
0x202c686f, 0x65766967, 0x756f7920,
0x29707520, 0x76654e0a, 0x67207265,
0x616e6e6f, 0x76696720, 0x6e202c65,
0x72657665, 0x6e6f6720, 0x6720616e,
0x0a657669, 0x76694728, 0x6f792065,
0x70752075, 0x654e0a29, 0x20726576,
0x6e6e6f67, 0x69672061, 0x202c6576,
0x6576656e, 0x6f672072, 0x20616e6e,
0x65766967, 0x6947280a, 0x79206576,
0x7520756f, 0x0a0a2970, 0x76276557,
0x6e6b2065, 0x206e776f, 0x68636165,
0x68746f20, 0x66207265, 0x7320726f,
0x6f6c206f, 0x590a676e, 0x2072756f,
0x72616568, 0x20732774, 0x6e656562,
0x68636120, 0x2c676e69, 0x74756220,
0x756f590a, 0x20657227, 0x206f6f74,
0x20796873, 0x73206f74, 0x69207961,
0x6e490a74, 0x65646973, 0x6577202c,
0x746f6220, 0x6e6b2068, 0x7720776f,
0x27746168, 0x65622073, 0x67206e65,
0x676e696f, 0x0a6e6f20, 0x6b206557,
0x20776f6e, 0x20656874, 0x656d6167,
0x646e6120, 0x27657720, 0x67206572,
0x616e6e6f, 0x616c7020, 0x74692079,
0x20490a0a, 0x7473756a, 0x6e617720,
0x7420616e, 0x206c6c65, 0x20756f79,
0x20776f68, 0x206d2749, 0x6c656566,
0x0a676e69, 0x74746f47, 0x616d2061,
0x7920656b, 0x7520756f, 0x7265646e,
0x6e617473, 0x4e0a0a64, 0x72657665,
0x6e6f6720, 0x6720616e, 0x20657669,
0x20756f79, 0x4e0a7075, 0x72657665,
0x6e6f6720, 0x6c20616e, 0x79207465,
0x6420756f, 0x0a6e776f, 0x6576654e,
0x6f672072, 0x20616e6e, 0x206e7572,
0x756f7261, 0x6120646e, 0x6420646e,
0x72657365, 0x6f792074, 0x654e0a75,
0x20726576, 0x6e6e6f67, 0x616d2061,
0x7920656b, 0x6320756f, 0x4e0a7972,
0x72657665, 0x6e6f6720, 0x7320616e,
0x67207961, 0x62646f6f, 0x4e0a6579,
0x72657665, 0x6e6f6720, 0x7420616e,
0x206c6c65, 0x696c2061, 0x6e612065,
0x75682064, 0x79207472, 0x0a0a756f,
0x6576654e, 0x6f672072, 0x20616e6e,
0x65766967, 0x756f7920, 0x0a707520,
0x6576654e, 0x6f672072, 0x20616e6e,
0x2074656c, 0x20756f79, 0x6e776f64,
0x76654e0a, 0x67207265, 0x616e6e6f,
0x6e757220, 0x6f726120, 0x20646e75,
0x20646e61, 0x65736564, 0x79207472,
0x4e0a756f, 0x72657665, 0x6e6f6720,
0x6d20616e, 0x20656b61, 0x20756f79,
0x0a797263, 0x6576654e, 0x6f672072,
0x20616e6e, 0x20796173, 0x646f6f67,
0x0a657962, 0x6576654e, 0x6f672072,
0x20616e6e, 0x6c6c6574, 0x6c206120,
0x61206569, 0x6820646e, 0x20747275,
0x0a756f79, 0x76654e0a, 0x67207265,
0x616e6e6f, 0x76696720, 0x6f792065,
0x70752075, 0x76654e0a, 0x67207265,
0x616e6e6f, 0x74656c20, 0x756f7920,
0x776f6420, 0x654e0a6e, 0x20726576,
0x6e6e6f67, 0x75722061, 0x7261206e,
0x646e756f, 0x646e6120, 0x73656420,
0x20747265, 0x0a756f79, 0x6576654e,
0x6f672072, 0x20616e6e, 0x656b616d,
0x756f7920, 0x79726320, 0x76654e0a,
0x67207265, 0x616e6e6f, 0x79617320,
0x6f6f6720, 0x65796264, 0x76654e0a,
0x67207265, 0x616e6e6f, 0x6c657420,
0x2061206c, 0x2065696c, 0x20646e61
};

5
gpio/CMakeLists.txt Normal file
View File

@ -0,0 +1,5 @@
if (NOT PICO_NO_HARDWARE)
add_subdirectory(dht_sensor)
add_subdirectory(hello_7segment)
add_subdirectory(hello_gpio_irq)
endif ()

View File

@ -0,0 +1,11 @@
add_executable(dht
dht.c
)
target_link_libraries(dht pico_stdlib)
pico_add_extra_outputs(dht)
# add url via pico_set_program_url
example_auto_set_url(dht)

View File

@ -0,0 +1,58 @@
= DHT-11, DHT-22, and AM2302 Sensors
:xrefstyle: short
The DHT sensors are fairly well known hobbyist sensors for measuring relative humidity and temperature using a capacitive humidity sensor, and a thermistor. While they are slow, one reading every ~2 seconds, they are reliable and good for basic data logging. Communication is based on a custom protocol which uses a single wire for data.
[NOTE]
======
The DHT-11 and DHT-22 sensors are the most common. They use the same protocol but have different characteristics, the DHT-22 has better accuracy, and has a larger sensor range than the DHT-11. The sensor is available from a number of retailers.
======
== Wiring information
See <<dht-wiring-diagram>> for wiring instructions.
[[dht-wiring-diagram]]
[pdfwidth=75%]
.Wiring the DHT-22 temperature sensor to Raspberry Pi Pico, and connecting Pico's UART0 to the Raspberry Pi 4.
image::pi-and-pico-uart-and-dht-sensor.png[]
NOTE: One of the pins (pin 3) on the DHT sensor will not be connected, it is not used.
You will want to place a 10 kΩ resistor between VCC and the data pin, to act as a medium-strength pull up on the data line.
Connecting UART0 of Pico to Raspberry Pi as in <<dht-wiring-diagram>> and you should see something similar to <<dht-serial-output-diagram>> in `minicom` when connected to `/dev/serial0` on the Raspberry Pi.
[[dht-serial-output-diagram]]
[pdfwidth=75%]
.Serial output over Pico's UART0 in a terminal window.
image::serial-output.png[]
Connect to `/dev/serial0` by typing,
----
$ minicom -b 115200 -o -D /dev/serial0
----
at the command line.
== List of Files
A list of files with descriptions of their function;
CMakeLists.txt:: Make file to incorporate the example in to the examples build tree.
dht.c:: The example code.
== Bill of Materials
.A list of materials required for the example
[[dht-22-bom-table]]
[cols=3]
|===
| *Item* | *Quantity* | Details
| Breadboard | 1 | generic part
| Raspberry Pi Pico | 1 | http://raspberrypi.org/
| 10 kΩ resistor | 1 | generic part
| M/M Jumper wires | 4 | generic part
| DHT-22 sensor | 1 | generic part
|===

83
gpio/dht_sensor/dht.c Normal file
View File

@ -0,0 +1,83 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
**/
#include <stdio.h>
#include <math.h>
#include "pico/stdlib.h"
#include "hardware/gpio.h"
const uint LED_PIN = PICO_DEFAULT_LED_PIN;
const uint DHT_PIN = 15;
const uint MAX_TIMINGS = 85;
typedef struct {
float humidity;
float temp_celsius;
} dht_reading;
void read_from_dht(dht_reading *result);
int main() {
stdio_init_all();
gpio_init(LED_PIN);
gpio_init(DHT_PIN);
gpio_set_dir(LED_PIN, GPIO_OUT);
while (1) {
dht_reading reading;
read_from_dht(&reading);
float fahrenheit = (reading.temp_celsius * 9 / 5) + 32;
printf("Humidity = %.1f%%, Temperature = %.1fC (%.1fF)\n",
reading.humidity, reading.temp_celsius, fahrenheit);
sleep_ms(2000);
}
}
void read_from_dht(dht_reading *result) {
int data[5] = {0, 0, 0, 0, 0};
uint last = 1;
uint j = 0;
gpio_set_dir(DHT_PIN, GPIO_OUT);
gpio_put(DHT_PIN, 0);
sleep_ms(20);
gpio_set_dir(DHT_PIN, GPIO_IN);
gpio_put(LED_PIN, 1);
for (uint i = 0; i < MAX_TIMINGS; i++) {
uint count = 0;
while (gpio_get(DHT_PIN) == last) {
count++;
sleep_us(1);
if (count == 255) break;
}
last = gpio_get(DHT_PIN);
if (count == 255) break;
if ((i >= 4) && (i % 2 == 0)) {
data[j / 8] <<= 1;
if (count > 16) data[j / 8] |= 1;
j++;
}
}
gpio_put(LED_PIN, 0);
if ((j >= 40) && (data[4] == ((data[0] + data[1] + data[2] + data[3]) & 0xFF))) {
result->humidity = (float) ((data[0] << 8) + data[1]) / 10;
if (result->humidity > 100) {
result->humidity = data[0];
}
result->temp_celsius = (float) (((data[2] & 0x7F) << 8) + data[3]) / 10;
if (result->temp_celsius > 125) {
result->temp_celsius = data[2];
}
if (data[2] & 0x80) {
result->temp_celsius = -result->temp_celsius;
}
} else {
printf("Bad data\n");
}
}

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 303 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 409 KiB

View File

@ -0,0 +1,12 @@
add_executable(hello_7segment
hello_7segment.c
)
# Pull in our pico_stdlib which pulls in commonly used features
target_link_libraries(hello_7segment pico_stdlib)
# create map/bin/hex file etc.
pico_add_extra_outputs(hello_7segment)
# add url via pico_set_program_url
example_auto_set_url(hello_7segment)

View File

@ -0,0 +1,50 @@
= Attaching a 7 segment LED via GPIO
This example code shows how to interface the Raspberry Pi Pico to a generic 7 segment LED device. It uses the LED to count from 0 to 9 and then repeat. If the button is pressed, then the numbers will count down instead of up.
== Wiring information
Our 7 Segment display has pins as follows.
----
--A--
F B
--G--
E C
--D--
----
By default we are allocating GPIO 2 to A, 3 to B etc.
So, connect GPIO 2 to pin A on the 7 segment LED display and so on. You will need the appropriate resistors (68 ohm should be fine) for each segment.
The LED device used here is common anode, so the anode pin is connected to the 3.3v supply, and the GPIO's need to pull low (to ground) to complete the circuit.
The pull direction of the GPIO's is specified in the code itself.
Connect the switch to connect on pressing. One side should be connected to ground, the other to GPIO 9.
[[hello_7segment_wiring]]
[pdfwidth=75%]
.Wiring Diagram for 7 segment LED.
image::hello_7segment_bb.png[]
== List of Files
CMakeLists.txt:: CMake file to incorporate the example in to the examples build tree.
hello_7segment.c:: The example code.
== Bill of Materials
.A list of materials required for the example
[[hello_7segment-bom-table]]
[cols=3]
|===
| *Item* | *Quantity* | Details
| Breadboard | 1 | generic part
| Raspberry Pi Pico | 1 | http://raspberrypi.org/
| 7 segment LED module | 1 | generic part
| 68 ohm resistor | 7 | generic part
| DIL push to make switch | 1 | generic switch
| M/M Jumper wires | 10 | generic part
|===

View File

@ -0,0 +1,95 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
#include "hardware/gpio.h"
/*
Our 7 Segment display has pins as follows:
--A--
F B
--G--
E C
--D--
By default we are allocating GPIO 2 to A, 3 to B etc.
So, connect GOIP 2 to pin A on the 7 segment LED display etc. Don't forget
the appropriate resistors, best to use one for each segment!
Connect button so that pressing the switch connects the GPIO 9 (default) to
ground (pull down)
*/
#define FIRST_GPIO 2
#define BUTTON_GPIO (FIRST_GPIO+7)
// This array converts a number 0-9 to a bit pattern to send to the GPIO's
int bits[10] = {
0x3f, // 0
0x06, // 1
0x5b, // 2
0x4f, // 3
0x66, // 4
0x6d, // 5
0x7d, // 6
0x07, // 7
0x7f, // 8
0x67 // 9
};
// tag::hello_gpio[]
int main() {
stdio_init_all();
printf("Hello, 7segment - press button to count down!\n");
// We could use gpio_set_dir_out_masked() here
for (int gpio = FIRST_GPIO; gpio < FIRST_GPIO + 7; gpio++) {
gpio_init(gpio);
gpio_set_dir(gpio, GPIO_OUT);
// Our bitmap above has a bit set where we need an LED on, BUT, we are pulling low to light
// so invert our output
gpio_set_outover(gpio, GPIO_OVERRIDE_INVERT);
}
gpio_init(BUTTON_GPIO);
gpio_set_dir(BUTTON_GPIO, GPIO_IN);
// We are using the button to pull down to 0v when pressed, so ensure that when
// unpressed, it uses internal pull ups. Otherwise when unpressed, the input will
// be floating.
gpio_pull_up(BUTTON_GPIO);
int val = 0;
while (true) {
// Count upwards or downwards depending on button input
// We are pulling down on switch active, so invert the get to make
// a press count downwards
if (!gpio_get(BUTTON_GPIO)) {
if (val == 9) {
val = 0;
} else {
val++;
}
} else if (val == 0) {
val = 9;
} else {
val--;
}
// We are starting with GPIO 2, our bitmap starts at bit 0 so shift to start at 2.
int32_t mask = bits[val] << FIRST_GPIO;
// Set all our GPIO's in one go!
// If something else is using GPIO, we might want to use gpio_put_masked()
gpio_set_mask(mask);
sleep_ms(250);
gpio_clr_mask(mask);
}
return 0;
}
// end::hello_gpio[]

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 220 KiB

View File

@ -0,0 +1,12 @@
add_executable(hello_gpio_irq
hello_gpio_irq.c
)
# Pull in our pico_stdlib which pulls in commonly used features
target_link_libraries(hello_gpio_irq pico_stdlib)
# create map/bin/hex file etc.
pico_add_extra_outputs(hello_gpio_irq)
# add url via pico_set_program_url
example_auto_set_url(hello_gpio_irq)

View File

@ -0,0 +1,61 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
#include "hardware/gpio.h"
static char event_str[128];
void gpio_event_string(char *buf, uint32_t events);
void gpio_callback(uint gpio, uint32_t events) {
// Put the GPIO event(s) that just happened into event_str
// so we can print it
gpio_event_string(event_str, events);
printf("GPIO %d %s\n", gpio, event_str);
}
int main() {
stdio_init_all();
printf("Hello GPIO IRQ\n");
gpio_set_irq_enabled_with_callback(2, GPIO_IRQ_EDGE_RISE | GPIO_IRQ_EDGE_FALL, true, &gpio_callback);
// Wait forever
while (1);
return 0;
}
static const char *gpio_irq_str[] = {
"LEVEL_LOW", // 0x1
"LEVEL_HIGH", // 0x2
"EDGE_FALL", // 0x4
"EDGE_RISE" // 0x8
};
void gpio_event_string(char *buf, uint32_t events) {
for (uint i = 0; i < 4; i++) {
uint mask = (1 << i);
if (events & mask) {
// Copy this event string into the user string
const char *event_str = gpio_irq_str[i];
while (*event_str != '\0') {
*buf++ = *event_str++;
}
events &= ~mask;
// If more events add ", "
if (events) {
*buf++ = ',';
*buf++ = ' ';
}
}
}
*buf++ = '\0';
}

View File

@ -0,0 +1,4 @@
if (NOT PICO_NO_HARDWARE)
add_subdirectory(usb)
add_subdirectory(serial)
endif ()

View File

@ -0,0 +1,12 @@
add_executable(hello_serial
hello_serial.c
)
# Pull in our pico_stdlib which aggregates commonly used features
target_link_libraries(hello_serial pico_stdlib)
# create map/bin/hex/uf2 file etc.
pico_add_extra_outputs(hello_serial)
# add url via pico_set_program_url
example_auto_set_url(hello_serial)

View File

@ -0,0 +1,17 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
int main() {
stdio_init_all();
while (true) {
printf("Hello, world!\n");
sleep_ms(1000);
}
return 0;
}

View File

@ -0,0 +1,16 @@
add_executable(hello_usb
hello_usb.c
)
# Pull in our pico_stdlib which aggregates commonly used features
target_link_libraries(hello_usb pico_stdlib)
# enable usb output, disable uart output
pico_enable_stdio_usb(hello_usb 1)
pico_enable_stdio_uart(hello_usb 0)
# create map/bin/hex/uf2 file etc.
pico_add_extra_outputs(hello_usb)
# add url via pico_set_program_url
example_auto_set_url(hello_usb)

View File

@ -0,0 +1,17 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
int main() {
stdio_init_all();
while (true) {
printf("Hello, world!\n");
sleep_ms(1000);
}
return 0;
}

5
i2c/CMakeLists.txt Normal file
View File

@ -0,0 +1,5 @@
if (NOT PICO_NO_HARDWARE)
add_subdirectory(bus_scan)
add_subdirectory(lcd_1602_i2c)
add_subdirectory(mpu6050_i2c)
endif ()

View File

@ -0,0 +1,12 @@
add_executable(i2c_bus_scan
bus_scan.c
)
# Pull in our (to be renamed) simple get you started dependencies
target_link_libraries(i2c_bus_scan pico_stdlib hardware_i2c)
# create map/bin/hex file etc.
pico_add_extra_outputs(i2c_bus_scan)
# add url via pico_set_program_url
example_auto_set_url(i2c_bus_scan)

70
i2c/bus_scan/bus_scan.c Normal file
View File

@ -0,0 +1,70 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
// Sweep through all 7-bit I2C addresses, to see if any slaves are present on
// the I2C bus. Print out a table that looks like this:
//
// I2C Bus Scan
// 0 1 2 3 4 5 6 7 8 9 A B C D E F
// 0
// 1 @
// 2
// 3 @
// 4
// 5
// 6
// 7
//
// E.g. if slave addresses 0x12 and 0x34 were acknowledged.
#include <stdio.h>
#include "pico/stdlib.h"
#include "hardware/i2c.h"
// I2C reserves some addresses for special purposes. We exclude these from the scan.
// These are any addresses of the form 000 0xxx or 111 1xxx
bool reserved_addr(uint8_t addr) {
return (addr & 0x78) == 0 || (addr & 0x78) == 0x78;
}
int main() {
// Enable UART so we can print status output
stdio_init_all();
// This example will use I2C0 on GPIO4 (SDA) and GPIO5 (SCL)
i2c_init(i2c0, 100 * 1000);
gpio_set_function(4, GPIO_FUNC_I2C);
gpio_set_function(5, GPIO_FUNC_I2C);
gpio_pull_up(4);
gpio_pull_up(5);
printf("\nI2C Bus Scan\n");
printf(" 0 1 2 3 4 5 6 7 8 9 A B C D E F\n");
for (int addr = 0; addr < (1 << 7); ++addr) {
if (addr % 16 == 0) {
printf("%02x ", addr);
}
// Perform a 1-byte dummy read from the probe address. If a slave
// acknowledges this address, the function returns the number of bytes
// transferred. If the address byte is ignored, the function returns
// -1.
// Skip over any reserved addresses.
int ret;
uint8_t rxdata;
if (reserved_addr(addr))
ret = PICO_ERROR_GENERIC;
else
ret = i2c_read_blocking(i2c0, addr, &rxdata, 1, false);
printf(ret < 0 ? "." : "@");
printf(addr % 16 == 15 ? "\n" : " ");
}
printf("Done.\n");
return 0;
}

View File

@ -0,0 +1,12 @@
add_executable(lcd_1602_i2c
lcd_1602_i2c.c
)
# Pull in our (to be renamed) simple get you started dependencies
target_link_libraries(lcd_1602_i2c pico_stdlib hardware_i2c)
# create map/bin/hex file etc.
pico_add_extra_outputs(lcd_1602_i2c)
# add url via pico_set_program_url
example_auto_set_url(lcd_1602_i2c)

View File

@ -0,0 +1,41 @@
= Attaching a 16x2 LCD via I2C
This example code shows how to interface the Raspberry Pi Pico to one of the very common 16x2 LCD character displays. The display will need a 3.3V I2C adapter board as this example uses I2C for communications.
[NOTE]
======
These LCD displays can also be driven directly using GPIO without the use of an adapter board. That is beyond the scope of this example.
======
== Wiring information
Wiring up the device requires 4 jumpers, to connect VCC (3.3v), GND, SDA and SCL. The example here uses I2C port 0, which is assigned to GPIO 4 (SDA) and 5 (SCL) in software. Power is supplied from the 3.3V pin.
WARNING: Many displays of this type are 5v. If you wish to use a 5v display you will need to use level shifters on the SDA and SCL lines to convert from the 3.3V used by the RP2040. Whilst a 5v display will just about work at 3.3v, the display will be dim.
[[lcd_1602_i2c_wiring]]
[pdfwidth=75%]
.Wiring Diagram for LCD1602A LCD with I2C bridge.
image::lcd_1602_i2c_bb.png[]
== List of Files
CMakeLists.txt:: CMake file to incorporate the example in to the examples build tree.
lcd_1602_i2c.c:: The example code.
== Bill of Materials
.A list of materials required for the example
[[lcd_1602_i2c-bom-table]]
[cols=3]
|===
| *Item* | *Quantity* | Details
| Breadboard | 1 | generic part
| Raspberry Pi Pico | 1 | http://raspberrypi.org/
| 1602A based LCD panel 3.3v | 1 | generic part
| 1602A to I2C bridge device 3.3v | 1 | generic part
| M/M Jumper wires | 4 | generic part
|===

View File

@ -0,0 +1,164 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include <string.h>
#include "pico/stdlib.h"
#include "hardware/i2c.h"
#include "pico/binary_info.h"
/* Example code to drive a 16x2 LCD panel via a I2C bridge chip (e.g. PCF8574)
NOTE: The panel must be capable of being driven at 3.3v NOT 5v. The Pico
GPIO (and therefor I2C) cannot be used at 5v.
You will need to use a level shifter on the I2C lines if you want to run the
board at 5v.
Connections on Raspberry Pi Pico board, other boards may vary.
GPIO 4 (pin 6)-> SDA on LCD bridge board
GPIO 5 (pin 7)-> SCL on LCD bridge board
3.3v (pin 36) -> VCC on LCD bridge board
GND (pin 38) -> GND on LCD bridge board
*/
// commands
const int LCD_CLEARDISPLAY = 0x01;
const int LCD_RETURNHOME = 0x02;
const int LCD_ENTRYMODESET = 0x04;
const int LCD_DISPLAYCONTROL = 0x08;
const int LCD_CURSORSHIFT = 0x10;
const int LCD_FUNCTIONSET = 0x20;
const int LCD_SETCGRAMADDR = 0x40;
const int LCD_SETDDRAMADDR = 0x80;
// flags for display entry mode
const int LCD_ENTRYSHIFTINCREMENT = 0x01;
const int LCD_ENTRYLEFT = 0x02;
// flags for display and cursor control
const int LCD_BLINKON = 0x01;
const int LCD_CURSORON = 0x02;
const int LCD_DISPLAYON = 0x04;
// flags for display and cursor shift
const int LCD_MOVERIGHT = 0x04;
const int LCD_DISPLAYMOVE = 0x08;
// flags for function set
const int LCD_5x10DOTS = 0x04;
const int LCD_2LINE = 0x08;
const int LCD_8BITMODE = 0x10;
// flag for backlight control
const int LCD_BACKLIGHT = 0x08;
const int LCD_ENABLE_BIT = 0x04;
#define I2C_PORT i2c0
// By default these LCD display drivers are on bus address 0x27
static int addr = 0x27;
// Modes for lcd_send_byte
#define LCD_CHARACTER 1
#define LCD_COMMAND 0
#define MAX_LINES 2
#define MAX_CHARS 16
/* Quick helper function for single byte transfers */
void i2c_write_byte(uint8_t val) {
i2c_write_blocking(I2C_PORT, addr, &val, 1, false);
}
void lcd_toggle_enable(uint8_t val) {
// Toggle enable pin on LCD display
// We cannot do this too quickly or things don't work
#define DELAY_US 600
sleep_us(DELAY_US);
i2c_write_byte(val | LCD_ENABLE_BIT);
sleep_us(DELAY_US);
i2c_write_byte(val & ~LCD_ENABLE_BIT);
sleep_us(DELAY_US);
}
// The display is sent a byte as two separate nibble transfers
void lcd_send_byte(uint8_t val, int mode) {
uint8_t high = mode | (val & 0xF0) | LCD_BACKLIGHT;
uint8_t low = mode | ((val << 4) & 0xF0) | LCD_BACKLIGHT;
i2c_write_byte(high);
lcd_toggle_enable(high);
i2c_write_byte(low);
lcd_toggle_enable(low);
}
void lcd_clear(void) {
lcd_send_byte(LCD_CLEARDISPLAY, LCD_COMMAND);
}
// go to location on LCD
void lcd_set_cursor(int line, int position) {
int val = (line == 0) ? 0x80 + position : 0xC0 + position;
lcd_send_byte(val, LCD_COMMAND);
}
static void inline lcd_char(char val) {
lcd_send_byte(val, LCD_CHARACTER);
}
void lcd_string(const char *s) {
while (*s) {
lcd_char(*s++);
}
}
void lcd_init() {
lcd_send_byte(0x03, LCD_COMMAND);
lcd_send_byte(0x03, LCD_COMMAND);
lcd_send_byte(0x03, LCD_COMMAND);
lcd_send_byte(0x02, LCD_COMMAND);
lcd_send_byte(LCD_ENTRYMODESET | LCD_ENTRYLEFT, LCD_COMMAND);
lcd_send_byte(LCD_FUNCTIONSET | LCD_2LINE, LCD_COMMAND);
lcd_send_byte(LCD_DISPLAYCONTROL | LCD_DISPLAYON, LCD_COMMAND);
lcd_clear();
}
int main() {
// This example will use I2C0 on GPIO4 (SDA) and GPIO5 (SCL)
i2c_init(I2C_PORT, 100 * 1000);
gpio_set_function(4, GPIO_FUNC_I2C);
gpio_set_function(5, GPIO_FUNC_I2C);
gpio_pull_up(4);
gpio_pull_up(5);
// Make the I2C pins available to picotool
bi_decl( bi_2pins_with_func(4, 5, GPIO_FUNC_I2C));
lcd_init();
static uint8_t *message[] =
{
"RP2040 by", "Raspberry Pi",
"A brand new", "microcontroller",
"Twin core M0", "Full C SDK",
"More power in", "your product",
"More beans", "than Heinz!"
};
while (1) {
for (int m = 0; m < sizeof(message) / sizeof(message[0]); m += MAX_LINES) {
for (int line = 0; line < MAX_LINES; line++) {
lcd_set_cursor(line, (MAX_CHARS / 2) - strlen(message[m + line]) / 2);
lcd_string(message[m + line]);
}
sleep_ms(2000);
lcd_clear();
}
}
return 0;
}

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 261 KiB

View File

@ -0,0 +1,12 @@
add_executable(mpu6050_i2c
mpu6050_i2c.c
)
# Pull in our (to be renamed) simple get you started dependencies
target_link_libraries(mpu6050_i2c pico_stdlib hardware_i2c)
# create map/bin/hex file etc.
pico_add_extra_outputs(mpu6050_i2c)
# add url via pico_set_program_url
example_auto_set_url(mpu6050_i2c)

View File

@ -0,0 +1,43 @@
= Attaching a MPU6050 accelerometer/gyroscope via I2C
This example code shows how to interface the Raspberry Pi Pico to the MPU6050 accelerometer/gyroscope board. This device uses I2C for communications, and most MPU6050 parts are happy running at either 3.3 or 5v. The Raspberry Pi RP2040 GPIO's work at 3.3v so that is what the example uses.
[NOTE]
======
This is a very basic example, and only recovers raw data from the sensor. There are various calibration options available that should be used to ensure that the final results are accurate. It is also possible to wire up the interrupt pin to a GPIO and read data only when it is ready, rather than using the polling approach in the example.
======
== Wiring information
Wiring up the device requires 4 jumpers, to connect VCC (3.3v), GND, SDA and SCL. The example here uses I2C port 0, which is assigned to GPIO 4 (SDA) and 5 (SCL) in software. Power is supplied from the 3.3V pin.
[NOTE]
======
There are many different manufacturers who sell boards with the MPU6050. Whilst they all appear slightly different, they all have, at least, the same 4 pins required to power and communicate. When wiring up a board that is different to the one in the diagram, ensure you connect up as described in the previous paragraph.
======
[[mpu6050_i2c_wiring]]
[pdfwidth=75%]
.Wiring Diagram for MPU6050.
image::mpu6050_i2c_bb.png[]
== List of Files
CMakeLists.txt:: CMake file to incorporate the example in to the examples build tree.
mpu6050_i2c.c:: The example code.
== Bill of Materials
.A list of materials required for the example
[[mpu6050-bom-table]]
[cols=3]
|===
| *Item* | *Quantity* | Details
| Breadboard | 1 | generic part
| Raspberry Pi Pico | 1 | http://raspberrypi.org/
| MPU6050 board| 1 | generic part
| M/M Jumper wires | 4 | generic part
|===

View File

@ -0,0 +1,110 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include <string.h>
#include "pico/stdlib.h"
#include "hardware/i2c.h"
/* Example code to talk to a MPU6050 MEMS accelerometer and gyroscope
This is taking to simple approach of simply reading registers. It's perfectly
possible to link up an interrupt line and set things up to read from the
inbuilt FIFO to make it more useful.
NOTE: Ensure the device is capable of being driven at 3.3v NOT 5v. The Pico
GPIO (and therefor I2C) cannot be used at 5v.
You will need to use a level shifter on the I2C lines if you want to run the
board at 5v.
Connections on Raspberry Pi Pico board, other boards may vary.
GPIO 4 (pin 6)-> SDA on MPU6050 board
GPIO 5 (pin 7)-> SCL on MPU6050 board
3.3v (pin 36) -> VCC on MPU6050 board
GND (pin 38) -> GND on MPU6050 board
*/
// By default these devices are on bus address 0x68
static int addr = 0x68;
#define I2C_PORT i2c0
static void mpu6050_reset() {
// Two byte reset. First byte register, second byte data
// There are a load more options to set up the device in different ways that could be added here
uint8_t buf[] = {0x6B, 0x00};
i2c_write_blocking(I2C_PORT, addr, buf, 2, false);
}
static void mpu6050_read_raw(int16_t accel[3], int16_t gyro[3], int16_t *temp) {
// For this particular device, we send the device the register we want to read
// first, then subsequently read from the device. The register is auto incrementing
// so we don't need to keep sending the register we want, just the first.
uint8_t buffer[6];
// Start reading acceleration registers from register 0x3B for 6 bytes
uint8_t val = 0x3B;
i2c_write_blocking(I2C_PORT, addr, &val, 1, true); // true to keep master control of bus
i2c_read_blocking(I2C_PORT, addr, buffer, 6, false);
for (int i = 0; i < 3; i++) {
accel[i] = (buffer[i * 2] << 8 | buffer[(i * 2) + 1]);
}
// Now gyro data from reg 0x43 for 6 bytes
// The register is auto incrementing on each read
val = 0x43;
i2c_write_blocking(I2C_PORT, addr, &val, 1, true);
i2c_read_blocking(I2C_PORT, addr, buffer, 6, false); // False - finished with bus
for (int i = 0; i < 3; i++) {
gyro[i] = (buffer[i * 2] << 8 | buffer[(i * 2) + 1]);;
}
// Now temperature from reg 0x41 for 2 bytes
// The register is auto incrementing on each read
val = 0x41;
i2c_write_blocking(I2C_PORT, addr, &val, 1, true);
i2c_read_blocking(I2C_PORT, addr, buffer, 2, false); // False - finished with bus
*temp = buffer[0] << 8 | buffer[1];
}
int main() {
stdio_init_all();
printf("Hello, MPU6050! Reading raw data from registers...\n");
// This example will use I2C0 on GPIO4 (SDA) and GPIO5 (SCL) running at 400kHz.
i2c_init(I2C_PORT, 400 * 1000);
gpio_set_function(4, GPIO_FUNC_I2C);
gpio_set_function(5, GPIO_FUNC_I2C);
gpio_pull_up(4);
gpio_pull_up(5);
mpu6050_reset();
int16_t acceleration[3], gyro[3], temp;
while (1) {
mpu6050_read_raw(acceleration, gyro, &temp);
// These are the raw numbers from the chip, so will need tweaking to be really useful.
// See the datasheet for more information
printf("Acc. X = %d, Y = %d, Z = %d\n", acceleration[0], acceleration[1], acceleration[2]);
printf("Gyro. X = %d, Y = %d, Z = %d\n", gyro[0], gyro[1], gyro[2]);
// Temperature is simple so use the datasheet calculation to get deg C.
// Note this is chip temperature.
printf("Temp. = %f\n", (temp / 340.0) + 36.53);
sleep_ms(100);
}
return 0;
}

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 223 KiB

View File

@ -0,0 +1,27 @@
{
"version": "0.2.0",
"configurations": [
{
"name": "Pico Debug",
"cwd": "${workspaceRoot}",
"executable": "${command:cmake.launchTargetPath}",
"request": "launch",
"type": "cortex-debug",
"servertype": "openocd",
// This may need to be arm-none-eabi-gdb depending on your system
"gdbpath" : "gdb-multiarch",
"device": "RP2040",
"configFiles": [
"interface/raspberrypi-swd.cfg",
"target/rp2040.cfg"
],
"svdFile": "/home/pi/pico/pico-sdk/src/rp2040/hardware_regs/rp2040.svd",
"runToMain": true,
// Work around for stopping at main on restart
"postRestartCommands": [
"break main",
"continue"
]
}
]
}

View File

@ -0,0 +1,24 @@
{
"version": "0.2.0",
"configurations": [
{
"name": "Pico Debug",
"type":"cortex-debug",
"cwd": "${workspaceRoot}",
"executable": "${command:cmake.launchTargetPath}",
"request": "launch",
"servertype": "external",
// This may need to be arm-none-eabi-gdb depending on your system
"gdbpath" : "gdb-multiarch",
// Connect to an already running OpenOCD instance
"gdbTarget": "your-openocd:3333",
"svdFile": "/home/liam/pico/pico-sdk/src/rp2040/hardware_regs/rp2040.svd",
"runToMain": true,
// Work around for stopping at main on restart
"postRestartCommands": [
"break main",
"continue"
]
}
]
}

21
ide/vscode/settings.json Normal file
View File

@ -0,0 +1,21 @@
{
// These settings tweaks to the cmake plugin will ensure
// that you debug using cortex-debug instead of trying to launch
// a Pico binary on the host
"cmake.statusbar.advanced": {
"debug": {
"visibility": "hidden"
},
"launch": {
"visibility": "hidden"
},
"build": {
"visibility": "hidden"
},
"buildTarget": {
"visibility": "hidden"
}
},
"cmake.buildBeforeRun": true,
"C_Cpp.default.configurationProvider": "ms-vscode.cmake-tools"
}

3
interp/CMakeLists.txt Normal file
View File

@ -0,0 +1,3 @@
if (NOT PICO_NO_HARDWARE)
add_subdirectory(hello_interp)
endif ()

View File

@ -0,0 +1,14 @@
if (TARGET hardware_interp)
add_executable(hello_interp
hello_interp.c
)
# Pull in dependencies
target_link_libraries(hello_interp pico_stdlib hardware_interp)
# create map/bin/hex file etc.
pico_add_extra_outputs(hello_interp)
# add url via pico_set_program_url
example_auto_set_url(hello_interp)
endif ()

View File

@ -0,0 +1,286 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
#include "hardware/interp.h"
void times_table() {
puts("9 times table:");
// Initialise lane 0 on interp0 on this core
interp_config cfg = interp_default_config();
interp_set_config(interp0, 0, &cfg);
interp0->accum[0] = 0;
interp0->base[0] = 9;
for (int i = 0; i < 10; ++i)
printf("%d\n", interp0->pop[0]);
}
void moving_mask() {
interp_config cfg = interp_default_config();
interp0->accum[0] = 0x1234abcd;
puts("Masking:");
printf("ACCUM0 = %08x\n", interp0->accum[0]);
for (int i = 0; i < 8; ++i) {
// LSB, then MSB. These are inclusive, so 0,31 means "the entire 32 bit register"
interp_config_set_mask(&cfg, i * 4, i * 4 + 3);
interp_set_config(interp0, 0, &cfg);
// Reading from ACCUMx_ADD returns the raw lane shift and mask value, without BASEx added
printf("Nibble %d: %08x\n", i, interp0->add_raw[0]);
}
puts("Masking with sign extension:");
interp_config_set_signed(&cfg, true);
for (int i = 0; i < 8; ++i) {
interp_config_set_mask(&cfg, i * 4, i * 4 + 3);
interp_set_config(interp0, 0, &cfg);
printf("Nibble %d: %08x\n", i, interp0->add_raw[0]);
}
}
void cross_lanes() {
interp_config cfg = interp_default_config();
interp_config_set_cross_result(&cfg, true);
// ACCUM0 gets lane 1 result:
interp_set_config(interp0, 0, &cfg);
// ACCUM1 gets lane 0 result:
interp_set_config(interp0, 1, &cfg);
interp0->accum[0] = 123;
interp0->accum[1] = 456;
interp0->base[0] = 1;
interp0->base[1] = 0;
puts("Lane result crossover:");
for (int i = 0; i < 10; ++i)
printf("PEEK0, POP1: %d, %d\n", interp0->peek[0], interp0->pop[1]);
}
void simple_blend1() {
puts("Simple blend 1:");
interp_config cfg = interp_default_config();
interp_config_set_blend(&cfg, true);
interp_set_config(interp0, 0, &cfg);
cfg = interp_default_config();
interp_set_config(interp0, 1, &cfg);
interp0->base[0] = 500;
interp0->base[1] = 1000;
for (int i = 0; i <= 6; i++) {
// set fraction to value between 0 and 255
interp0->accum[1] = 255 * i / 6;
// ≈ 500 + (1000 - 500) * i / 6;
printf("%d\n", (int) interp0->peek[1]);
}
}
/// \tag::simple_blend2[]
void print_simple_blend2_results(bool is_signed) {
// lane 1 signed flag controls whether base 0/1 are treated as signed or unsigned
interp_config cfg = interp_default_config();
interp_config_set_signed(&cfg, is_signed);
interp_set_config(interp0, 1, &cfg);
for (int i = 0; i <= 6; i++) {
interp0->accum[1] = 255 * i / 6;
if (is_signed) {
printf("%d\n", (int) interp0->peek[1]);
} else {
printf("0x%08x\n", (uint) interp0->peek[1]);
}
}
}
void simple_blend2() {
puts("Simple blend 2:");
interp_config cfg = interp_default_config();
interp_config_set_blend(&cfg, true);
interp_set_config(interp0, 0, &cfg);
interp0->base[0] = -1000;
interp0->base[1] = 1000;
puts("signed:");
print_simple_blend2_results(true);
puts("unsigned:");
print_simple_blend2_results(false);
}
/// \end::simple_blend2[]
void simple_blend3() {
puts("Simple blend 3:");
interp_config cfg = interp_default_config();
interp_config_set_blend(&cfg, true);
interp_set_config(interp0, 0, &cfg);
cfg = interp_default_config();
interp_set_config(interp0, 1, &cfg);
interp0->accum[1] = 128;
interp0->base01 = 0x30005000;
printf("0x%08x\n", (int) interp0->peek[1]);
interp0->base01 = 0xe000f000;
printf("0x%08x\n", (int) interp0->peek[1]);
interp_config_set_signed(&cfg, true);
interp_set_config(interp0, 1, &cfg);
interp0->base01 = 0xe000f000;
printf("0x%08x\n", (int) interp0->peek[1]);
}
void linear_interpolation() {
puts("Linear interpolation:");
const int uv_fractional_bits = 12;
// for lane 0
// shift and mask XXXX XXXX XXXX XXXX XXXX FFFF FFFF FFFF (accum 0)
// to 0000 0000 000X XXXX XXXX XXXX XXXX XXX0
// i.e. non fractional part times 2 (for uint16_t)
interp_config cfg = interp_default_config();
interp_config_set_shift(&cfg, uv_fractional_bits - 1);
interp_config_set_mask(&cfg, 1, 32 - uv_fractional_bits);
interp_config_set_blend(&cfg, true);
interp_set_config(interp0, 0, &cfg);
// for lane 1
// shift XXXX XXXX XXXX XXXX XXXX FFFF FFFF FFFF (accum 0 via cross input)
// to 0000 XXXX XXXX XXXX XXXX FFFF FFFF FFFF
cfg = interp_default_config();
interp_config_set_shift(&cfg, uv_fractional_bits - 8);
interp_config_set_signed(&cfg, true);
interp_config_set_cross_input(&cfg, true); // signed blending
interp_set_config(interp0, 1, &cfg);
int16_t samples[] = {0, 10, -20, -1000, 500};
// step is 1/4 in our fractional representation
uint step = (1 << uv_fractional_bits) / 4;
interp0->accum[0] = 0; // initial sample_offset;
interp0->base[2] = (uintptr_t) samples;
for (int i = 0; i < 16; i++) {
// result2 = samples + (lane0 raw result)
// i.e. ptr to the first of two samples to blend between
int16_t *sample_pair = (int16_t *) interp0->peek[2];
interp0->base[0] = sample_pair[0];
interp0->base[1] = sample_pair[1];
printf("%d\t(%d%% between %d and %d)\n", (int) interp0->peek[1],
100 * (interp0->add_raw[1] & 0xff) / 0xff,
sample_pair[0], sample_pair[1]);
interp0->add_raw[0] = step;
}
}
void clamp() {
puts("Clamp:");
interp_config cfg = interp_default_config();
interp_config_set_clamp(&cfg, true);
interp_config_set_shift(&cfg, 2);
// set mask according to new position of sign bit..
interp_config_set_mask(&cfg, 0, 29);
// ...so that the shifted value is correctly sign extended
interp_config_set_signed(&cfg, true);
interp_set_config(interp1, 0, &cfg);
interp1->base[0] = 0;
interp1->base[1] = 255;
for (int i = -1024; i <= 1024; i += 256) {
interp1->accum[0] = i;
printf("%d\t%d\n", i, (int) interp1->peek[0]);
}
}
/// \tag::texture_mapping[]
void texture_mapping_setup(uint8_t *texture, uint texture_width_bits, uint texture_height_bits,
uint uv_fractional_bits) {
interp_config cfg = interp_default_config();
// set add_raw flag to use raw (un-shifted and un-masked) lane accumulator value when adding
// it to the the lane base to make the lane result
interp_config_set_add_raw(&cfg, true);
interp_config_set_shift(&cfg, uv_fractional_bits);
interp_config_set_mask(&cfg, 0, texture_width_bits - 1);
interp_set_config(interp0, 0, &cfg);
interp_config_set_shift(&cfg, uv_fractional_bits - texture_width_bits);
interp_config_set_mask(&cfg, texture_width_bits, texture_width_bits + texture_height_bits - 1);
interp_set_config(interp0, 1, &cfg);
interp0->base[2] = (uintptr_t) texture;
}
void texture_mapped_span(uint8_t *output, uint32_t u, uint32_t v, uint32_t du, uint32_t dv, uint count) {
// u, v are texture coordinates in fixed point with uv_fractional_bits fractional bits
// du, dv are texture coordinate steps across the span in same fixed point.
interp0->accum[0] = u;
interp0->base[0] = du;
interp0->accum[1] = v;
interp0->base[1] = dv;
for (uint i = 0; i < count; i++) {
// equivalent to
// uint32_t sm_result0 = (accum0 >> uv_fractional_bits) & (1 << (texture_width_bits - 1);
// uint32_t sm_result1 = (accum1 >> uv_fractional_bits) & (1 << (texture_height_bits - 1);
// uint8_t *address = texture + sm_result0 + (sm_result1 << texture_width_bits);
// output[i] = *address;
// accum0 = du + accum0;
// accum1 = dv + accum1;
// result2 is the texture address for the current pixel;
// popping the result advances to the next iteration
output[i] = *(uint8_t *) interp0->pop[2];
}
}
void texture_mapping() {
puts("Affine Texture mapping (with texture wrap):");
uint8_t texture[] = {
0x00, 0x01, 0x02, 0x03,
0x10, 0x11, 0x12, 0x13,
0x20, 0x21, 0x22, 0x23,
0x30, 0x31, 0x32, 0x33,
};
// 4x4 texture
texture_mapping_setup(texture, 2, 2, 16);
uint8_t output[12];
uint32_t du = 65536 / 2; // step of 1/2
uint32_t dv = 65536 / 3; // step of 1/3
texture_mapped_span(output, 0, 0, du, dv, 12);
for (uint i = 0; i < 12; i++) {
printf("0x%02x\n", output[i]);
}
}
/// \end::texture_mapping[]
int main() {
stdio_init_all();
puts("Interpolator example");
times_table();
moving_mask();
cross_lanes();
simple_blend1();
simple_blend2();
simple_blend3();
clamp();
linear_interpolation();
texture_mapping();
return 0;
}

5
multicore/CMakeLists.txt Normal file
View File

@ -0,0 +1,5 @@
if (NOT PICO_NO_HARDWARE)
add_subdirectory(hello_multicore)
add_subdirectory(multicore_runner)
add_subdirectory(multicore_fifo_irqs)
endif ()

View File

@ -0,0 +1,14 @@
add_executable(hello_multicore
multicore.c
)
# Add pico_multicore which is required for multicore functionality
target_link_libraries(hello_multicore
pico_stdlib
pico_multicore)
# create map/bin/hex file etc.
pico_add_extra_outputs(hello_multicore)
# add url via pico_set_program_url
example_auto_set_url(hello_multicore)

View File

@ -0,0 +1,48 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
#include "pico/multicore.h"
#define FLAG_VALUE 123
void core1_entry() {
multicore_fifo_push_blocking(FLAG_VALUE);
uint32_t g = multicore_fifo_pop_blocking();
if (g != FLAG_VALUE)
printf("Hmm, that's not right on core 1!\n");
else
printf("Its all gone well on core 1!");
while (1)
tight_loop_contents();
}
int main() {
stdio_init_all();
printf("Hello, multicore!\n");
///tag::setup_multicore[]
multicore_launch_core1(core1_entry);
// Wait for it to start up
uint32_t g = multicore_fifo_pop_blocking();
if (g != FLAG_VALUE)
printf("Hmm, that's not right on core 0!\n");
else {
multicore_fifo_push_blocking(FLAG_VALUE);
printf("It's all gone well on core 0!");
}
///end::setup_multicore[]
}

View File

@ -0,0 +1,13 @@
add_executable(multicore_fifo_irqs
multicore_fifo_irqs.c
)
target_link_libraries(multicore_fifo_irqs
pico_multicore
pico_stdlib)
# create map/bin/hex file etc.
pico_add_extra_outputs(multicore_fifo_irqs)
# add url via pico_set_program_url
example_auto_set_url(multicore_fifo_irqs)

View File

@ -0,0 +1,76 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
#include "pico/multicore.h"
#include "hardware/irq.h"
///tag::multicore_fifo_irqs[]
#define FLAG_VALUE1 123
#define FLAG_VALUE2 321
static int core0_rx_val = 0, core1_rx_val = 0;
void core0_sio_irq() {
// Just record the latest entry
while (multicore_fifo_rvalid())
core0_rx_val = multicore_fifo_pop_blocking();
multicore_fifo_clear_irq();
}
void core1_sio_irq() {
// Just record the latest entry
while (multicore_fifo_rvalid())
core1_rx_val = multicore_fifo_pop_blocking();
multicore_fifo_clear_irq();
}
void core1_entry() {
multicore_fifo_clear_irq();
irq_set_exclusive_handler(SIO_IRQ_PROC1, core1_sio_irq);
irq_set_enabled(SIO_IRQ_PROC1, true);
// Send something to Core0, this should fire the interrupt.
multicore_fifo_push_blocking(FLAG_VALUE1);
while (1)
tight_loop_contents();
}
int main() {
stdio_init_all();
printf("Hello, multicore_fifo_irqs!\n");
// We MUST start the other core before we enabled FIFO interrupts.
// This is because the launch uses the FIFO's, enabling interrupts before
// they are used for the launch will result in unexpected behaviour.
multicore_launch_core1(core1_entry);
irq_set_exclusive_handler(SIO_IRQ_PROC0, core0_sio_irq);
irq_set_enabled(SIO_IRQ_PROC0, true);
// Wait for a bit for things to happen
sleep_ms(10);
// Send something back to the other core
multicore_fifo_push_blocking(FLAG_VALUE2);
// Wait for a bit for things to happen
sleep_ms(10);
printf("Irq handlers should have rx'd some stuff - core 0 got %d, core 1 got %d!\n", core0_rx_val, core1_rx_val);
while (1)
tight_loop_contents();
}
///end::multicore_fifo_irqs[]

View File

@ -0,0 +1,13 @@
add_executable(multicore_runner
multicore_runner.c
)
target_link_libraries(multicore_runner
pico_multicore
pico_stdlib)
# create map/bin/hex file etc.
pico_add_extra_outputs(multicore_runner)
# add url via pico_set_program_url
example_auto_set_url(multicore_runner)

View File

@ -0,0 +1,83 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
#include "pico/multicore.h"
///tag::multicore_dispatch[]
#define FLAG_VALUE 123
void core1_entry() {
while (1) {
// Function pointer is passed to us via the FIFO
// We have one incoming int32_t as a parameter, and will provide an
// int32_t return value by simply pushing it back on the FIFO
// which also indicates the result is ready.
int32_t (*func)() = (int32_t(*)()) multicore_fifo_pop_blocking();
int32_t p = multicore_fifo_pop_blocking();
int32_t result = (*func)(p);
multicore_fifo_push_blocking(result);
}
}
int32_t factorial(int32_t n) {
int32_t f = 1;
for (int i = 2; i <= n; i++) {
f *= i;
}
return f;
}
int32_t fibonacci(int32_t n) {
if (n == 0) return 0;
if (n == 1) return 1;
int n1 = 0, n2 = 1, n3;
for (int i = 2; i <= n; i++) {
n3 = n1 + n2;
n1 = n2;
n2 = n3;
}
return n3;
}
#define TEST_NUM 10
int main() {
int res;
stdio_init_all();
printf("Hello, multicore_runner!\n");
// This example dispatches arbitrary functions to run on the second core
// To do this we run a dispatcher on the second core that accepts a function
// pointer and runs it
multicore_launch_core1(core1_entry);
multicore_fifo_push_blocking((uintptr_t) &factorial);
multicore_fifo_push_blocking(TEST_NUM);
// We could now do a load of stuff on core 0 and get our result later
res = multicore_fifo_pop_blocking();
printf("Factorial %d is %d\n", TEST_NUM, res);
// Now try a different function
multicore_fifo_push_blocking((uintptr_t) &fibonacci);
multicore_fifo_push_blocking(TEST_NUM);
res = multicore_fifo_pop_blocking();
printf("Fibonacci %d is %d\n", TEST_NUM, res);
}
///end::multicore_dispatch[]

64
pico_sdk_import.cmake Normal file
View File

@ -0,0 +1,64 @@
# This is a copy of <PICO_SDK_PATH>/external/pico_sdk_import.cmake
# This can be dropped into an external project to help locate this SDK
# It should be include()ed prior to project()
# todo document
if (DEFINED ENV{PICO_SDK_PATH} AND (NOT PICO_SDK_PATH))
set(PICO_SDK_PATH $ENV{PICO_SDK_PATH})
message("Using PICO_SDK_PATH from environment ('${PICO_SDK_PATH}')")
endif ()
if (DEFINED ENV{PICO_SDK_FETCH_FROM_GIT} AND (NOT PICO_SDK_FETCH_FROM_GIT))
set(PICO_SDK_FETCH_FROM_GIT $ENV{PICO_SDK_FETCH_FROM_GIT})
message("Using PICO_SDK_FETCH_FROM_GIT from environment ('${PICO_SDK_FETCH_FROM_GIT}')")
endif ()
if (DEFINED ENV{PICO_SDK_FETCH_FROM_GIT_PATH} AND (NOT PICO_SDK_FETCH_FROM_GIT_PATH))
set(PICO_SDK_FETCH_FROM_GIT_PATH $ENV{PICO_SDK_FETCH_FROM_GIT_PATH})
message("Using PICO_SDK_FETCH_FROM_GIT_PATH from environment ('${PICO_SDK_FETCH_FROM_GIT_PATH}')")
endif ()
set(PICO_SDK_PATH "${PICO_SDK_PATH}" CACHE PATH "Path to the PICO SDK")
set(PICO_SDK_FETCH_FROM_GIT "${PICO_SDK_FETCH_FROM_GIT}" CACHE BOOL "Set to ON to fetch copy of PICO SDK from git if not otherwise locatable")
set(PICO_SDK_FETCH_FROM_GIT_PATH "${PICO_SDK_FETCH_FROM_GIT_PATH}" CACHE FILEPATH "location to download SDK")
if (NOT PICO_SDK_PATH)
if (PICO_SDK_FETCH_FROM_GIT)
include(FetchContent)
set(FETCHCONTENT_BASE_DIR_SAVE ${FETCHCONTENT_BASE_DIR})
if (PICO_SDK_FETCH_FROM_GIT_PATH)
get_filename_component(FETCHCONTENT_BASE_DIR "${PICO_SDK_FETCH_FROM_GIT_PATH}" REALPATH BASE_DIR "${CMAKE_SOURCE_DIR}")
endif ()
FetchContent_Declare(
pico_sdk
GIT_REPOSITORY https://github.com/raspberrypi/pico-sdk
GIT_TAG master
)
if (NOT pico_sdk)
message("Downloading PICO SDK")
FetchContent_Populate(pico_sdk)
set(PICO_SDK_PATH ${pico_sdk_SOURCE_DIR})
endif ()
set(FETCHCONTENT_BASE_DIR ${FETCHCONTENT_BASE_DIR_SAVE})
else ()
message(FATAL_ERROR
"PICO SDK location was not specified. Please set PICO_SDK_PATH or set PICO_SDK_FETCH_FROM_GIT to on to fetch from git."
)
endif ()
endif ()
get_filename_component(PICO_SDK_PATH "${PICO_SDK_PATH}" REALPATH BASE_DIR "${CMAKE_BINARY_DIR}")
if (NOT EXISTS ${PICO_SDK_PATH})
message(FATAL_ERROR "Directory '${PICO_SDK_PATH}' not found")
endif ()
set(PICO_SDK_INIT_CMAKE_FILE ${PICO_SDK_PATH}/pico_sdk_init.cmake)
if (NOT EXISTS ${PICO_SDK_INIT_CMAKE_FILE})
message(FATAL_ERROR "Directory '${PICO_SDK_PATH}' does not appear to contain the PICO SDK")
endif ()
set(PICO_SDK_PATH ${PICO_SDK_PATH} CACHE PATH "Path to the PICO SDK" FORCE)
include(${PICO_SDK_INIT_CMAKE_FILE})

4
picoboard/CMakeLists.txt Normal file
View File

@ -0,0 +1,4 @@
if (NOT PICO_NO_HARDWARE)
add_subdirectory(blinky)
add_subdirectory(button)
endif ()

View File

@ -0,0 +1,12 @@
add_executable(picoboard_blinky
blinky.c
)
# Pull in our pico_stdlib which pulls in commonly used features
target_link_libraries(picoboard_blinky pico_stdlib)
# create map/bin/hex file etc.
pico_add_extra_outputs(picoboard_blinky)
# add url via pico_set_program_url
example_auto_set_url(picoboard_blinky)

75
picoboard/blinky/blinky.c Normal file
View File

@ -0,0 +1,75 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
#include "hardware/gpio.h"
const uint LED_PIN = 25;
const uint DOT_PERIOD_MS = 100;
const char *morse_letters[] = {
".-", // A
"-...", // B
"-.-.", // C
"-..", // D
".", // E
"..-.", // F
"--.", // G
"....", // H
"..", // I
".---", // J
"-.-", // K
".-..", // L
"--", // M
"-.", // N
"---", // O
".--.", // P
"--.-", // Q
".-.", // R
"...", // S
"-", // T
"..-", // U
"...-", // V
".--", // W
"-..-", // X
"-.--", // Y
"--.." // Z
};
void put_morse_letter(const char *pattern) {
for (; *pattern; ++pattern) {
gpio_put(LED_PIN, 1);
if (*pattern == '.')
sleep_ms(DOT_PERIOD_MS);
else
sleep_ms(DOT_PERIOD_MS * 3);
gpio_put(LED_PIN, 0);
sleep_ms(DOT_PERIOD_MS * 1);
}
sleep_ms(DOT_PERIOD_MS * 2);
}
void put_morse_str(const char *str) {
for (; *str; ++str) {
if (*str >= 'A' && *str < 'Z') {
put_morse_letter(morse_letters[*str - 'A']);
} else if (*str >= 'a' && *str < 'z') {
put_morse_letter(morse_letters[*str - 'a']);
} else if (*str == ' ') {
sleep_ms(DOT_PERIOD_MS * 4);
}
}
}
int main() {
gpio_init(LED_PIN);
gpio_set_dir(LED_PIN, GPIO_OUT);
while (true) {
put_morse_str("Hello world");
sleep_ms(1000);
}
}

View File

@ -0,0 +1,12 @@
add_executable(picoboard_button
button.c
)
# Pull in our pico_stdlib which pulls in commonly used features
target_link_libraries(picoboard_button pico_stdlib)
# create map/bin/hex file etc.
pico_add_extra_outputs(picoboard_button)
# add url via pico_set_program_url
example_auto_set_url(picoboard_button)

62
picoboard/button/button.c Normal file
View File

@ -0,0 +1,62 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
#include "hardware/gpio.h"
#include "hardware/sync.h"
#include "hardware/structs/ioqspi.h"
#include "hardware/structs/sio.h"
// This example blinks the Picoboard LED when the BOOTSEL button is pressed.
//
// Picoboard has a button attached to the flash CS pin, which the bootrom
// checks, and jumps straight to the USB bootcode if the button is pressed
// (pulling flash CS low). We can check this pin in by jumping to some code in
// SRAM (so that the XIP interface is not required), floating the flash CS
// pin, and observing whether it is pulled low.
//
// This doesn't work if others are trying to access flash at the same time,
// e.g. XIP streamer, or the other core.
bool __no_inline_not_in_flash_func(get_bootsel_button)() {
const uint CS_PIN_INDEX = 1;
// Must disable interrupts, as interrupt handlers may be in flash, and we
// are about to temporarily disable flash access!
uint32_t flags = save_and_disable_interrupts();
// Set chip select to Hi-Z
hw_write_masked(&ioqspi_hw->io[CS_PIN_INDEX].ctrl,
GPIO_OVERRIDE_LOW << IO_QSPI_GPIO_QSPI_SS_CTRL_OEOVER_LSB,
IO_QSPI_GPIO_QSPI_SS_CTRL_OEOVER_BITS);
// Note we can't call into any sleep functions in flash right now
for (volatile int i = 0; i < 1000; ++i);
// The HI GPIO registers in SIO can observe and control the 6 QSPI pins.
// Note the button pulls the pin *low* when pressed.
bool button_state = !(sio_hw->gpio_hi_in & (1u << CS_PIN_INDEX));
// Need to restore the state of chip select, else we are going to have a
// bad time when we return to code in flash!
hw_write_masked(&ioqspi_hw->io[CS_PIN_INDEX].ctrl,
GPIO_OVERRIDE_NORMAL << IO_QSPI_GPIO_QSPI_SS_CTRL_OEOVER_LSB,
IO_QSPI_GPIO_QSPI_SS_CTRL_OEOVER_BITS);
restore_interrupts(flags);
return button_state;
}
int main() {
gpio_init(PICO_DEFAULT_LED_PIN);
gpio_set_dir(PICO_DEFAULT_LED_PIN, GPIO_OUT);
while (true) {
gpio_put(PICO_DEFAULT_LED_PIN, get_bootsel_button());
sleep_ms(10);
}
}

18
pio/CMakeLists.txt Normal file
View File

@ -0,0 +1,18 @@
if (NOT PICO_NO_HARDWARE)
add_subdirectory(addition)
add_subdirectory(apa102)
add_subdirectory(differential_manchester)
add_subdirectory(hello_pio)
add_subdirectory(hub75)
add_subdirectory(i2c)
add_subdirectory(logic_analyser)
add_subdirectory(manchester_encoding)
add_subdirectory(pio_blink)
add_subdirectory(pwm)
add_subdirectory(spi)
add_subdirectory(squarewave)
add_subdirectory(st7789_lcd)
add_subdirectory(uart_rx)
add_subdirectory(uart_tx)
add_subdirectory(ws2812)
endif ()

Some files were not shown because too many files have changed in this diff Show More