Swap line endings to avoid showing in diff + no secrets

This commit is contained in:
tyeth 2024-07-02 14:58:52 +01:00
parent ea35d73117
commit 75b9aff477
7 changed files with 2201 additions and 2198 deletions

99
.gitignore vendored
View file

@ -1,48 +1,51 @@
# Prerequisites
*.d
# Compiled Object files
*.slo
*.lo
*.o
*.obj
# Precompiled Headers
*.gch
*.pch
# Compiled Dynamic libraries
*.so
*.dylib
*.dll
# Fortran module files
*.mod
*.smod
# Compiled Static libraries
*.lai
*.la
*.a
*.lib
# Executables
*.exe
*.out
*.app
# Doxygen
*.bak
html/*
# VSCode artifacts
.vscode/*
src/.vscode/settings.json
.DS_STORE
examples/Wippersnapper_demo/build/
#Platformio artifacts
.pio/
# Prerequisites
*.d
# Compiled Object files
*.slo
*.lo
*.o
*.obj
# Precompiled Headers
*.gch
*.pch
# Compiled Dynamic libraries
*.so
*.dylib
*.dll
# Fortran module files
*.mod
*.smod
# Compiled Static libraries
*.lai
*.la
*.a
*.lib
# Executables
*.exe
*.out
*.app
# Doxygen
*.bak
html/*
# VSCode artifacts
.vscode/*
src/.vscode/settings.json
.DS_STORE
examples/Wippersnapper_demo/build/
# Platformio artifacts
.pio/
# Secrets
data/

View file

@ -1,494 +1,494 @@
/*!
* @file Wippersnapper.h
*
* This is the documentation for Adafruit's Wippersnapper firmware for the
* Arduino platform. It is designed specifically to work with
* Adafruit IO Wippersnapper IoT platform.
*
* Adafruit invests time and resources providing this open source code,
* please support Adafruit and open-source hardware by purchasing
* products from Adafruit!
*
* Copyright (c) Brent Rubell 2020-2024 for Adafruit Industries.
*
* BSD license, all text here must be included in any redistribution.
*
*/
#ifndef WIPPERSNAPPER_H
#define WIPPERSNAPPER_H
// Cpp STD
#include <vector>
// Nanopb dependencies
#include <nanopb/pb_common.h>
#include <nanopb/pb_decode.h>
#include <nanopb/pb_encode.h>
#include <pb.h>
#include <wippersnapper/description/v1/description.pb.h> // description.proto
#include <wippersnapper/signal/v1/signal.pb.h> // signal.proto
// External libraries
#include "Adafruit_MQTT.h" // MQTT Client
#include "Adafruit_SleepyDog.h" // Watchdog
#include "Arduino.h" // Wiring
#include <SPI.h> // SPI
// Wippersnapper API Helpers
#include "Wippersnapper_Boards.h"
#include "components/statusLED/Wippersnapper_StatusLED.h"
#include "provisioning/ConfigJson.h"
#define WS_DEBUG ///< Define to enable debugging to serial terminal
#define WS_PRINTER Serial ///< Where debug messages will be printed
// Define actual debug output functions when necessary.
#ifdef WS_DEBUG
#define WS_DEBUG_PRINT(...) \
{ WS_PRINTER.print(__VA_ARGS__); } ///< Prints debug output.
#define WS_DEBUG_PRINTLN(...) \
{ WS_PRINTER.println(__VA_ARGS__); } ///< Prints line from debug output.
#define WS_DEBUG_PRINTHEX(...) \
{ WS_PRINTER.print(__VA_ARGS__, HEX); } ///< Prints debug output.
#else
#define WS_DEBUG_PRINT(...) \
{} ///< Prints debug output
#define WS_DEBUG_PRINTLN(...) \
{} ///< Prints line from debug output.
#endif
#define WS_DELAY_WITH_WDT(timeout) \
{ \
unsigned long start = millis(); \
while (millis() - start < timeout) { \
delay(10); \
yield(); \
feedWDT(); \
if (millis() < start) { \
start = millis(); /* if rollover */ \
} \
} \
} ///< Delay function
/**************************************************************************/
/*!
@brief Retry a function until a condition is met or a timeout is reached.
@param func
The function to retry.
@param result_type
The type of the result of the function.
@param result_var
The variable to store the last result of the function.
@param condition
The condition to check the result against.
@param timeout
The maximum time to retry the function.
@param interval
The time to wait between retries.
@param ...
The arguments to pass to the function.
*/
/**************************************************************************/
#define RETRY_FUNCTION_UNTIL_TIMEOUT(func, result_type, result_var, condition, \
timeout, interval, ...) \
{ \
unsigned long startTime = millis(); \
while (millis() - startTime < timeout) { \
result_type result_var = func(__VA_ARGS__); \
if (condition(result_var)) { \
break; \
} \
if (startTime < millis()) { \
startTime = millis(); /* if rollover */ \
} \
WS_DELAY_WITH_WDT(interval); \
} \
} ///< Retry a function until a condition is met or a timeout is reached.
// Wippersnapper pb helpers
#include <nanopb/ws_pb_helpers.h>
// Wippersnapper components
#include "components/analogIO/Wippersnapper_AnalogIO.h"
#include "components/digitalIO/Wippersnapper_DigitalGPIO.h"
#include "components/i2c/WipperSnapper_I2C.h"
// LEDC-Manager, ESP32-only
#ifdef ARDUINO_ARCH_ESP32
#include "components/ledc/ws_ledc.h"
#endif
// Display
#ifdef USE_DISPLAY
#include "display/ws_display_driver.h"
#include "display/ws_display_ui_helper.h"
#endif
#include "components/ds18x20/ws_ds18x20.h"
#include "components/pixels/ws_pixels.h"
#include "components/pwm/ws_pwm.h"
#include "components/servo/ws_servo.h"
#include "components/uart/ws_uart.h"
#if defined(USE_TINYUSB)
#include "provisioning/tinyusb/Wippersnapper_FS.h"
#endif
#if defined(USE_LITTLEFS)
#include "provisioning/littlefs/WipperSnapper_LittleFS.h"
#endif
#define WS_VERSION \
"1.0.0-beta.85" ///< WipperSnapper app. version (semver-formatted)
// Reserved Adafruit IO MQTT topics
#define TOPIC_IO_THROTTLE "/throttle" ///< Adafruit IO Throttle MQTT Topic
#define TOPIC_IO_ERRORS "/errors" ///< Adafruit IO Error MQTT Topic
// Reserved Wippersnapper topics
#define TOPIC_WS "/wprsnpr/" ///< WipperSnapper topic
#define TOPIC_INFO "/info/" ///< Registration sub-topic
#define TOPIC_SIGNALS "/signals/" ///< Signals sub-topic
#define TOPIC_I2C "/i2c" ///< I2C sub-topic
#define MQTT_TOPIC_PIXELS_DEVICE \
"/signals/device/pixel" ///< Pixels device->broker topic
#define MQTT_TOPIC_PIXELS_BROKER \
"/signals/broker/pixel" ///< Pixels broker->device topic
/** Defines the Adafruit IO connection status */
typedef enum {
WS_IDLE = 0, // Waiting for connection establishement
WS_NET_DISCONNECTED = 1, // Network disconnected
WS_DISCONNECTED = 2, // Disconnected from Adafruit IO
WS_FINGERPRINT_UNKOWN = 3, // Unknown WS_SSL_FINGERPRINT
WS_NET_CONNECT_FAILED = 10, // Failed to connect to network
WS_CONNECT_FAILED = 11, // Failed to connect to Adafruit IO
WS_FINGERPRINT_INVALID = 12, // Unknown WS_SSL_FINGERPRINT
WS_AUTH_FAILED = 13, // Invalid Adafruit IO login credentials provided.
WS_SSID_INVALID =
14, // SSID is "" or otherwise invalid, connection not attempted
WS_NET_CONNECTED = 20, // Connected to Adafruit IO
WS_CONNECTED = 21, // Connected to network
WS_CONNECTED_INSECURE = 22, // Insecurely (non-SSL) connected to network
WS_FINGERPRINT_UNSUPPORTED = 23, // Unsupported WS_SSL_FINGERPRINT
WS_FINGERPRINT_VALID = 24, // Valid WS_SSL_FINGERPRINT
WS_BOARD_DESC_INVALID = 25, // Unable to send board description
WS_BOARD_RESYNC_FAILED = 26 // Board sync failure
} ws_status_t;
/** Defines the Adafruit IO MQTT broker's connection return codes */
typedef enum {
WS_MQTT_CONNECTED = 0, // Connected
WS_MQTT_INVALID_PROTOCOL = 1, // Invalid mqtt protocol
WS_MQTT_INVALID_CID = 2, // Client id rejected
WS_MQTT_SERVICE_UNAVALIABLE = 3, // Malformed user/pass
WS_MQTT_INVALID_USER_PASS = 4, // Unauthorized access to resource
WS_MQTT_UNAUTHORIZED = 5, // MQTT service unavailable
WS_MQTT_THROTTLED = 6, // Account throttled
WS_MQTT_BANNED = 7 // Account banned
} ws_mqtt_status_t;
/** Defines the Wippersnapper client's hardware registration status */
typedef enum {
WS_BOARD_DEF_IDLE,
WS_BOARD_DEF_SEND_FAILED,
WS_BOARD_DEF_SENT,
WS_BOARD_DEF_OK,
WS_BOARD_DEF_INVALID,
WS_BOARD_DEF_UNSPECIFIED
} ws_board_status_t;
/** Defines the Wippersnapper client's network status */
typedef enum {
FSM_NET_IDLE,
FSM_NET_CONNECTED,
FSM_MQTT_CONNECTED,
FSM_NET_CHECK_MQTT,
FSM_NET_CHECK_NETWORK,
FSM_NET_ESTABLISH_NETWORK,
FSM_NET_ESTABLISH_MQTT,
} fsm_net_t;
#define WS_WDT_TIMEOUT 60000 ///< WDT timeout
/* MQTT Configuration */
#define WS_KEEPALIVE_INTERVAL_MS \
5000 ///< Session keepalive interval time, in milliseconds
#define WS_MQTT_MAX_PAYLOAD_SIZE \
512 ///< MAXIMUM expected payload size, in bytes
class Wippersnapper_DigitalGPIO;
class Wippersnapper_AnalogIO;
class Wippersnapper_FS;
class WipperSnapper_LittleFS;
#ifdef USE_DISPLAY
class ws_display_driver;
class ws_display_ui_helper;
#endif
#ifdef ARDUINO_ARCH_ESP32
class ws_ledc;
#endif
class WipperSnapper_Component_I2C;
class ws_servo;
class ws_pwm;
class ws_ds18x20;
class ws_pixels;
class ws_uart;
/**************************************************************************/
/*!
@brief Class that provides storage and functions for the Adafruit IO
Wippersnapper interface.
*/
/**************************************************************************/
class Wippersnapper {
public:
Wippersnapper();
virtual ~Wippersnapper();
void provision();
bool lockStatusNeoPixel; ///< True if status LED is using the status neopixel
bool lockStatusDotStar; ///< True if status LED is using the status dotstar
bool lockStatusLED; ///< True if status LED is using the built-in LED
float status_pixel_brightness =
STATUS_PIXEL_BRIGHTNESS_DEFAULT; ///< Global status pixel's brightness
///< (from 0.0 to 1.0)
virtual void set_user_key();
virtual void set_ssid_pass(const char *ssid, const char *ssidPassword);
virtual void set_ssid_pass();
virtual bool check_valid_ssid();
virtual void _connect();
virtual void _disconnect();
void connect();
void disconnect();
virtual void getMacAddr();
virtual int32_t getRSSI();
virtual void setupMQTTClient(const char *clientID);
virtual ws_status_t networkStatus();
ws_board_status_t getBoardStatus();
bool generateDeviceUID();
bool generateWSTopics();
bool generateWSErrorTopics();
// Registration API
bool registerBoard();
bool encodePubRegistrationReq();
void decodeRegistrationResp(char *data, uint16_t len);
void pollRegistrationResp();
// Configuration API
void publishPinConfigComplete();
// run() loop
ws_status_t run();
void processPackets();
void publish(const char *topic, uint8_t *payload, uint16_t bLen,
uint8_t qos = 0);
// Networking helpers
void pingBroker();
void runNetFSM();
// WDT helpers
void enableWDT(int timeoutMS = 0);
void feedWDT();
// Error handling helpers
void haltError(String error,
ws_led_status_t ledStatusColor = WS_LED_STATUS_ERROR_RUNTIME);
void errorWriteHang(String error);
// MQTT topic callbacks //
// Decodes a signal message
bool decodeSignalMsg(
wippersnapper_signal_v1_CreateSignalRequest *encodedSignalMsg);
// Encodes a pin event message
bool
encodePinEvent(wippersnapper_signal_v1_CreateSignalRequest *outgoingSignalMsg,
uint8_t pinName, int pinVal);
// Pin configure message
bool configureDigitalPinReq(wippersnapper_pin_v1_ConfigurePinRequest *pinMsg);
bool configAnalogInPinReq(wippersnapper_pin_v1_ConfigurePinRequest *pinMsg);
// I2C
std::vector<WipperSnapper_Component_I2C *>
i2cComponents; ///< Vector containing all I2C components
WipperSnapper_Component_I2C *_i2cPort0 =
NULL; ///< WipperSnapper I2C Component for I2C port #0
WipperSnapper_Component_I2C *_i2cPort1 =
NULL; ///< WipperSnapper I2C Component for I2C port #1
bool _isI2CPort0Init =
false; ///< True if I2C port 0 has been initialized, False otherwise.
bool _isI2CPort1Init =
false; ///< True if I2C port 1 has been initialized, False otherwise.
uint8_t _buffer[WS_MQTT_MAX_PAYLOAD_SIZE]; /*!< Shared buffer to save callback
payload */
uint8_t
_buffer_outgoing[WS_MQTT_MAX_PAYLOAD_SIZE]; /*!< buffer which contains
outgoing payload data */
uint16_t bufSize; /*!< Length of data inside buffer */
ws_board_status_t _boardStatus =
WS_BOARD_DEF_IDLE; ///< Hardware's registration status
// TODO: We really should look at making these static definitions, not dynamic
// to free up space on the heap
Wippersnapper_DigitalGPIO *_digitalGPIO; ///< Instance of digital gpio class
Wippersnapper_AnalogIO *_analogIO; ///< Instance of analog io class
Wippersnapper_FS *_fileSystem; ///< Instance of Filesystem (native USB)
WipperSnapper_LittleFS
*_littleFS; ///< Instance of LittleFS Filesystem (non-native USB)
#ifdef USE_DISPLAY
ws_display_driver *_display = nullptr; ///< Instance of display driver class
ws_display_ui_helper *_ui_helper =
nullptr; ///< Instance of display UI helper class
#endif
ws_pixels *_ws_pixelsComponent; ///< ptr to instance of ws_pixels class
ws_pwm *_pwmComponent; ///< Instance of pwm class
ws_servo *_servoComponent; ///< Instance of servo class
ws_ds18x20 *_ds18x20Component; ///< Instance of DS18x20 class
ws_uart *_uartComponent; ///< Instance of UART class
// TODO: does this really need to be global?
uint8_t _macAddr[6]; /*!< Unique network iface identifier */
char sUID[13]; /*!< Unique network iface identifier */
const char *_boardId; /*!< Adafruit IO+ board string */
Adafruit_MQTT *_mqtt; /*!< Reference to Adafruit_MQTT, _mqtt. */
secretsConfig _config; /*!< Wippersnapper secrets.json as a struct. */
// TODO: Does this need to be within this class?
int32_t totalDigitalPins; /*!< Total number of digital-input capable pins */
char *_topic_description = NULL; /*!< MQTT topic for the device description */
char *_topic_signal_device = NULL; /*!< Device->Wprsnpr messages */
char *_topic_signal_i2c_brkr = NULL; /*!< Topic carries messages from a device
to a broker. */
char *_topic_signal_i2c_device = NULL; /*!< Topic carries messages from a
broker to a device. */
char *_topic_signal_servo_brkr = NULL; /*!< Topic carries messages from a
device to a broker. */
char *_topic_signal_servo_device = NULL; /*!< Topic carries messages from a
broker to a device. */
char *_topic_signal_pwm_brkr =
NULL; /*!< Topic carries PWM messages from a device to a broker. */
char *_topic_signal_pwm_device =
NULL; /*!< Topic carries PWM messages from a broker to a device. */
char *_topic_signal_ds18_brkr = NULL; /*!< Topic carries ds18x20 messages from
a device to a broker. */
char *_topic_signal_ds18_device = NULL; /*!< Topic carries ds18x20 messages
from a broker to a device. */
char *_topic_signal_pixels_brkr = NULL; /*!< Topic carries pixel messages */
char *_topic_signal_pixels_device = NULL; /*!< Topic carries pixel messages */
char *_topic_signal_uart_brkr = NULL; /*!< Topic carries UART messages */
char *_topic_signal_uart_device = NULL; /*!< Topic carries UART messages */
wippersnapper_signal_v1_CreateSignalRequest
_incomingSignalMsg; /*!< Incoming signal message from broker */
wippersnapper_signal_v1_I2CRequest msgSignalI2C =
wippersnapper_signal_v1_I2CRequest_init_zero; ///< I2C request wrapper
///< message
// ds signal msg
wippersnapper_signal_v1_Ds18x20Request msgSignalDS =
wippersnapper_signal_v1_Ds18x20Request_init_zero; ///< DS request message
///< wrapper
// servo message
wippersnapper_signal_v1_ServoRequest
msgServo; ///< ServoRequest wrapper message
wippersnapper_signal_v1_PWMRequest msgPWM =
wippersnapper_signal_v1_PWMRequest_init_zero; ///< PWM request wrapper
///< message.
// pixels signal message
wippersnapper_signal_v1_PixelsRequest
msgPixels; ///< PixelsRequest wrapper message
wippersnapper_signal_v1_UARTRequest
msgSignalUART; ///< UARTReq wrapper message
char *throttleMessage; /*!< Pointer to throttle message data. */
int throttleTime; /*!< Total amount of time to throttle the device, in
milliseconds. */
bool pinCfgCompleted = false; /*!< Did initial pin sync complete? */
// enable LEDC if esp32
#ifdef ARDUINO_ARCH_ESP32
ws_ledc *_ledc = nullptr; ///< Pointer to LEDC object
#endif
private:
void _init();
protected:
ws_status_t _status = WS_IDLE; /*!< Adafruit IO connection status */
uint32_t _last_mqtt_connect = 0; /*!< Previous time when client connected to
Adafruit IO, in milliseconds. */
uint32_t _prv_ping = 0; /*!< Previous time when client pinged Adafruit IO's
MQTT broker, in milliseconds. */
uint32_t _prvKATBlink = 0; /*!< Previous time when client pinged Adafruit IO's
MQTT broker, in milliseconds. */
// Device information
const char *_deviceId; /*!< Adafruit IO+ device identifier string */
char *_device_uid; /*!< Unique device identifier */
// MQTT topics
char *_topic_description_status =
NULL; /*!< MQTT subtopic carrying the description
status resp. from the broker */
char *_topic_description_status_complete = NULL; /*!< MQTT topic carrying the
ACK signal from the device to the
broker after registration */
char *_topic_device_pin_config_complete =
NULL; /*!< MQTT topic carrying the ACK signal
from the device to the broker after
hardware configuration */
char *_topic_signal_brkr = NULL; /*!< Wprsnpr->Device messages */
char *_err_topic = NULL; /*!< Adafruit IO MQTT error message topic. */
char *_throttle_topic = NULL; /*!< Adafruit IO MQTT throttle message topic. */
Adafruit_MQTT_Subscribe *_topic_description_sub; /*!< Subscription callback
for registration topic. */
Adafruit_MQTT_Publish *_topic_signal_device_pub; /*!< Subscription callback
for D2C signal topic. */
Adafruit_MQTT_Subscribe *_topic_signal_brkr_sub; /*!< Subscription callback
for C2D signal topic. */
Adafruit_MQTT_Subscribe
*_topic_signal_i2c_sub; /*!< Subscription callback for I2C topic. */
Adafruit_MQTT_Subscribe
*_topic_signal_servo_sub; /*!< Subscription callback for servo topic. */
Adafruit_MQTT_Subscribe
*_topic_signal_pwm_sub; /*!< Subscription callback for pwm topic. */
Adafruit_MQTT_Subscribe
*_topic_signal_ds18_sub; /*!< Subscribes to signal's ds18x20 topic. */
Adafruit_MQTT_Subscribe
*_topic_signal_pixels_sub; /*!< Subscribes to pixel device topic. */
Adafruit_MQTT_Subscribe
*_topic_signal_uart_sub; /*!< Subscribes to signal's UART topic. */
Adafruit_MQTT_Subscribe
*_err_sub; /*!< Subscription to Adafruit IO Error topic. */
Adafruit_MQTT_Subscribe
*_throttle_sub; /*!< Subscription to Adafruit IO Throttle topic. */
wippersnapper_signal_v1_CreateSignalRequest
_outgoingSignalMsg; /*!< Outgoing signal message from device */
};
extern Wippersnapper WS; ///< Global member variable for callbacks
#endif // ADAFRUIT_WIPPERSNAPPER_H
/*!
* @file Wippersnapper.h
*
* This is the documentation for Adafruit's Wippersnapper firmware for the
* Arduino platform. It is designed specifically to work with
* Adafruit IO Wippersnapper IoT platform.
*
* Adafruit invests time and resources providing this open source code,
* please support Adafruit and open-source hardware by purchasing
* products from Adafruit!
*
* Copyright (c) Brent Rubell 2020-2024 for Adafruit Industries.
*
* BSD license, all text here must be included in any redistribution.
*
*/
#ifndef WIPPERSNAPPER_H
#define WIPPERSNAPPER_H
// Cpp STD
#include <vector>
// Nanopb dependencies
#include <nanopb/pb_common.h>
#include <nanopb/pb_decode.h>
#include <nanopb/pb_encode.h>
#include <pb.h>
#include <wippersnapper/description/v1/description.pb.h> // description.proto
#include <wippersnapper/signal/v1/signal.pb.h> // signal.proto
// External libraries
#include "Adafruit_MQTT.h" // MQTT Client
#include "Adafruit_SleepyDog.h" // Watchdog
#include "Arduino.h" // Wiring
#include <SPI.h> // SPI
// Wippersnapper API Helpers
#include "Wippersnapper_Boards.h"
#include "components/statusLED/Wippersnapper_StatusLED.h"
#include "provisioning/ConfigJson.h"
#define WS_DEBUG ///< Define to enable debugging to serial terminal
#define WS_PRINTER Serial ///< Where debug messages will be printed
// Define actual debug output functions when necessary.
#ifdef WS_DEBUG
#define WS_DEBUG_PRINT(...) \
{ WS_PRINTER.print(__VA_ARGS__); } ///< Prints debug output.
#define WS_DEBUG_PRINTLN(...) \
{ WS_PRINTER.println(__VA_ARGS__); } ///< Prints line from debug output.
#define WS_DEBUG_PRINTHEX(...) \
{ WS_PRINTER.print(__VA_ARGS__, HEX); } ///< Prints debug output.
#else
#define WS_DEBUG_PRINT(...) \
{} ///< Prints debug output
#define WS_DEBUG_PRINTLN(...) \
{} ///< Prints line from debug output.
#endif
#define WS_DELAY_WITH_WDT(timeout) \
{ \
unsigned long start = millis(); \
while (millis() - start < timeout) { \
delay(10); \
yield(); \
feedWDT(); \
if (millis() < start) { \
start = millis(); /* if rollover */ \
} \
} \
} ///< Delay function
/**************************************************************************/
/*!
@brief Retry a function until a condition is met or a timeout is reached.
@param func
The function to retry.
@param result_type
The type of the result of the function.
@param result_var
The variable to store the last result of the function.
@param condition
The condition to check the result against.
@param timeout
The maximum time to retry the function.
@param interval
The time to wait between retries.
@param ...
The arguments to pass to the function.
*/
/**************************************************************************/
#define RETRY_FUNCTION_UNTIL_TIMEOUT(func, result_type, result_var, condition, \
timeout, interval, ...) \
{ \
unsigned long startTime = millis(); \
while (millis() - startTime < timeout) { \
result_type result_var = func(__VA_ARGS__); \
if (condition(result_var)) { \
break; \
} \
if (startTime < millis()) { \
startTime = millis(); /* if rollover */ \
} \
WS_DELAY_WITH_WDT(interval); \
} \
} ///< Retry a function until a condition is met or a timeout is reached.
// Wippersnapper pb helpers
#include <nanopb/ws_pb_helpers.h>
// Wippersnapper components
#include "components/analogIO/Wippersnapper_AnalogIO.h"
#include "components/digitalIO/Wippersnapper_DigitalGPIO.h"
#include "components/i2c/WipperSnapper_I2C.h"
// LEDC-Manager, ESP32-only
#ifdef ARDUINO_ARCH_ESP32
#include "components/ledc/ws_ledc.h"
#endif
// Display
#ifdef USE_DISPLAY
#include "display/ws_display_driver.h"
#include "display/ws_display_ui_helper.h"
#endif
#include "components/ds18x20/ws_ds18x20.h"
#include "components/pixels/ws_pixels.h"
#include "components/pwm/ws_pwm.h"
#include "components/servo/ws_servo.h"
#include "components/uart/ws_uart.h"
#if defined(USE_TINYUSB)
#include "provisioning/tinyusb/Wippersnapper_FS.h"
#endif
#if defined(USE_LITTLEFS)
#include "provisioning/littlefs/WipperSnapper_LittleFS.h"
#endif
#define WS_VERSION \
"1.0.0-beta.85" ///< WipperSnapper app. version (semver-formatted)
// Reserved Adafruit IO MQTT topics
#define TOPIC_IO_THROTTLE "/throttle" ///< Adafruit IO Throttle MQTT Topic
#define TOPIC_IO_ERRORS "/errors" ///< Adafruit IO Error MQTT Topic
// Reserved Wippersnapper topics
#define TOPIC_WS "/wprsnpr/" ///< WipperSnapper topic
#define TOPIC_INFO "/info/" ///< Registration sub-topic
#define TOPIC_SIGNALS "/signals/" ///< Signals sub-topic
#define TOPIC_I2C "/i2c" ///< I2C sub-topic
#define MQTT_TOPIC_PIXELS_DEVICE \
"/signals/device/pixel" ///< Pixels device->broker topic
#define MQTT_TOPIC_PIXELS_BROKER \
"/signals/broker/pixel" ///< Pixels broker->device topic
/** Defines the Adafruit IO connection status */
typedef enum {
WS_IDLE = 0, // Waiting for connection establishement
WS_NET_DISCONNECTED = 1, // Network disconnected
WS_DISCONNECTED = 2, // Disconnected from Adafruit IO
WS_FINGERPRINT_UNKOWN = 3, // Unknown WS_SSL_FINGERPRINT
WS_NET_CONNECT_FAILED = 10, // Failed to connect to network
WS_CONNECT_FAILED = 11, // Failed to connect to Adafruit IO
WS_FINGERPRINT_INVALID = 12, // Unknown WS_SSL_FINGERPRINT
WS_AUTH_FAILED = 13, // Invalid Adafruit IO login credentials provided.
WS_SSID_INVALID =
14, // SSID is "" or otherwise invalid, connection not attempted
WS_NET_CONNECTED = 20, // Connected to Adafruit IO
WS_CONNECTED = 21, // Connected to network
WS_CONNECTED_INSECURE = 22, // Insecurely (non-SSL) connected to network
WS_FINGERPRINT_UNSUPPORTED = 23, // Unsupported WS_SSL_FINGERPRINT
WS_FINGERPRINT_VALID = 24, // Valid WS_SSL_FINGERPRINT
WS_BOARD_DESC_INVALID = 25, // Unable to send board description
WS_BOARD_RESYNC_FAILED = 26 // Board sync failure
} ws_status_t;
/** Defines the Adafruit IO MQTT broker's connection return codes */
typedef enum {
WS_MQTT_CONNECTED = 0, // Connected
WS_MQTT_INVALID_PROTOCOL = 1, // Invalid mqtt protocol
WS_MQTT_INVALID_CID = 2, // Client id rejected
WS_MQTT_SERVICE_UNAVALIABLE = 3, // Malformed user/pass
WS_MQTT_INVALID_USER_PASS = 4, // Unauthorized access to resource
WS_MQTT_UNAUTHORIZED = 5, // MQTT service unavailable
WS_MQTT_THROTTLED = 6, // Account throttled
WS_MQTT_BANNED = 7 // Account banned
} ws_mqtt_status_t;
/** Defines the Wippersnapper client's hardware registration status */
typedef enum {
WS_BOARD_DEF_IDLE,
WS_BOARD_DEF_SEND_FAILED,
WS_BOARD_DEF_SENT,
WS_BOARD_DEF_OK,
WS_BOARD_DEF_INVALID,
WS_BOARD_DEF_UNSPECIFIED
} ws_board_status_t;
/** Defines the Wippersnapper client's network status */
typedef enum {
FSM_NET_IDLE,
FSM_NET_CONNECTED,
FSM_MQTT_CONNECTED,
FSM_NET_CHECK_MQTT,
FSM_NET_CHECK_NETWORK,
FSM_NET_ESTABLISH_NETWORK,
FSM_NET_ESTABLISH_MQTT,
} fsm_net_t;
#define WS_WDT_TIMEOUT 60000 ///< WDT timeout
/* MQTT Configuration */
#define WS_KEEPALIVE_INTERVAL_MS \
5000 ///< Session keepalive interval time, in milliseconds
#define WS_MQTT_MAX_PAYLOAD_SIZE \
512 ///< MAXIMUM expected payload size, in bytes
class Wippersnapper_DigitalGPIO;
class Wippersnapper_AnalogIO;
class Wippersnapper_FS;
class WipperSnapper_LittleFS;
#ifdef USE_DISPLAY
class ws_display_driver;
class ws_display_ui_helper;
#endif
#ifdef ARDUINO_ARCH_ESP32
class ws_ledc;
#endif
class WipperSnapper_Component_I2C;
class ws_servo;
class ws_pwm;
class ws_ds18x20;
class ws_pixels;
class ws_uart;
/**************************************************************************/
/*!
@brief Class that provides storage and functions for the Adafruit IO
Wippersnapper interface.
*/
/**************************************************************************/
class Wippersnapper {
public:
Wippersnapper();
virtual ~Wippersnapper();
void provision();
bool lockStatusNeoPixel; ///< True if status LED is using the status neopixel
bool lockStatusDotStar; ///< True if status LED is using the status dotstar
bool lockStatusLED; ///< True if status LED is using the built-in LED
float status_pixel_brightness =
STATUS_PIXEL_BRIGHTNESS_DEFAULT; ///< Global status pixel's brightness
///< (from 0.0 to 1.0)
virtual void set_user_key();
virtual void set_ssid_pass(const char *ssid, const char *ssidPassword);
virtual void set_ssid_pass();
virtual bool check_valid_ssid();
virtual void _connect();
virtual void _disconnect();
void connect();
void disconnect();
virtual void getMacAddr();
virtual int32_t getRSSI();
virtual void setupMQTTClient(const char *clientID);
virtual ws_status_t networkStatus();
ws_board_status_t getBoardStatus();
bool generateDeviceUID();
bool generateWSTopics();
bool generateWSErrorTopics();
// Registration API
bool registerBoard();
bool encodePubRegistrationReq();
void decodeRegistrationResp(char *data, uint16_t len);
void pollRegistrationResp();
// Configuration API
void publishPinConfigComplete();
// run() loop
ws_status_t run();
void processPackets();
void publish(const char *topic, uint8_t *payload, uint16_t bLen,
uint8_t qos = 0);
// Networking helpers
void pingBroker();
void runNetFSM();
// WDT helpers
void enableWDT(int timeoutMS = 0);
void feedWDT();
// Error handling helpers
void haltError(String error,
ws_led_status_t ledStatusColor = WS_LED_STATUS_ERROR_RUNTIME);
void errorWriteHang(String error);
// MQTT topic callbacks //
// Decodes a signal message
bool decodeSignalMsg(
wippersnapper_signal_v1_CreateSignalRequest *encodedSignalMsg);
// Encodes a pin event message
bool
encodePinEvent(wippersnapper_signal_v1_CreateSignalRequest *outgoingSignalMsg,
uint8_t pinName, int pinVal);
// Pin configure message
bool configureDigitalPinReq(wippersnapper_pin_v1_ConfigurePinRequest *pinMsg);
bool configAnalogInPinReq(wippersnapper_pin_v1_ConfigurePinRequest *pinMsg);
// I2C
std::vector<WipperSnapper_Component_I2C *>
i2cComponents; ///< Vector containing all I2C components
WipperSnapper_Component_I2C *_i2cPort0 =
NULL; ///< WipperSnapper I2C Component for I2C port #0
WipperSnapper_Component_I2C *_i2cPort1 =
NULL; ///< WipperSnapper I2C Component for I2C port #1
bool _isI2CPort0Init =
false; ///< True if I2C port 0 has been initialized, False otherwise.
bool _isI2CPort1Init =
false; ///< True if I2C port 1 has been initialized, False otherwise.
uint8_t _buffer[WS_MQTT_MAX_PAYLOAD_SIZE]; /*!< Shared buffer to save callback
payload */
uint8_t
_buffer_outgoing[WS_MQTT_MAX_PAYLOAD_SIZE]; /*!< buffer which contains
outgoing payload data */
uint16_t bufSize; /*!< Length of data inside buffer */
ws_board_status_t _boardStatus =
WS_BOARD_DEF_IDLE; ///< Hardware's registration status
// TODO: We really should look at making these static definitions, not dynamic
// to free up space on the heap
Wippersnapper_DigitalGPIO *_digitalGPIO; ///< Instance of digital gpio class
Wippersnapper_AnalogIO *_analogIO; ///< Instance of analog io class
Wippersnapper_FS *_fileSystem; ///< Instance of Filesystem (native USB)
WipperSnapper_LittleFS
*_littleFS; ///< Instance of LittleFS Filesystem (non-native USB)
#ifdef USE_DISPLAY
ws_display_driver *_display = nullptr; ///< Instance of display driver class
ws_display_ui_helper *_ui_helper =
nullptr; ///< Instance of display UI helper class
#endif
ws_pixels *_ws_pixelsComponent; ///< ptr to instance of ws_pixels class
ws_pwm *_pwmComponent; ///< Instance of pwm class
ws_servo *_servoComponent; ///< Instance of servo class
ws_ds18x20 *_ds18x20Component; ///< Instance of DS18x20 class
ws_uart *_uartComponent; ///< Instance of UART class
// TODO: does this really need to be global?
uint8_t _macAddr[6]; /*!< Unique network iface identifier */
char sUID[13]; /*!< Unique network iface identifier */
const char *_boardId; /*!< Adafruit IO+ board string */
Adafruit_MQTT *_mqtt; /*!< Reference to Adafruit_MQTT, _mqtt. */
secretsConfig _config; /*!< Wippersnapper secrets.json as a struct. */
// TODO: Does this need to be within this class?
int32_t totalDigitalPins; /*!< Total number of digital-input capable pins */
char *_topic_description = NULL; /*!< MQTT topic for the device description */
char *_topic_signal_device = NULL; /*!< Device->Wprsnpr messages */
char *_topic_signal_i2c_brkr = NULL; /*!< Topic carries messages from a device
to a broker. */
char *_topic_signal_i2c_device = NULL; /*!< Topic carries messages from a
broker to a device. */
char *_topic_signal_servo_brkr = NULL; /*!< Topic carries messages from a
device to a broker. */
char *_topic_signal_servo_device = NULL; /*!< Topic carries messages from a
broker to a device. */
char *_topic_signal_pwm_brkr =
NULL; /*!< Topic carries PWM messages from a device to a broker. */
char *_topic_signal_pwm_device =
NULL; /*!< Topic carries PWM messages from a broker to a device. */
char *_topic_signal_ds18_brkr = NULL; /*!< Topic carries ds18x20 messages from
a device to a broker. */
char *_topic_signal_ds18_device = NULL; /*!< Topic carries ds18x20 messages
from a broker to a device. */
char *_topic_signal_pixels_brkr = NULL; /*!< Topic carries pixel messages */
char *_topic_signal_pixels_device = NULL; /*!< Topic carries pixel messages */
char *_topic_signal_uart_brkr = NULL; /*!< Topic carries UART messages */
char *_topic_signal_uart_device = NULL; /*!< Topic carries UART messages */
wippersnapper_signal_v1_CreateSignalRequest
_incomingSignalMsg; /*!< Incoming signal message from broker */
wippersnapper_signal_v1_I2CRequest msgSignalI2C =
wippersnapper_signal_v1_I2CRequest_init_zero; ///< I2C request wrapper
///< message
// ds signal msg
wippersnapper_signal_v1_Ds18x20Request msgSignalDS =
wippersnapper_signal_v1_Ds18x20Request_init_zero; ///< DS request message
///< wrapper
// servo message
wippersnapper_signal_v1_ServoRequest
msgServo; ///< ServoRequest wrapper message
wippersnapper_signal_v1_PWMRequest msgPWM =
wippersnapper_signal_v1_PWMRequest_init_zero; ///< PWM request wrapper
///< message.
// pixels signal message
wippersnapper_signal_v1_PixelsRequest
msgPixels; ///< PixelsRequest wrapper message
wippersnapper_signal_v1_UARTRequest
msgSignalUART; ///< UARTReq wrapper message
char *throttleMessage; /*!< Pointer to throttle message data. */
int throttleTime; /*!< Total amount of time to throttle the device, in
milliseconds. */
bool pinCfgCompleted = false; /*!< Did initial pin sync complete? */
// enable LEDC if esp32
#ifdef ARDUINO_ARCH_ESP32
ws_ledc *_ledc = nullptr; ///< Pointer to LEDC object
#endif
private:
void _init();
protected:
ws_status_t _status = WS_IDLE; /*!< Adafruit IO connection status */
uint32_t _last_mqtt_connect = 0; /*!< Previous time when client connected to
Adafruit IO, in milliseconds. */
uint32_t _prv_ping = 0; /*!< Previous time when client pinged Adafruit IO's
MQTT broker, in milliseconds. */
uint32_t _prvKATBlink = 0; /*!< Previous time when client pinged Adafruit IO's
MQTT broker, in milliseconds. */
// Device information
const char *_deviceId; /*!< Adafruit IO+ device identifier string */
char *_device_uid; /*!< Unique device identifier */
// MQTT topics
char *_topic_description_status =
NULL; /*!< MQTT subtopic carrying the description
status resp. from the broker */
char *_topic_description_status_complete = NULL; /*!< MQTT topic carrying the
ACK signal from the device to the
broker after registration */
char *_topic_device_pin_config_complete =
NULL; /*!< MQTT topic carrying the ACK signal
from the device to the broker after
hardware configuration */
char *_topic_signal_brkr = NULL; /*!< Wprsnpr->Device messages */
char *_err_topic = NULL; /*!< Adafruit IO MQTT error message topic. */
char *_throttle_topic = NULL; /*!< Adafruit IO MQTT throttle message topic. */
Adafruit_MQTT_Subscribe *_topic_description_sub; /*!< Subscription callback
for registration topic. */
Adafruit_MQTT_Publish *_topic_signal_device_pub; /*!< Subscription callback
for D2C signal topic. */
Adafruit_MQTT_Subscribe *_topic_signal_brkr_sub; /*!< Subscription callback
for C2D signal topic. */
Adafruit_MQTT_Subscribe
*_topic_signal_i2c_sub; /*!< Subscription callback for I2C topic. */
Adafruit_MQTT_Subscribe
*_topic_signal_servo_sub; /*!< Subscription callback for servo topic. */
Adafruit_MQTT_Subscribe
*_topic_signal_pwm_sub; /*!< Subscription callback for pwm topic. */
Adafruit_MQTT_Subscribe
*_topic_signal_ds18_sub; /*!< Subscribes to signal's ds18x20 topic. */
Adafruit_MQTT_Subscribe
*_topic_signal_pixels_sub; /*!< Subscribes to pixel device topic. */
Adafruit_MQTT_Subscribe
*_topic_signal_uart_sub; /*!< Subscribes to signal's UART topic. */
Adafruit_MQTT_Subscribe
*_err_sub; /*!< Subscription to Adafruit IO Error topic. */
Adafruit_MQTT_Subscribe
*_throttle_sub; /*!< Subscription to Adafruit IO Throttle topic. */
wippersnapper_signal_v1_CreateSignalRequest
_outgoingSignalMsg; /*!< Outgoing signal message from device */
};
extern Wippersnapper WS; ///< Global member variable for callbacks
#endif // ADAFRUIT_WIPPERSNAPPER_H

View file

@ -1,396 +1,396 @@
/*!
* @file Wippersnapper_AnalogIO.cpp
*
* This file provides an API for interacting with
* a board's analog IO pins.
*
* Adafruit invests time and resources providing this open source code,
* please support Adafruit and open-source hardware by purchasing
* products from Adafruit!
*
* Copyright (c) Brent Rubell 2020-2023 for Adafruit Industries.
*
* BSD license, all text here must be included in any redistribution.
*
*/
#include "Wippersnapper_AnalogIO.h"
/***********************************************************************************/
/*!
@brief Initializes Analog IO class.
@param totalAnalogInputPins
Total number of analog input pins to allocate.
@param aRef
ADC's voltage reference value, in volts.
*/
/***********************************************************************************/
Wippersnapper_AnalogIO::Wippersnapper_AnalogIO(int32_t totalAnalogInputPins,
float aRef) {
_totalAnalogInputPins = totalAnalogInputPins;
// Set aref
setAref(aRef);
// Set ADC resolution, default to 16-bit
setADCResolution(16);
// allocate analog input pins
_analog_input_pins = new analogInputPin[_totalAnalogInputPins];
// TODO: Refactor this to use list-based initialization
for (int pin = 0; pin < _totalAnalogInputPins; pin++) {
// turn sampling off
_analog_input_pins[pin].enabled = false;
}
}
/***********************************************************************************/
/*!
@brief Destructor for Analog IO class.
*/
/***********************************************************************************/
Wippersnapper_AnalogIO::~Wippersnapper_AnalogIO() {
_aRef = 0.0;
_totalAnalogInputPins = 0;
delete _analog_input_pins;
}
/***********************************************************************************/
/*!
@brief Sets the device's reference voltage.
@param refVoltage
The voltage reference to use during conversions.
*/
/***********************************************************************************/
void Wippersnapper_AnalogIO::setAref(float refVoltage) { _aRef = refVoltage; }
/***********************************************************************************/
/*!
@brief Returns the device's reference voltage.
@returns Analog reference voltage, in volts.
*/
/***********************************************************************************/
float Wippersnapper_AnalogIO::getAref() { return _aRef; }
/***********************************************************************************/
/*!
@brief Sets the device's ADC resolution, either natively via calling
Arduino API's analogReadResolution() or via scaling.
@param resolution
The desired analog resolution, in bits.
*/
/***********************************************************************************/
void Wippersnapper_AnalogIO::setADCResolution(int resolution) {
// set the resolution natively in the BSP
#if defined(ARDUINO_ARCH_SAMD)
analogReadResolution(16);
_nativeResolution = 12;
#elif defined(ARDUINO_ARCH_ESP32)
scaleAnalogRead = true;
_nativeResolution = 13;
#endif
_adcResolution = resolution;
}
/***********************************************************************************/
/*!
@brief Gets the scaled ADC resolution.
@returns resolution
The scaled analog resolution, in bits.
*/
/***********************************************************************************/
int Wippersnapper_AnalogIO::getADCresolution() { return _adcResolution; }
/***********************************************************************************/
/*!
@brief Gets the device's native ADC resolution.
@returns resolution
The native analog resolution, in bits.
*/
/***********************************************************************************/
int Wippersnapper_AnalogIO::getNativeResolution() { return _nativeResolution; }
/***********************************************************************************/
/*!
@brief Initializes an analog input pin
@param pin
The analog pin to read from.
@param period
Time between measurements, in seconds.
@param pullMode
The pin's pull value.
@param analogReadMode
Defines if pin will read and return an ADC value or a voltage value.
*/
/***********************************************************************************/
void Wippersnapper_AnalogIO::initAnalogInputPin(
int pin, float period,
wippersnapper_pin_v1_ConfigurePinRequest_Pull pullMode,
wippersnapper_pin_v1_ConfigurePinRequest_AnalogReadMode analogReadMode) {
// Set analog read pull mode
if (pullMode == wippersnapper_pin_v1_ConfigurePinRequest_Pull_PULL_UP)
pinMode(pin, INPUT_PULLUP);
else
pinMode(pin, INPUT);
// Period is in seconds, cast it to long and convert it to milliseconds
long periodMs = (long)period * 1000;
// TODO: Maybe pull this out into a func. or use map() lookup instead
// attempt to allocate pin within _analog_input_pins[]
for (int i = 0; i < _totalAnalogInputPins; i++) {
if (_analog_input_pins[i].enabled == false) {
_analog_input_pins[i].pinName = pin;
_analog_input_pins[i].period = periodMs;
_analog_input_pins[i].prvPeriod = 0L;
_analog_input_pins[i].readMode = analogReadMode;
_analog_input_pins[i].enabled = true;
break;
}
}
WS_DEBUG_PRINT("Configured Analog Input pin with polling time (ms):");
WS_DEBUG_PRINTLN(periodMs);
}
/***********************************************************************************/
/*!
@brief Disables an analog input pin from sampling
@param pin
The analog input pin to disable.
*/
/***********************************************************************************/
void Wippersnapper_AnalogIO::disableAnalogInPin(int pin) {
for (int i = 0; i < _totalAnalogInputPins; i++) {
if (_analog_input_pins[i].pinName == pin) {
_analog_input_pins[i].enabled = false;
break;
}
}
}
/***********************************************************************************/
/*!
@brief Deinitializes an analog pin.
@param direction
The analog pin's direction.
@param pin
The analog pin to deinitialize.
*/
/***********************************************************************************/
void Wippersnapper_AnalogIO::deinitAnalogPin(
wippersnapper_pin_v1_ConfigurePinRequest_Direction direction, int pin) {
WS_DEBUG_PRINT("Deinitializing analog pin A");
WS_DEBUG_PRINTLN(pin);
if (direction ==
wippersnapper_pin_v1_ConfigurePinRequest_Direction_DIRECTION_INPUT) {
WS_DEBUG_PRINTLN("Deinitialized analog input pin obj.");
disableAnalogInPin(pin);
}
pinMode(pin, INPUT); // hi-z
}
/**********************************************************/
/*!
@brief Reads the raw ADC value of an analog pin.
Value is always scaled to 16-bit.
@param pin
The pin to be read.
@returns The pin's ADC value.
*/
/**********************************************************/
uint16_t Wippersnapper_AnalogIO::getPinValue(int pin) {
// get pin value
uint16_t value = analogRead(pin);
// scale by the ADC resolution manually if not implemented by BSP
if (scaleAnalogRead) {
if (getADCresolution() > getNativeResolution()) {
value = value << (getADCresolution() - getNativeResolution());
} else {
value = value >> (getNativeResolution() - getADCresolution());
}
}
return value;
}
/**********************************************************/
/*!
@brief Calculates analog pin's voltage provided
a 16-bit ADC value.
@param pin
The value from a previous ADC reading.
@returns The pin's voltage.
*/
/**********************************************************/
float Wippersnapper_AnalogIO::getPinValueVolts(int pin) {
uint16_t rawValue = getPinValue(pin);
return rawValue * getAref() / 65536;
}
/******************************************************************/
/*!
@brief Encodes an analog input pin event into a
signal message and publish it to IO.
@param pinName
Specifies the pin's name.
@param readMode
Read mode - raw ADC or voltage.
@param pinValRaw
Raw pin value, used if readmode is raw.
@param pinValVolts
Raw pin value expressed in Volts, used if readmode is
volts.
@returns True if successfully encoded a PinEvent signal
message, False otherwise.
*/
/******************************************************************/
bool Wippersnapper_AnalogIO::encodePinEvent(
uint8_t pinName,
wippersnapper_pin_v1_ConfigurePinRequest_AnalogReadMode readMode,
uint16_t pinValRaw, float pinValVolts) {
// Create new signal message
wippersnapper_signal_v1_CreateSignalRequest outgoingSignalMsg =
wippersnapper_signal_v1_CreateSignalRequest_init_zero;
// Fill payload
outgoingSignalMsg.which_payload =
wippersnapper_signal_v1_CreateSignalRequest_pin_event_tag;
sprintf(outgoingSignalMsg.payload.pin_event.pin_name, "A%d", pinName);
// Fill pinValue based on the analog read mode
char buffer[100];
if (readMode ==
wippersnapper_pin_v1_ConfigurePinRequest_AnalogReadMode_ANALOG_READ_MODE_PIN_VALUE) {
sprintf(outgoingSignalMsg.payload.pin_event.pin_value, "%u", pinValRaw);
snprintf(buffer, 100, "[Pin] A%d read: %u\n", pinName, pinValRaw);
} else {
sprintf(outgoingSignalMsg.payload.pin_event.pin_value, "%0.3f",
pinValVolts);
snprintf(buffer, 100, "[Pin] A%d read: %0.2f\n", pinName, pinValVolts);
}
// display analog pin read on terminal
#ifdef USE_DISPLAY
WS._ui_helper->add_text_to_terminal(buffer);
#endif
// Encode signal message
pb_ostream_t stream =
pb_ostream_from_buffer(WS._buffer_outgoing, sizeof(WS._buffer_outgoing));
if (!ws_pb_encode(&stream, wippersnapper_signal_v1_CreateSignalRequest_fields,
&outgoingSignalMsg)) {
WS_DEBUG_PRINTLN("ERROR: Unable to encode signal message");
return false;
}
// Publish out to IO
size_t msgSz;
pb_get_encoded_size(&msgSz,
wippersnapper_signal_v1_CreateSignalRequest_fields,
&outgoingSignalMsg);
WS_DEBUG_PRINT("Publishing pinEvent...");
WS.publish(WS._topic_signal_device, WS._buffer_outgoing, msgSz, 1);
WS_DEBUG_PRINTLN("Published!");
return true;
}
/**********************************************************/
/*!
@brief Checks if pin's period is expired.
@param currentTime
The current software timer value.
@param pin
The desired analog pin to check
@returns True if pin's period expired, False otherwise.
*/
/**********************************************************/
bool Wippersnapper_AnalogIO::timerExpired(long currentTime,
analogInputPin pin) {
if (currentTime - pin.prvPeriod > pin.period && pin.period != 0L)
return true;
return false;
}
/**********************************************************/
/*!
@brief Iterates thru analog inputs
*/
/**********************************************************/
void Wippersnapper_AnalogIO::update() {
// TODO: Globally scope these, dont have them here every time
float pinValVolts = 0.0;
uint16_t pinValRaw = 0;
// Process analog input pins
for (int i = 0; i < _totalAnalogInputPins; i++) {
// TODO: Can we collapse the conditionals below?
if (_analog_input_pins[i].enabled == true) {
// Does the pin execute on-period?
if ((long)millis() - _analog_input_pins[i].prvPeriod >
_analog_input_pins[i].period &&
_analog_input_pins[i].period != 0L) {
WS_DEBUG_PRINT("Executing periodic event on A");
WS_DEBUG_PRINTLN(_analog_input_pins[i].pinName);
// Read from analog pin
if (_analog_input_pins[i].readMode ==
wippersnapper_pin_v1_ConfigurePinRequest_AnalogReadMode_ANALOG_READ_MODE_PIN_VOLTAGE) {
pinValVolts = getPinValueVolts(_analog_input_pins[i].pinName);
} else if (
_analog_input_pins[i].readMode ==
wippersnapper_pin_v1_ConfigurePinRequest_AnalogReadMode_ANALOG_READ_MODE_PIN_VALUE) {
pinValRaw = getPinValue(_analog_input_pins[i].pinName);
} else {
WS_DEBUG_PRINTLN("ERROR: Unable to read pin value, cannot determine "
"analog read mode!");
pinValRaw = 0.0;
}
// Publish a new pin event
encodePinEvent(_analog_input_pins[i].pinName,
_analog_input_pins[i].readMode, pinValRaw, pinValVolts);
// IMPT - reset the digital pin
_analog_input_pins[i].prvPeriod = millis();
}
// Does the pin execute on_change?
else if (_analog_input_pins[i].period == 0L) {
// note: on-change requires ADC DEFAULT_HYSTERISIS to check against prv
// pin value
uint16_t pinValRaw = getPinValue(_analog_input_pins[i].pinName);
uint16_t _pinValThreshHi =
_analog_input_pins[i].prvPinVal +
(_analog_input_pins[i].prvPinVal * DEFAULT_HYSTERISIS);
uint16_t _pinValThreshLow =
_analog_input_pins[i].prvPinVal -
(_analog_input_pins[i].prvPinVal * DEFAULT_HYSTERISIS);
if (pinValRaw > _pinValThreshHi || pinValRaw < _pinValThreshLow) {
// Perform voltage conversion if we need to
if (_analog_input_pins[i].readMode ==
wippersnapper_pin_v1_ConfigurePinRequest_AnalogReadMode_ANALOG_READ_MODE_PIN_VOLTAGE) {
pinValVolts = pinValRaw * getAref() / 65536;
}
// Publish pin event to IO
encodePinEvent(_analog_input_pins[i].pinName,
_analog_input_pins[i].readMode, pinValRaw,
pinValVolts);
} else {
// WS_DEBUG_PRINTLN("ADC has not changed enough, continue...");
continue;
}
// set the pin value in the digital pin object for comparison on next
// run
_analog_input_pins[i].prvPinVal = pinValRaw;
}
}
}
/*!
* @file Wippersnapper_AnalogIO.cpp
*
* This file provides an API for interacting with
* a board's analog IO pins.
*
* Adafruit invests time and resources providing this open source code,
* please support Adafruit and open-source hardware by purchasing
* products from Adafruit!
*
* Copyright (c) Brent Rubell 2020-2023 for Adafruit Industries.
*
* BSD license, all text here must be included in any redistribution.
*
*/
#include "Wippersnapper_AnalogIO.h"
/***********************************************************************************/
/*!
@brief Initializes Analog IO class.
@param totalAnalogInputPins
Total number of analog input pins to allocate.
@param aRef
ADC's voltage reference value, in volts.
*/
/***********************************************************************************/
Wippersnapper_AnalogIO::Wippersnapper_AnalogIO(int32_t totalAnalogInputPins,
float aRef) {
_totalAnalogInputPins = totalAnalogInputPins;
// Set aref
setAref(aRef);
// Set ADC resolution, default to 16-bit
setADCResolution(16);
// allocate analog input pins
_analog_input_pins = new analogInputPin[_totalAnalogInputPins];
// TODO: Refactor this to use list-based initialization
for (int pin = 0; pin < _totalAnalogInputPins; pin++) {
// turn sampling off
_analog_input_pins[pin].enabled = false;
}
}
/***********************************************************************************/
/*!
@brief Destructor for Analog IO class.
*/
/***********************************************************************************/
Wippersnapper_AnalogIO::~Wippersnapper_AnalogIO() {
_aRef = 0.0;
_totalAnalogInputPins = 0;
delete _analog_input_pins;
}
/***********************************************************************************/
/*!
@brief Sets the device's reference voltage.
@param refVoltage
The voltage reference to use during conversions.
*/
/***********************************************************************************/
void Wippersnapper_AnalogIO::setAref(float refVoltage) { _aRef = refVoltage; }
/***********************************************************************************/
/*!
@brief Returns the device's reference voltage.
@returns Analog reference voltage, in volts.
*/
/***********************************************************************************/
float Wippersnapper_AnalogIO::getAref() { return _aRef; }
/***********************************************************************************/
/*!
@brief Sets the device's ADC resolution, either natively via calling
Arduino API's analogReadResolution() or via scaling.
@param resolution
The desired analog resolution, in bits.
*/
/***********************************************************************************/
void Wippersnapper_AnalogIO::setADCResolution(int resolution) {
// set the resolution natively in the BSP
#if defined(ARDUINO_ARCH_SAMD)
analogReadResolution(16);
_nativeResolution = 12;
#elif defined(ARDUINO_ARCH_ESP32)
scaleAnalogRead = true;
_nativeResolution = 13;
#endif
_adcResolution = resolution;
}
/***********************************************************************************/
/*!
@brief Gets the scaled ADC resolution.
@returns resolution
The scaled analog resolution, in bits.
*/
/***********************************************************************************/
int Wippersnapper_AnalogIO::getADCresolution() { return _adcResolution; }
/***********************************************************************************/
/*!
@brief Gets the device's native ADC resolution.
@returns resolution
The native analog resolution, in bits.
*/
/***********************************************************************************/
int Wippersnapper_AnalogIO::getNativeResolution() { return _nativeResolution; }
/***********************************************************************************/
/*!
@brief Initializes an analog input pin
@param pin
The analog pin to read from.
@param period
Time between measurements, in seconds.
@param pullMode
The pin's pull value.
@param analogReadMode
Defines if pin will read and return an ADC value or a voltage value.
*/
/***********************************************************************************/
void Wippersnapper_AnalogIO::initAnalogInputPin(
int pin, float period,
wippersnapper_pin_v1_ConfigurePinRequest_Pull pullMode,
wippersnapper_pin_v1_ConfigurePinRequest_AnalogReadMode analogReadMode) {
// Set analog read pull mode
if (pullMode == wippersnapper_pin_v1_ConfigurePinRequest_Pull_PULL_UP)
pinMode(pin, INPUT_PULLUP);
else
pinMode(pin, INPUT);
// Period is in seconds, cast it to long and convert it to milliseconds
long periodMs = (long)period * 1000;
// TODO: Maybe pull this out into a func. or use map() lookup instead
// attempt to allocate pin within _analog_input_pins[]
for (int i = 0; i < _totalAnalogInputPins; i++) {
if (_analog_input_pins[i].enabled == false) {
_analog_input_pins[i].pinName = pin;
_analog_input_pins[i].period = periodMs;
_analog_input_pins[i].prvPeriod = 0L;
_analog_input_pins[i].readMode = analogReadMode;
_analog_input_pins[i].enabled = true;
break;
}
}
WS_DEBUG_PRINT("Configured Analog Input pin with polling time (ms):");
WS_DEBUG_PRINTLN(periodMs);
}
/***********************************************************************************/
/*!
@brief Disables an analog input pin from sampling
@param pin
The analog input pin to disable.
*/
/***********************************************************************************/
void Wippersnapper_AnalogIO::disableAnalogInPin(int pin) {
for (int i = 0; i < _totalAnalogInputPins; i++) {
if (_analog_input_pins[i].pinName == pin) {
_analog_input_pins[i].enabled = false;
break;
}
}
}
/***********************************************************************************/
/*!
@brief Deinitializes an analog pin.
@param direction
The analog pin's direction.
@param pin
The analog pin to deinitialize.
*/
/***********************************************************************************/
void Wippersnapper_AnalogIO::deinitAnalogPin(
wippersnapper_pin_v1_ConfigurePinRequest_Direction direction, int pin) {
WS_DEBUG_PRINT("Deinitializing analog pin A");
WS_DEBUG_PRINTLN(pin);
if (direction ==
wippersnapper_pin_v1_ConfigurePinRequest_Direction_DIRECTION_INPUT) {
WS_DEBUG_PRINTLN("Deinitialized analog input pin obj.");
disableAnalogInPin(pin);
}
pinMode(pin, INPUT); // hi-z
}
/**********************************************************/
/*!
@brief Reads the raw ADC value of an analog pin.
Value is always scaled to 16-bit.
@param pin
The pin to be read.
@returns The pin's ADC value.
*/
/**********************************************************/
uint16_t Wippersnapper_AnalogIO::getPinValue(int pin) {
// get pin value
uint16_t value = analogRead(pin);
// scale by the ADC resolution manually if not implemented by BSP
if (scaleAnalogRead) {
if (getADCresolution() > getNativeResolution()) {
value = value << (getADCresolution() - getNativeResolution());
} else {
value = value >> (getNativeResolution() - getADCresolution());
}
}
return value;
}
/**********************************************************/
/*!
@brief Calculates analog pin's voltage provided
a 16-bit ADC value.
@param pin
The value from a previous ADC reading.
@returns The pin's voltage.
*/
/**********************************************************/
float Wippersnapper_AnalogIO::getPinValueVolts(int pin) {
uint16_t rawValue = getPinValue(pin);
return rawValue * getAref() / 65536;
}
/******************************************************************/
/*!
@brief Encodes an analog input pin event into a
signal message and publish it to IO.
@param pinName
Specifies the pin's name.
@param readMode
Read mode - raw ADC or voltage.
@param pinValRaw
Raw pin value, used if readmode is raw.
@param pinValVolts
Raw pin value expressed in Volts, used if readmode is
volts.
@returns True if successfully encoded a PinEvent signal
message, False otherwise.
*/
/******************************************************************/
bool Wippersnapper_AnalogIO::encodePinEvent(
uint8_t pinName,
wippersnapper_pin_v1_ConfigurePinRequest_AnalogReadMode readMode,
uint16_t pinValRaw, float pinValVolts) {
// Create new signal message
wippersnapper_signal_v1_CreateSignalRequest outgoingSignalMsg =
wippersnapper_signal_v1_CreateSignalRequest_init_zero;
// Fill payload
outgoingSignalMsg.which_payload =
wippersnapper_signal_v1_CreateSignalRequest_pin_event_tag;
sprintf(outgoingSignalMsg.payload.pin_event.pin_name, "A%d", pinName);
// Fill pinValue based on the analog read mode
char buffer[100];
if (readMode ==
wippersnapper_pin_v1_ConfigurePinRequest_AnalogReadMode_ANALOG_READ_MODE_PIN_VALUE) {
sprintf(outgoingSignalMsg.payload.pin_event.pin_value, "%u", pinValRaw);
snprintf(buffer, 100, "[Pin] A%d read: %u\n", pinName, pinValRaw);
} else {
sprintf(outgoingSignalMsg.payload.pin_event.pin_value, "%0.3f",
pinValVolts);
snprintf(buffer, 100, "[Pin] A%d read: %0.2f\n", pinName, pinValVolts);
}
// display analog pin read on terminal
#ifdef USE_DISPLAY
WS._ui_helper->add_text_to_terminal(buffer);
#endif
// Encode signal message
pb_ostream_t stream =
pb_ostream_from_buffer(WS._buffer_outgoing, sizeof(WS._buffer_outgoing));
if (!ws_pb_encode(&stream, wippersnapper_signal_v1_CreateSignalRequest_fields,
&outgoingSignalMsg)) {
WS_DEBUG_PRINTLN("ERROR: Unable to encode signal message");
return false;
}
// Publish out to IO
size_t msgSz;
pb_get_encoded_size(&msgSz,
wippersnapper_signal_v1_CreateSignalRequest_fields,
&outgoingSignalMsg);
WS_DEBUG_PRINT("Publishing pinEvent...");
WS.publish(WS._topic_signal_device, WS._buffer_outgoing, msgSz, 1);
WS_DEBUG_PRINTLN("Published!");
return true;
}
/**********************************************************/
/*!
@brief Checks if pin's period is expired.
@param currentTime
The current software timer value.
@param pin
The desired analog pin to check
@returns True if pin's period expired, False otherwise.
*/
/**********************************************************/
bool Wippersnapper_AnalogIO::timerExpired(long currentTime,
analogInputPin pin) {
if (currentTime - pin.prvPeriod > pin.period && pin.period != 0L)
return true;
return false;
}
/**********************************************************/
/*!
@brief Iterates thru analog inputs
*/
/**********************************************************/
void Wippersnapper_AnalogIO::update() {
// TODO: Globally scope these, dont have them here every time
float pinValVolts = 0.0;
uint16_t pinValRaw = 0;
// Process analog input pins
for (int i = 0; i < _totalAnalogInputPins; i++) {
// TODO: Can we collapse the conditionals below?
if (_analog_input_pins[i].enabled == true) {
// Does the pin execute on-period?
if ((long)millis() - _analog_input_pins[i].prvPeriod >
_analog_input_pins[i].period &&
_analog_input_pins[i].period != 0L) {
WS_DEBUG_PRINT("Executing periodic event on A");
WS_DEBUG_PRINTLN(_analog_input_pins[i].pinName);
// Read from analog pin
if (_analog_input_pins[i].readMode ==
wippersnapper_pin_v1_ConfigurePinRequest_AnalogReadMode_ANALOG_READ_MODE_PIN_VOLTAGE) {
pinValVolts = getPinValueVolts(_analog_input_pins[i].pinName);
} else if (
_analog_input_pins[i].readMode ==
wippersnapper_pin_v1_ConfigurePinRequest_AnalogReadMode_ANALOG_READ_MODE_PIN_VALUE) {
pinValRaw = getPinValue(_analog_input_pins[i].pinName);
} else {
WS_DEBUG_PRINTLN("ERROR: Unable to read pin value, cannot determine "
"analog read mode!");
pinValRaw = 0.0;
}
// Publish a new pin event
encodePinEvent(_analog_input_pins[i].pinName,
_analog_input_pins[i].readMode, pinValRaw, pinValVolts);
// IMPT - reset the digital pin
_analog_input_pins[i].prvPeriod = millis();
}
// Does the pin execute on_change?
else if (_analog_input_pins[i].period == 0L) {
// note: on-change requires ADC DEFAULT_HYSTERISIS to check against prv
// pin value
uint16_t pinValRaw = getPinValue(_analog_input_pins[i].pinName);
uint16_t _pinValThreshHi =
_analog_input_pins[i].prvPinVal +
(_analog_input_pins[i].prvPinVal * DEFAULT_HYSTERISIS);
uint16_t _pinValThreshLow =
_analog_input_pins[i].prvPinVal -
(_analog_input_pins[i].prvPinVal * DEFAULT_HYSTERISIS);
if (pinValRaw > _pinValThreshHi || pinValRaw < _pinValThreshLow) {
// Perform voltage conversion if we need to
if (_analog_input_pins[i].readMode ==
wippersnapper_pin_v1_ConfigurePinRequest_AnalogReadMode_ANALOG_READ_MODE_PIN_VOLTAGE) {
pinValVolts = pinValRaw * getAref() / 65536;
}
// Publish pin event to IO
encodePinEvent(_analog_input_pins[i].pinName,
_analog_input_pins[i].readMode, pinValRaw,
pinValVolts);
} else {
// WS_DEBUG_PRINTLN("ADC has not changed enough, continue...");
continue;
}
// set the pin value in the digital pin object for comparison on next
// run
_analog_input_pins[i].prvPinVal = pinValRaw;
}
}
}
}

View file

@ -1,313 +1,313 @@
/*!
* @file ws_ds18x20.cpp
*
* This component implements 1-wire communication
* for the DS18X20-line of Maxim Temperature ICs.
*
* Adafruit invests time and resources providing this open source code,
* please support Adafruit and open-source hardware by purchasing
* products from Adafruit!
*
* Copyright (c) Brent Rubell 2022-2023 for Adafruit Industries.
*
* BSD license, all text here must be included in any redistribution.
*
*/
#include "ws_ds18x20.h"
/*************************************************************/
/*!
@brief Creates a new WipperSnapper Ds18x20 component.
*/
/*************************************************************/
ws_ds18x20::ws_ds18x20() {}
/*************************************************************/
/*!
@brief Destructor for a WipperSnapper DS18X20 component.
*/
/*************************************************************/
ws_ds18x20::~ws_ds18x20() {
// delete DallasTemp sensors and release onewire buses
for (size_t idx = 0; idx < _ds18xDrivers.size(); idx++) {
delete _ds18xDrivers[idx]->dallasTempObj;
delete _ds18xDrivers[idx]->oneWire;
}
// remove all elements
_ds18xDrivers.clear();
}
/********************************************************************/
/*!
@brief Initializes a DS18x20 sensor using a
configuration sent by the broker and adds it to a
vector of ds18x20 sensor drivers.
@param msgDs18x20InitReq
Message containing configuration data for a
ds18x20 sensor.
@returns True if initialized successfully, False otherwise.
*/
/********************************************************************/
bool ws_ds18x20::addDS18x20(
wippersnapper_ds18x20_v1_Ds18x20InitRequest *msgDs18x20InitReq) {
bool is_success = false;
// init. new ds18x20 object
ds18x20Obj *newObj = new ds18x20Obj();
char *oneWirePin = msgDs18x20InitReq->onewire_pin + 1;
newObj->oneWire = new OneWire(atoi(oneWirePin));
newObj->dallasTempObj = new DallasTemperature(newObj->oneWire);
newObj->dallasTempObj->begin();
// attempt to obtain sensor address
if (newObj->dallasTempObj->getAddress(newObj->dallasTempAddr, 0)) {
// attempt to set sensor resolution
newObj->dallasTempObj->setResolution(msgDs18x20InitReq->sensor_resolution);
// copy the device's sensor properties
newObj->sensorPropertiesCount =
msgDs18x20InitReq->i2c_device_properties_count;
// TODO: Make sure this works, it's a new idea and untested :)
for (int i = 0; i < newObj->sensorPropertiesCount; i++) {
newObj->sensorProperties[i].sensor_type =
msgDs18x20InitReq->i2c_device_properties[i].sensor_type;
newObj->sensorProperties[i].sensor_period =
(long)msgDs18x20InitReq->i2c_device_properties[i].sensor_period *
1000;
}
// set pin
strcpy(newObj->onewire_pin, msgDs18x20InitReq->onewire_pin);
// add the new ds18x20 driver to vec.
_ds18xDrivers.push_back(newObj);
is_success = true;
} else {
WS_DEBUG_PRINTLN("Failed to find DSx sensor on specified pin.");
}
// fill and publish the initialization response back to the broker
size_t msgSz; // message's encoded size
wippersnapper_signal_v1_Ds18x20Response msgInitResp =
wippersnapper_signal_v1_Ds18x20Response_init_zero;
msgInitResp.which_payload =
wippersnapper_signal_v1_Ds18x20Response_resp_ds18x20_init_tag;
msgInitResp.payload.resp_ds18x20_init.is_initialized = is_success;
strcpy(msgInitResp.payload.resp_ds18x20_init.onewire_pin,
msgDs18x20InitReq->onewire_pin);
WS_DEBUG_PRINT("Created OneWireBus on GPIO ");
WS_DEBUG_PRINT(msgDs18x20InitReq->onewire_pin);
WS_DEBUG_PRINTLN(" with DS18x20 attached!");
#ifdef USE_DISPLAY
char buffer[100];
snprintf(buffer, 100, "[DS18x] Attached DS18x20 sensor to pin %s\n",
msgDs18x20InitReq->onewire_pin);
WS._ui_helper->add_text_to_terminal(buffer);
#endif
// Encode and publish response back to broker
memset(WS._buffer_outgoing, 0, sizeof(WS._buffer_outgoing));
pb_ostream_t ostream =
pb_ostream_from_buffer(WS._buffer_outgoing, sizeof(WS._buffer_outgoing));
if (!ws_pb_encode(&ostream, wippersnapper_signal_v1_Ds18x20Response_fields,
&msgInitResp)) {
WS_DEBUG_PRINTLN("ERROR: Unable to encode msg_init response message!");
return false;
}
pb_get_encoded_size(&msgSz, wippersnapper_signal_v1_Ds18x20Response_fields,
&msgInitResp);
WS_DEBUG_PRINT("-> DS18x Init Response...");
WS._mqtt->publish(WS._topic_signal_ds18_device, WS._buffer_outgoing, msgSz,
1);
WS_DEBUG_PRINTLN("Published!");
return is_success;
}
/********************************************************************/
/*!
@brief De-initializes a DS18x20 sensor and releases its
pin and resources.
@param msgDS18x20DeinitReq
Message containing configuration data for a
ds18x20 sensor.
*/
/********************************************************************/
void ws_ds18x20::deleteDS18x20(
wippersnapper_ds18x20_v1_Ds18x20DeInitRequest *msgDS18x20DeinitReq) {
// Loop thru vector of drivers to find the unique address
for (size_t idx = 0; idx < _ds18xDrivers.size(); idx++) {
if (strcmp(_ds18xDrivers[idx]->onewire_pin,
msgDS18x20DeinitReq->onewire_pin) == 0) {
WS_DEBUG_PRINT("Deleting OneWire instance on pin ");
WS_DEBUG_PRINTLN(msgDS18x20DeinitReq->onewire_pin);
delete _ds18xDrivers[idx]
->dallasTempObj; // delete dallas temp instance on pin
delete _ds18xDrivers[idx]
->oneWire; // delete OneWire instance on pin and release pin for reuse
_ds18xDrivers.erase(_ds18xDrivers.begin() +
idx); // erase vector and re-allocate
}
}
#ifdef USE_DISPLAY
char buffer[100];
snprintf(buffer, 100, "[DS18x] Deleted DS18x20 sensor on pin %s\n",
msgDS18x20DeinitReq->onewire_pin);
WS._ui_helper->add_text_to_terminal(buffer);
#endif
}
/*************************************************************/
/*!
@brief Iterates through each ds18x20 sensor and
reports data (if period expired) to Adafruit IO.
*/
/*************************************************************/
void ws_ds18x20::update() {
// return immediately if no drivers have been initialized
if (_ds18xDrivers.size() == 0)
return;
long curTime; // used for holding the millis() value
std::vector<ds18x20Obj *>::iterator iter, end;
for (iter = _ds18xDrivers.begin(), end = _ds18xDrivers.end(); iter != end;
++iter) {
// Create an empty DS18x20 event signal message and configure
wippersnapper_signal_v1_Ds18x20Response msgDS18x20Response =
wippersnapper_signal_v1_Ds18x20Response_init_zero;
msgDS18x20Response.which_payload =
wippersnapper_signal_v1_Ds18x20Response_resp_ds18x20_event_tag;
// take the current time for the driver (*iter)
curTime = millis();
// Poll each sensor type, if period has elapsed
for (int i = 0; i < (*iter)->sensorPropertiesCount; i++) {
// has sensor_period elapsed?
if (curTime - (*iter)->sensorPeriodPrv >
(long)(*iter)->sensorProperties[i].sensor_period) {
// issue global temperature request to all DS sensors
WS_DEBUG_PRINTLN("Requesting temperature..");
(*iter)->dallasTempObj->requestTemperatures();
// poll the DS sensor driver
float tempC = (*iter)->dallasTempObj->getTempC((*iter)->dallasTempAddr);
if (tempC == DEVICE_DISCONNECTED_C) {
WS_DEBUG_PRINTLN("ERROR: Could not read temperature data, is the "
"sensor disconnected?");
#ifdef USE_DISPLAY
WS._ui_helper->add_text_to_terminal(
"[DS18x ERROR] Unable to read temperature, is the sensor "
"disconnected?\n");
#endif
break;
}
// check and pack based on sensorType
char buffer[100];
if ((*iter)->sensorProperties[i].sensor_type ==
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_AMBIENT_TEMPERATURE) {
WS_DEBUG_PRINT("(OneWireBus GPIO: ");
WS_DEBUG_PRINT((*iter)->onewire_pin);
WS_DEBUG_PRINT(") DS18x20 Value: ");
WS_DEBUG_PRINT(tempC);
WS_DEBUG_PRINTLN("*C")
snprintf(buffer, 100, "[DS18x] Read %0.2f*C on GPIO %s\n", tempC,
(*iter)->onewire_pin);
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event[i].type =
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_AMBIENT_TEMPERATURE;
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event[i].value =
tempC;
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event_count++;
}
if ((*iter)->sensorProperties[i].sensor_type ==
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_AMBIENT_TEMPERATURE_FAHRENHEIT) {
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event[i].type =
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_AMBIENT_TEMPERATURE_FAHRENHEIT;
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event[i].value =
(*iter)->dallasTempObj->toFahrenheit(tempC);
WS_DEBUG_PRINT("(OneWireBus GPIO: ");
WS_DEBUG_PRINT((*iter)->onewire_pin);
WS_DEBUG_PRINT(") DS18x20 Value: ");
WS_DEBUG_PRINT(
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event[i]
.value);
WS_DEBUG_PRINTLN("*F")
snprintf(buffer, 100, "[DS18x] Read %0.2f*F on GPIO %s\n",
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event[i]
.value,
(*iter)->onewire_pin);
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event_count++;
}
// did we obtain the expected amount of sensor events for the
// `resp_ds18x20_event` message?
if (msgDS18x20Response.payload.resp_ds18x20_event.sensor_event_count ==
(*iter)->sensorPropertiesCount) {
// prep sensor event data for sending to IO
// use onewire_pin as the "address"
strcpy(msgDS18x20Response.payload.resp_ds18x20_event.onewire_pin,
(*iter)->onewire_pin);
// prep and encode buffer
memset(WS._buffer_outgoing, 0, sizeof(WS._buffer_outgoing));
pb_ostream_t ostream = pb_ostream_from_buffer(
WS._buffer_outgoing, sizeof(WS._buffer_outgoing));
if (!ws_pb_encode(&ostream,
wippersnapper_signal_v1_Ds18x20Response_fields,
&msgDS18x20Response)) {
WS_DEBUG_PRINTLN(
"ERROR: Unable to encode DS18x20 event responsemessage!");
snprintf(buffer, 100,
"[DS18x ERROR] Unable to encode event message!");
return;
}
WS_DEBUG_PRINTLN(
"DEBUG: msgDS18x20Response sensor_event message contents:");
for (int i = 0;
i <
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event_count;
i++) {
WS_DEBUG_PRINT("sensor_event[#]: ");
WS_DEBUG_PRINTLN(i);
WS_DEBUG_PRINT("\tOneWire Bus: ");
WS_DEBUG_PRINTLN(
msgDS18x20Response.payload.resp_ds18x20_event.onewire_pin);
WS_DEBUG_PRINT("\tsensor_event type: ");
WS_DEBUG_PRINTLN(
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event[i]
.type);
WS_DEBUG_PRINT("\tsensor_event value: ");
WS_DEBUG_PRINTLN(
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event[i]
.value);
}
// Publish I2CResponse msg
size_t msgSz;
pb_get_encoded_size(&msgSz,
wippersnapper_signal_v1_Ds18x20Response_fields,
&msgDS18x20Response);
WS_DEBUG_PRINT("PUBLISHING -> msgDS18x20Response Event Message...");
if (!WS._mqtt->publish(WS._topic_signal_ds18_device,
WS._buffer_outgoing, msgSz, 1)) {
WS_DEBUG_PRINTLN("ERROR: Unable to publish DS18x20 event message - "
"MQTT Publish failed!");
return;
};
WS_DEBUG_PRINTLN("PUBLISHED!");
#ifdef USE_DISPLAY
WS._ui_helper->add_text_to_terminal(buffer);
#endif
(*iter)->sensorPeriodPrv = curTime; // set prv period
}
}
}
}
/*!
* @file ws_ds18x20.cpp
*
* This component implements 1-wire communication
* for the DS18X20-line of Maxim Temperature ICs.
*
* Adafruit invests time and resources providing this open source code,
* please support Adafruit and open-source hardware by purchasing
* products from Adafruit!
*
* Copyright (c) Brent Rubell 2022-2023 for Adafruit Industries.
*
* BSD license, all text here must be included in any redistribution.
*
*/
#include "ws_ds18x20.h"
/*************************************************************/
/*!
@brief Creates a new WipperSnapper Ds18x20 component.
*/
/*************************************************************/
ws_ds18x20::ws_ds18x20() {}
/*************************************************************/
/*!
@brief Destructor for a WipperSnapper DS18X20 component.
*/
/*************************************************************/
ws_ds18x20::~ws_ds18x20() {
// delete DallasTemp sensors and release onewire buses
for (size_t idx = 0; idx < _ds18xDrivers.size(); idx++) {
delete _ds18xDrivers[idx]->dallasTempObj;
delete _ds18xDrivers[idx]->oneWire;
}
// remove all elements
_ds18xDrivers.clear();
}
/********************************************************************/
/*!
@brief Initializes a DS18x20 sensor using a
configuration sent by the broker and adds it to a
vector of ds18x20 sensor drivers.
@param msgDs18x20InitReq
Message containing configuration data for a
ds18x20 sensor.
@returns True if initialized successfully, False otherwise.
*/
/********************************************************************/
bool ws_ds18x20::addDS18x20(
wippersnapper_ds18x20_v1_Ds18x20InitRequest *msgDs18x20InitReq) {
bool is_success = false;
// init. new ds18x20 object
ds18x20Obj *newObj = new ds18x20Obj();
char *oneWirePin = msgDs18x20InitReq->onewire_pin + 1;
newObj->oneWire = new OneWire(atoi(oneWirePin));
newObj->dallasTempObj = new DallasTemperature(newObj->oneWire);
newObj->dallasTempObj->begin();
// attempt to obtain sensor address
if (newObj->dallasTempObj->getAddress(newObj->dallasTempAddr, 0)) {
// attempt to set sensor resolution
newObj->dallasTempObj->setResolution(msgDs18x20InitReq->sensor_resolution);
// copy the device's sensor properties
newObj->sensorPropertiesCount =
msgDs18x20InitReq->i2c_device_properties_count;
// TODO: Make sure this works, it's a new idea and untested :)
for (int i = 0; i < newObj->sensorPropertiesCount; i++) {
newObj->sensorProperties[i].sensor_type =
msgDs18x20InitReq->i2c_device_properties[i].sensor_type;
newObj->sensorProperties[i].sensor_period =
(long)msgDs18x20InitReq->i2c_device_properties[i].sensor_period *
1000;
}
// set pin
strcpy(newObj->onewire_pin, msgDs18x20InitReq->onewire_pin);
// add the new ds18x20 driver to vec.
_ds18xDrivers.push_back(newObj);
is_success = true;
} else {
WS_DEBUG_PRINTLN("Failed to find DSx sensor on specified pin.");
}
// fill and publish the initialization response back to the broker
size_t msgSz; // message's encoded size
wippersnapper_signal_v1_Ds18x20Response msgInitResp =
wippersnapper_signal_v1_Ds18x20Response_init_zero;
msgInitResp.which_payload =
wippersnapper_signal_v1_Ds18x20Response_resp_ds18x20_init_tag;
msgInitResp.payload.resp_ds18x20_init.is_initialized = is_success;
strcpy(msgInitResp.payload.resp_ds18x20_init.onewire_pin,
msgDs18x20InitReq->onewire_pin);
WS_DEBUG_PRINT("Created OneWireBus on GPIO ");
WS_DEBUG_PRINT(msgDs18x20InitReq->onewire_pin);
WS_DEBUG_PRINTLN(" with DS18x20 attached!");
#ifdef USE_DISPLAY
char buffer[100];
snprintf(buffer, 100, "[DS18x] Attached DS18x20 sensor to pin %s\n",
msgDs18x20InitReq->onewire_pin);
WS._ui_helper->add_text_to_terminal(buffer);
#endif
// Encode and publish response back to broker
memset(WS._buffer_outgoing, 0, sizeof(WS._buffer_outgoing));
pb_ostream_t ostream =
pb_ostream_from_buffer(WS._buffer_outgoing, sizeof(WS._buffer_outgoing));
if (!ws_pb_encode(&ostream, wippersnapper_signal_v1_Ds18x20Response_fields,
&msgInitResp)) {
WS_DEBUG_PRINTLN("ERROR: Unable to encode msg_init response message!");
return false;
}
pb_get_encoded_size(&msgSz, wippersnapper_signal_v1_Ds18x20Response_fields,
&msgInitResp);
WS_DEBUG_PRINT("-> DS18x Init Response...");
WS._mqtt->publish(WS._topic_signal_ds18_device, WS._buffer_outgoing, msgSz,
1);
WS_DEBUG_PRINTLN("Published!");
return is_success;
}
/********************************************************************/
/*!
@brief De-initializes a DS18x20 sensor and releases its
pin and resources.
@param msgDS18x20DeinitReq
Message containing configuration data for a
ds18x20 sensor.
*/
/********************************************************************/
void ws_ds18x20::deleteDS18x20(
wippersnapper_ds18x20_v1_Ds18x20DeInitRequest *msgDS18x20DeinitReq) {
// Loop thru vector of drivers to find the unique address
for (size_t idx = 0; idx < _ds18xDrivers.size(); idx++) {
if (strcmp(_ds18xDrivers[idx]->onewire_pin,
msgDS18x20DeinitReq->onewire_pin) == 0) {
WS_DEBUG_PRINT("Deleting OneWire instance on pin ");
WS_DEBUG_PRINTLN(msgDS18x20DeinitReq->onewire_pin);
delete _ds18xDrivers[idx]
->dallasTempObj; // delete dallas temp instance on pin
delete _ds18xDrivers[idx]
->oneWire; // delete OneWire instance on pin and release pin for reuse
_ds18xDrivers.erase(_ds18xDrivers.begin() +
idx); // erase vector and re-allocate
}
}
#ifdef USE_DISPLAY
char buffer[100];
snprintf(buffer, 100, "[DS18x] Deleted DS18x20 sensor on pin %s\n",
msgDS18x20DeinitReq->onewire_pin);
WS._ui_helper->add_text_to_terminal(buffer);
#endif
}
/*************************************************************/
/*!
@brief Iterates through each ds18x20 sensor and
reports data (if period expired) to Adafruit IO.
*/
/*************************************************************/
void ws_ds18x20::update() {
// return immediately if no drivers have been initialized
if (_ds18xDrivers.size() == 0)
return;
long curTime; // used for holding the millis() value
std::vector<ds18x20Obj *>::iterator iter, end;
for (iter = _ds18xDrivers.begin(), end = _ds18xDrivers.end(); iter != end;
++iter) {
// Create an empty DS18x20 event signal message and configure
wippersnapper_signal_v1_Ds18x20Response msgDS18x20Response =
wippersnapper_signal_v1_Ds18x20Response_init_zero;
msgDS18x20Response.which_payload =
wippersnapper_signal_v1_Ds18x20Response_resp_ds18x20_event_tag;
// take the current time for the driver (*iter)
curTime = millis();
// Poll each sensor type, if period has elapsed
for (int i = 0; i < (*iter)->sensorPropertiesCount; i++) {
// has sensor_period elapsed?
if (curTime - (*iter)->sensorPeriodPrv >
(long)(*iter)->sensorProperties[i].sensor_period) {
// issue global temperature request to all DS sensors
WS_DEBUG_PRINTLN("Requesting temperature..");
(*iter)->dallasTempObj->requestTemperatures();
// poll the DS sensor driver
float tempC = (*iter)->dallasTempObj->getTempC((*iter)->dallasTempAddr);
if (tempC == DEVICE_DISCONNECTED_C) {
WS_DEBUG_PRINTLN("ERROR: Could not read temperature data, is the "
"sensor disconnected?");
#ifdef USE_DISPLAY
WS._ui_helper->add_text_to_terminal(
"[DS18x ERROR] Unable to read temperature, is the sensor "
"disconnected?\n");
#endif
break;
}
// check and pack based on sensorType
char buffer[100];
if ((*iter)->sensorProperties[i].sensor_type ==
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_AMBIENT_TEMPERATURE) {
WS_DEBUG_PRINT("(OneWireBus GPIO: ");
WS_DEBUG_PRINT((*iter)->onewire_pin);
WS_DEBUG_PRINT(") DS18x20 Value: ");
WS_DEBUG_PRINT(tempC);
WS_DEBUG_PRINTLN("*C")
snprintf(buffer, 100, "[DS18x] Read %0.2f*C on GPIO %s\n", tempC,
(*iter)->onewire_pin);
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event[i].type =
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_AMBIENT_TEMPERATURE;
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event[i].value =
tempC;
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event_count++;
}
if ((*iter)->sensorProperties[i].sensor_type ==
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_AMBIENT_TEMPERATURE_FAHRENHEIT) {
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event[i].type =
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_AMBIENT_TEMPERATURE_FAHRENHEIT;
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event[i].value =
(*iter)->dallasTempObj->toFahrenheit(tempC);
WS_DEBUG_PRINT("(OneWireBus GPIO: ");
WS_DEBUG_PRINT((*iter)->onewire_pin);
WS_DEBUG_PRINT(") DS18x20 Value: ");
WS_DEBUG_PRINT(
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event[i]
.value);
WS_DEBUG_PRINTLN("*F")
snprintf(buffer, 100, "[DS18x] Read %0.2f*F on GPIO %s\n",
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event[i]
.value,
(*iter)->onewire_pin);
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event_count++;
}
// did we obtain the expected amount of sensor events for the
// `resp_ds18x20_event` message?
if (msgDS18x20Response.payload.resp_ds18x20_event.sensor_event_count ==
(*iter)->sensorPropertiesCount) {
// prep sensor event data for sending to IO
// use onewire_pin as the "address"
strcpy(msgDS18x20Response.payload.resp_ds18x20_event.onewire_pin,
(*iter)->onewire_pin);
// prep and encode buffer
memset(WS._buffer_outgoing, 0, sizeof(WS._buffer_outgoing));
pb_ostream_t ostream = pb_ostream_from_buffer(
WS._buffer_outgoing, sizeof(WS._buffer_outgoing));
if (!ws_pb_encode(&ostream,
wippersnapper_signal_v1_Ds18x20Response_fields,
&msgDS18x20Response)) {
WS_DEBUG_PRINTLN(
"ERROR: Unable to encode DS18x20 event responsemessage!");
snprintf(buffer, 100,
"[DS18x ERROR] Unable to encode event message!");
return;
}
WS_DEBUG_PRINTLN(
"DEBUG: msgDS18x20Response sensor_event message contents:");
for (int i = 0;
i <
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event_count;
i++) {
WS_DEBUG_PRINT("sensor_event[#]: ");
WS_DEBUG_PRINTLN(i);
WS_DEBUG_PRINT("\tOneWire Bus: ");
WS_DEBUG_PRINTLN(
msgDS18x20Response.payload.resp_ds18x20_event.onewire_pin);
WS_DEBUG_PRINT("\tsensor_event type: ");
WS_DEBUG_PRINTLN(
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event[i]
.type);
WS_DEBUG_PRINT("\tsensor_event value: ");
WS_DEBUG_PRINTLN(
msgDS18x20Response.payload.resp_ds18x20_event.sensor_event[i]
.value);
}
// Publish I2CResponse msg
size_t msgSz;
pb_get_encoded_size(&msgSz,
wippersnapper_signal_v1_Ds18x20Response_fields,
&msgDS18x20Response);
WS_DEBUG_PRINT("PUBLISHING -> msgDS18x20Response Event Message...");
if (!WS._mqtt->publish(WS._topic_signal_ds18_device,
WS._buffer_outgoing, msgSz, 1)) {
WS_DEBUG_PRINTLN("ERROR: Unable to publish DS18x20 event message - "
"MQTT Publish failed!");
return;
};
WS_DEBUG_PRINTLN("PUBLISHED!");
#ifdef USE_DISPLAY
WS._ui_helper->add_text_to_terminal(buffer);
#endif
(*iter)->sensorPeriodPrv = curTime; // set prv period
}
}
}
}
}

View file

@ -1,453 +1,453 @@
/*!
* @file ws_pixels.cpp
*
* High-level interface for wippersnapper to manage addressable RGB pixel
* strands
*
* Adafruit invests time and resources providing this open source code,
* please support Adafruit and open-source hardware by purchasing
* products from Adafruit!
*
*
* Written by Brent Rubell for Adafruit Industries, 2022-2023
*
* MIT license, all text here must be included in any redistribution.
*
*/
#include "ws_pixels.h"
strand_s strands[MAX_PIXEL_STRANDS]{
nullptr,
nullptr,
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_UNSPECIFIED,
0,
0,
wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_UNSPECIFIED,
-1,
-1,
-1}; ///< Contains all pixel strands used by WipperSnapper
/**************************************************************************/
/*!
@brief Destructor
*/
/**************************************************************************/
ws_pixels::~ws_pixels() {
// de-allocate all strands
for (size_t i = 0; i < sizeof(strands) / sizeof(strands[0]); i++)
deallocateStrand(i);
}
/******************************************************************************/
/*!
@brief Allocates an index of a free strand_t within the strand array.
@returns Index of a free strand_t, ERR_INVALID_STRAND if strand array is
full.
*/
/******************************************************************************/
int16_t ws_pixels::allocateStrand() {
for (size_t strandIdx = 0; strandIdx < sizeof(strands) / sizeof(strands[0]);
strandIdx++) {
if (strands[strandIdx].type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_UNSPECIFIED) {
return strandIdx;
}
}
return ERR_INVALID_STRAND;
}
/**************************************************************************/
/*!
@brief Deallocates a `strand_t` within `strands`, provided an index.
@param strandIdx
The desired index of a `strand_t` within `strands`.
*/
/**************************************************************************/
void ws_pixels::deallocateStrand(int16_t strandIdx) {
// delete the pixel object
if (strands[strandIdx].neoPixelPtr != nullptr)
delete strands[strandIdx].neoPixelPtr;
if ((strands[strandIdx].dotStarPtr != nullptr))
delete strands[strandIdx].dotStarPtr;
// re-initialize status pixel (if pixel was prvsly used)
if (strands[strandIdx].pinNeoPixel == getStatusNeoPixelPin() ||
strands[strandIdx].pinDotStarData == getStatusDotStarDataPin()) {
initStatusLED();
}
// reset the strand
strands[strandIdx] = {
nullptr,
nullptr,
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_UNSPECIFIED,
0,
0,
wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_UNSPECIFIED,
-1,
-1,
-1};
}
/**************************************************************************/
/*!
@brief Returns the `neoPixelType` provided the strand's pixelOrder
@param pixelOrder
Desired pixel order, from init. message.
@returns Type of NeoPixel strand, usable by Adafruit_NeoPixel
constructor
*/
/**************************************************************************/
neoPixelType ws_pixels::getNeoPixelStrandOrder(
wippersnapper_pixels_v1_PixelsOrder pixelOrder) {
switch (pixelOrder) {
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_GRB:
return NEO_GRB + NEO_KHZ800;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_GRBW:
return NEO_GRBW + NEO_KHZ800;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_RGB:
return NEO_RGB + NEO_KHZ800;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_RGBW:
return NEO_RGBW + NEO_KHZ800;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_BRG:
return NEO_BRG + NEO_KHZ800;
default:
return NEO_GRB + NEO_KHZ800;
}
}
/**************************************************************************/
/*!
@brief Returns the color order of the DotStar strand.
@param pixelOrder
Desired pixel order, from init. message.
@returns Type of DotStar strand.
*/
/**************************************************************************/
uint8_t ws_pixels::getDotStarStrandOrder(
wippersnapper_pixels_v1_PixelsOrder pixelOrder) {
switch (pixelOrder) {
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_GRB:
return DOTSTAR_GRB;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_RGB:
return DOTSTAR_RGB;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_BRG:
return DOTSTAR_BRG;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_RBG:
return DOTSTAR_RBG;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_GBR:
return DOTSTAR_GBR;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_BGR:
return DOTSTAR_BGR;
default:
return DOTSTAR_BRG;
}
}
/**************************************************************************/
/*!
@brief Creates a PixelsResponse message and publishes it to IO.
@param is_success
True if `addStrand()` succeeded, False otherwise.
@param pixels_pin_data
The strand's data pin..
*/
/**************************************************************************/
void ws_pixels::publishAddStrandResponse(bool is_success,
char *pixels_pin_data) {
// Create response message
wippersnapper_signal_v1_PixelsResponse msgInitResp =
wippersnapper_signal_v1_PixelsResponse_init_zero;
msgInitResp.which_payload =
wippersnapper_signal_v1_PixelsResponse_resp_pixels_create_tag;
// Fill response message
msgInitResp.payload.resp_pixels_create.is_success = is_success;
memcpy(msgInitResp.payload.resp_pixels_create.pixels_pin_data,
pixels_pin_data, sizeof(char) * 6);
// Encode `wippersnapper_pixels_v1_PixelsCreateResponse` message
memset(WS._buffer_outgoing, 0, sizeof(WS._buffer_outgoing));
pb_ostream_t ostream =
pb_ostream_from_buffer(WS._buffer_outgoing, sizeof(WS._buffer_outgoing));
if (!ws_pb_encode(&ostream, wippersnapper_signal_v1_PixelsResponse_fields,
&msgInitResp)) {
WS_DEBUG_PRINTLN("ERROR: Unable to encode "
"wippersnapper_signal_v1_PixelsResponse message!");
return;
}
// Publish message to broker
size_t msgSz;
pb_get_encoded_size(&msgSz, wippersnapper_signal_v1_PixelsResponse_fields,
&msgInitResp);
WS_DEBUG_PRINT("-> wippersnapper_signal_v1_PixelsResponse...");
WS._mqtt->publish(WS._topic_signal_pixels_device, WS._buffer_outgoing, msgSz,
1);
WS_DEBUG_PRINTLN("Published!");
}
/**************************************************************************/
/*!
@brief Initializes a strand of addressable RGB Pixels.
@param pixelsCreateReqMsg
Pointer to strand init. request message
@returns True if successfully initialized, False otherwise.
*/
/**************************************************************************/
bool ws_pixels::addStrand(
wippersnapper_pixels_v1_PixelsCreateRequest *pixelsCreateReqMsg) {
// attempt to allocate a free strand from array of strands
int16_t strandIdx = allocateStrand();
if (strandIdx == ERR_INVALID_STRAND) { // unable to allocate a strand
if (pixelsCreateReqMsg->pixels_type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_NEOPIXEL)
publishAddStrandResponse(false, pixelsCreateReqMsg->pixels_pin_neopixel);
else if (pixelsCreateReqMsg->pixels_type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_DOTSTAR)
publishAddStrandResponse(false,
pixelsCreateReqMsg->pixels_pin_dotstar_data);
return false;
}
// fill generic members of the strand obj.
strands[strandIdx].type = pixelsCreateReqMsg->pixels_type;
strands[strandIdx].brightness = pixelsCreateReqMsg->pixels_brightness;
strands[strandIdx].numPixels = pixelsCreateReqMsg->pixels_num;
strands[strandIdx].ordering = pixelsCreateReqMsg->pixels_ordering;
// fill strand pins
if (pixelsCreateReqMsg->pixels_type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_NEOPIXEL) {
strands[strandIdx].pinNeoPixel =
atoi(pixelsCreateReqMsg->pixels_pin_neopixel + 1);
} else if (pixelsCreateReqMsg->pixels_type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_DOTSTAR) {
strands[strandIdx].pinDotStarData =
atoi(pixelsCreateReqMsg->pixels_pin_dotstar_data + 1);
strands[strandIdx].pinDotStarClock =
atoi(pixelsCreateReqMsg->pixels_pin_dotstar_clock + 1);
} else {
WS_DEBUG_PRINTLN("ERROR: Invalid strand type provided!");
publishAddStrandResponse(false, pixelsCreateReqMsg->pixels_pin_neopixel);
return false;
}
// Fill specific members of strand obj.
if (pixelsCreateReqMsg->pixels_type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_NEOPIXEL) {
// Release status LED
// is requested pin in-use by the status pixel?
if (getStatusNeoPixelPin() == strands[strandIdx].pinNeoPixel &&
WS.lockStatusNeoPixel)
releaseStatusLED(); // release it!
// Create a new strand of NeoPixels
strands[strandIdx].neoPixelPtr = new Adafruit_NeoPixel(
pixelsCreateReqMsg->pixels_num, strands[strandIdx].pinNeoPixel,
getNeoPixelStrandOrder(pixelsCreateReqMsg->pixels_ordering));
// Initialize strand
strands[strandIdx].neoPixelPtr->begin();
strands[strandIdx].neoPixelPtr->setBrightness(
strands[strandIdx].brightness);
strands[strandIdx].neoPixelPtr->clear();
strands[strandIdx].neoPixelPtr->show();
// Check that we've correctly initialized the strand
if (strands[strandIdx].neoPixelPtr->numPixels() == 0) {
publishAddStrandResponse(false, pixelsCreateReqMsg->pixels_pin_neopixel);
return false;
}
WS_DEBUG_PRINT("Created NeoPixel strand of length ");
WS_DEBUG_PRINT(pixelsCreateReqMsg->pixels_num);
WS_DEBUG_PRINT(" on GPIO #");
WS_DEBUG_PRINTLN(pixelsCreateReqMsg->pixels_pin_neopixel);
#ifdef USE_DISPLAY
char buffer[100];
snprintf(buffer, 100, "[Pixel] Added NeoPixel strand on Pin %s\n.",
pixelsCreateReqMsg->pixels_pin_neopixel);
WS._ui_helper->add_text_to_terminal(buffer);
#endif
publishAddStrandResponse(true, pixelsCreateReqMsg->pixels_pin_neopixel);
} else if (pixelsCreateReqMsg->pixels_type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_DOTSTAR) {
// release the status dotstar, if it is both in-use and the pin within
// `pixelsCreateReqMsg`
if ((strands[strandIdx].pinDotStarData == getStatusDotStarDataPin()) &&
WS.lockStatusDotStar) {
releaseStatusLED();
}
// Create Dotstar strand
strands[strandIdx].dotStarPtr = new Adafruit_DotStar(
strands[strandIdx].numPixels, strands[strandIdx].pinDotStarData,
strands[strandIdx].pinDotStarClock,
getDotStarStrandOrder(strands[strandIdx].ordering));
// initialize strand
strands[strandIdx].dotStarPtr->begin();
strands[strandIdx].dotStarPtr->setBrightness(strands[strandIdx].brightness);
strands[strandIdx].dotStarPtr->clear();
strands[strandIdx].dotStarPtr->show();
// post-init sanity check
if (strands[strandIdx].dotStarPtr->numPixels() == 0) {
publishAddStrandResponse(false,
pixelsCreateReqMsg->pixels_pin_dotstar_data);
return false;
}
WS_DEBUG_PRINT("Created DotStar strand of length ");
WS_DEBUG_PRINT(strands[strandIdx].numPixels);
WS_DEBUG_PRINT(" on Data GPIO #");
WS_DEBUG_PRINTLN(strands[strandIdx].pinDotStarData);
#ifdef USE_DISPLAY
char buffer[100];
snprintf(buffer, 100, "[Pixel] Added NeoPixel strand on Pin %s\n.",
pixelsCreateReqMsg->pixels_pin_neopixel);
WS._ui_helper->add_text_to_terminal(buffer);
#endif
publishAddStrandResponse(true, pixelsCreateReqMsg->pixels_pin_dotstar_data);
} else {
WS_DEBUG_PRINTLN("ERROR: Invalid strand type provided!");
publishAddStrandResponse(false,
pixelsCreateReqMsg->pixels_pin_dotstar_data);
return false;
}
return true;
}
/**************************************************************************/
/*!
@brief Obtains the index of a `strand_t` within array of `strands`.
@param dataPin
strand_t's data dataPin
@param type
Type of strand_t, NeoPixel or DotStar.
@returns The index of a strand_t if within strands[],
ERR_INVALID_STRAND otherwise.
*/
/**************************************************************************/
int ws_pixels::getStrandIdx(int16_t dataPin,
wippersnapper_pixels_v1_PixelsType type) {
for (size_t strandIdx = 0; strandIdx < sizeof(strands) / sizeof(strands[0]);
strandIdx++) {
if (type == wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_NEOPIXEL &&
strands[strandIdx].pinNeoPixel == dataPin)
return strandIdx;
if (type == wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_DOTSTAR &&
strands[strandIdx].pinDotStarData == dataPin)
return strandIdx;
}
return ERR_INVALID_STRAND;
}
/**************************************************************************/
/*!
@brief Deletes a `strand_t` from `strands`, deinitializes a strand,
and frees its resources.
@param pixelsDeleteMsg
Protobuf message from Adafruit IO containing a
`wippersnapper_pixels_v1_PixelsDeleteRequest`.
*/
/**************************************************************************/
void ws_pixels::deleteStrand(
wippersnapper_pixels_v1_PixelsDeleteRequest *pixelsDeleteMsg) {
int strandIdx = getStrandIdx(atoi(pixelsDeleteMsg->pixels_pin_data + 1),
pixelsDeleteMsg->pixels_type);
if (strandIdx == ERR_INVALID_STRAND) {
WS_DEBUG_PRINTLN("ERROR: Strand not found, unable to delete strand!");
return;
}
// deallocate and release resources of strand object
deallocateStrand(strandIdx);
WS_DEBUG_PRINT("Deleted strand on data pin ");
WS_DEBUG_PRINTLN(pixelsDeleteMsg->pixels_pin_data);
#ifdef USE_DISPLAY
char buffer[100];
snprintf(buffer, 100, "[Pixel] Deleted strand on pin %s\n.",
pixelsDeleteMsg->pixels_pin_data);
WS._ui_helper->add_text_to_terminal(buffer);
#endif
}
/**************************************************************************/
/*!
@brief Gets the gamma-corrected color, provided a pixel_color
@param pixel_color
Strand's color from Adafruit IO.
@param strand
Desired strand struct. to access.
@returns A gamma-corrected strand color
*/
/**************************************************************************/
uint32_t ws_pixels::getGammaCorrectedColor(uint32_t pixel_color,
strand_s strand) {
if (strand.neoPixelPtr != nullptr) {
return strand.neoPixelPtr->gamma32(pixel_color);
} else if (strand.dotStarPtr != nullptr) {
return strand.dotStarPtr->gamma32(pixel_color);
} else {
WS_DEBUG_PRINTLN(
"ERROR: Unable to perform gamma correction, unknown strand type!");
return 0;
}
}
/**************************************************************************/
/*!
@brief Writes a color from Adafruit IO to a strand of
addressable pixels
@param pixelsWriteMsg
Protobuf message from Adafruit IO containing a
`wippersnapper_pixels_v1_PixelsWriteRequest`.
*/
/**************************************************************************/
void ws_pixels::fillStrand(
wippersnapper_pixels_v1_PixelsWriteRequest *pixelsWriteMsg) {
// Get index of pixel strand
int strandIdx = getStrandIdx(atoi(pixelsWriteMsg->pixels_pin_data + 1),
pixelsWriteMsg->pixels_type);
if (strandIdx == ERR_INVALID_STRAND) {
WS_DEBUG_PRINTLN(
"ERROR: Pixel strand not found, can not write a color to the strand!");
return;
}
uint32_t rgbColorGamma =
getGammaCorrectedColor(pixelsWriteMsg->pixels_color, strands[strandIdx]);
WS_DEBUG_PRINT("Filling color: ");
WS_DEBUG_PRINTLN(pixelsWriteMsg->pixels_color);
#ifdef USE_DISPLAY
char buffer[100];
snprintf(buffer, 100, "[Pixel] Filling strand on pin %s with color %u\n",
pixelsWriteMsg->pixels_pin_data,
(unsigned int)pixelsWriteMsg->pixels_color);
WS._ui_helper->add_text_to_terminal(buffer);
#endif
if (pixelsWriteMsg->pixels_type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_NEOPIXEL) {
strands[strandIdx].neoPixelPtr->fill(rgbColorGamma);
strands[strandIdx].neoPixelPtr->show();
} else if (pixelsWriteMsg->pixels_type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_DOTSTAR) {
strands[strandIdx].dotStarPtr->fill(rgbColorGamma);
strands[strandIdx].dotStarPtr->show();
} else {
WS_DEBUG_PRINTLN("ERROR: Unable to determine pixel type to write to!");
}
/*!
* @file ws_pixels.cpp
*
* High-level interface for wippersnapper to manage addressable RGB pixel
* strands
*
* Adafruit invests time and resources providing this open source code,
* please support Adafruit and open-source hardware by purchasing
* products from Adafruit!
*
*
* Written by Brent Rubell for Adafruit Industries, 2022-2023
*
* MIT license, all text here must be included in any redistribution.
*
*/
#include "ws_pixels.h"
strand_s strands[MAX_PIXEL_STRANDS]{
nullptr,
nullptr,
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_UNSPECIFIED,
0,
0,
wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_UNSPECIFIED,
-1,
-1,
-1}; ///< Contains all pixel strands used by WipperSnapper
/**************************************************************************/
/*!
@brief Destructor
*/
/**************************************************************************/
ws_pixels::~ws_pixels() {
// de-allocate all strands
for (size_t i = 0; i < sizeof(strands) / sizeof(strands[0]); i++)
deallocateStrand(i);
}
/******************************************************************************/
/*!
@brief Allocates an index of a free strand_t within the strand array.
@returns Index of a free strand_t, ERR_INVALID_STRAND if strand array is
full.
*/
/******************************************************************************/
int16_t ws_pixels::allocateStrand() {
for (size_t strandIdx = 0; strandIdx < sizeof(strands) / sizeof(strands[0]);
strandIdx++) {
if (strands[strandIdx].type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_UNSPECIFIED) {
return strandIdx;
}
}
return ERR_INVALID_STRAND;
}
/**************************************************************************/
/*!
@brief Deallocates a `strand_t` within `strands`, provided an index.
@param strandIdx
The desired index of a `strand_t` within `strands`.
*/
/**************************************************************************/
void ws_pixels::deallocateStrand(int16_t strandIdx) {
// delete the pixel object
if (strands[strandIdx].neoPixelPtr != nullptr)
delete strands[strandIdx].neoPixelPtr;
if ((strands[strandIdx].dotStarPtr != nullptr))
delete strands[strandIdx].dotStarPtr;
// re-initialize status pixel (if pixel was prvsly used)
if (strands[strandIdx].pinNeoPixel == getStatusNeoPixelPin() ||
strands[strandIdx].pinDotStarData == getStatusDotStarDataPin()) {
initStatusLED();
}
// reset the strand
strands[strandIdx] = {
nullptr,
nullptr,
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_UNSPECIFIED,
0,
0,
wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_UNSPECIFIED,
-1,
-1,
-1};
}
/**************************************************************************/
/*!
@brief Returns the `neoPixelType` provided the strand's pixelOrder
@param pixelOrder
Desired pixel order, from init. message.
@returns Type of NeoPixel strand, usable by Adafruit_NeoPixel
constructor
*/
/**************************************************************************/
neoPixelType ws_pixels::getNeoPixelStrandOrder(
wippersnapper_pixels_v1_PixelsOrder pixelOrder) {
switch (pixelOrder) {
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_GRB:
return NEO_GRB + NEO_KHZ800;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_GRBW:
return NEO_GRBW + NEO_KHZ800;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_RGB:
return NEO_RGB + NEO_KHZ800;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_RGBW:
return NEO_RGBW + NEO_KHZ800;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_BRG:
return NEO_BRG + NEO_KHZ800;
default:
return NEO_GRB + NEO_KHZ800;
}
}
/**************************************************************************/
/*!
@brief Returns the color order of the DotStar strand.
@param pixelOrder
Desired pixel order, from init. message.
@returns Type of DotStar strand.
*/
/**************************************************************************/
uint8_t ws_pixels::getDotStarStrandOrder(
wippersnapper_pixels_v1_PixelsOrder pixelOrder) {
switch (pixelOrder) {
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_GRB:
return DOTSTAR_GRB;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_RGB:
return DOTSTAR_RGB;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_BRG:
return DOTSTAR_BRG;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_RBG:
return DOTSTAR_RBG;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_GBR:
return DOTSTAR_GBR;
case wippersnapper_pixels_v1_PixelsOrder_PIXELS_ORDER_BGR:
return DOTSTAR_BGR;
default:
return DOTSTAR_BRG;
}
}
/**************************************************************************/
/*!
@brief Creates a PixelsResponse message and publishes it to IO.
@param is_success
True if `addStrand()` succeeded, False otherwise.
@param pixels_pin_data
The strand's data pin..
*/
/**************************************************************************/
void ws_pixels::publishAddStrandResponse(bool is_success,
char *pixels_pin_data) {
// Create response message
wippersnapper_signal_v1_PixelsResponse msgInitResp =
wippersnapper_signal_v1_PixelsResponse_init_zero;
msgInitResp.which_payload =
wippersnapper_signal_v1_PixelsResponse_resp_pixels_create_tag;
// Fill response message
msgInitResp.payload.resp_pixels_create.is_success = is_success;
memcpy(msgInitResp.payload.resp_pixels_create.pixels_pin_data,
pixels_pin_data, sizeof(char) * 6);
// Encode `wippersnapper_pixels_v1_PixelsCreateResponse` message
memset(WS._buffer_outgoing, 0, sizeof(WS._buffer_outgoing));
pb_ostream_t ostream =
pb_ostream_from_buffer(WS._buffer_outgoing, sizeof(WS._buffer_outgoing));
if (!ws_pb_encode(&ostream, wippersnapper_signal_v1_PixelsResponse_fields,
&msgInitResp)) {
WS_DEBUG_PRINTLN("ERROR: Unable to encode "
"wippersnapper_signal_v1_PixelsResponse message!");
return;
}
// Publish message to broker
size_t msgSz;
pb_get_encoded_size(&msgSz, wippersnapper_signal_v1_PixelsResponse_fields,
&msgInitResp);
WS_DEBUG_PRINT("-> wippersnapper_signal_v1_PixelsResponse...");
WS._mqtt->publish(WS._topic_signal_pixels_device, WS._buffer_outgoing, msgSz,
1);
WS_DEBUG_PRINTLN("Published!");
}
/**************************************************************************/
/*!
@brief Initializes a strand of addressable RGB Pixels.
@param pixelsCreateReqMsg
Pointer to strand init. request message
@returns True if successfully initialized, False otherwise.
*/
/**************************************************************************/
bool ws_pixels::addStrand(
wippersnapper_pixels_v1_PixelsCreateRequest *pixelsCreateReqMsg) {
// attempt to allocate a free strand from array of strands
int16_t strandIdx = allocateStrand();
if (strandIdx == ERR_INVALID_STRAND) { // unable to allocate a strand
if (pixelsCreateReqMsg->pixels_type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_NEOPIXEL)
publishAddStrandResponse(false, pixelsCreateReqMsg->pixels_pin_neopixel);
else if (pixelsCreateReqMsg->pixels_type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_DOTSTAR)
publishAddStrandResponse(false,
pixelsCreateReqMsg->pixels_pin_dotstar_data);
return false;
}
// fill generic members of the strand obj.
strands[strandIdx].type = pixelsCreateReqMsg->pixels_type;
strands[strandIdx].brightness = pixelsCreateReqMsg->pixels_brightness;
strands[strandIdx].numPixels = pixelsCreateReqMsg->pixels_num;
strands[strandIdx].ordering = pixelsCreateReqMsg->pixels_ordering;
// fill strand pins
if (pixelsCreateReqMsg->pixels_type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_NEOPIXEL) {
strands[strandIdx].pinNeoPixel =
atoi(pixelsCreateReqMsg->pixels_pin_neopixel + 1);
} else if (pixelsCreateReqMsg->pixels_type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_DOTSTAR) {
strands[strandIdx].pinDotStarData =
atoi(pixelsCreateReqMsg->pixels_pin_dotstar_data + 1);
strands[strandIdx].pinDotStarClock =
atoi(pixelsCreateReqMsg->pixels_pin_dotstar_clock + 1);
} else {
WS_DEBUG_PRINTLN("ERROR: Invalid strand type provided!");
publishAddStrandResponse(false, pixelsCreateReqMsg->pixels_pin_neopixel);
return false;
}
// Fill specific members of strand obj.
if (pixelsCreateReqMsg->pixels_type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_NEOPIXEL) {
// Release status LED
// is requested pin in-use by the status pixel?
if (getStatusNeoPixelPin() == strands[strandIdx].pinNeoPixel &&
WS.lockStatusNeoPixel)
releaseStatusLED(); // release it!
// Create a new strand of NeoPixels
strands[strandIdx].neoPixelPtr = new Adafruit_NeoPixel(
pixelsCreateReqMsg->pixels_num, strands[strandIdx].pinNeoPixel,
getNeoPixelStrandOrder(pixelsCreateReqMsg->pixels_ordering));
// Initialize strand
strands[strandIdx].neoPixelPtr->begin();
strands[strandIdx].neoPixelPtr->setBrightness(
strands[strandIdx].brightness);
strands[strandIdx].neoPixelPtr->clear();
strands[strandIdx].neoPixelPtr->show();
// Check that we've correctly initialized the strand
if (strands[strandIdx].neoPixelPtr->numPixels() == 0) {
publishAddStrandResponse(false, pixelsCreateReqMsg->pixels_pin_neopixel);
return false;
}
WS_DEBUG_PRINT("Created NeoPixel strand of length ");
WS_DEBUG_PRINT(pixelsCreateReqMsg->pixels_num);
WS_DEBUG_PRINT(" on GPIO #");
WS_DEBUG_PRINTLN(pixelsCreateReqMsg->pixels_pin_neopixel);
#ifdef USE_DISPLAY
char buffer[100];
snprintf(buffer, 100, "[Pixel] Added NeoPixel strand on Pin %s\n.",
pixelsCreateReqMsg->pixels_pin_neopixel);
WS._ui_helper->add_text_to_terminal(buffer);
#endif
publishAddStrandResponse(true, pixelsCreateReqMsg->pixels_pin_neopixel);
} else if (pixelsCreateReqMsg->pixels_type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_DOTSTAR) {
// release the status dotstar, if it is both in-use and the pin within
// `pixelsCreateReqMsg`
if ((strands[strandIdx].pinDotStarData == getStatusDotStarDataPin()) &&
WS.lockStatusDotStar) {
releaseStatusLED();
}
// Create Dotstar strand
strands[strandIdx].dotStarPtr = new Adafruit_DotStar(
strands[strandIdx].numPixels, strands[strandIdx].pinDotStarData,
strands[strandIdx].pinDotStarClock,
getDotStarStrandOrder(strands[strandIdx].ordering));
// initialize strand
strands[strandIdx].dotStarPtr->begin();
strands[strandIdx].dotStarPtr->setBrightness(strands[strandIdx].brightness);
strands[strandIdx].dotStarPtr->clear();
strands[strandIdx].dotStarPtr->show();
// post-init sanity check
if (strands[strandIdx].dotStarPtr->numPixels() == 0) {
publishAddStrandResponse(false,
pixelsCreateReqMsg->pixels_pin_dotstar_data);
return false;
}
WS_DEBUG_PRINT("Created DotStar strand of length ");
WS_DEBUG_PRINT(strands[strandIdx].numPixels);
WS_DEBUG_PRINT(" on Data GPIO #");
WS_DEBUG_PRINTLN(strands[strandIdx].pinDotStarData);
#ifdef USE_DISPLAY
char buffer[100];
snprintf(buffer, 100, "[Pixel] Added NeoPixel strand on Pin %s\n.",
pixelsCreateReqMsg->pixels_pin_neopixel);
WS._ui_helper->add_text_to_terminal(buffer);
#endif
publishAddStrandResponse(true, pixelsCreateReqMsg->pixels_pin_dotstar_data);
} else {
WS_DEBUG_PRINTLN("ERROR: Invalid strand type provided!");
publishAddStrandResponse(false,
pixelsCreateReqMsg->pixels_pin_dotstar_data);
return false;
}
return true;
}
/**************************************************************************/
/*!
@brief Obtains the index of a `strand_t` within array of `strands`.
@param dataPin
strand_t's data dataPin
@param type
Type of strand_t, NeoPixel or DotStar.
@returns The index of a strand_t if within strands[],
ERR_INVALID_STRAND otherwise.
*/
/**************************************************************************/
int ws_pixels::getStrandIdx(int16_t dataPin,
wippersnapper_pixels_v1_PixelsType type) {
for (size_t strandIdx = 0; strandIdx < sizeof(strands) / sizeof(strands[0]);
strandIdx++) {
if (type == wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_NEOPIXEL &&
strands[strandIdx].pinNeoPixel == dataPin)
return strandIdx;
if (type == wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_DOTSTAR &&
strands[strandIdx].pinDotStarData == dataPin)
return strandIdx;
}
return ERR_INVALID_STRAND;
}
/**************************************************************************/
/*!
@brief Deletes a `strand_t` from `strands`, deinitializes a strand,
and frees its resources.
@param pixelsDeleteMsg
Protobuf message from Adafruit IO containing a
`wippersnapper_pixels_v1_PixelsDeleteRequest`.
*/
/**************************************************************************/
void ws_pixels::deleteStrand(
wippersnapper_pixels_v1_PixelsDeleteRequest *pixelsDeleteMsg) {
int strandIdx = getStrandIdx(atoi(pixelsDeleteMsg->pixels_pin_data + 1),
pixelsDeleteMsg->pixels_type);
if (strandIdx == ERR_INVALID_STRAND) {
WS_DEBUG_PRINTLN("ERROR: Strand not found, unable to delete strand!");
return;
}
// deallocate and release resources of strand object
deallocateStrand(strandIdx);
WS_DEBUG_PRINT("Deleted strand on data pin ");
WS_DEBUG_PRINTLN(pixelsDeleteMsg->pixels_pin_data);
#ifdef USE_DISPLAY
char buffer[100];
snprintf(buffer, 100, "[Pixel] Deleted strand on pin %s\n.",
pixelsDeleteMsg->pixels_pin_data);
WS._ui_helper->add_text_to_terminal(buffer);
#endif
}
/**************************************************************************/
/*!
@brief Gets the gamma-corrected color, provided a pixel_color
@param pixel_color
Strand's color from Adafruit IO.
@param strand
Desired strand struct. to access.
@returns A gamma-corrected strand color
*/
/**************************************************************************/
uint32_t ws_pixels::getGammaCorrectedColor(uint32_t pixel_color,
strand_s strand) {
if (strand.neoPixelPtr != nullptr) {
return strand.neoPixelPtr->gamma32(pixel_color);
} else if (strand.dotStarPtr != nullptr) {
return strand.dotStarPtr->gamma32(pixel_color);
} else {
WS_DEBUG_PRINTLN(
"ERROR: Unable to perform gamma correction, unknown strand type!");
return 0;
}
}
/**************************************************************************/
/*!
@brief Writes a color from Adafruit IO to a strand of
addressable pixels
@param pixelsWriteMsg
Protobuf message from Adafruit IO containing a
`wippersnapper_pixels_v1_PixelsWriteRequest`.
*/
/**************************************************************************/
void ws_pixels::fillStrand(
wippersnapper_pixels_v1_PixelsWriteRequest *pixelsWriteMsg) {
// Get index of pixel strand
int strandIdx = getStrandIdx(atoi(pixelsWriteMsg->pixels_pin_data + 1),
pixelsWriteMsg->pixels_type);
if (strandIdx == ERR_INVALID_STRAND) {
WS_DEBUG_PRINTLN(
"ERROR: Pixel strand not found, can not write a color to the strand!");
return;
}
uint32_t rgbColorGamma =
getGammaCorrectedColor(pixelsWriteMsg->pixels_color, strands[strandIdx]);
WS_DEBUG_PRINT("Filling color: ");
WS_DEBUG_PRINTLN(pixelsWriteMsg->pixels_color);
#ifdef USE_DISPLAY
char buffer[100];
snprintf(buffer, 100, "[Pixel] Filling strand on pin %s with color %u\n",
pixelsWriteMsg->pixels_pin_data,
(unsigned int)pixelsWriteMsg->pixels_color);
WS._ui_helper->add_text_to_terminal(buffer);
#endif
if (pixelsWriteMsg->pixels_type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_NEOPIXEL) {
strands[strandIdx].neoPixelPtr->fill(rgbColorGamma);
strands[strandIdx].neoPixelPtr->show();
} else if (pixelsWriteMsg->pixels_type ==
wippersnapper_pixels_v1_PixelsType_PIXELS_TYPE_DOTSTAR) {
strands[strandIdx].dotStarPtr->fill(rgbColorGamma);
strands[strandIdx].dotStarPtr->show();
} else {
WS_DEBUG_PRINTLN("ERROR: Unable to determine pixel type to write to!");
}
}

View file

@ -1,215 +1,215 @@
/*!
* @file ws_uart_drv_pm25aqi.h
*
* WipperSnapper device driver for the Adafruit_PM25AQI Arduino Library
*
* Adafruit invests time and resources providing this open source code,
* please support Adafruit and open-source hardware by purchasing
* products from Adafruit!
*
* Copyright (c) Brent Rubell 2023 for Adafruit Industries.
*
* MIT license, all text here must be included in any redistribution.
*
*/
#ifndef WS_UART_DRV_PM25AQI_H
#define WS_UART_DRV_PM25AQI_H
#include "Wippersnapper.h"
#include "ws_uart_drv.h"
#include <Adafruit_PM25AQI.h>
/**************************************************************************/
/*!
@brief Class that provides an interface for a PM25 AQI UART sensor.
*/
/**************************************************************************/
class ws_uart_drv_pm25aqi : public ws_uart_drv {
public:
#ifdef USE_SW_UART
/*******************************************************************************/
/*!
@brief Initializes a PM25AQI UART device driver.
@param swSerial
Pointer to an instance of a SoftwareSerial object.
@param pollingInterval
How often the PM25AQI device will be polled, in milliseconds.
*/
/*******************************************************************************/
ws_uart_drv_pm25aqi(SoftwareSerial *swSerial, int32_t interval)
: ws_uart_drv(swSerial, interval) {
_swSerial = swSerial;
pollingInterval = (unsigned long)interval;
};
#else
/*******************************************************************************/
/*!
@brief Initializes the PM25AQI UART device driver.
@param hwSerial
Pointer to an instance of a HardwareSerial object.
@param interval
How often the PM25AQI device will be polled, in milliseconds.
*/
/*******************************************************************************/
ws_uart_drv_pm25aqi(HardwareSerial *hwSerial, int32_t interval)
: ws_uart_drv(hwSerial, interval) {
_hwSerial = hwSerial;
pollingInterval = (unsigned long)interval;
};
#endif // USE_SW_UART
/*******************************************************************************/
/*!
@brief Destructor for a PM25AQI sensor.
*/
/*******************************************************************************/
~ws_uart_drv_pm25aqi() {
delete _aqi;
#ifdef USE_SW_UART
_swSerial = nullptr;
#else
_hwSerial = nullptr;
#endif
}
/*******************************************************************************/
/*!
@brief Initializes a PM25AQI sensor.
@returns True if the PM25AQI sensor was successfully initialized,
False otherwise.
*/
/*******************************************************************************/
bool begin() override {
_aqi = new Adafruit_PM25AQI();
#ifdef USE_SW_UART
if (!_aqi->begin_UART(
_swSerial)) { // connect to the sensor over software serial
return false;
}
#else
if (!_aqi->begin_UART(
_hwSerial)) { // connect to the sensor over hardware serial
return false;
}
#endif
return true;
}
/*******************************************************************************/
/*!
@brief Attempts to read data from the PM25AQI sensor.
@returns True if data was successfully read, False otherwise.
*/
/*******************************************************************************/
bool read_data() override {
Serial.println("[UART, PM25] Reading data...");
// Attempt to read the PM2.5 Sensor
if (!_aqi->read(&_data)) {
Serial.println("[UART, PM25] Data not available.");
delay(500);
return false;
}
Serial.println("[UART, PM25] Read data OK");
Serial.println();
Serial.println(F("---------------------------------------"));
Serial.println(F("Concentration Units (standard)"));
Serial.println(F("---------------------------------------"));
Serial.print(F("PM 1.0: "));
Serial.print(_data.pm10_standard);
Serial.print(F("\t\tPM 2.5: "));
Serial.print(_data.pm25_standard);
Serial.print(F("\t\tPM 10: "));
Serial.println(_data.pm100_standard);
Serial.println(F("Concentration Units (environmental)"));
Serial.println(F("---------------------------------------"));
Serial.print(F("PM 1.0: "));
Serial.print(_data.pm10_env);
Serial.print(F("\t\tPM 2.5: "));
Serial.print(_data.pm25_env);
Serial.print(F("\t\tPM 10: "));
Serial.println(_data.pm100_env);
Serial.println(F("---------------------------------------"));
return true;
}
/*******************************************************************************/
/*!
@brief Packs and sends the device's event data to Adafruit IO.
*/
/*******************************************************************************/
void send_data() override {
// Create a new UART response message
wippersnapper_signal_v1_UARTResponse msgUARTResponse =
wippersnapper_signal_v1_UARTResponse_init_zero;
msgUARTResponse.which_payload =
wippersnapper_signal_v1_UARTResponse_resp_uart_device_event_tag;
strcpy(msgUARTResponse.payload.resp_uart_device_event.device_id,
getDriverID());
// check if driverID is pm1006
if (strcmp(getDriverID(), "pm1006") == 0) {
// PM1006 returns only PM2.5_ENV readings
msgUARTResponse.payload.resp_uart_device_event.sensor_event_count = 1;
packUARTResponse(&msgUARTResponse, 0,
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_PM25_ENV,
(float)_data.pm25_env);
} else {
msgUARTResponse.payload.resp_uart_device_event.sensor_event_count = 6;
packUARTResponse(&msgUARTResponse, 0,
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_PM10_STD,
(float)_data.pm10_standard);
packUARTResponse(&msgUARTResponse, 1,
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_PM25_STD,
(float)_data.pm25_standard);
packUARTResponse(&msgUARTResponse, 2,
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_PM100_STD,
(float)_data.pm100_standard);
packUARTResponse(&msgUARTResponse, 3,
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_PM10_ENV,
(float)_data.pm10_env);
packUARTResponse(&msgUARTResponse, 4,
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_PM25_ENV,
(float)_data.pm25_env);
packUARTResponse(&msgUARTResponse, 5,
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_PM100_ENV,
(float)_data.pm100_env);
}
// Encode message data
uint8_t mqttBuffer[512] = {0};
pb_ostream_t ostream =
pb_ostream_from_buffer(mqttBuffer, sizeof(mqttBuffer));
if (!ws_pb_encode(&ostream, wippersnapper_signal_v1_UARTResponse_fields,
&msgUARTResponse)) {
Serial.println("[ERROR, UART]: Unable to encode device response!");
return;
}
// Publish message to IO
size_t msgSz;
pb_get_encoded_size(&msgSz, wippersnapper_signal_v1_UARTResponse_fields,
&msgUARTResponse);
Serial.print("[UART] Publishing event to IO..");
mqttClient->publish(uartTopic, mqttBuffer, msgSz, 1);
Serial.println("Published!");
setPrvPollTime(millis());
}
protected:
Adafruit_PM25AQI *_aqi = nullptr; ///< Pointer to PM25AQI sensor object
PM25_AQI_Data _data; ///< PM25AQI sensor data struct.
#ifdef USE_SW_UART
SoftwareSerial *_swSerial = nullptr; ///< Pointer to Software UART interface
#else
HardwareSerial *_hwSerial = nullptr; ///< Pointer to Hardware UART interface
#endif
};
/*!
* @file ws_uart_drv_pm25aqi.h
*
* WipperSnapper device driver for the Adafruit_PM25AQI Arduino Library
*
* Adafruit invests time and resources providing this open source code,
* please support Adafruit and open-source hardware by purchasing
* products from Adafruit!
*
* Copyright (c) Brent Rubell 2023 for Adafruit Industries.
*
* MIT license, all text here must be included in any redistribution.
*
*/
#ifndef WS_UART_DRV_PM25AQI_H
#define WS_UART_DRV_PM25AQI_H
#include "Wippersnapper.h"
#include "ws_uart_drv.h"
#include <Adafruit_PM25AQI.h>
/**************************************************************************/
/*!
@brief Class that provides an interface for a PM25 AQI UART sensor.
*/
/**************************************************************************/
class ws_uart_drv_pm25aqi : public ws_uart_drv {
public:
#ifdef USE_SW_UART
/*******************************************************************************/
/*!
@brief Initializes a PM25AQI UART device driver.
@param swSerial
Pointer to an instance of a SoftwareSerial object.
@param pollingInterval
How often the PM25AQI device will be polled, in milliseconds.
*/
/*******************************************************************************/
ws_uart_drv_pm25aqi(SoftwareSerial *swSerial, int32_t interval)
: ws_uart_drv(swSerial, interval) {
_swSerial = swSerial;
pollingInterval = (unsigned long)interval;
};
#else
/*******************************************************************************/
/*!
@brief Initializes the PM25AQI UART device driver.
@param hwSerial
Pointer to an instance of a HardwareSerial object.
@param interval
How often the PM25AQI device will be polled, in milliseconds.
*/
/*******************************************************************************/
ws_uart_drv_pm25aqi(HardwareSerial *hwSerial, int32_t interval)
: ws_uart_drv(hwSerial, interval) {
_hwSerial = hwSerial;
pollingInterval = (unsigned long)interval;
};
#endif // USE_SW_UART
/*******************************************************************************/
/*!
@brief Destructor for a PM25AQI sensor.
*/
/*******************************************************************************/
~ws_uart_drv_pm25aqi() {
delete _aqi;
#ifdef USE_SW_UART
_swSerial = nullptr;
#else
_hwSerial = nullptr;
#endif
}
/*******************************************************************************/
/*!
@brief Initializes a PM25AQI sensor.
@returns True if the PM25AQI sensor was successfully initialized,
False otherwise.
*/
/*******************************************************************************/
bool begin() override {
_aqi = new Adafruit_PM25AQI();
#ifdef USE_SW_UART
if (!_aqi->begin_UART(
_swSerial)) { // connect to the sensor over software serial
return false;
}
#else
if (!_aqi->begin_UART(
_hwSerial)) { // connect to the sensor over hardware serial
return false;
}
#endif
return true;
}
/*******************************************************************************/
/*!
@brief Attempts to read data from the PM25AQI sensor.
@returns True if data was successfully read, False otherwise.
*/
/*******************************************************************************/
bool read_data() override {
Serial.println("[UART, PM25] Reading data...");
// Attempt to read the PM2.5 Sensor
if (!_aqi->read(&_data)) {
Serial.println("[UART, PM25] Data not available.");
delay(500);
return false;
}
Serial.println("[UART, PM25] Read data OK");
Serial.println();
Serial.println(F("---------------------------------------"));
Serial.println(F("Concentration Units (standard)"));
Serial.println(F("---------------------------------------"));
Serial.print(F("PM 1.0: "));
Serial.print(_data.pm10_standard);
Serial.print(F("\t\tPM 2.5: "));
Serial.print(_data.pm25_standard);
Serial.print(F("\t\tPM 10: "));
Serial.println(_data.pm100_standard);
Serial.println(F("Concentration Units (environmental)"));
Serial.println(F("---------------------------------------"));
Serial.print(F("PM 1.0: "));
Serial.print(_data.pm10_env);
Serial.print(F("\t\tPM 2.5: "));
Serial.print(_data.pm25_env);
Serial.print(F("\t\tPM 10: "));
Serial.println(_data.pm100_env);
Serial.println(F("---------------------------------------"));
return true;
}
/*******************************************************************************/
/*!
@brief Packs and sends the device's event data to Adafruit IO.
*/
/*******************************************************************************/
void send_data() override {
// Create a new UART response message
wippersnapper_signal_v1_UARTResponse msgUARTResponse =
wippersnapper_signal_v1_UARTResponse_init_zero;
msgUARTResponse.which_payload =
wippersnapper_signal_v1_UARTResponse_resp_uart_device_event_tag;
strcpy(msgUARTResponse.payload.resp_uart_device_event.device_id,
getDriverID());
// check if driverID is pm1006
if (strcmp(getDriverID(), "pm1006") == 0) {
// PM1006 returns only PM2.5_ENV readings
msgUARTResponse.payload.resp_uart_device_event.sensor_event_count = 1;
packUARTResponse(&msgUARTResponse, 0,
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_PM25_ENV,
(float)_data.pm25_env);
} else {
msgUARTResponse.payload.resp_uart_device_event.sensor_event_count = 6;
packUARTResponse(&msgUARTResponse, 0,
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_PM10_STD,
(float)_data.pm10_standard);
packUARTResponse(&msgUARTResponse, 1,
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_PM25_STD,
(float)_data.pm25_standard);
packUARTResponse(&msgUARTResponse, 2,
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_PM100_STD,
(float)_data.pm100_standard);
packUARTResponse(&msgUARTResponse, 3,
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_PM10_ENV,
(float)_data.pm10_env);
packUARTResponse(&msgUARTResponse, 4,
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_PM25_ENV,
(float)_data.pm25_env);
packUARTResponse(&msgUARTResponse, 5,
wippersnapper_i2c_v1_SensorType_SENSOR_TYPE_PM100_ENV,
(float)_data.pm100_env);
}
// Encode message data
uint8_t mqttBuffer[512] = {0};
pb_ostream_t ostream =
pb_ostream_from_buffer(mqttBuffer, sizeof(mqttBuffer));
if (!ws_pb_encode(&ostream, wippersnapper_signal_v1_UARTResponse_fields,
&msgUARTResponse)) {
Serial.println("[ERROR, UART]: Unable to encode device response!");
return;
}
// Publish message to IO
size_t msgSz;
pb_get_encoded_size(&msgSz, wippersnapper_signal_v1_UARTResponse_fields,
&msgUARTResponse);
Serial.print("[UART] Publishing event to IO..");
mqttClient->publish(uartTopic, mqttBuffer, msgSz, 1);
Serial.println("Published!");
setPrvPollTime(millis());
}
protected:
Adafruit_PM25AQI *_aqi = nullptr; ///< Pointer to PM25AQI sensor object
PM25_AQI_Data _data; ///< PM25AQI sensor data struct.
#ifdef USE_SW_UART
SoftwareSerial *_swSerial = nullptr; ///< Pointer to Software UART interface
#else
HardwareSerial *_hwSerial = nullptr; ///< Pointer to Hardware UART interface
#endif
};
#endif // WS_UART_DRV_PM25AQI_H

View file

@ -1,284 +1,284 @@
/*!
* @file Wippersnapper_WIFININA.h
*
* Network interface for the ublox wifi module on the
* Arduino MKR WiFi 1010, Arduino Nano 33 IoT and Arduino UNO WiFi Rev.2.
*
* Adafruit invests time and resources providing this open source code,
* please support Adafruit and open-source hardware by purchasing
* products from Adafruit!
*
* Copyright (c) Brent Rubell 2021 for Adafruit Industries.
*
* MIT license, all text here must be included in any redistribution.
*
*/
#ifndef WIPPERSNAPPER_WIFININA_H
#define WIPPERSNAPPER_WIFININA_H
#include <Adafruit_MQTT.h>
#include <Adafruit_MQTT_Client.h>
#include <Arduino.h>
#include <SPI.h>
#include <WiFiNINA.h>
#include "Wippersnapper.h"
#define SPIWIFI \
SPI /*!< Instance of SPI interface used by an external uBlox module. */
extern Wippersnapper WS;
/****************************************************************************/
/*!
@brief Class for using the AirLift Co-Processor network iface.
*/
/****************************************************************************/
class Wippersnapper_WIFININA : public Wippersnapper {
public:
/**************************************************************************/
/*!
@brief Initializes the Adafruit IO class for ublox devices.
@param aioUsername
Adafruit IO username
@param aioKey
Adafruit IO key
@param netSSID
Wireless Network SSID
@param netPass
Wireless Network password
*/
/**************************************************************************/
Wippersnapper_WIFININA(const char *aioUsername, const char *aioKey,
const char *netSSID, const char *netPass)
: Wippersnapper() {
_ssid = netSSID;
_pass = netPass;
_username = aioUsername;
_key = aioKey;
_wifi = &SPIWIFI;
_mqtt_client = new WiFiSSLClient;
}
/**************************************************************************/
/*!
@brief Destructor for the Adafruit IO ublox class.
*/
/**************************************************************************/
~Wippersnapper_WIFININA() {
if (_mqtt)
delete _mqtt;
}
/****************************************************************************/
/*!
@brief Configures the device's Adafruit IO credentials. This method
should be used only if filesystem-backed provisioning is
not avaliable.
*/
/****************************************************************************/
void set_user_key() {
strlcpy(WS._config.aio_user, _username, sizeof(WS._config.aio_user));
strlcpy(WS._config.aio_key, _key, sizeof(WS._config.aio_key));
}
/**********************************************************/
/*!
@brief Sets the WiFi client's ssid and password.
@param ssid
Wireless network's SSID.
@param ssidPassword
Wireless network's password.
*/
/**********************************************************/
void set_ssid_pass(const char *ssid, const char *ssidPassword) {
strlcpy(WS._config.network.ssid, ssid, sizeof(WS._config.network.ssid));
strlcpy(WS._config.network.pass, ssidPassword,
sizeof(WS._config.network.pass));
}
/**********************************************************/
/*!
@brief Sets the WiFi client's ssid and password from the
header file's credentials.
*/
/**********************************************************/
void set_ssid_pass() {
strlcpy(WS._config.network.ssid, _ssid, sizeof(WS._config.network.ssid));
strlcpy(WS._config.network.pass, _pass, sizeof(WS._config.network.pass));
}
/***********************************************************/
/*!
@brief Performs a scan of local WiFi networks.
@returns True if `_network_ssid` is found, False otherwise.
*/
/***********************************************************/
bool check_valid_ssid() {
// Set WiFi to station mode and disconnect from an AP if it was previously
// connected
WiFi.disconnect();
delay(100);
// Perform a network scan
int n = WiFi.scanNetworks();
if (n == 0) {
WS_DEBUG_PRINTLN("ERROR: No WiFi networks found!");
return false;
}
// Was the network within secrets.json found?
for (int i = 0; i < n; ++i) {
if (strcmp(_ssid, WiFi.SSID(i)) == 0) {
return true;
}
}
// User-set network not found, print scan results to serial console
WS_DEBUG_PRINTLN("ERROR: Your requested WiFi network was not found!");
WS_DEBUG_PRINTLN("WipperSnapper found these WiFi networks: ");
for (int i = 0; i < n; ++i) {
WS_DEBUG_PRINT(WiFi.SSID(i));
WS_DEBUG_PRINT(" ");
WS_DEBUG_PRINT(WiFi.RSSI(i));
WS_DEBUG_PRINTLN("dB");
}
return false;
}
/********************************************************/
/*!
@brief Sets the WiFi client.
@param wifi
Instance of SPIClass.
*/
/********************************************************/
void set_wifi(SPIClass *wifi) {
_wifi = wifi;
_mqtt_client = new WiFiSSLClient;
}
/***********************************************************/
/*!
@brief Checks the nina-fw version on the module.
@return True if firmware on the ublox module matches
the latest version of the library, False otherwise.
*/
/***********************************************************/
bool firmwareCheck() {
String fv = WiFi.firmwareVersion();
if (fv < WIFI_FIRMWARE_LATEST_VERSION)
return false;
return true;
}
/********************************************************/
/*!
@brief Gets the ESP32's unique client identifier.
@note For the ESP32, the UID is the MAC address.
*/
/********************************************************/
void getMacAddr() {
uint8_t mac[6] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00};
WiFi.macAddress(mac);
memcpy(WS._macAddr, mac, sizeof(mac));
}
/********************************************************/
/*!
@brief Gets the current network RSSI value
@return int32_t RSSI value
*/
/********************************************************/
int32_t getRSSI() { return WiFi.RSSI(); }
/********************************************************/
/*!
@brief Initializes the MQTT client.
@param clientID
MQTT client identifier
*/
/********************************************************/
void setupMQTTClient(const char *clientID) {
WS._mqtt = new Adafruit_MQTT_Client(
_mqtt_client, WS._config.aio_url, WS._config.io_port, clientID,
WS._config.aio_user, WS._config.aio_key);
}
/********************************************************/
/*!
@brief Returns the network status of an ESP32 module.
@return ws_status_t
*/
/********************************************************/
ws_status_t networkStatus() {
switch (WiFi.status()) {
case WL_CONNECTED:
return WS_NET_CONNECTED;
case WL_CONNECT_FAILED:
return WS_NET_CONNECT_FAILED;
case WL_IDLE_STATUS:
return WS_IDLE;
default:
return WS_NET_DISCONNECTED;
}
}
/*******************************************************************/
/*!
@brief Returns the type of network connection used by Wippersnapper
@return AIRLIFT
*/
/*******************************************************************/
const char *connectionType() { return "AIRLIFT"; }
protected:
const char *_ssid; /*!< Network SSID. */
const char *_pass; /*!< Network password. */
const char *_username; /*!< Adafruit IO username. */
const char *_key; /*!< Adafruit IO key. */
WiFiSSLClient *_mqtt_client; /*!< Instance of a secure WiFi client. */
SPIClass *_wifi; /*!< Instance of the SPI bus used by the ublox. */
/**************************************************************************/
/*!
@brief Establishes a connection with the wireless network.
*/
/**************************************************************************/
void _connect() {
// check if co-processor connected first
if (WiFi.status() == WL_NO_MODULE)
errorWriteHang("No WiFi Module Detected!");
// validate the nina-fw version
if (!firmwareCheck())
errorWriteHang("Please upgrade the firmware on the ESP module to the "
"latest version.");
if (strlen(_ssid) == 0) {
_status = WS_SSID_INVALID;
} else {
// disconnect from possible previous connection
_disconnect();
WiFi.begin(_ssid, _pass);
_status = WS_NET_DISCONNECTED;
}
}
/**************************************************************************/
/*!
@brief Disconnects from the wireless network.
*/
/**************************************************************************/
void _disconnect() {
WiFi.disconnect();
delay(500);
}
};
/*!
* @file Wippersnapper_WIFININA.h
*
* Network interface for the ublox wifi module on the
* Arduino MKR WiFi 1010, Arduino Nano 33 IoT and Arduino UNO WiFi Rev.2.
*
* Adafruit invests time and resources providing this open source code,
* please support Adafruit and open-source hardware by purchasing
* products from Adafruit!
*
* Copyright (c) Brent Rubell 2021 for Adafruit Industries.
*
* MIT license, all text here must be included in any redistribution.
*
*/
#ifndef WIPPERSNAPPER_WIFININA_H
#define WIPPERSNAPPER_WIFININA_H
#include <Adafruit_MQTT.h>
#include <Adafruit_MQTT_Client.h>
#include <Arduino.h>
#include <SPI.h>
#include <WiFiNINA.h>
#include "Wippersnapper.h"
#define SPIWIFI \
SPI /*!< Instance of SPI interface used by an external uBlox module. */
extern Wippersnapper WS;
/****************************************************************************/
/*!
@brief Class for using the AirLift Co-Processor network iface.
*/
/****************************************************************************/
class Wippersnapper_WIFININA : public Wippersnapper {
public:
/**************************************************************************/
/*!
@brief Initializes the Adafruit IO class for ublox devices.
@param aioUsername
Adafruit IO username
@param aioKey
Adafruit IO key
@param netSSID
Wireless Network SSID
@param netPass
Wireless Network password
*/
/**************************************************************************/
Wippersnapper_WIFININA(const char *aioUsername, const char *aioKey,
const char *netSSID, const char *netPass)
: Wippersnapper() {
_ssid = netSSID;
_pass = netPass;
_username = aioUsername;
_key = aioKey;
_wifi = &SPIWIFI;
_mqtt_client = new WiFiSSLClient;
}
/**************************************************************************/
/*!
@brief Destructor for the Adafruit IO ublox class.
*/
/**************************************************************************/
~Wippersnapper_WIFININA() {
if (_mqtt)
delete _mqtt;
}
/****************************************************************************/
/*!
@brief Configures the device's Adafruit IO credentials. This method
should be used only if filesystem-backed provisioning is
not avaliable.
*/
/****************************************************************************/
void set_user_key() {
strlcpy(WS._config.aio_user, _username, sizeof(WS._config.aio_user));
strlcpy(WS._config.aio_key, _key, sizeof(WS._config.aio_key));
}
/**********************************************************/
/*!
@brief Sets the WiFi client's ssid and password.
@param ssid
Wireless network's SSID.
@param ssidPassword
Wireless network's password.
*/
/**********************************************************/
void set_ssid_pass(const char *ssid, const char *ssidPassword) {
strlcpy(WS._config.network.ssid, ssid, sizeof(WS._config.network.ssid));
strlcpy(WS._config.network.pass, ssidPassword,
sizeof(WS._config.network.pass));
}
/**********************************************************/
/*!
@brief Sets the WiFi client's ssid and password from the
header file's credentials.
*/
/**********************************************************/
void set_ssid_pass() {
strlcpy(WS._config.network.ssid, _ssid, sizeof(WS._config.network.ssid));
strlcpy(WS._config.network.pass, _pass, sizeof(WS._config.network.pass));
}
/***********************************************************/
/*!
@brief Performs a scan of local WiFi networks.
@returns True if `_network_ssid` is found, False otherwise.
*/
/***********************************************************/
bool check_valid_ssid() {
// Set WiFi to station mode and disconnect from an AP if it was previously
// connected
WiFi.disconnect();
delay(100);
// Perform a network scan
int n = WiFi.scanNetworks();
if (n == 0) {
WS_DEBUG_PRINTLN("ERROR: No WiFi networks found!");
return false;
}
// Was the network within secrets.json found?
for (int i = 0; i < n; ++i) {
if (strcmp(_ssid, WiFi.SSID(i)) == 0) {
return true;
}
}
// User-set network not found, print scan results to serial console
WS_DEBUG_PRINTLN("ERROR: Your requested WiFi network was not found!");
WS_DEBUG_PRINTLN("WipperSnapper found these WiFi networks: ");
for (int i = 0; i < n; ++i) {
WS_DEBUG_PRINT(WiFi.SSID(i));
WS_DEBUG_PRINT(" ");
WS_DEBUG_PRINT(WiFi.RSSI(i));
WS_DEBUG_PRINTLN("dB");
}
return false;
}
/********************************************************/
/*!
@brief Sets the WiFi client.
@param wifi
Instance of SPIClass.
*/
/********************************************************/
void set_wifi(SPIClass *wifi) {
_wifi = wifi;
_mqtt_client = new WiFiSSLClient;
}
/***********************************************************/
/*!
@brief Checks the nina-fw version on the module.
@return True if firmware on the ublox module matches
the latest version of the library, False otherwise.
*/
/***********************************************************/
bool firmwareCheck() {
String fv = WiFi.firmwareVersion();
if (fv < WIFI_FIRMWARE_LATEST_VERSION)
return false;
return true;
}
/********************************************************/
/*!
@brief Gets the ESP32's unique client identifier.
@note For the ESP32, the UID is the MAC address.
*/
/********************************************************/
void getMacAddr() {
uint8_t mac[6] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00};
WiFi.macAddress(mac);
memcpy(WS._macAddr, mac, sizeof(mac));
}
/********************************************************/
/*!
@brief Gets the current network RSSI value
@return int32_t RSSI value
*/
/********************************************************/
int32_t getRSSI() { return WiFi.RSSI(); }
/********************************************************/
/*!
@brief Initializes the MQTT client.
@param clientID
MQTT client identifier
*/
/********************************************************/
void setupMQTTClient(const char *clientID) {
WS._mqtt = new Adafruit_MQTT_Client(
_mqtt_client, WS._config.aio_url, WS._config.io_port, clientID,
WS._config.aio_user, WS._config.aio_key);
}
/********************************************************/
/*!
@brief Returns the network status of an ESP32 module.
@return ws_status_t
*/
/********************************************************/
ws_status_t networkStatus() {
switch (WiFi.status()) {
case WL_CONNECTED:
return WS_NET_CONNECTED;
case WL_CONNECT_FAILED:
return WS_NET_CONNECT_FAILED;
case WL_IDLE_STATUS:
return WS_IDLE;
default:
return WS_NET_DISCONNECTED;
}
}
/*******************************************************************/
/*!
@brief Returns the type of network connection used by Wippersnapper
@return AIRLIFT
*/
/*******************************************************************/
const char *connectionType() { return "AIRLIFT"; }
protected:
const char *_ssid; /*!< Network SSID. */
const char *_pass; /*!< Network password. */
const char *_username; /*!< Adafruit IO username. */
const char *_key; /*!< Adafruit IO key. */
WiFiSSLClient *_mqtt_client; /*!< Instance of a secure WiFi client. */
SPIClass *_wifi; /*!< Instance of the SPI bus used by the ublox. */
/**************************************************************************/
/*!
@brief Establishes a connection with the wireless network.
*/
/**************************************************************************/
void _connect() {
// check if co-processor connected first
if (WiFi.status() == WL_NO_MODULE)
errorWriteHang("No WiFi Module Detected!");
// validate the nina-fw version
if (!firmwareCheck())
errorWriteHang("Please upgrade the firmware on the ESP module to the "
"latest version.");
if (strlen(_ssid) == 0) {
_status = WS_SSID_INVALID;
} else {
// disconnect from possible previous connection
_disconnect();
WiFi.begin(_ssid, _pass);
_status = WS_NET_DISCONNECTED;
}
}
/**************************************************************************/
/*!
@brief Disconnects from the wireless network.
*/
/**************************************************************************/
void _disconnect() {
WiFi.disconnect();
delay(500);
}
};
#endif // WIPPERSNAPPER_WIFININA_H