Add SPI support and FIFO functionality with proper sign extension
Some checks failed
Arduino Library CI / build (push) Has been cancelled

- Add hardware and software SPI interface support via BusIO
- Implement FIFO test example with correct 23-bit sign extension fix
- Add calculateTemperature() and calculatePressure() functions for raw data
- Refactor existing read functions to use calculation functions
- Fix SPI mode to MODE3 and rename fulltest example directory

🤖 Generated with [Claude Code](https://claude.ai/code)

Co-Authored-By: Claude <noreply@anthropic.com>
This commit is contained in:
ladyada 2025-08-27 17:50:01 -04:00
parent 969dad2a1b
commit 95a782a0f9
7 changed files with 290 additions and 84 deletions

View file

@ -97,7 +97,7 @@ bool Adafruit_SPA06_003::begin(int8_t cspin, SPIClass *theSPI) {
} }
spi_dev = new Adafruit_SPIDevice(cspin, SPA06_003_DEFAULT_SPIFREQ, spi_dev = new Adafruit_SPIDevice(cspin, SPA06_003_DEFAULT_SPIFREQ,
SPI_BITORDER_MSBFIRST, SPI_MODE0, theSPI); SPI_BITORDER_MSBFIRST, SPI_MODE3, theSPI);
if (!spi_dev->begin()) { if (!spi_dev->begin()) {
return false; return false;
@ -126,7 +126,7 @@ bool Adafruit_SPA06_003::begin(int8_t cspin, int8_t mosipin, int8_t misopin,
spi_dev = new Adafruit_SPIDevice(cspin, sckpin, misopin, mosipin, spi_dev = new Adafruit_SPIDevice(cspin, sckpin, misopin, mosipin,
SPA06_003_DEFAULT_SPIFREQ, SPA06_003_DEFAULT_SPIFREQ,
SPI_BITORDER_MSBFIRST, SPI_MODE0); SPI_BITORDER_MSBFIRST, SPI_MODE3);
if (!spi_dev->begin()) { if (!spi_dev->begin()) {
return false; return false;
@ -685,15 +685,38 @@ float Adafruit_SPA06_003::getScalingFactor(spa06_003_oversample_t oversample) {
* @return Temperature in degrees Celsius * @return Temperature in degrees Celsius
*/ */
float Adafruit_SPA06_003::readTemperature() { float Adafruit_SPA06_003::readTemperature() {
// Get current temperature oversampling setting and scale factor
spa06_003_oversample_t oversample = getTemperatureOversampling();
float kT = getScalingFactor(oversample);
// Read raw temperature data (24-bit 2's complement) // Read raw temperature data (24-bit 2's complement)
uint32_t temp_raw = getTemperatureData(); uint32_t temp_raw = getTemperatureData();
// Use the calculation function
return calculateTemperature(temp_raw);
}
/*!
* @brief Reads compensated pressure value in hectopascals
* @return Pressure in hectopascals (hPa)
*/
float Adafruit_SPA06_003::readPressure() {
// Read raw pressure and temperature data (24-bit 2's complement)
uint32_t pres_raw = getPressureData();
uint32_t temp_raw = getTemperatureData();
// Use the calculation function
return calculatePressure(pres_raw, temp_raw);
}
/*!
* @brief Calculates compensated temperature from raw data
* @param raw_temp Raw 24-bit temperature data
* @return Temperature in degrees Celsius
*/
float Adafruit_SPA06_003::calculateTemperature(uint32_t raw_temp) {
// Get temperature oversampling setting for scaling
spa06_003_oversample_t oversample = getTemperatureOversampling();
float kT = getScalingFactor(oversample);
// Convert to signed 32-bit // Convert to signed 32-bit
int32_t temp_raw_signed = (int32_t)temp_raw; int32_t temp_raw_signed = (int32_t)raw_temp;
// Calculate scaled measurement result // Calculate scaled measurement result
float temp_raw_sc = (float)temp_raw_signed / kT; float temp_raw_sc = (float)temp_raw_signed / kT;
@ -705,21 +728,23 @@ float Adafruit_SPA06_003::readTemperature() {
} }
/*! /*!
* @brief Reads compensated pressure value in hectopascals * @brief Calculates compensated pressure from raw data
* @param raw_pres Raw 24-bit pressure data
* @param raw_temp Raw 24-bit temperature data (for compensation)
* @return Pressure in hectopascals (hPa) * @return Pressure in hectopascals (hPa)
*/ */
float Adafruit_SPA06_003::readPressure() { float Adafruit_SPA06_003::calculatePressure(uint32_t raw_pres,
// Get scaling factors based on current oversampling settings uint32_t raw_temp) {
float kP = getScalingFactor(getPressureOversampling()); // Get oversampling settings for scaling
float kT = getScalingFactor(getTemperatureOversampling()); spa06_003_oversample_t pres_oversample = getPressureOversampling();
spa06_003_oversample_t temp_oversample = getTemperatureOversampling();
// Read raw pressure and temperature data (24-bit 2's complement) float kP = getScalingFactor(pres_oversample);
uint32_t pres_raw = getPressureData(); float kT = getScalingFactor(temp_oversample);
uint32_t temp_raw = getTemperatureData();
// Convert to signed 32-bit // Convert to signed 32-bit
int32_t pres_raw_signed = (int32_t)pres_raw; int32_t pres_raw_signed = (int32_t)raw_pres;
int32_t temp_raw_signed = (int32_t)temp_raw; int32_t temp_raw_signed = (int32_t)raw_temp;
// Calculate scaled measurement results // Calculate scaled measurement results
float pres_raw_sc = (float)pres_raw_signed / kP; float pres_raw_sc = (float)pres_raw_signed / kP;
@ -733,14 +758,13 @@ float Adafruit_SPA06_003::readPressure() {
// Calculate compensated pressure using the formula: // Calculate compensated pressure using the formula:
// Pcomp = c00 + c10*Praw_sc + c20*Praw_sc^2 + c30*Praw_sc^3 + c40*Praw_sc^4 + // Pcomp = c00 + c10*Praw_sc + c20*Praw_sc^2 + c30*Praw_sc^3 + c40*Praw_sc^4 +
// Traw_sc*(c01 + c11*Praw_sc + c21*Praw_sc^2 + c31*Praw_sc^3) // Traw_sc*(c01 + c11*Praw_sc + c21*Praw_sc^2 + c31*Praw_sc^3)
float pres_comp = float pres_comp =
(float)c00 + (float)c10 * pres_raw_sc + (float)c20 * pres_raw_sc_2 + (float)c00 + (float)c10 * pres_raw_sc + (float)c20 * pres_raw_sc_2 +
(float)c30 * pres_raw_sc_3 + (float)c40 * pres_raw_sc_4 + (float)c30 * pres_raw_sc_3 + (float)c40 * pres_raw_sc_4 +
temp_raw_sc * ((float)c01 + (float)c11 * pres_raw_sc + temp_raw_sc * ((float)c01 + (float)c11 * pres_raw_sc +
(float)c21 * pres_raw_sc_2 + (float)c31 * pres_raw_sc_3); (float)c21 * pres_raw_sc_2 + (float)c31 * pres_raw_sc_3);
// Convert from Pascals to hectopascals (hPa) // Convert from Pa to hPa (divide by 100)
return pres_comp / 100.0f; return pres_comp / 100.0f;
} }
@ -838,4 +862,4 @@ bool Adafruit_SPA06_003_Pressure::getEvent(sensors_event_t *event) {
event->timestamp = millis(); event->timestamp = millis();
event->pressure = _theSPA06003->readPressure(); event->pressure = _theSPA06003->readPressure();
return true; return true;
} }

View file

@ -212,6 +212,8 @@ class Adafruit_SPA06_003 {
bool reset(); bool reset();
float readTemperature(); float readTemperature();
float readPressure(); float readPressure();
float calculateTemperature(uint32_t raw_temp);
float calculatePressure(uint32_t raw_pres, uint32_t raw_temp);
Adafruit_Sensor *getTemperatureSensor(); Adafruit_Sensor *getTemperatureSensor();
Adafruit_Sensor *getPressureSensor(); Adafruit_Sensor *getPressureSensor();

View file

@ -0,0 +1,142 @@
/*!
* @file fifotest.ino
*
* Demonstrates using the SPA06_003 FIFO functionality with I2C interface.
* This example enables the FIFO, fills it up, then reads all data at once
* when the FIFO becomes full.
*
* The FIFO can store up to 32 pressure and temperature measurements,
* allowing for burst data collection and reducing I2C traffic.
*
* Designed specifically to work with the Adafruit SPA06_003 Breakout
* ----> https://www.adafruit.com/products/xxxx
*
* These sensors use I2C to communicate, 2 pins are required to interface.
*
* Written by Limor 'ladyada' Fried with assistance from Claude Code
* for Adafruit Industries.
* MIT license, check license.txt for more information
* All text above must be included in any redistribution
*/
#include <Adafruit_SPA06_003.h>
Adafruit_SPA06_003 spa;
void setup() {
Serial.begin(115200);
while (!Serial)
delay(10); // will pause Zero, Leonardo, etc until serial console opens
Serial.println("Adafruit SPA06_003 FIFO Test");
// Try to initialize!
if (!spa.begin()) {
Serial.println("Failed to find SPA06_003 chip");
while (1) {
delay(10);
}
}
Serial.println("SPA06_003 Found!");
// Configure for FIFO operation
Serial.println("Configuring sensor for FIFO operation...");
// Set moderate precision for faster sampling
spa.setPressureOversampling(SPA06_003_OVERSAMPLE_8); // 8x oversampling
spa.setTemperatureOversampling(SPA06_003_OVERSAMPLE_8); // 8x oversampling
// Set high measurement rate to fill FIFO quickly
spa.setPressureMeasureRate(SPA06_003_RATE_32); // 32 Hz
spa.setTemperatureMeasureRate(SPA06_003_RATE_32); // 32 Hz
// Enable FIFO and FIFO full interrupt
spa.enableFIFO(true);
spa.setInterruptSource(true, false,
false); // Enable only FIFO full interrupt
// Start continuous measurement
spa.setMeasurementMode(SPA06_003_MEAS_CONTINUOUS_BOTH);
Serial.println("FIFO enabled and continuous measurement started");
Serial.println("Waiting for FIFO to fill...");
Serial.println("FIFO holds up to 32 measurements");
Serial.println();
}
void loop() {
// Check if FIFO is full
if (spa.isFIFOFull()) {
Serial.println("*** FIFO IS FULL! ***");
Serial.println("Reading all data from FIFO...");
uint8_t count = 0;
// Read all data from FIFO until empty
uint32_t last_temp_raw =
0; // Store last temperature for pressure compensation
while (!spa.isFIFOEmpty() && count < 64) { // Safety limit
// Read raw 24-bit data from FIFO (always from pressure registers)
uint32_t raw_data = spa.getPressureData();
// Check LSB to determine measurement type
bool is_pressure = (raw_data & 0x01) == 1;
// Clear the LSB for actual measurement calculation and properly handle
// sign extension
uint32_t measurement_data = raw_data & 0xFFFFFE;
// After clearing LSB, we now have a 23-bit signed value
// Check if bit 22 is set (sign bit of the 23-bit number)
if (measurement_data & 0x400000) {
// Sign extend from 23 bits to 32 bits
measurement_data |= 0xFF800000;
}
Serial.print("Sample ");
Serial.print(count + 1);
Serial.print(": ");
if (is_pressure) {
// This is pressure data - need temperature for compensation
float pressure = spa.calculatePressure(measurement_data, last_temp_raw);
Serial.print("Pressure=");
Serial.print(pressure, 2);
Serial.println(" hPa");
} else {
// This is temperature data
last_temp_raw = measurement_data; // Store for pressure compensation
float temperature = spa.calculateTemperature(measurement_data);
Serial.print("Temperature=");
Serial.print(temperature, 2);
Serial.println(" °C");
}
count++;
delay(10); // Small delay between reads
}
Serial.print("Total samples read from FIFO: ");
Serial.println(count);
Serial.println();
Serial.println("FIFO emptied. Waiting for next fill...");
Serial.println("-----------------------------------");
Serial.println();
}
// Check FIFO status periodically
static unsigned long lastStatusCheck = 0;
if (millis() - lastStatusCheck > 1000) { // Check every second
Serial.print("FIFO Status - ");
Serial.print("Empty: ");
Serial.print(spa.isFIFOEmpty() ? "Yes" : "No");
Serial.print(", Full: ");
Serial.print(spa.isFIFOFull() ? "Yes" : "No");
Serial.print(", Enabled: ");
Serial.println(spa.isFIFOEnabled() ? "Yes" : "No");
lastStatusCheck = millis();
}
delay(100); // Check FIFO status every 100ms
}

View file

@ -1,8 +1,8 @@
/* /*
Basic test sketch for SPA06_003 Digital Pressure Sensor Basic test sketch for SPA06_003 Digital Pressure Sensor
This sketch initializes the sensor and verifies communication. This sketch initializes the sensor and verifies communication.
Written by Limor 'ladyada' Fried with assistance from Claude Code Written by Limor 'ladyada' Fried with assistance from Claude Code
for Adafruit Industries. for Adafruit Industries.
MIT license, check license.txt for more information MIT license, check license.txt for more information
@ -102,23 +102,25 @@ void printOversampling(spa06_003_oversample_t prc) {
void setup() { void setup() {
Serial.begin(115200); Serial.begin(115200);
while (!Serial) delay(10); while (!Serial)
delay(10);
Serial.println("SPA06_003 test!"); Serial.println("SPA06_003 test!");
if (!spa.begin()) { if (!spa.begin()) {
Serial.println("Could not find a valid SPA06_003 sensor, check wiring!"); Serial.println("Could not find a valid SPA06_003 sensor, check wiring!");
while (1) delay(10); while (1)
delay(10);
} }
Serial.println(F("SPA06_003 sensor found and initialized!")); Serial.println(F("SPA06_003 sensor found and initialized!"));
Serial.println(F("Setting measurement mode to continuous both...")); Serial.println(F("Setting measurement mode to continuous both..."));
spa.setMeasurementMode(SPA06_003_MEAS_CONTINUOUS_BOTH); spa.setMeasurementMode(SPA06_003_MEAS_CONTINUOUS_BOTH);
Serial.print(F("Current measurement mode: ")); Serial.print(F("Current measurement mode: "));
spa06_003_meas_mode_t current_mode = spa.getMeasurementMode(); spa06_003_meas_mode_t current_mode = spa.getMeasurementMode();
switch (current_mode) { switch (current_mode) {
case SPA06_003_MEAS_IDLE: case SPA06_003_MEAS_IDLE:
Serial.println(F("Idle")); Serial.println(F("Idle"));
@ -142,33 +144,34 @@ void setup() {
Serial.println(F("Unknown")); Serial.println(F("Unknown"));
break; break;
} }
spa.enableFIFO(false); spa.enableFIFO(false);
spa.setInterruptPolarity(SPA06_003_INT_ACTIVE_HIGH); spa.setInterruptPolarity(SPA06_003_INT_ACTIVE_HIGH);
spa.setInterruptSource(false /*fifo*/, true /*temp_ready*/, true /*pres_ready*/); spa.setInterruptSource(false /*fifo*/, true /*temp_ready*/,
true /*pres_ready*/);
spa.setTemperatureOversampling(SPA06_003_OVERSAMPLE_8); spa.setTemperatureOversampling(SPA06_003_OVERSAMPLE_8);
spa06_003_oversample_t temp_prc = spa.getTemperatureOversampling(); spa06_003_oversample_t temp_prc = spa.getTemperatureOversampling();
Serial.print(F("Current temperature oversampling: ")); Serial.print(F("Current temperature oversampling: "));
printOversampling(temp_prc); printOversampling(temp_prc);
spa.setTemperatureMeasureRate(SPA06_003_RATE_64); spa.setTemperatureMeasureRate(SPA06_003_RATE_64);
spa06_003_rate_t temp_rate = spa.getTemperatureMeasureRate(); spa06_003_rate_t temp_rate = spa.getTemperatureMeasureRate();
Serial.print(F("Current temperature measurement rate: ")); Serial.print(F("Current temperature measurement rate: "));
printMeasureRate(temp_rate); printMeasureRate(temp_rate);
spa.setPressureMeasureRate(SPA06_003_RATE_128); spa.setPressureMeasureRate(SPA06_003_RATE_128);
spa06_003_rate_t current_rate = spa.getPressureMeasureRate(); spa06_003_rate_t current_rate = spa.getPressureMeasureRate();
Serial.print(F("Current pressure measurement rate: ")); Serial.print(F("Current pressure measurement rate: "));
printMeasureRate(current_rate); printMeasureRate(current_rate);
spa.setPressureOversampling(SPA06_003_OVERSAMPLE_8); spa.setPressureOversampling(SPA06_003_OVERSAMPLE_8);
spa06_003_oversample_t current_prc = spa.getPressureOversampling(); spa06_003_oversample_t current_prc = spa.getPressureOversampling();
Serial.print(F("Current pressure oversampling: ")); Serial.print(F("Current pressure oversampling: "));
printOversampling(current_prc); printOversampling(current_prc);
@ -180,18 +183,18 @@ void loop() {
Serial.print(spa.readTemperature()); Serial.print(spa.readTemperature());
Serial.print(F("°C")); Serial.print(F("°C"));
} }
if (spa.isPresDataReady()) { if (spa.isPresDataReady()) {
Serial.print(F(", Pressure: ")); Serial.print(F(", Pressure: "));
Serial.print(spa.readPressure()); Serial.print(spa.readPressure());
Serial.print(F(" hPa")); Serial.print(F(" hPa"));
} }
uint8_t status_flags = spa.getStatusFlags(); uint8_t status_flags = spa.getStatusFlags();
Serial.print(F(", Status flags: 0x")); Serial.print(F(", Status flags: 0x"));
Serial.print(status_flags, HEX); Serial.print(status_flags, HEX);
Serial.print(F(" [")); Serial.print(F(" ["));
if (status_flags & SPA06_003_INT_FIFO_FULL) { if (status_flags & SPA06_003_INT_FIFO_FULL) {
Serial.print(F("FIFO_FULL ")); Serial.print(F("FIFO_FULL "));
} }
@ -204,9 +207,9 @@ void loop() {
if (status_flags == 0) { if (status_flags == 0) {
Serial.print(F("NONE")); Serial.print(F("NONE"));
} }
Serial.println(F("]")); Serial.println(F("]"));
Serial.print(F(", FIFO: ")); Serial.print(F(", FIFO: "));
if (spa.isFIFOEnabled()) { if (spa.isFIFOEnabled()) {
Serial.print(F("enabled ")); Serial.print(F("enabled "));
@ -221,6 +224,6 @@ void loop() {
Serial.print(F("disabled")); Serial.print(F("disabled"));
} }
Serial.println(); Serial.println();
delay(1000); delay(1000);
} }

View file

@ -1,10 +1,10 @@
/*! /*!
* @file sensorapi.ino * @file sensorapi.ino
* *
* Demonstrates using the SPA06_003 sensor with Adafruit's Unified Sensor interface. * Demonstrates using the SPA06_003 sensor with Adafruit's Unified Sensor
* This example shows how to get sensor information and read values using the * interface. This example shows how to get sensor information and read values
* standardized Adafruit Sensor API, which allows easy integration with other * using the standardized Adafruit Sensor API, which allows easy integration
* sensor libraries and data logging systems. * with other sensor libraries and data logging systems.
* *
* The begin() function automatically configures the sensor for: * The begin() function automatically configures the sensor for:
* - Highest precision (128x oversampling) * - Highest precision (128x oversampling)
@ -34,21 +34,24 @@ Adafruit_Sensor *spa_pressure;
void setup() { void setup() {
Serial.begin(115200); Serial.begin(115200);
while (!Serial) delay(10); // will pause Zero, Leonardo, etc until serial console opens while (!Serial)
delay(10); // will pause Zero, Leonardo, etc until serial console opens
Serial.println("Adafruit SPA06_003 Unified Sensor API Test"); Serial.println("Adafruit SPA06_003 Unified Sensor API Test");
// Try to initialize the sensor // Try to initialize the sensor
if (!spa.begin()) { if (!spa.begin()) {
Serial.println("Failed to find SPA06_003 chip"); Serial.println("Failed to find SPA06_003 chip");
while (1) { delay(10); } while (1) {
delay(10);
}
} }
Serial.println("SPA06_003 Found!"); Serial.println("SPA06_003 Found!");
// Get sensor objects for temperature and pressure // Get sensor objects for temperature and pressure
spa_temp = spa.getTemperatureSensor(); spa_temp = spa.getTemperatureSensor();
spa_pressure = spa.getPressureSensor(); spa_pressure = spa.getPressureSensor();
// Print sensor details // Print sensor details
printSensorDetails(); printSensorDetails();
} }
@ -61,47 +64,65 @@ void loop() {
Serial.print(temp_event.temperature); Serial.print(temp_event.temperature);
Serial.print(" °C"); Serial.print(" °C");
} }
// Read pressure using unified sensor interface // Read pressure using unified sensor interface
sensors_event_t pressure_event; sensors_event_t pressure_event;
if (spa_pressure->getEvent(&pressure_event)) { if (spa_pressure->getEvent(&pressure_event)) {
Serial.print("\tPressure: "); Serial.print("\tPressure: ");
Serial.print(pressure_event.pressure); Serial.print(pressure_event.pressure);
Serial.print(" hPa"); Serial.print(" hPa");
Serial.print("\tTimestamp: "); Serial.print("\tTimestamp: ");
Serial.println(pressure_event.timestamp); Serial.println(pressure_event.timestamp);
} }
delay(500); // Wait 500ms between readings delay(500); // Wait 500ms between readings
} }
void printSensorDetails() { void printSensorDetails() {
Serial.println("------------------------------------"); Serial.println("------------------------------------");
// Print temperature sensor details // Print temperature sensor details
sensor_t sensor; sensor_t sensor;
spa_temp->getSensor(&sensor); spa_temp->getSensor(&sensor);
Serial.println("Temperature Sensor:"); Serial.println("Temperature Sensor:");
Serial.print(" Sensor Type: "); Serial.println(sensor.name); Serial.print(" Sensor Type: ");
Serial.print(" Driver Ver: "); Serial.println(sensor.version); Serial.println(sensor.name);
Serial.print(" Unique ID: "); Serial.println(sensor.sensor_id); Serial.print(" Driver Ver: ");
Serial.print(" Max Value: "); Serial.print(sensor.max_value); Serial.println(" °C"); Serial.println(sensor.version);
Serial.print(" Min Value: "); Serial.print(sensor.min_value); Serial.println(" °C"); Serial.print(" Unique ID: ");
Serial.print(" Resolution: "); Serial.print(sensor.resolution); Serial.println(" °C"); Serial.println(sensor.sensor_id);
Serial.print(" Max Value: ");
Serial.print(sensor.max_value);
Serial.println(" °C");
Serial.print(" Min Value: ");
Serial.print(sensor.min_value);
Serial.println(" °C");
Serial.print(" Resolution: ");
Serial.print(sensor.resolution);
Serial.println(" °C");
Serial.println(""); Serial.println("");
// Print pressure sensor details // Print pressure sensor details
spa_pressure->getSensor(&sensor); spa_pressure->getSensor(&sensor);
Serial.println("Pressure Sensor:"); Serial.println("Pressure Sensor:");
Serial.print(" Sensor Type: "); Serial.println(sensor.name); Serial.print(" Sensor Type: ");
Serial.print(" Driver Ver: "); Serial.println(sensor.version); Serial.println(sensor.name);
Serial.print(" Unique ID: "); Serial.println(sensor.sensor_id); Serial.print(" Driver Ver: ");
Serial.print(" Max Value: "); Serial.print(sensor.max_value); Serial.println(" hPa"); Serial.println(sensor.version);
Serial.print(" Min Value: "); Serial.print(sensor.min_value); Serial.println(" hPa"); Serial.print(" Unique ID: ");
Serial.print(" Resolution: "); Serial.print(sensor.resolution); Serial.println(" hPa"); Serial.println(sensor.sensor_id);
Serial.print(" Max Value: ");
Serial.print(sensor.max_value);
Serial.println(" hPa");
Serial.print(" Min Value: ");
Serial.print(sensor.min_value);
Serial.println(" hPa");
Serial.print(" Resolution: ");
Serial.print(sensor.resolution);
Serial.println(" hPa");
Serial.println(""); Serial.println("");
Serial.println("------------------------------------"); Serial.println("------------------------------------");
Serial.println(""); Serial.println("");
} }

View file

@ -3,9 +3,9 @@
* *
* A simple test for the SPA06_003 pressure and temperature sensor. * A simple test for the SPA06_003 pressure and temperature sensor.
* This example shows basic pressure and temperature readings using the sensor. * This example shows basic pressure and temperature readings using the sensor.
* *
* The begin() function automatically configures the sensor for: * The begin() function automatically configures the sensor for:
* - Highest precision (128x oversampling) * - Highest precision (128x oversampling)
* - Highest sample rate (200 Hz) * - Highest sample rate (200 Hz)
* - Continuous measurement mode * - Continuous measurement mode
* *
@ -26,14 +26,17 @@ Adafruit_SPA06_003 spa;
void setup() { void setup() {
Serial.begin(115200); Serial.begin(115200);
while (!Serial) delay(10); // will pause Zero, Leonardo, etc until serial console opens while (!Serial)
delay(10); // will pause Zero, Leonardo, etc until serial console opens
Serial.println("Adafruit SPA06_003 Simple Test"); Serial.println("Adafruit SPA06_003 Simple Test");
// Try to initialize! // Try to initialize!
if (!spa.begin()) { if (!spa.begin()) {
Serial.println("Failed to find SPA06_003 chip"); Serial.println("Failed to find SPA06_003 chip");
while (1) { delay(10); } while (1) {
delay(10);
}
} }
Serial.println("SPA06_003 Found!"); Serial.println("SPA06_003 Found!");
} }
@ -43,15 +46,15 @@ void loop() {
if (spa.isTempDataReady() || spa.isPresDataReady()) { if (spa.isTempDataReady() || spa.isPresDataReady()) {
float temperature = spa.readTemperature(); float temperature = spa.readTemperature();
float pressure = spa.readPressure(); float pressure = spa.readPressure();
Serial.print("Temperature: "); Serial.print("Temperature: ");
Serial.print(temperature); Serial.print(temperature);
Serial.print(" °C"); Serial.print(" °C");
Serial.print("\tPressure: "); Serial.print("\tPressure: ");
Serial.print(pressure); Serial.print(pressure);
Serial.println(" hPa"); Serial.println(" hPa");
} }
delay(10); // Short delay to avoid overwhelming the sensor delay(10); // Short delay to avoid overwhelming the sensor
} }

View file

@ -35,7 +35,8 @@ Adafruit_SPA06_003 spa;
void setup() { void setup() {
Serial.begin(115200); Serial.begin(115200);
while (!Serial) delay(10); // will pause Zero, Leonardo, etc until serial console opens while (!Serial)
delay(10); // will pause Zero, Leonardo, etc until serial console opens
Serial.println("Adafruit SPA06_003 SPI Test"); Serial.println("Adafruit SPA06_003 SPI Test");
@ -44,10 +45,20 @@ void setup() {
if (!spa.begin(SPA_CS_PIN, &SPI)) { if (!spa.begin(SPA_CS_PIN, &SPI)) {
Serial.println("Failed to find SPA06_003 chip via hardware SPI"); Serial.println("Failed to find SPA06_003 chip via hardware SPI");
Serial.println("Check wiring and try software SPI example"); Serial.println("Check wiring and try software SPI example");
while (1) { delay(10); } while (1) {
delay(10);
}
} }
Serial.println("SPA06_003 Found via Hardware SPI!"); Serial.println("SPA06_003 Found via Hardware SPI!");
// Alternative: Software SPI (uncomment to use instead of hardware SPI)
// Default ATmega328 pins: MOSI=11, MISO=12, SCK=13, CS=10
// if (!spa.begin(10, 11, 12, 13)) {
// Serial.println("Failed to find SPA06_003 chip via software SPI");
// while (1) { delay(10); }
// }
// Serial.println("SPA06_003 Found via Software SPI!");
Serial.println("Starting continuous measurement..."); Serial.println("Starting continuous measurement...");
Serial.println("Temperature and pressure readings:"); Serial.println("Temperature and pressure readings:");
Serial.println("Format: Temp (°C) | Pressure (hPa)"); Serial.println("Format: Temp (°C) | Pressure (hPa)");
@ -62,7 +73,7 @@ void loop() {
Serial.print(" °C"); Serial.print(" °C");
} }
// Check if new pressure data is available // Check if new pressure data is available
if (spa.isPresDataReady()) { if (spa.isPresDataReady()) {
float pressure = spa.readPressure(); float pressure = spa.readPressure();
Serial.print(" | "); Serial.print(" | ");