diff --git a/Changelog.md b/Changelog.md index db3772138..1c6c4dd6b 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,4 +1,6 @@ ## [Unreleased] +### Added +- Merge PACE into POCS ## [0.5.1] - 2017-12-02 ### Added diff --git a/resources/arduino_files/camera_board/camera_board.ino b/resources/arduino_files/camera_board/camera_board.ino new file mode 100644 index 000000000..0e6b4529c --- /dev/null +++ b/resources/arduino_files/camera_board/camera_board.ino @@ -0,0 +1,165 @@ +#include +#include +#include +#include +#include + +#define DHT_TYPE DHT22 // DHT 22 (AM2302) + +/* DECLARE PINS */ +const int DHT_PIN = 9; // DHT Temp & Humidity Pin +const int CAM_01_RELAY = 5; +const int CAM_02_RELAY = 6; +const int RESET_PIN = 12; + + +/* CONSTANTS */ +Adafruit_MMA8451 accelerometer = Adafruit_MMA8451(); + +// Setup DHT22 +DHT dht(DHT_PIN, DHT_TYPE); + +int led_value = LOW; + +void setup(void) { + Serial.begin(9600); + Serial.flush(); + + // Turn off LED inside camera box + pinMode(LED_BUILTIN, OUTPUT); + digitalWrite(LED_BUILTIN, LOW); + + // Setup Camera relays + pinMode(CAM_01_RELAY, OUTPUT); + pinMode(CAM_02_RELAY, OUTPUT); + + pinMode(RESET_PIN, OUTPUT); + + // Turn on Camera relays + turn_pin_on(CAM_01_RELAY); + turn_pin_on(CAM_02_RELAY); + + if (! accelerometer.begin()) { + while (1); + } + + dht.begin(); + + // Check Accelerometer range + // accelerometer.setRange(MMA8451_RANGE_2_G); + // Serial.print("Accelerometer Range = "); Serial.print(2 << accelerometer.getRange()); + // Serial.println("G"); +} + +void loop() { + + // Read any serial input + // - Input will be two comma separated integers, the + // first specifying the pin and the second the status + // to change to (1/0). Cameras and debug led are + // supported. + // Example serial input: + // 4,1 # Turn fan on + // 13,0 # Turn led off + while (Serial.available() > 0) { + int pin_num = Serial.parseInt(); + int pin_status = Serial.parseInt(); + + switch (pin_num) { + case CAM_01_RELAY: + case CAM_02_RELAY: + if (pin_status == 1) { + turn_pin_on(pin_num); + } else if (pin_status == 0) { + turn_pin_off(pin_num); + } else if (pin_status == 9) { + toggle_pin(pin_num); + } + break; + case RESET_PIN: + if (pin_status == 1) { + turn_pin_off(RESET_PIN); + } + break; + case LED_BUILTIN: + digitalWrite(pin_num, pin_status); + break; + } + } + + // Begin reading values and outputting as JSON string + Serial.print("{"); + + read_status(); + + read_accelerometer(); + + read_dht_temp(); + + Serial.print("\"name\":\"camera_board\""); Serial.print(","); + + Serial.print("\"count\":"); Serial.print(millis()); + + Serial.println("}"); + + Serial.flush(); + delay(1000); +} + +void read_status() { + + Serial.print("\"power\":{"); + Serial.print("\"camera_00\":"); Serial.print(is_pin_on(CAM_01_RELAY)); Serial.print(','); + Serial.print("\"camera_01\":"); Serial.print(is_pin_on(CAM_02_RELAY)); Serial.print(','); + Serial.print("},"); +} + +/* ACCELEROMETER */ +void read_accelerometer() { + /* Get a new sensor event */ + sensors_event_t event; + accelerometer.getEvent(&event); + uint8_t o = accelerometer.getOrientation(); // Orientation + + Serial.print("\"accelerometer\":{"); + Serial.print("\"x\":"); Serial.print(event.acceleration.x); Serial.print(','); + Serial.print("\"y\":"); Serial.print(event.acceleration.y); Serial.print(','); + Serial.print("\"z\":"); Serial.print(event.acceleration.z); Serial.print(','); + Serial.print("\"o\": "); Serial.print(o); + Serial.print("},"); +} + +//// Reading temperature or humidity takes about 250 milliseconds! +//// Sensor readings may also be up to 2 seconds 'old' (its a very slow sensor) +void read_dht_temp() { + float h = dht.readHumidity(); + float c = dht.readTemperature(); // Celsius + + Serial.print("\"humidity\":"); Serial.print(h); Serial.print(','); + Serial.print("\"temp_00\":"); Serial.print(c); Serial.print(","); +} + +/************************************ +* Utitlity Methods +*************************************/ + +void toggle_led() { + led_value = ! led_value; + digitalWrite(LED_BUILTIN, led_value); +} + +void toggle_pin(int pin_num) { + digitalWrite(pin_num, !digitalRead(pin_num)); +} + +void turn_pin_on(int camera_pin) { + digitalWrite(camera_pin, HIGH); +} + +void turn_pin_off(int camera_pin) { + digitalWrite(camera_pin, LOW); +} + +int is_pin_on(int camera_pin) { + return digitalRead(camera_pin); +} diff --git a/resources/arduino_files/libraries/Adafruit_MMA8451/Adafruit_MMA8451.cpp b/resources/arduino_files/libraries/Adafruit_MMA8451/Adafruit_MMA8451.cpp new file mode 100644 index 000000000..74f1556d6 --- /dev/null +++ b/resources/arduino_files/libraries/Adafruit_MMA8451/Adafruit_MMA8451.cpp @@ -0,0 +1,258 @@ +/**************************************************************************/ +/*! + @file Adafruit_MMA8451.h + @author K. Townsend (Adafruit Industries) + @license BSD (see license.txt) + + This is a library for the Adafruit MMA8451 Accel breakout board + ----> https://www.adafruit.com/products/2019 + + Adafruit invests time and resources providing this open source code, + please support Adafruit and open-source hardware by purchasing + products from Adafruit! + + @section HISTORY + + v1.0 - First release +*/ +/**************************************************************************/ + +#if ARDUINO >= 100 + #include "Arduino.h" +#else + #include "WProgram.h" +#endif + +#include +#include + +/**************************************************************************/ +/*! + @brief Abstract away platform differences in Arduino wire library +*/ +/**************************************************************************/ +static inline uint8_t i2cread(void) { + #if ARDUINO >= 100 + return Wire.read(); + #else + return Wire.receive(); + #endif +} + +static inline void i2cwrite(uint8_t x) { + #if ARDUINO >= 100 + Wire.write((uint8_t)x); + #else + Wire.send(x); + #endif +} + + +/**************************************************************************/ +/*! + @brief Writes 8-bits to the specified destination register +*/ +/**************************************************************************/ +void Adafruit_MMA8451::writeRegister8(uint8_t reg, uint8_t value) { + Wire.beginTransmission(_i2caddr); + i2cwrite((uint8_t)reg); + i2cwrite((uint8_t)(value)); + Wire.endTransmission(); +} + +/**************************************************************************/ +/*! + @brief Reads 8-bits from the specified register +*/ +/**************************************************************************/ +uint8_t Adafruit_MMA8451::readRegister8(uint8_t reg) { + Wire.beginTransmission(_i2caddr); + i2cwrite(reg); + Wire.endTransmission(false); // MMA8451 + friends uses repeated start!! + + Wire.requestFrom(_i2caddr, 1); + if (! Wire.available()) return -1; + return (i2cread()); +} + +/**************************************************************************/ +/*! + @brief Instantiates a new MMA8451 class in I2C mode +*/ +/**************************************************************************/ +Adafruit_MMA8451::Adafruit_MMA8451(int32_t sensorID) { + _sensorID = sensorID; +} + +/**************************************************************************/ +/*! + @brief Setups the HW (reads coefficients values, etc.) +*/ +/**************************************************************************/ +bool Adafruit_MMA8451::begin(uint8_t i2caddr) { + Wire.begin(); + _i2caddr = i2caddr; + + /* Check connection */ + uint8_t deviceid = readRegister8(MMA8451_REG_WHOAMI); + if (deviceid != 0x1A) + { + /* No MMA8451 detected ... return false */ + //Serial.println(deviceid, HEX); + return false; + } + + writeRegister8(MMA8451_REG_CTRL_REG2, 0x40); // reset + + while (readRegister8(MMA8451_REG_CTRL_REG2) & 0x40); + + // enable 4G range + writeRegister8(MMA8451_REG_XYZ_DATA_CFG, MMA8451_RANGE_4_G); + // High res + writeRegister8(MMA8451_REG_CTRL_REG2, 0x02); + // Low noise! + writeRegister8(MMA8451_REG_CTRL_REG4, 0x01); + // DRDY on INT1 + writeRegister8(MMA8451_REG_CTRL_REG4, 0x01); + writeRegister8(MMA8451_REG_CTRL_REG5, 0x01); + + // Turn on orientation config + writeRegister8(MMA8451_REG_PL_CFG, 0x40); + + // Activate! + writeRegister8(MMA8451_REG_CTRL_REG1, 0x01); // active, max rate + + /* + for (uint8_t i=0; i<0x30; i++) { + Serial.print("$"); + Serial.print(i, HEX); Serial.print(" = 0x"); + Serial.println(readRegister8(i), HEX); + } + */ + + return true; +} + + +void Adafruit_MMA8451::read(void) { + // read x y z at once + Wire.beginTransmission(_i2caddr); + i2cwrite(MMA8451_REG_OUT_X_MSB); + Wire.endTransmission(false); // MMA8451 + friends uses repeated start!! + + Wire.requestFrom(_i2caddr, 6); + x = Wire.read(); x <<= 8; x |= Wire.read(); x >>= 2; + y = Wire.read(); y <<= 8; y |= Wire.read(); y >>= 2; + z = Wire.read(); z <<= 8; z |= Wire.read(); z >>= 2; + + + uint8_t range = getRange(); + uint16_t divider = 1; + if (range == MMA8451_RANGE_8_G) divider = 1024; + if (range == MMA8451_RANGE_4_G) divider = 2048; + if (range == MMA8451_RANGE_2_G) divider = 4096; + + x_g = (float)x / divider; + y_g = (float)y / divider; + z_g = (float)z / divider; + +} + +/**************************************************************************/ +/*! + @brief Read the orientation: + Portrait/Landscape + Up/Down/Left/Right + Front/Back +*/ +/**************************************************************************/ +uint8_t Adafruit_MMA8451::getOrientation(void) { + return readRegister8(MMA8451_REG_PL_STATUS) & 0x07; +} + +/**************************************************************************/ +/*! + @brief Sets the g range for the accelerometer +*/ +/**************************************************************************/ +void Adafruit_MMA8451::setRange(mma8451_range_t range) +{ + // lower bits are range + writeRegister8(MMA8451_REG_CTRL_REG1, 0x00); // deactivate + writeRegister8(MMA8451_REG_XYZ_DATA_CFG, range & 0x3); + writeRegister8(MMA8451_REG_CTRL_REG1, 0x01); // active, max rate +} + +/**************************************************************************/ +/*! + @brief Sets the g range for the accelerometer +*/ +/**************************************************************************/ +mma8451_range_t Adafruit_MMA8451::getRange(void) +{ + /* Read the data format register to preserve bits */ + return (mma8451_range_t)(readRegister8(MMA8451_REG_XYZ_DATA_CFG) & 0x03); +} + +/**************************************************************************/ +/*! + @brief Sets the data rate for the MMA8451 (controls power consumption) +*/ +/**************************************************************************/ +void Adafruit_MMA8451::setDataRate(mma8451_dataRate_t dataRate) +{ + uint8_t ctl1 = readRegister8(MMA8451_REG_CTRL_REG1); + ctl1 &= ~(0x28); // mask off bits + ctl1 |= (dataRate << 3); + writeRegister8(MMA8451_REG_CTRL_REG1, ctl1); +} + +/**************************************************************************/ +/*! + @brief Sets the data rate for the MMA8451 (controls power consumption) +*/ +/**************************************************************************/ +mma8451_dataRate_t Adafruit_MMA8451::getDataRate(void) +{ + return (mma8451_dataRate_t)((readRegister8(MMA8451_REG_CTRL_REG1) >> 3)& 0x07); +} + +/**************************************************************************/ +/*! + @brief Gets the most recent sensor event +*/ +/**************************************************************************/ +void Adafruit_MMA8451::getEvent(sensors_event_t *event) { + /* Clear the event */ + memset(event, 0, sizeof(sensors_event_t)); + + event->version = sizeof(sensors_event_t); + event->sensor_id = _sensorID; + event->type = SENSOR_TYPE_ACCELEROMETER; + event->timestamp = 0; + + read(); + + event->acceleration.x = x_g; + event->acceleration.y = y_g; + event->acceleration.z = z_g; +} + +/**************************************************************************/ +/*! + @brief Gets the sensor_t data +*/ +/**************************************************************************/ +void Adafruit_MMA8451::getSensor(sensor_t *sensor) { + /* Clear the sensor_t object */ + memset(sensor, 0, sizeof(sensor_t)); + + /* Insert the sensor name in the fixed length char array */ + strncpy (sensor->name, "MMA8451", sizeof(sensor->name) - 1); + sensor->name[sizeof(sensor->name)- 1] = 0; + sensor->version = 1; + sensor->sensor_id = _sensorID; + sensor->type = SENSOR_TYPE_ACCELEROMETER; + sensor->min_delay = 0; + sensor->max_value = 0; + sensor->min_value = 0; + sensor->resolution = 0; +} diff --git a/resources/arduino_files/libraries/Adafruit_MMA8451/Adafruit_MMA8451.h b/resources/arduino_files/libraries/Adafruit_MMA8451/Adafruit_MMA8451.h new file mode 100644 index 000000000..54040bff5 --- /dev/null +++ b/resources/arduino_files/libraries/Adafruit_MMA8451/Adafruit_MMA8451.h @@ -0,0 +1,106 @@ +/**************************************************************************/ +/*! + @file Adafruit_MMA8451.h + @author K. Townsend (Adafruit Industries) + @license BSD (see license.txt) + + This is a library for the Adafruit MMA8451 Accel breakout board + ----> https://www.adafruit.com/products/2019 + + Adafruit invests time and resources providing this open source code, + please support Adafruit and open-source hardware by purchasing + products from Adafruit! + + @section HISTORY + + v1.0 - First release +*/ +/**************************************************************************/ + +#if ARDUINO >= 100 + #include "Arduino.h" +#else + #include "WProgram.h" +#endif + +#include +#include + +/*========================================================================= + I2C ADDRESS/BITS + -----------------------------------------------------------------------*/ + #define MMA8451_DEFAULT_ADDRESS (0x1D) // if A is GND, its 0x1C +/*=========================================================================*/ + +#define MMA8451_REG_OUT_X_MSB 0x01 +#define MMA8451_REG_SYSMOD 0x0B +#define MMA8451_REG_WHOAMI 0x0D +#define MMA8451_REG_XYZ_DATA_CFG 0x0E +#define MMA8451_REG_PL_STATUS 0x10 +#define MMA8451_REG_PL_CFG 0x11 +#define MMA8451_REG_CTRL_REG1 0x2A +#define MMA8451_REG_CTRL_REG2 0x2B +#define MMA8451_REG_CTRL_REG4 0x2D +#define MMA8451_REG_CTRL_REG5 0x2E + + + +#define MMA8451_PL_PUF 0 +#define MMA8451_PL_PUB 1 +#define MMA8451_PL_PDF 2 +#define MMA8451_PL_PDB 3 +#define MMA8451_PL_LRF 4 +#define MMA8451_PL_LRB 5 +#define MMA8451_PL_LLF 6 +#define MMA8451_PL_LLB 7 + +typedef enum +{ + MMA8451_RANGE_8_G = 0b10, // +/- 8g + MMA8451_RANGE_4_G = 0b01, // +/- 4g + MMA8451_RANGE_2_G = 0b00 // +/- 2g (default value) +} mma8451_range_t; + + +/* Used with register 0x2A (MMA8451_REG_CTRL_REG1) to set bandwidth */ +typedef enum +{ + MMA8451_DATARATE_800_HZ = 0b000, // 400Hz + MMA8451_DATARATE_400_HZ = 0b001, // 200Hz + MMA8451_DATARATE_200_HZ = 0b010, // 100Hz + MMA8451_DATARATE_100_HZ = 0b011, // 50Hz + MMA8451_DATARATE_50_HZ = 0b100, // 25Hz + MMA8451_DATARATE_12_5_HZ = 0b101, // 6.25Hz + MMA8451_DATARATE_6_25HZ = 0b110, // 3.13Hz + MMA8451_DATARATE_1_56_HZ = 0b111, // 1.56Hz +} mma8451_dataRate_t; + +class Adafruit_MMA8451 : public Adafruit_Sensor { + public: + Adafruit_MMA8451(int32_t id = -1); + + + bool begin(uint8_t addr = MMA8451_DEFAULT_ADDRESS); + + void read(); + + void setRange(mma8451_range_t range); + mma8451_range_t getRange(void); + + void setDataRate(mma8451_dataRate_t dataRate); + mma8451_dataRate_t getDataRate(void); + + void getEvent(sensors_event_t *event); + void getSensor(sensor_t *sensor); + + uint8_t getOrientation(void); + + int16_t x, y, z; + float x_g, y_g, z_g; + + void writeRegister8(uint8_t reg, uint8_t value); + private: + uint8_t readRegister8(uint8_t reg); + int32_t _sensorID; + int8_t _i2caddr; +}; diff --git a/resources/arduino_files/libraries/Adafruit_MMA8451/README.md b/resources/arduino_files/libraries/Adafruit_MMA8451/README.md new file mode 100644 index 000000000..fff9086ec --- /dev/null +++ b/resources/arduino_files/libraries/Adafruit_MMA8451/README.md @@ -0,0 +1,29 @@ +#Adafruit MMA8451 Accelerometer Driver # + +This driver is for the Adafruit MMA8451 Accelerometer Breakout (http://www.adafruit.com/products/2019), and is based on Adafruit's Unified Sensor Library (Adafruit_Sensor). + +## About the MMA8451 ## + +The MMA8451 is a low-cost but high-precision digital accelerometer that uses repeated-start I2C mode, with adjustable data rata and 'range' (+/-2/4/8). + +More information on the MMA8451 can be found in the datasheet: http://www.adafruit.com/datasheets/MMA8451Q-1.pdf + +## What is the Adafruit Unified Sensor Library? ## + +The Adafruit Unified Sensor Library (https://github.com/adafruit/Adafruit_Sensor) provides a common interface and data type for any supported sensor. It defines some basic information about the sensor (sensor limits, etc.), and returns standard SI units of a specific type and scale for each supported sensor type. + +It provides a simple abstraction layer between your application and the actual sensor HW, allowing you to drop in any comparable sensor with only one or two lines of code to change in your project (essentially the constructor since the functions to read sensor data and get information about the sensor are defined in the base Adafruit_Sensor class). + +This is imporant useful for two reasons: + +1.) You can use the data right away because it's already converted to SI units that you understand and can compare, rather than meaningless values like 0..1023. + +2.) Because SI units are standardised in the sensor library, you can also do quick sanity checks working with new sensors, or drop in any comparable sensor if you need better sensitivity or if a lower cost unit becomes available, etc. + +Light sensors will always report units in lux, gyroscopes will always report units in rad/s, etc. ... freeing you up to focus on the data, rather than digging through the datasheet to understand what the sensor's raw numbers really mean. + +## About this Driver ## + +Adafruit invests time and resources providing this open source code. Please support Adafruit and open-source hardware by purchasing products from Adafruit! + +Written by Kevin (KTOWN) Townsend & Limor (LADYADA) Fried for Adafruit Industries. diff --git a/resources/arduino_files/libraries/Adafruit_MMA8451/examples/MMA8451demo/MMA8451demo.ino b/resources/arduino_files/libraries/Adafruit_MMA8451/examples/MMA8451demo/MMA8451demo.ino new file mode 100644 index 000000000..e035a18bd --- /dev/null +++ b/resources/arduino_files/libraries/Adafruit_MMA8451/examples/MMA8451demo/MMA8451demo.ino @@ -0,0 +1,95 @@ +/**************************************************************************/ +/*! + @file Adafruit_MMA8451.h + @author K. Townsend (Adafruit Industries) + @license BSD (see license.txt) + + This is an example for the Adafruit MMA8451 Accel breakout board + ----> https://www.adafruit.com/products/2019 + + Adafruit invests time and resources providing this open source code, + please support Adafruit and open-source hardware by purchasing + products from Adafruit! + + @section HISTORY + + v1.0 - First release +*/ +/**************************************************************************/ + +#include +#include +#include + +Adafruit_MMA8451 mma = Adafruit_MMA8451(); + +void setup(void) { + Serial.begin(9600); + + Serial.println("Adafruit MMA8451 test!"); + + + if (! mma.begin()) { + Serial.println("Couldnt start"); + while (1); + } + Serial.println("MMA8451 found!"); + + mma.setRange(MMA8451_RANGE_2_G); + + Serial.print("Range = "); Serial.print(2 << mma.getRange()); + Serial.println("G"); + +} + +void loop() { + // Read the 'raw' data in 14-bit counts + mma.read(); + Serial.print("X:\t"); Serial.print(mma.x); + Serial.print("\tY:\t"); Serial.print(mma.y); + Serial.print("\tZ:\t"); Serial.print(mma.z); + Serial.println(); + + /* Get a new sensor event */ + sensors_event_t event; + mma.getEvent(&event); + + /* Display the results (acceleration is measured in m/s^2) */ + Serial.print("X: \t"); Serial.print(event.acceleration.x); Serial.print("\t"); + Serial.print("Y: \t"); Serial.print(event.acceleration.y); Serial.print("\t"); + Serial.print("Z: \t"); Serial.print(event.acceleration.z); Serial.print("\t"); + Serial.println("m/s^2 "); + + /* Get the orientation of the sensor */ + uint8_t o = mma.getOrientation(); + + switch (o) { + case MMA8451_PL_PUF: + Serial.println("Portrait Up Front"); + break; + case MMA8451_PL_PUB: + Serial.println("Portrait Up Back"); + break; + case MMA8451_PL_PDF: + Serial.println("Portrait Down Front"); + break; + case MMA8451_PL_PDB: + Serial.println("Portrait Down Back"); + break; + case MMA8451_PL_LRF: + Serial.println("Landscape Right Front"); + break; + case MMA8451_PL_LRB: + Serial.println("Landscape Right Back"); + break; + case MMA8451_PL_LLF: + Serial.println("Landscape Left Front"); + break; + case MMA8451_PL_LLB: + Serial.println("Landscape Left Back"); + break; + } + Serial.println(); + delay(500); + +} \ No newline at end of file diff --git a/resources/arduino_files/libraries/Adafruit_MMA8451/license.txt b/resources/arduino_files/libraries/Adafruit_MMA8451/license.txt new file mode 100644 index 000000000..f6a0f22b8 --- /dev/null +++ b/resources/arduino_files/libraries/Adafruit_MMA8451/license.txt @@ -0,0 +1,26 @@ +Software License Agreement (BSD License) + +Copyright (c) 2012, Adafruit Industries +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: +1. Redistributions of source code must retain the above copyright +notice, this list of conditions and the following disclaimer. +2. Redistributions in binary form must reproduce the above copyright +notice, this list of conditions and the following disclaimer in the +documentation and/or other materials provided with the distribution. +3. Neither the name of the copyright holders nor the +names of its contributors may be used to endorse or promote products +derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/resources/arduino_files/libraries/Adafruit_Sensor/Adafruit_Sensor.cpp b/resources/arduino_files/libraries/Adafruit_Sensor/Adafruit_Sensor.cpp new file mode 100644 index 000000000..2977b275c --- /dev/null +++ b/resources/arduino_files/libraries/Adafruit_Sensor/Adafruit_Sensor.cpp @@ -0,0 +1,5 @@ +#include "Adafruit_Sensor.h" +#include + +void Adafruit_Sensor::constructor() { +} diff --git a/resources/arduino_files/libraries/Adafruit_Sensor/Adafruit_Sensor.h b/resources/arduino_files/libraries/Adafruit_Sensor/Adafruit_Sensor.h new file mode 100644 index 000000000..7c0db4fa1 --- /dev/null +++ b/resources/arduino_files/libraries/Adafruit_Sensor/Adafruit_Sensor.h @@ -0,0 +1,153 @@ +/* +* Copyright (C) 2008 The Android Open Source Project +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software< /span> +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*/ + +/* Update by K. Townsend (Adafruit Industries) for lighter typedefs, and + * extended sensor support to include color, voltage and current */ + +#ifndef _ADAFRUIT_SENSOR_H +#define _ADAFRUIT_SENSOR_H + +#if ARDUINO >= 100 + #include "Arduino.h" + #include "Print.h" +#else + #include "WProgram.h" +#endif + +/* Intentionally modeled after sensors.h in the Android API: + * https://github.com/android/platform_hardware_libhardware/blob/master/include/hardware/sensors.h */ + +/* Constants */ +#define SENSORS_GRAVITY_EARTH (9.80665F) /**< Earth's gravity in m/s^2 */ +#define SENSORS_GRAVITY_MOON (1.6F) /**< The moon's gravity in m/s^2 */ +#define SENSORS_GRAVITY_SUN (275.0F) /**< The sun's gravity in m/s^2 */ +#define SENSORS_GRAVITY_STANDARD (SENSORS_GRAVITY_EARTH) +#define SENSORS_MAGFIELD_EARTH_MAX (60.0F) /**< Maximum magnetic field on Earth's surface */ +#define SENSORS_MAGFIELD_EARTH_MIN (30.0F) /**< Minimum magnetic field on Earth's surface */ +#define SENSORS_PRESSURE_SEALEVELHPA (1013.25F) /**< Average sea level pressure is 1013.25 hPa */ +#define SENSORS_DPS_TO_RADS (0.017453293F) /**< Degrees/s to rad/s multiplier */ +#define SENSORS_GAUSS_TO_MICROTESLA (100) /**< Gauss to micro-Tesla multiplier */ + +/** Sensor types */ +typedef enum +{ + SENSOR_TYPE_ACCELEROMETER = (1), /**< Gravity + linear acceleration */ + SENSOR_TYPE_MAGNETIC_FIELD = (2), + SENSOR_TYPE_ORIENTATION = (3), + SENSOR_TYPE_GYROSCOPE = (4), + SENSOR_TYPE_LIGHT = (5), + SENSOR_TYPE_PRESSURE = (6), + SENSOR_TYPE_PROXIMITY = (8), + SENSOR_TYPE_GRAVITY = (9), + SENSOR_TYPE_LINEAR_ACCELERATION = (10), /**< Acceleration not including gravity */ + SENSOR_TYPE_ROTATION_VECTOR = (11), + SENSOR_TYPE_RELATIVE_HUMIDITY = (12), + SENSOR_TYPE_AMBIENT_TEMPERATURE = (13), + SENSOR_TYPE_VOLTAGE = (15), + SENSOR_TYPE_CURRENT = (16), + SENSOR_TYPE_COLOR = (17) +} sensors_type_t; + +/** struct sensors_vec_s is used to return a vector in a common format. */ +typedef struct { + union { + float v[3]; + struct { + float x; + float y; + float z; + }; + /* Orientation sensors */ + struct { + float roll; /**< Rotation around the longitudinal axis (the plane body, 'X axis'). Roll is positive and increasing when moving downward. -90�<=roll<=90� */ + float pitch; /**< Rotation around the lateral axis (the wing span, 'Y axis'). Pitch is positive and increasing when moving upwards. -180�<=pitch<=180�) */ + float heading; /**< Angle between the longitudinal axis (the plane body) and magnetic north, measured clockwise when viewing from the top of the device. 0-359� */ + }; + }; + int8_t status; + uint8_t reserved[3]; +} sensors_vec_t; + +/** struct sensors_color_s is used to return color data in a common format. */ +typedef struct { + union { + float c[3]; + /* RGB color space */ + struct { + float r; /**< Red component */ + float g; /**< Green component */ + float b; /**< Blue component */ + }; + }; + uint32_t rgba; /**< 24-bit RGBA value */ +} sensors_color_t; + +/* Sensor event (36 bytes) */ +/** struct sensor_event_s is used to provide a single sensor event in a common format. */ +typedef struct +{ + int32_t version; /**< must be sizeof(struct sensors_event_t) */ + int32_t sensor_id; /**< unique sensor identifier */ + int32_t type; /**< sensor type */ + int32_t reserved0; /**< reserved */ + int32_t timestamp; /**< time is in milliseconds */ + union + { + float data[4]; + sensors_vec_t acceleration; /**< acceleration values are in meter per second per second (m/s^2) */ + sensors_vec_t magnetic; /**< magnetic vector values are in micro-Tesla (uT) */ + sensors_vec_t orientation; /**< orientation values are in degrees */ + sensors_vec_t gyro; /**< gyroscope values are in rad/s */ + float temperature; /**< temperature is in degrees centigrade (Celsius) */ + float distance; /**< distance in centimeters */ + float light; /**< light in SI lux units */ + float pressure; /**< pressure in hectopascal (hPa) */ + float relative_humidity; /**< relative humidity in percent */ + float current; /**< current in milliamps (mA) */ + float voltage; /**< voltage in volts (V) */ + sensors_color_t color; /**< color in RGB component values */ + }; +} sensors_event_t; + +/* Sensor details (40 bytes) */ +/** struct sensor_s is used to describe basic information about a specific sensor. */ +typedef struct +{ + char name[12]; /**< sensor name */ + int32_t version; /**< version of the hardware + driver */ + int32_t sensor_id; /**< unique sensor identifier */ + int32_t type; /**< this sensor's type (ex. SENSOR_TYPE_LIGHT) */ + float max_value; /**< maximum value of this sensor's value in SI units */ + float min_value; /**< minimum value of this sensor's value in SI units */ + float resolution; /**< smallest difference between two values reported by this sensor */ + int32_t min_delay; /**< min delay in microseconds between events. zero = not a constant rate */ +} sensor_t; + +class Adafruit_Sensor { + public: + // Constructor(s) + void constructor(); + + // These must be defined by the subclass + virtual void enableAutoRange(bool enabled) {}; + virtual void getEvent(sensors_event_t*); + virtual void getSensor(sensor_t*); + + private: + bool _autoRange; +}; + +#endif diff --git a/resources/arduino_files/libraries/Adafruit_Sensor/README.md b/resources/arduino_files/libraries/Adafruit_Sensor/README.md new file mode 100644 index 000000000..068028607 --- /dev/null +++ b/resources/arduino_files/libraries/Adafruit_Sensor/README.md @@ -0,0 +1,214 @@ +# Adafruit Unified Sensor Driver # + +Many small embedded systems exist to collect data from sensors, analyse the data, and either take an appropriate action or send that sensor data to another system for processing. + +One of the many challenges of embedded systems design is the fact that parts you used today may be out of production tomorrow, or system requirements may change and you may need to choose a different sensor down the road. + +Creating new drivers is a relatively easy task, but integrating them into existing systems is both error prone and time consuming since sensors rarely use the exact same units of measurement. + +By reducing all data to a single **sensors\_event\_t** 'type' and settling on specific, **standardised SI units** for each sensor family the same sensor types return values that are comparable with any other similar sensor. This enables you to switch sensor models with very little impact on the rest of the system, which can help mitigate some of the risks and problems of sensor availability and code reuse. + +The unified sensor abstraction layer is also useful for data-logging and data-transmission since you only have one well-known type to log or transmit over the air or wire. + +## Unified Sensor Drivers ## + +The following drivers are based on the Adafruit Unified Sensor Driver: + +**Accelerometers** + - [Adafruit\_ADXL345](https://github.com/adafruit/Adafruit_ADXL345) + - [Adafruit\_LSM303DLHC](https://github.com/adafruit/Adafruit_LSM303DLHC) + +**Gyroscope** + - [Adafruit\_L3GD20\_U](https://github.com/adafruit/Adafruit_L3GD20_U) + +**Light** + - [Adafruit\_TSL2561](https://github.com/adafruit/Adafruit_TSL2561) + +**Magnetometers** + - [Adafruit\_LSM303DLHC](https://github.com/adafruit/Adafruit_LSM303DLHC) + +**Barometric Pressure** + - [Adafruit\_BMP085\_Unified](https://github.com/adafruit/Adafruit_BMP085_Unified) + +**Humidity & Temperature** + - [Adafruit\_DHT\_Unified](https://github.com/adafruit/Adafruit_DHT_Unified) + +## How Does it Work? ## + +Any driver that supports the Adafruit unified sensor abstraction layer will implement the Adafruit\_Sensor base class. There are two main typedefs and one enum defined in Adafruit_Sensor.h that are used to 'abstract' away the sensor details and values: + +**Sensor Types (sensors\_type\_t)** + +These pre-defined sensor types are used to properly handle the two related typedefs below, and allows us determine what types of units the sensor uses, etc. + +``` +/** Sensor types */ +typedef enum +{ + SENSOR_TYPE_ACCELEROMETER = (1), + SENSOR_TYPE_MAGNETIC_FIELD = (2), + SENSOR_TYPE_ORIENTATION = (3), + SENSOR_TYPE_GYROSCOPE = (4), + SENSOR_TYPE_LIGHT = (5), + SENSOR_TYPE_PRESSURE = (6), + SENSOR_TYPE_PROXIMITY = (8), + SENSOR_TYPE_GRAVITY = (9), + SENSOR_TYPE_LINEAR_ACCELERATION = (10), + SENSOR_TYPE_ROTATION_VECTOR = (11), + SENSOR_TYPE_RELATIVE_HUMIDITY = (12), + SENSOR_TYPE_AMBIENT_TEMPERATURE = (13), + SENSOR_TYPE_VOLTAGE = (15), + SENSOR_TYPE_CURRENT = (16), + SENSOR_TYPE_COLOR = (17) +} sensors_type_t; +``` + +**Sensor Details (sensor\_t)** + +This typedef describes the specific capabilities of this sensor, and allows us to know what sensor we are using beneath the abstraction layer. + +``` +/* Sensor details (40 bytes) */ +/** struct sensor_s is used to describe basic information about a specific sensor. */ +typedef struct +{ + char name[12]; + int32_t version; + int32_t sensor_id; + int32_t type; + float max_value; + float min_value; + float resolution; + int32_t min_delay; +} sensor_t; +``` + +The individual fields are intended to be used as follows: + +- **name**: The sensor name or ID, up to a maximum of twelve characters (ex. "MPL115A2") +- **version**: The version of the sensor HW and the driver to allow us to differentiate versions of the board or driver +- **sensor\_id**: A unique sensor identifier that is used to differentiate this specific sensor instance from any others that are present on the system or in the sensor network +- **type**: The sensor type, based on **sensors\_type\_t** in sensors.h +- **max\_value**: The maximum value that this sensor can return (in the appropriate SI unit) +- **min\_value**: The minimum value that this sensor can return (in the appropriate SI unit) +- **resolution**: The smallest difference between two values that this sensor can report (in the appropriate SI unit) +- **min\_delay**: The minimum delay in microseconds between two sensor events, or '0' if there is no constant sensor rate + +**Sensor Data/Events (sensors\_event\_t)** + +This typedef is used to return sensor data from any sensor supported by the abstraction layer, using standard SI units and scales. + +``` +/* Sensor event (36 bytes) */ +/** struct sensor_event_s is used to provide a single sensor event in a common format. */ +typedef struct +{ + int32_t version; + int32_t sensor_id; + int32_t type; + int32_t reserved0; + int32_t timestamp; + union + { + float data[4]; + sensors_vec_t acceleration; + sensors_vec_t magnetic; + sensors_vec_t orientation; + sensors_vec_t gyro; + float temperature; + float distance; + float light; + float pressure; + float relative_humidity; + float current; + float voltage; + sensors_color_t color; + }; +} sensors_event_t; +``` +It includes the following fields: + +- **version**: Contain 'sizeof(sensors\_event\_t)' to identify which version of the API we're using in case this changes in the future +- **sensor\_id**: A unique sensor identifier that is used to differentiate this specific sensor instance from any others that are present on the system or in the sensor network (must match the sensor\_id value in the corresponding sensor\_t enum above!) +- **type**: the sensor type, based on **sensors\_type\_t** in sensors.h +- **timestamp**: time in milliseconds when the sensor value was read +- **data[4]**: An array of four 32-bit values that allows us to encapsulate any type of sensor data via a simple union (further described below) + +**Required Functions** + +In addition to the two standard types and the sensor type enum, all drivers based on Adafruit_Sensor must also implement the following two functions: + +``` +void getEvent(sensors_event_t*); +``` +Calling this function will populate the supplied sensors\_event\_t reference with the latest available sensor data. You should call this function as often as you want to update your data. + +``` +void getSensor(sensor_t*); +``` +Calling this function will provide some basic information about the sensor (the sensor name, driver version, min and max values, etc. + +**Standardised SI values for sensors\_event\_t** + +A key part of the abstraction layer is the standardisation of values on SI units of a particular scale, which is accomplished via the data[4] union in sensors\_event\_t above. This 16 byte union includes fields for each main sensor type, and uses the following SI units and scales: + +- **acceleration**: values are in **meter per second per second** (m/s^2) +- **magnetic**: values are in **micro-Tesla** (uT) +- **orientation**: values are in **degrees** +- **gyro**: values are in **rad/s** +- **temperature**: values in **degrees centigrade** (Celsius) +- **distance**: values are in **centimeters** +- **light**: values are in **SI lux** units +- **pressure**: values are in **hectopascal** (hPa) +- **relative\_humidity**: values are in **percent** +- **current**: values are in **milliamps** (mA) +- **voltage**: values are in **volts** (V) +- **color**: values are in 0..1.0 RGB channel luminosity and 32-bit RGBA format + +## The Unified Driver Abstraction Layer in Practice ## + +Using the unified sensor abstraction layer is relatively easy once a compliant driver has been created. + +Every compliant sensor can now be read using a single, well-known 'type' (sensors\_event\_t), and there is a standardised way of interrogating a sensor about its specific capabilities (via sensor\_t). + +An example of reading the [TSL2561](https://github.com/adafruit/Adafruit_TSL2561) light sensor can be seen below: + +``` + Adafruit_TSL2561 tsl = Adafruit_TSL2561(TSL2561_ADDR_FLOAT, 12345); + ... + /* Get a new sensor event */ + sensors_event_t event; + tsl.getEvent(&event); + + /* Display the results (light is measured in lux) */ + if (event.light) + { + Serial.print(event.light); Serial.println(" lux"); + } + else + { + /* If event.light = 0 lux the sensor is probably saturated + and no reliable data could be generated! */ + Serial.println("Sensor overload"); + } +``` + +Similarly, we can get the basic technical capabilities of this sensor with the following code: + +``` + sensor_t sensor; + + sensor_t sensor; + tsl.getSensor(&sensor); + + /* Display the sensor details */ + Serial.println("------------------------------------"); + Serial.print ("Sensor: "); Serial.println(sensor.name); + Serial.print ("Driver Ver: "); Serial.println(sensor.version); + Serial.print ("Unique ID: "); Serial.println(sensor.sensor_id); + Serial.print ("Max Value: "); Serial.print(sensor.max_value); Serial.println(" lux"); + Serial.print ("Min Value: "); Serial.print(sensor.min_value); Serial.println(" lux"); + Serial.print ("Resolution: "); Serial.print(sensor.resolution); Serial.println(" lux"); + Serial.println("------------------------------------"); + Serial.println(""); +``` diff --git a/resources/arduino_files/libraries/DHT/DHT.cpp b/resources/arduino_files/libraries/DHT/DHT.cpp new file mode 100644 index 000000000..2ef244c35 --- /dev/null +++ b/resources/arduino_files/libraries/DHT/DHT.cpp @@ -0,0 +1,179 @@ +/* DHT library + +MIT license +written by Adafruit Industries +*/ + +#include "DHT.h" + +DHT::DHT(uint8_t pin, uint8_t type, uint8_t count) { + _pin = pin; + _type = type; + _count = count; + firstreading = true; +} + +void DHT::begin(void) { + // set up the pins! + pinMode(_pin, INPUT); + digitalWrite(_pin, HIGH); + _lastreadtime = 0; +} + +//boolean S == Scale. True == Farenheit; False == Celcius +float DHT::readTemperature(bool S) { + float f; + + if (read()) { + switch (_type) { + case DHT11: + f = data[2]; + if(S) + f = convertCtoF(f); + + return f; + case DHT22: + case DHT21: + f = data[2] & 0x7F; + f *= 256; + f += data[3]; + f /= 10; + if (data[2] & 0x80) + f *= -1; + if(S) + f = convertCtoF(f); + + return f; + } + } + return NAN; +} + +float DHT::convertCtoF(float c) { + return c * 9 / 5 + 32; +} + +float DHT::convertFtoC(float f) { + return (f - 32) * 5 / 9; +} + +float DHT::readHumidity(void) { + float f; + if (read()) { + switch (_type) { + case DHT11: + f = data[0]; + return f; + case DHT22: + case DHT21: + f = data[0]; + f *= 256; + f += data[1]; + f /= 10; + return f; + } + } + return NAN; +} + +float DHT::computeHeatIndex(float tempFahrenheit, float percentHumidity) { + // Adapted from equation at: https://github.com/adafruit/DHT-sensor-library/issues/9 and + // Wikipedia: http://en.wikipedia.org/wiki/Heat_index + return -42.379 + + 2.04901523 * tempFahrenheit + + 10.14333127 * percentHumidity + + -0.22475541 * tempFahrenheit*percentHumidity + + -0.00683783 * pow(tempFahrenheit, 2) + + -0.05481717 * pow(percentHumidity, 2) + + 0.00122874 * pow(tempFahrenheit, 2) * percentHumidity + + 0.00085282 * tempFahrenheit*pow(percentHumidity, 2) + + -0.00000199 * pow(tempFahrenheit, 2) * pow(percentHumidity, 2); +} + + +boolean DHT::read(void) { + uint8_t laststate = HIGH; + uint8_t counter = 0; + uint8_t j = 0, i; + unsigned long currenttime; + + // Check if sensor was read less than two seconds ago and return early + // to use last reading. + currenttime = millis(); + if (currenttime < _lastreadtime) { + // ie there was a rollover + _lastreadtime = 0; + } + if (!firstreading && ((currenttime - _lastreadtime) < 2000)) { + return true; // return last correct measurement + //delay(2000 - (currenttime - _lastreadtime)); + } + firstreading = false; + /* + Serial.print("Currtime: "); Serial.print(currenttime); + Serial.print(" Lasttime: "); Serial.print(_lastreadtime); + */ + _lastreadtime = millis(); + + data[0] = data[1] = data[2] = data[3] = data[4] = 0; + + // pull the pin high and wait 250 milliseconds + digitalWrite(_pin, HIGH); + delay(250); + + // now pull it low for ~20 milliseconds + pinMode(_pin, OUTPUT); + digitalWrite(_pin, LOW); + delay(20); + noInterrupts(); + digitalWrite(_pin, HIGH); + delayMicroseconds(40); + pinMode(_pin, INPUT); + + // read in timings + for ( i=0; i< MAXTIMINGS; i++) { + counter = 0; + while (digitalRead(_pin) == laststate) { + counter++; + delayMicroseconds(1); + if (counter == 255) { + break; + } + } + laststate = digitalRead(_pin); + + if (counter == 255) break; + + // ignore first 3 transitions + if ((i >= 4) && (i%2 == 0)) { + // shove each bit into the storage bytes + data[j/8] <<= 1; + if (counter > _count) + data[j/8] |= 1; + j++; + } + + } + + interrupts(); + + /* + Serial.println(j, DEC); + Serial.print(data[0], HEX); Serial.print(", "); + Serial.print(data[1], HEX); Serial.print(", "); + Serial.print(data[2], HEX); Serial.print(", "); + Serial.print(data[3], HEX); Serial.print(", "); + Serial.print(data[4], HEX); Serial.print(" =? "); + Serial.println(data[0] + data[1] + data[2] + data[3], HEX); + */ + + // check we read 40 bits and that the checksum matches + if ((j >= 40) && + (data[4] == ((data[0] + data[1] + data[2] + data[3]) & 0xFF)) ) { + return true; + } + + + return false; + +} diff --git a/resources/arduino_files/libraries/DHT/DHT.h b/resources/arduino_files/libraries/DHT/DHT.h new file mode 100644 index 000000000..5280f9c12 --- /dev/null +++ b/resources/arduino_files/libraries/DHT/DHT.h @@ -0,0 +1,41 @@ +#ifndef DHT_H +#define DHT_H +#if ARDUINO >= 100 + #include "Arduino.h" +#else + #include "WProgram.h" +#endif + +/* DHT library + +MIT license +written by Adafruit Industries +*/ + +// how many timing transitions we need to keep track of. 2 * number bits + extra +#define MAXTIMINGS 85 + +#define DHT11 11 +#define DHT22 22 +#define DHT21 21 +#define AM2301 21 + +class DHT { + private: + uint8_t data[6]; + uint8_t _pin, _type, _count; + unsigned long _lastreadtime; + boolean firstreading; + + public: + DHT(uint8_t pin, uint8_t type, uint8_t count=6); + void begin(void); + float readTemperature(bool S=false); + float convertCtoF(float); + float convertFtoC(float); + float computeHeatIndex(float tempFahrenheit, float percentHumidity); + float readHumidity(void); + boolean read(void); + +}; +#endif diff --git a/resources/arduino_files/libraries/DHT/README.txt b/resources/arduino_files/libraries/DHT/README.txt new file mode 100644 index 000000000..4dfcbab3c --- /dev/null +++ b/resources/arduino_files/libraries/DHT/README.txt @@ -0,0 +1,3 @@ +This is an Arduino library for the DHT series of low cost temperature/humidity sensors. + +To download. click the DOWNLOADS button in the top right corner, rename the uncompressed folder DHT. Check that the DHT folder contains DHT.cpp and DHT.h. Place the DHT library folder your /libraries/ folder. You may need to create the libraries subfolder if its your first library. Restart the IDE. \ No newline at end of file diff --git a/resources/arduino_files/libraries/DHT/examples/DHTtester/DHTtester.ino b/resources/arduino_files/libraries/DHT/examples/DHTtester/DHTtester.ino new file mode 100644 index 000000000..021107faf --- /dev/null +++ b/resources/arduino_files/libraries/DHT/examples/DHTtester/DHTtester.ino @@ -0,0 +1,71 @@ +// Example testing sketch for various DHT humidity/temperature sensors +// Written by ladyada, public domain + +#include "DHT.h" + +#define DHTPIN 2 // what pin we're connected to + +// Uncomment whatever type you're using! +//#define DHTTYPE DHT11 // DHT 11 +#define DHTTYPE DHT22 // DHT 22 (AM2302) +//#define DHTTYPE DHT21 // DHT 21 (AM2301) + +// Connect pin 1 (on the left) of the sensor to +5V +// NOTE: If using a board with 3.3V logic like an Arduino Due connect pin 1 +// to 3.3V instead of 5V! +// Connect pin 2 of the sensor to whatever your DHTPIN is +// Connect pin 4 (on the right) of the sensor to GROUND +// Connect a 10K resistor from pin 2 (data) to pin 1 (power) of the sensor + +// Initialize DHT sensor for normal 16mhz Arduino +DHT dht(DHTPIN, DHTTYPE); +// NOTE: For working with a faster chip, like an Arduino Due or Teensy, you +// might need to increase the threshold for cycle counts considered a 1 or 0. +// You can do this by passing a 3rd parameter for this threshold. It's a bit +// of fiddling to find the right value, but in general the faster the CPU the +// higher the value. The default for a 16mhz AVR is a value of 6. For an +// Arduino Due that runs at 84mhz a value of 30 works. +// Example to initialize DHT sensor for Arduino Due: +//DHT dht(DHTPIN, DHTTYPE, 30); + +void setup() { + Serial.begin(9600); + Serial.println("DHTxx test!"); + + dht.begin(); +} + +void loop() { + // Wait a few seconds between measurements. + delay(2000); + + // Reading temperature or humidity takes about 250 milliseconds! + // Sensor readings may also be up to 2 seconds 'old' (its a very slow sensor) + float h = dht.readHumidity(); + // Read temperature as Celsius + float t = dht.readTemperature(); + // Read temperature as Fahrenheit + float f = dht.readTemperature(true); + + // Check if any reads failed and exit early (to try again). + if (isnan(h) || isnan(t) || isnan(f)) { + Serial.println("Failed to read from DHT sensor!"); + return; + } + + // Compute heat index + // Must send in temp in Fahrenheit! + float hi = dht.computeHeatIndex(f, h); + + Serial.print("Humidity: "); + Serial.print(h); + Serial.print(" %\t"); + Serial.print("Temperature: "); + Serial.print(t); + Serial.print(" *C "); + Serial.print(f); + Serial.print(" *F\t"); + Serial.print("Heat index: "); + Serial.print(hi); + Serial.println(" *F"); +} diff --git a/resources/arduino_files/libraries/OneWire/OneWire.cpp b/resources/arduino_files/libraries/OneWire/OneWire.cpp new file mode 100644 index 000000000..cf349338e --- /dev/null +++ b/resources/arduino_files/libraries/OneWire/OneWire.cpp @@ -0,0 +1,567 @@ +/* +Copyright (c) 2007, Jim Studt (original old version - many contributors since) + +The latest version of this library may be found at: + http://www.pjrc.com/teensy/td_libs_OneWire.html + +OneWire has been maintained by Paul Stoffregen (paul@pjrc.com) since +January 2010. At the time, it was in need of many bug fixes, but had +been abandoned the original author (Jim Studt). None of the known +contributors were interested in maintaining OneWire. Paul typically +works on OneWire every 6 to 12 months. Patches usually wait that +long. If anyone is interested in more actively maintaining OneWire, +please contact Paul. + +Version 2.3: + Unknonw chip fallback mode, Roger Clark + Teensy-LC compatibility, Paul Stoffregen + Search bug fix, Love Nystrom + +Version 2.2: + Teensy 3.0 compatibility, Paul Stoffregen, paul@pjrc.com + Arduino Due compatibility, http://arduino.cc/forum/index.php?topic=141030 + Fix DS18B20 example negative temperature + Fix DS18B20 example's low res modes, Ken Butcher + Improve reset timing, Mark Tillotson + Add const qualifiers, Bertrik Sikken + Add initial value input to crc16, Bertrik Sikken + Add target_search() function, Scott Roberts + +Version 2.1: + Arduino 1.0 compatibility, Paul Stoffregen + Improve temperature example, Paul Stoffregen + DS250x_PROM example, Guillermo Lovato + PIC32 (chipKit) compatibility, Jason Dangel, dangel.jason AT gmail.com + Improvements from Glenn Trewitt: + - crc16() now works + - check_crc16() does all of calculation/checking work. + - Added read_bytes() and write_bytes(), to reduce tedious loops. + - Added ds2408 example. + Delete very old, out-of-date readme file (info is here) + +Version 2.0: Modifications by Paul Stoffregen, January 2010: +http://www.pjrc.com/teensy/td_libs_OneWire.html + Search fix from Robin James + http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1238032295/27#27 + Use direct optimized I/O in all cases + Disable interrupts during timing critical sections + (this solves many random communication errors) + Disable interrupts during read-modify-write I/O + Reduce RAM consumption by eliminating unnecessary + variables and trimming many to 8 bits + Optimize both crc8 - table version moved to flash + +Modified to work with larger numbers of devices - avoids loop. +Tested in Arduino 11 alpha with 12 sensors. +26 Sept 2008 -- Robin James +http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1238032295/27#27 + +Updated to work with arduino-0008 and to include skip() as of +2007/07/06. --RJL20 + +Modified to calculate the 8-bit CRC directly, avoiding the need for +the 256-byte lookup table to be loaded in RAM. Tested in arduino-0010 +-- Tom Pollard, Jan 23, 2008 + +Jim Studt's original library was modified by Josh Larios. + +Tom Pollard, pollard@alum.mit.edu, contributed around May 20, 2008 + +Permission is hereby granted, free of charge, to any person obtaining +a copy of this software and associated documentation files (the +"Software"), to deal in the Software without restriction, including +without limitation the rights to use, copy, modify, merge, publish, +distribute, sublicense, and/or sell copies of the Software, and to +permit persons to whom the Software is furnished to do so, subject to +the following conditions: + +The above copyright notice and this permission notice shall be +included in all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, +EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF +MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND +NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE +LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION +OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION +WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +Much of the code was inspired by Derek Yerger's code, though I don't +think much of that remains. In any event that was.. + (copyleft) 2006 by Derek Yerger - Free to distribute freely. + +The CRC code was excerpted and inspired by the Dallas Semiconductor +sample code bearing this copyright. +//--------------------------------------------------------------------------- +// Copyright (C) 2000 Dallas Semiconductor Corporation, All Rights Reserved. +// +// Permission is hereby granted, free of charge, to any person obtaining a +// copy of this software and associated documentation files (the "Software"), +// to deal in the Software without restriction, including without limitation +// the rights to use, copy, modify, merge, publish, distribute, sublicense, +// and/or sell copies of the Software, and to permit persons to whom the +// Software is furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included +// in all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF +// MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. +// IN NO EVENT SHALL DALLAS SEMICONDUCTOR BE LIABLE FOR ANY CLAIM, DAMAGES +// OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, +// ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR +// OTHER DEALINGS IN THE SOFTWARE. +// +// Except as contained in this notice, the name of Dallas Semiconductor +// shall not be used except as stated in the Dallas Semiconductor +// Branding Policy. +//-------------------------------------------------------------------------- +*/ + +#include "OneWire.h" + + +OneWire::OneWire(uint8_t pin) +{ + pinMode(pin, INPUT); + bitmask = PIN_TO_BITMASK(pin); + baseReg = PIN_TO_BASEREG(pin); +#if ONEWIRE_SEARCH + reset_search(); +#endif +} + + +// Perform the onewire reset function. We will wait up to 250uS for +// the bus to come high, if it doesn't then it is broken or shorted +// and we return a 0; +// +// Returns 1 if a device asserted a presence pulse, 0 otherwise. +// +uint8_t OneWire::reset(void) +{ + IO_REG_TYPE mask = bitmask; + volatile IO_REG_TYPE *reg IO_REG_ASM = baseReg; + uint8_t r; + uint8_t retries = 125; + + noInterrupts(); + DIRECT_MODE_INPUT(reg, mask); + interrupts(); + // wait until the wire is high... just in case + do { + if (--retries == 0) return 0; + delayMicroseconds(2); + } while ( !DIRECT_READ(reg, mask)); + + noInterrupts(); + DIRECT_WRITE_LOW(reg, mask); + DIRECT_MODE_OUTPUT(reg, mask); // drive output low + interrupts(); + delayMicroseconds(480); + noInterrupts(); + DIRECT_MODE_INPUT(reg, mask); // allow it to float + delayMicroseconds(70); + r = !DIRECT_READ(reg, mask); + interrupts(); + delayMicroseconds(410); + return r; +} + +// +// Write a bit. Port and bit is used to cut lookup time and provide +// more certain timing. +// +void OneWire::write_bit(uint8_t v) +{ + IO_REG_TYPE mask=bitmask; + volatile IO_REG_TYPE *reg IO_REG_ASM = baseReg; + + if (v & 1) { + noInterrupts(); + DIRECT_WRITE_LOW(reg, mask); + DIRECT_MODE_OUTPUT(reg, mask); // drive output low + delayMicroseconds(10); + DIRECT_WRITE_HIGH(reg, mask); // drive output high + interrupts(); + delayMicroseconds(55); + } else { + noInterrupts(); + DIRECT_WRITE_LOW(reg, mask); + DIRECT_MODE_OUTPUT(reg, mask); // drive output low + delayMicroseconds(65); + DIRECT_WRITE_HIGH(reg, mask); // drive output high + interrupts(); + delayMicroseconds(5); + } +} + +// +// Read a bit. Port and bit is used to cut lookup time and provide +// more certain timing. +// +uint8_t OneWire::read_bit(void) +{ + IO_REG_TYPE mask=bitmask; + volatile IO_REG_TYPE *reg IO_REG_ASM = baseReg; + uint8_t r; + + noInterrupts(); + DIRECT_MODE_OUTPUT(reg, mask); + DIRECT_WRITE_LOW(reg, mask); + delayMicroseconds(3); + DIRECT_MODE_INPUT(reg, mask); // let pin float, pull up will raise + delayMicroseconds(10); + r = DIRECT_READ(reg, mask); + interrupts(); + delayMicroseconds(53); + return r; +} + +// +// Write a byte. The writing code uses the active drivers to raise the +// pin high, if you need power after the write (e.g. DS18S20 in +// parasite power mode) then set 'power' to 1, otherwise the pin will +// go tri-state at the end of the write to avoid heating in a short or +// other mishap. +// +void OneWire::write(uint8_t v, uint8_t power /* = 0 */) { + uint8_t bitMask; + + for (bitMask = 0x01; bitMask; bitMask <<= 1) { + OneWire::write_bit( (bitMask & v)?1:0); + } + if ( !power) { + noInterrupts(); + DIRECT_MODE_INPUT(baseReg, bitmask); + DIRECT_WRITE_LOW(baseReg, bitmask); + interrupts(); + } +} + +void OneWire::write_bytes(const uint8_t *buf, uint16_t count, bool power /* = 0 */) { + for (uint16_t i = 0 ; i < count ; i++) + write(buf[i]); + if (!power) { + noInterrupts(); + DIRECT_MODE_INPUT(baseReg, bitmask); + DIRECT_WRITE_LOW(baseReg, bitmask); + interrupts(); + } +} + +// +// Read a byte +// +uint8_t OneWire::read() { + uint8_t bitMask; + uint8_t r = 0; + + for (bitMask = 0x01; bitMask; bitMask <<= 1) { + if ( OneWire::read_bit()) r |= bitMask; + } + return r; +} + +void OneWire::read_bytes(uint8_t *buf, uint16_t count) { + for (uint16_t i = 0 ; i < count ; i++) + buf[i] = read(); +} + +// +// Do a ROM select +// +void OneWire::select(const uint8_t rom[8]) +{ + uint8_t i; + + write(0x55); // Choose ROM + + for (i = 0; i < 8; i++) write(rom[i]); +} + +// +// Do a ROM skip +// +void OneWire::skip() +{ + write(0xCC); // Skip ROM +} + +void OneWire::depower() +{ + noInterrupts(); + DIRECT_MODE_INPUT(baseReg, bitmask); + interrupts(); +} + +#if ONEWIRE_SEARCH + +// +// You need to use this function to start a search again from the beginning. +// You do not need to do it for the first search, though you could. +// +void OneWire::reset_search() +{ + // reset the search state + LastDiscrepancy = 0; + LastDeviceFlag = FALSE; + LastFamilyDiscrepancy = 0; + for(int i = 7; ; i--) { + ROM_NO[i] = 0; + if ( i == 0) break; + } +} + +// Setup the search to find the device type 'family_code' on the next call +// to search(*newAddr) if it is present. +// +void OneWire::target_search(uint8_t family_code) +{ + // set the search state to find SearchFamily type devices + ROM_NO[0] = family_code; + for (uint8_t i = 1; i < 8; i++) + ROM_NO[i] = 0; + LastDiscrepancy = 64; + LastFamilyDiscrepancy = 0; + LastDeviceFlag = FALSE; +} + +// +// Perform a search. If this function returns a '1' then it has +// enumerated the next device and you may retrieve the ROM from the +// OneWire::address variable. If there are no devices, no further +// devices, or something horrible happens in the middle of the +// enumeration then a 0 is returned. If a new device is found then +// its address is copied to newAddr. Use OneWire::reset_search() to +// start over. +// +// --- Replaced by the one from the Dallas Semiconductor web site --- +//-------------------------------------------------------------------------- +// Perform the 1-Wire Search Algorithm on the 1-Wire bus using the existing +// search state. +// Return TRUE : device found, ROM number in ROM_NO buffer +// FALSE : device not found, end of search +// +uint8_t OneWire::search(uint8_t *newAddr, bool search_mode /* = true */) +{ + uint8_t id_bit_number; + uint8_t last_zero, rom_byte_number, search_result; + uint8_t id_bit, cmp_id_bit; + + unsigned char rom_byte_mask, search_direction; + + // initialize for search + id_bit_number = 1; + last_zero = 0; + rom_byte_number = 0; + rom_byte_mask = 1; + search_result = 0; + + // if the last call was not the last one + if (!LastDeviceFlag) + { + // 1-Wire reset + if (!reset()) + { + // reset the search + LastDiscrepancy = 0; + LastDeviceFlag = FALSE; + LastFamilyDiscrepancy = 0; + return FALSE; + } + + // issue the search command + if (search_mode == true) { + write(0xF0); // NORMAL SEARCH + } else { + write(0xEC); // CONDITIONAL SEARCH + } + + // loop to do the search + do + { + // read a bit and its complement + id_bit = read_bit(); + cmp_id_bit = read_bit(); + + // check for no devices on 1-wire + if ((id_bit == 1) && (cmp_id_bit == 1)) + break; + else + { + // all devices coupled have 0 or 1 + if (id_bit != cmp_id_bit) + search_direction = id_bit; // bit write value for search + else + { + // if this discrepancy if before the Last Discrepancy + // on a previous next then pick the same as last time + if (id_bit_number < LastDiscrepancy) + search_direction = ((ROM_NO[rom_byte_number] & rom_byte_mask) > 0); + else + // if equal to last pick 1, if not then pick 0 + search_direction = (id_bit_number == LastDiscrepancy); + + // if 0 was picked then record its position in LastZero + if (search_direction == 0) + { + last_zero = id_bit_number; + + // check for Last discrepancy in family + if (last_zero < 9) + LastFamilyDiscrepancy = last_zero; + } + } + + // set or clear the bit in the ROM byte rom_byte_number + // with mask rom_byte_mask + if (search_direction == 1) + ROM_NO[rom_byte_number] |= rom_byte_mask; + else + ROM_NO[rom_byte_number] &= ~rom_byte_mask; + + // serial number search direction write bit + write_bit(search_direction); + + // increment the byte counter id_bit_number + // and shift the mask rom_byte_mask + id_bit_number++; + rom_byte_mask <<= 1; + + // if the mask is 0 then go to new SerialNum byte rom_byte_number and reset mask + if (rom_byte_mask == 0) + { + rom_byte_number++; + rom_byte_mask = 1; + } + } + } + while(rom_byte_number < 8); // loop until through all ROM bytes 0-7 + + // if the search was successful then + if (!(id_bit_number < 65)) + { + // search successful so set LastDiscrepancy,LastDeviceFlag,search_result + LastDiscrepancy = last_zero; + + // check for last device + if (LastDiscrepancy == 0) + LastDeviceFlag = TRUE; + + search_result = TRUE; + } + } + + // if no device found then reset counters so next 'search' will be like a first + if (!search_result || !ROM_NO[0]) + { + LastDiscrepancy = 0; + LastDeviceFlag = FALSE; + LastFamilyDiscrepancy = 0; + search_result = FALSE; + } else { + for (int i = 0; i < 8; i++) newAddr[i] = ROM_NO[i]; + } + return search_result; + } + +#endif + +#if ONEWIRE_CRC +// The 1-Wire CRC scheme is described in Maxim Application Note 27: +// "Understanding and Using Cyclic Redundancy Checks with Maxim iButton Products" +// + +#if ONEWIRE_CRC8_TABLE +// This table comes from Dallas sample code where it is freely reusable, +// though Copyright (C) 2000 Dallas Semiconductor Corporation +static const uint8_t PROGMEM dscrc_table[] = { + 0, 94,188,226, 97, 63,221,131,194,156,126, 32,163,253, 31, 65, + 157,195, 33,127,252,162, 64, 30, 95, 1,227,189, 62, 96,130,220, + 35,125,159,193, 66, 28,254,160,225,191, 93, 3,128,222, 60, 98, + 190,224, 2, 92,223,129, 99, 61,124, 34,192,158, 29, 67,161,255, + 70, 24,250,164, 39,121,155,197,132,218, 56,102,229,187, 89, 7, + 219,133,103, 57,186,228, 6, 88, 25, 71,165,251,120, 38,196,154, + 101, 59,217,135, 4, 90,184,230,167,249, 27, 69,198,152,122, 36, + 248,166, 68, 26,153,199, 37,123, 58,100,134,216, 91, 5,231,185, + 140,210, 48,110,237,179, 81, 15, 78, 16,242,172, 47,113,147,205, + 17, 79,173,243,112, 46,204,146,211,141,111, 49,178,236, 14, 80, + 175,241, 19, 77,206,144,114, 44,109, 51,209,143, 12, 82,176,238, + 50,108,142,208, 83, 13,239,177,240,174, 76, 18,145,207, 45,115, + 202,148,118, 40,171,245, 23, 73, 8, 86,180,234,105, 55,213,139, + 87, 9,235,181, 54,104,138,212,149,203, 41,119,244,170, 72, 22, + 233,183, 85, 11,136,214, 52,106, 43,117,151,201, 74, 20,246,168, + 116, 42,200,150, 21, 75,169,247,182,232, 10, 84,215,137,107, 53}; + +// +// Compute a Dallas Semiconductor 8 bit CRC. These show up in the ROM +// and the registers. (note: this might better be done without to +// table, it would probably be smaller and certainly fast enough +// compared to all those delayMicrosecond() calls. But I got +// confused, so I use this table from the examples.) +// +uint8_t OneWire::crc8(const uint8_t *addr, uint8_t len) +{ + uint8_t crc = 0; + + while (len--) { + crc = pgm_read_byte(dscrc_table + (crc ^ *addr++)); + } + return crc; +} +#else +// +// Compute a Dallas Semiconductor 8 bit CRC directly. +// this is much slower, but much smaller, than the lookup table. +// +uint8_t OneWire::crc8(const uint8_t *addr, uint8_t len) +{ + uint8_t crc = 0; + + while (len--) { + uint8_t inbyte = *addr++; + for (uint8_t i = 8; i; i--) { + uint8_t mix = (crc ^ inbyte) & 0x01; + crc >>= 1; + if (mix) crc ^= 0x8C; + inbyte >>= 1; + } + } + return crc; +} +#endif + +#if ONEWIRE_CRC16 +bool OneWire::check_crc16(const uint8_t* input, uint16_t len, const uint8_t* inverted_crc, uint16_t crc) +{ + crc = ~crc16(input, len, crc); + return (crc & 0xFF) == inverted_crc[0] && (crc >> 8) == inverted_crc[1]; +} + +uint16_t OneWire::crc16(const uint8_t* input, uint16_t len, uint16_t crc) +{ + static const uint8_t oddparity[16] = + { 0, 1, 1, 0, 1, 0, 0, 1, 1, 0, 0, 1, 0, 1, 1, 0 }; + + for (uint16_t i = 0 ; i < len ; i++) { + // Even though we're just copying a byte from the input, + // we'll be doing 16-bit computation with it. + uint16_t cdata = input[i]; + cdata = (cdata ^ crc) & 0xff; + crc >>= 8; + + if (oddparity[cdata & 0x0F] ^ oddparity[cdata >> 4]) + crc ^= 0xC001; + + cdata <<= 6; + crc ^= cdata; + cdata <<= 1; + crc ^= cdata; + } + return crc; +} +#endif + +#endif diff --git a/resources/arduino_files/libraries/OneWire/OneWire.h b/resources/arduino_files/libraries/OneWire/OneWire.h new file mode 100644 index 000000000..8753e912f --- /dev/null +++ b/resources/arduino_files/libraries/OneWire/OneWire.h @@ -0,0 +1,367 @@ +#ifndef OneWire_h +#define OneWire_h + +#include + +#if ARDUINO >= 100 +#include "Arduino.h" // for delayMicroseconds, digitalPinToBitMask, etc +#else +#include "WProgram.h" // for delayMicroseconds +#include "pins_arduino.h" // for digitalPinToBitMask, etc +#endif + +// You can exclude certain features from OneWire. In theory, this +// might save some space. In practice, the compiler automatically +// removes unused code (technically, the linker, using -fdata-sections +// and -ffunction-sections when compiling, and Wl,--gc-sections +// when linking), so most of these will not result in any code size +// reduction. Well, unless you try to use the missing features +// and redesign your program to not need them! ONEWIRE_CRC8_TABLE +// is the exception, because it selects a fast but large algorithm +// or a small but slow algorithm. + +// you can exclude onewire_search by defining that to 0 +#ifndef ONEWIRE_SEARCH +#define ONEWIRE_SEARCH 1 +#endif + +// You can exclude CRC checks altogether by defining this to 0 +#ifndef ONEWIRE_CRC +#define ONEWIRE_CRC 1 +#endif + +// Select the table-lookup method of computing the 8-bit CRC +// by setting this to 1. The lookup table enlarges code size by +// about 250 bytes. It does NOT consume RAM (but did in very +// old versions of OneWire). If you disable this, a slower +// but very compact algorithm is used. +#ifndef ONEWIRE_CRC8_TABLE +#define ONEWIRE_CRC8_TABLE 1 +#endif + +// You can allow 16-bit CRC checks by defining this to 1 +// (Note that ONEWIRE_CRC must also be 1.) +#ifndef ONEWIRE_CRC16 +#define ONEWIRE_CRC16 1 +#endif + +#ifndef FALSE +#define FALSE 0 +#endif +#ifndef TRUE +#define TRUE 1 +#endif + +// Platform specific I/O definitions + +#if defined(__AVR__) +#define PIN_TO_BASEREG(pin) (portInputRegister(digitalPinToPort(pin))) +#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) +#define IO_REG_TYPE uint8_t +#define IO_REG_ASM asm("r30") +#define DIRECT_READ(base, mask) (((*(base)) & (mask)) ? 1 : 0) +#define DIRECT_MODE_INPUT(base, mask) ((*((base)+1)) &= ~(mask)) +#define DIRECT_MODE_OUTPUT(base, mask) ((*((base)+1)) |= (mask)) +#define DIRECT_WRITE_LOW(base, mask) ((*((base)+2)) &= ~(mask)) +#define DIRECT_WRITE_HIGH(base, mask) ((*((base)+2)) |= (mask)) + +#elif defined(__MK20DX128__) || defined(__MK20DX256__) || defined(__MK66FX1M0__) || defined(__MK64FX512__) +#define PIN_TO_BASEREG(pin) (portOutputRegister(pin)) +#define PIN_TO_BITMASK(pin) (1) +#define IO_REG_TYPE uint8_t +#define IO_REG_ASM +#define DIRECT_READ(base, mask) (*((base)+512)) +#define DIRECT_MODE_INPUT(base, mask) (*((base)+640) = 0) +#define DIRECT_MODE_OUTPUT(base, mask) (*((base)+640) = 1) +#define DIRECT_WRITE_LOW(base, mask) (*((base)+256) = 1) +#define DIRECT_WRITE_HIGH(base, mask) (*((base)+128) = 1) + +#elif defined(__MKL26Z64__) +#define PIN_TO_BASEREG(pin) (portOutputRegister(pin)) +#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) +#define IO_REG_TYPE uint8_t +#define IO_REG_ASM +#define DIRECT_READ(base, mask) ((*((base)+16) & (mask)) ? 1 : 0) +#define DIRECT_MODE_INPUT(base, mask) (*((base)+20) &= ~(mask)) +#define DIRECT_MODE_OUTPUT(base, mask) (*((base)+20) |= (mask)) +#define DIRECT_WRITE_LOW(base, mask) (*((base)+8) = (mask)) +#define DIRECT_WRITE_HIGH(base, mask) (*((base)+4) = (mask)) + +#elif defined(__SAM3X8E__) +// Arduino 1.5.1 may have a bug in delayMicroseconds() on Arduino Due. +// http://arduino.cc/forum/index.php/topic,141030.msg1076268.html#msg1076268 +// If you have trouble with OneWire on Arduino Due, please check the +// status of delayMicroseconds() before reporting a bug in OneWire! +#define PIN_TO_BASEREG(pin) (&(digitalPinToPort(pin)->PIO_PER)) +#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) +#define IO_REG_TYPE uint32_t +#define IO_REG_ASM +#define DIRECT_READ(base, mask) (((*((base)+15)) & (mask)) ? 1 : 0) +#define DIRECT_MODE_INPUT(base, mask) ((*((base)+5)) = (mask)) +#define DIRECT_MODE_OUTPUT(base, mask) ((*((base)+4)) = (mask)) +#define DIRECT_WRITE_LOW(base, mask) ((*((base)+13)) = (mask)) +#define DIRECT_WRITE_HIGH(base, mask) ((*((base)+12)) = (mask)) +#ifndef PROGMEM +#define PROGMEM +#endif +#ifndef pgm_read_byte +#define pgm_read_byte(addr) (*(const uint8_t *)(addr)) +#endif + +#elif defined(__PIC32MX__) +#define PIN_TO_BASEREG(pin) (portModeRegister(digitalPinToPort(pin))) +#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) +#define IO_REG_TYPE uint32_t +#define IO_REG_ASM +#define DIRECT_READ(base, mask) (((*(base+4)) & (mask)) ? 1 : 0) //PORTX + 0x10 +#define DIRECT_MODE_INPUT(base, mask) ((*(base+2)) = (mask)) //TRISXSET + 0x08 +#define DIRECT_MODE_OUTPUT(base, mask) ((*(base+1)) = (mask)) //TRISXCLR + 0x04 +#define DIRECT_WRITE_LOW(base, mask) ((*(base+8+1)) = (mask)) //LATXCLR + 0x24 +#define DIRECT_WRITE_HIGH(base, mask) ((*(base+8+2)) = (mask)) //LATXSET + 0x28 + +#elif defined(ARDUINO_ARCH_ESP8266) +#define PIN_TO_BASEREG(pin) ((volatile uint32_t*) GPO) +#define PIN_TO_BITMASK(pin) (1 << pin) +#define IO_REG_TYPE uint32_t +#define IO_REG_ASM +#define DIRECT_READ(base, mask) ((GPI & (mask)) ? 1 : 0) //GPIO_IN_ADDRESS +#define DIRECT_MODE_INPUT(base, mask) (GPE &= ~(mask)) //GPIO_ENABLE_W1TC_ADDRESS +#define DIRECT_MODE_OUTPUT(base, mask) (GPE |= (mask)) //GPIO_ENABLE_W1TS_ADDRESS +#define DIRECT_WRITE_LOW(base, mask) (GPOC = (mask)) //GPIO_OUT_W1TC_ADDRESS +#define DIRECT_WRITE_HIGH(base, mask) (GPOS = (mask)) //GPIO_OUT_W1TS_ADDRESS + +#elif defined(__SAMD21G18A__) +#define PIN_TO_BASEREG(pin) portModeRegister(digitalPinToPort(pin)) +#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) +#define IO_REG_TYPE uint32_t +#define IO_REG_ASM +#define DIRECT_READ(base, mask) (((*((base)+8)) & (mask)) ? 1 : 0) +#define DIRECT_MODE_INPUT(base, mask) ((*((base)+1)) = (mask)) +#define DIRECT_MODE_OUTPUT(base, mask) ((*((base)+2)) = (mask)) +#define DIRECT_WRITE_LOW(base, mask) ((*((base)+5)) = (mask)) +#define DIRECT_WRITE_HIGH(base, mask) ((*((base)+6)) = (mask)) + +#elif defined(RBL_NRF51822) +#define PIN_TO_BASEREG(pin) (0) +#define PIN_TO_BITMASK(pin) (pin) +#define IO_REG_TYPE uint32_t +#define IO_REG_ASM +#define DIRECT_READ(base, pin) nrf_gpio_pin_read(pin) +#define DIRECT_WRITE_LOW(base, pin) nrf_gpio_pin_clear(pin) +#define DIRECT_WRITE_HIGH(base, pin) nrf_gpio_pin_set(pin) +#define DIRECT_MODE_INPUT(base, pin) nrf_gpio_cfg_input(pin, NRF_GPIO_PIN_NOPULL) +#define DIRECT_MODE_OUTPUT(base, pin) nrf_gpio_cfg_output(pin) + +#elif defined(__arc__) /* Arduino101/Genuino101 specifics */ + +#include "scss_registers.h" +#include "portable.h" +#include "avr/pgmspace.h" + +#define GPIO_ID(pin) (g_APinDescription[pin].ulGPIOId) +#define GPIO_TYPE(pin) (g_APinDescription[pin].ulGPIOType) +#define GPIO_BASE(pin) (g_APinDescription[pin].ulGPIOBase) +#define DIR_OFFSET_SS 0x01 +#define DIR_OFFSET_SOC 0x04 +#define EXT_PORT_OFFSET_SS 0x0A +#define EXT_PORT_OFFSET_SOC 0x50 + +/* GPIO registers base address */ +#define PIN_TO_BASEREG(pin) ((volatile uint32_t *)g_APinDescription[pin].ulGPIOBase) +#define PIN_TO_BITMASK(pin) pin +#define IO_REG_TYPE uint32_t +#define IO_REG_ASM + +static inline __attribute__((always_inline)) +IO_REG_TYPE directRead(volatile IO_REG_TYPE *base, IO_REG_TYPE pin) +{ + IO_REG_TYPE ret; + if (SS_GPIO == GPIO_TYPE(pin)) { + ret = READ_ARC_REG(((IO_REG_TYPE)base + EXT_PORT_OFFSET_SS)); + } else { + ret = MMIO_REG_VAL_FROM_BASE((IO_REG_TYPE)base, EXT_PORT_OFFSET_SOC); + } + return ((ret >> GPIO_ID(pin)) & 0x01); +} + +static inline __attribute__((always_inline)) +void directModeInput(volatile IO_REG_TYPE *base, IO_REG_TYPE pin) +{ + if (SS_GPIO == GPIO_TYPE(pin)) { + WRITE_ARC_REG(READ_ARC_REG((((IO_REG_TYPE)base) + DIR_OFFSET_SS)) & ~(0x01 << GPIO_ID(pin)), + ((IO_REG_TYPE)(base) + DIR_OFFSET_SS)); + } else { + MMIO_REG_VAL_FROM_BASE((IO_REG_TYPE)base, DIR_OFFSET_SOC) &= ~(0x01 << GPIO_ID(pin)); + } +} + +static inline __attribute__((always_inline)) +void directModeOutput(volatile IO_REG_TYPE *base, IO_REG_TYPE pin) +{ + if (SS_GPIO == GPIO_TYPE(pin)) { + WRITE_ARC_REG(READ_ARC_REG(((IO_REG_TYPE)(base) + DIR_OFFSET_SS)) | (0x01 << GPIO_ID(pin)), + ((IO_REG_TYPE)(base) + DIR_OFFSET_SS)); + } else { + MMIO_REG_VAL_FROM_BASE((IO_REG_TYPE)base, DIR_OFFSET_SOC) |= (0x01 << GPIO_ID(pin)); + } +} + +static inline __attribute__((always_inline)) +void directWriteLow(volatile IO_REG_TYPE *base, IO_REG_TYPE pin) +{ + if (SS_GPIO == GPIO_TYPE(pin)) { + WRITE_ARC_REG(READ_ARC_REG(base) & ~(0x01 << GPIO_ID(pin)), base); + } else { + MMIO_REG_VAL(base) &= ~(0x01 << GPIO_ID(pin)); + } +} + +static inline __attribute__((always_inline)) +void directWriteHigh(volatile IO_REG_TYPE *base, IO_REG_TYPE pin) +{ + if (SS_GPIO == GPIO_TYPE(pin)) { + WRITE_ARC_REG(READ_ARC_REG(base) | (0x01 << GPIO_ID(pin)), base); + } else { + MMIO_REG_VAL(base) |= (0x01 << GPIO_ID(pin)); + } +} + +#define DIRECT_READ(base, pin) directRead(base, pin) +#define DIRECT_MODE_INPUT(base, pin) directModeInput(base, pin) +#define DIRECT_MODE_OUTPUT(base, pin) directModeOutput(base, pin) +#define DIRECT_WRITE_LOW(base, pin) directWriteLow(base, pin) +#define DIRECT_WRITE_HIGH(base, pin) directWriteHigh(base, pin) + +#else +#define PIN_TO_BASEREG(pin) (0) +#define PIN_TO_BITMASK(pin) (pin) +#define IO_REG_TYPE unsigned int +#define IO_REG_ASM +#define DIRECT_READ(base, pin) digitalRead(pin) +#define DIRECT_WRITE_LOW(base, pin) digitalWrite(pin, LOW) +#define DIRECT_WRITE_HIGH(base, pin) digitalWrite(pin, HIGH) +#define DIRECT_MODE_INPUT(base, pin) pinMode(pin,INPUT) +#define DIRECT_MODE_OUTPUT(base, pin) pinMode(pin,OUTPUT) +#warning "OneWire. Fallback mode. Using API calls for pinMode,digitalRead and digitalWrite. Operation of this library is not guaranteed on this architecture." + +#endif + + +class OneWire +{ + private: + IO_REG_TYPE bitmask; + volatile IO_REG_TYPE *baseReg; + +#if ONEWIRE_SEARCH + // global search state + unsigned char ROM_NO[8]; + uint8_t LastDiscrepancy; + uint8_t LastFamilyDiscrepancy; + uint8_t LastDeviceFlag; +#endif + + public: + OneWire( uint8_t pin); + + // Perform a 1-Wire reset cycle. Returns 1 if a device responds + // with a presence pulse. Returns 0 if there is no device or the + // bus is shorted or otherwise held low for more than 250uS + uint8_t reset(void); + + // Issue a 1-Wire rom select command, you do the reset first. + void select(const uint8_t rom[8]); + + // Issue a 1-Wire rom skip command, to address all on bus. + void skip(void); + + // Write a byte. If 'power' is one then the wire is held high at + // the end for parasitically powered devices. You are responsible + // for eventually depowering it by calling depower() or doing + // another read or write. + void write(uint8_t v, uint8_t power = 0); + + void write_bytes(const uint8_t *buf, uint16_t count, bool power = 0); + + // Read a byte. + uint8_t read(void); + + void read_bytes(uint8_t *buf, uint16_t count); + + // Write a bit. The bus is always left powered at the end, see + // note in write() about that. + void write_bit(uint8_t v); + + // Read a bit. + uint8_t read_bit(void); + + // Stop forcing power onto the bus. You only need to do this if + // you used the 'power' flag to write() or used a write_bit() call + // and aren't about to do another read or write. You would rather + // not leave this powered if you don't have to, just in case + // someone shorts your bus. + void depower(void); + +#if ONEWIRE_SEARCH + // Clear the search state so that if will start from the beginning again. + void reset_search(); + + // Setup the search to find the device type 'family_code' on the next call + // to search(*newAddr) if it is present. + void target_search(uint8_t family_code); + + // Look for the next device. Returns 1 if a new address has been + // returned. A zero might mean that the bus is shorted, there are + // no devices, or you have already retrieved all of them. It + // might be a good idea to check the CRC to make sure you didn't + // get garbage. The order is deterministic. You will always get + // the same devices in the same order. + uint8_t search(uint8_t *newAddr, bool search_mode = true); +#endif + +#if ONEWIRE_CRC + // Compute a Dallas Semiconductor 8 bit CRC, these are used in the + // ROM and scratchpad registers. + static uint8_t crc8(const uint8_t *addr, uint8_t len); + +#if ONEWIRE_CRC16 + // Compute the 1-Wire CRC16 and compare it against the received CRC. + // Example usage (reading a DS2408): + // // Put everything in a buffer so we can compute the CRC easily. + // uint8_t buf[13]; + // buf[0] = 0xF0; // Read PIO Registers + // buf[1] = 0x88; // LSB address + // buf[2] = 0x00; // MSB address + // WriteBytes(net, buf, 3); // Write 3 cmd bytes + // ReadBytes(net, buf+3, 10); // Read 6 data bytes, 2 0xFF, 2 CRC16 + // if (!CheckCRC16(buf, 11, &buf[11])) { + // // Handle error. + // } + // + // @param input - Array of bytes to checksum. + // @param len - How many bytes to use. + // @param inverted_crc - The two CRC16 bytes in the received data. + // This should just point into the received data, + // *not* at a 16-bit integer. + // @param crc - The crc starting value (optional) + // @return True, iff the CRC matches. + static bool check_crc16(const uint8_t* input, uint16_t len, const uint8_t* inverted_crc, uint16_t crc = 0); + + // Compute a Dallas Semiconductor 16 bit CRC. This is required to check + // the integrity of data received from many 1-Wire devices. Note that the + // CRC computed here is *not* what you'll get from the 1-Wire network, + // for two reasons: + // 1) The CRC is transmitted bitwise inverted. + // 2) Depending on the endian-ness of your processor, the binary + // representation of the two-byte return value may have a different + // byte order than the two bytes you get from 1-Wire. + // @param input - Array of bytes to checksum. + // @param len - How many bytes to use. + // @param crc - The crc starting value (optional) + // @return The CRC16, as defined by Dallas Semiconductor. + static uint16_t crc16(const uint8_t* input, uint16_t len, uint16_t crc = 0); +#endif +#endif +}; + +#endif diff --git a/resources/arduino_files/libraries/OneWire/examples/DS18x20_Temperature/DS18x20_Temperature.pde b/resources/arduino_files/libraries/OneWire/examples/DS18x20_Temperature/DS18x20_Temperature.pde new file mode 100644 index 000000000..68ca19432 --- /dev/null +++ b/resources/arduino_files/libraries/OneWire/examples/DS18x20_Temperature/DS18x20_Temperature.pde @@ -0,0 +1,112 @@ +#include + +// OneWire DS18S20, DS18B20, DS1822 Temperature Example +// +// http://www.pjrc.com/teensy/td_libs_OneWire.html +// +// The DallasTemperature library can do all this work for you! +// http://milesburton.com/Dallas_Temperature_Control_Library + +OneWire ds(10); // on pin 10 (a 4.7K resistor is necessary) + +void setup(void) { + Serial.begin(9600); +} + +void loop(void) { + byte i; + byte present = 0; + byte type_s; + byte data[12]; + byte addr[8]; + float celsius, fahrenheit; + + if ( !ds.search(addr)) { + Serial.println("No more addresses."); + Serial.println(); + ds.reset_search(); + delay(250); + return; + } + + Serial.print("ROM ="); + for( i = 0; i < 8; i++) { + Serial.write(' '); + Serial.print(addr[i], HEX); + } + + if (OneWire::crc8(addr, 7) != addr[7]) { + Serial.println("CRC is not valid!"); + return; + } + Serial.println(); + + // the first ROM byte indicates which chip + switch (addr[0]) { + case 0x10: + Serial.println(" Chip = DS18S20"); // or old DS1820 + type_s = 1; + break; + case 0x28: + Serial.println(" Chip = DS18B20"); + type_s = 0; + break; + case 0x22: + Serial.println(" Chip = DS1822"); + type_s = 0; + break; + default: + Serial.println("Device is not a DS18x20 family device."); + return; + } + + ds.reset(); + ds.select(addr); + ds.write(0x44, 1); // start conversion, with parasite power on at the end + + delay(1000); // maybe 750ms is enough, maybe not + // we might do a ds.depower() here, but the reset will take care of it. + + present = ds.reset(); + ds.select(addr); + ds.write(0xBE); // Read Scratchpad + + Serial.print(" Data = "); + Serial.print(present, HEX); + Serial.print(" "); + for ( i = 0; i < 9; i++) { // we need 9 bytes + data[i] = ds.read(); + Serial.print(data[i], HEX); + Serial.print(" "); + } + Serial.print(" CRC="); + Serial.print(OneWire::crc8(data, 8), HEX); + Serial.println(); + + // Convert the data to actual temperature + // because the result is a 16 bit signed integer, it should + // be stored to an "int16_t" type, which is always 16 bits + // even when compiled on a 32 bit processor. + int16_t raw = (data[1] << 8) | data[0]; + if (type_s) { + raw = raw << 3; // 9 bit resolution default + if (data[7] == 0x10) { + // "count remain" gives full 12 bit resolution + raw = (raw & 0xFFF0) + 12 - data[6]; + } + } else { + byte cfg = (data[4] & 0x60); + // at lower res, the low bits are undefined, so let's zero them + if (cfg == 0x00) raw = raw & ~7; // 9 bit resolution, 93.75 ms + else if (cfg == 0x20) raw = raw & ~3; // 10 bit res, 187.5 ms + else if (cfg == 0x40) raw = raw & ~1; // 11 bit res, 375 ms + //// default is 12 bit resolution, 750 ms conversion time + } + celsius = (float)raw / 16.0; + fahrenheit = celsius * 1.8 + 32.0; + Serial.print(" Temperature = "); + Serial.print(celsius); + Serial.print(" Celsius, "); + Serial.print(fahrenheit); + Serial.println(" Fahrenheit"); +} diff --git a/resources/arduino_files/libraries/OneWire/examples/DS2408_Switch/DS2408_Switch.pde b/resources/arduino_files/libraries/OneWire/examples/DS2408_Switch/DS2408_Switch.pde new file mode 100644 index 000000000..d171f9ba0 --- /dev/null +++ b/resources/arduino_files/libraries/OneWire/examples/DS2408_Switch/DS2408_Switch.pde @@ -0,0 +1,77 @@ +#include + +/* + * DS2408 8-Channel Addressable Switch + * + * Writte by Glenn Trewitt, glenn at trewitt dot org + * + * Some notes about the DS2408: + * - Unlike most input/output ports, the DS2408 doesn't have mode bits to + * set whether the pins are input or output. If you issue a read command, + * they're inputs. If you write to them, they're outputs. + * - For reading from a switch, you should use 10K pull-up resisters. + */ + +void PrintBytes(uint8_t* addr, uint8_t count, bool newline=0) { + for (uint8_t i = 0; i < count; i++) { + Serial.print(addr[i]>>4, HEX); + Serial.print(addr[i]&0x0f, HEX); + } + if (newline) + Serial.println(); +} + +void ReadAndReport(OneWire* net, uint8_t* addr) { + Serial.print(" Reading DS2408 "); + PrintBytes(addr, 8); + Serial.println(); + + uint8_t buf[13]; // Put everything in the buffer so we can compute CRC easily. + buf[0] = 0xF0; // Read PIO Registers + buf[1] = 0x88; // LSB address + buf[2] = 0x00; // MSB address + net->write_bytes(buf, 3); + net->read_bytes(buf+3, 10); // 3 cmd bytes, 6 data bytes, 2 0xFF, 2 CRC16 + net->reset(); + + if (!OneWire::check_crc16(buf, 11, &buf[11])) { + Serial.print("CRC failure in DS2408 at "); + PrintBytes(addr, 8, true); + return; + } + Serial.print(" DS2408 data = "); + // First 3 bytes contain command, register address. + Serial.println(buf[3], BIN); +} + +OneWire net(10); // on pin 10 + +void setup(void) { + Serial.begin(9600); +} + +void loop(void) { + byte i; + byte present = 0; + byte addr[8]; + + if (!net.search(addr)) { + Serial.print("No more addresses.\n"); + net.reset_search(); + delay(1000); + return; + } + + if (OneWire::crc8(addr, 7) != addr[7]) { + Serial.print("CRC is not valid!\n"); + return; + } + + if (addr[0] != 0x29) { + PrintBytes(addr, 8); + Serial.print(" is not a DS2408.\n"); + return; + } + + ReadAndReport(&net, addr); +} diff --git a/resources/arduino_files/libraries/OneWire/examples/DS250x_PROM/DS250x_PROM.pde b/resources/arduino_files/libraries/OneWire/examples/DS250x_PROM/DS250x_PROM.pde new file mode 100644 index 000000000..baa51c8f3 --- /dev/null +++ b/resources/arduino_files/libraries/OneWire/examples/DS250x_PROM/DS250x_PROM.pde @@ -0,0 +1,90 @@ +/* +DS250x add-only programmable memory reader w/SKIP ROM. + + The DS250x is a 512/1024bit add-only PROM(you can add data but cannot change the old one) that's used mainly for device identification purposes + like serial number, mfgr data, unique identifiers, etc. It uses the Maxim 1-wire bus. + + This sketch will use the SKIP ROM function that skips the 1-Wire search phase since we only have one device connected in the bus on digital pin 6. + If more than one device is connected to the bus, it will fail. + Sketch will not verify if device connected is from the DS250x family since the skip rom function effectively skips the family-id byte readout. + thus it is possible to run this sketch with any Maxim OneWire device in which case the command CRC will most likely fail. + Sketch will only read the first page of memory(32bits) starting from the lower address(0000h), if more than 1 device is present, then use the sketch with search functions. + Remember to put a 4.7K pullup resistor between pin 6 and +Vcc + + To change the range or ammount of data to read, simply change the data array size, LSB/MSB addresses and for loop iterations + + This example code is in the public domain and is provided AS-IS. + + Built with Arduino 0022 and PJRC OneWire 2.0 library http://www.pjrc.com/teensy/td_libs_OneWire.html + + created by Guillermo Lovato + march/2011 + + */ + +#include +OneWire ds(6); // OneWire bus on digital pin 6 +void setup() { + Serial.begin (9600); +} + +void loop() { + byte i; // This is for the for loops + boolean present; // device present var + byte data[32]; // container for the data from device + byte leemem[3] = { // array with the commands to initiate a read, DS250x devices expect 3 bytes to start a read: command,LSB&MSB adresses + 0xF0 , 0x00 , 0x00 }; // 0xF0 is the Read Data command, followed by 00h 00h as starting address(the beginning, 0000h) + byte ccrc; // Variable to store the command CRC + byte ccrc_calc; + + present = ds.reset(); // OneWire bus reset, always needed to start operation on the bus, returns a 1/TRUE if there's a device present. + ds.skip(); // Skip ROM search + + if (present == TRUE){ // We only try to read the data if there's a device present + Serial.println("DS250x device present"); + ds.write(leemem[0],1); // Read data command, leave ghost power on + ds.write(leemem[1],1); // LSB starting address, leave ghost power on + ds.write(leemem[2],1); // MSB starting address, leave ghost power on + + ccrc = ds.read(); // DS250x generates a CRC for the command we sent, we assign a read slot and store it's value + ccrc_calc = OneWire::crc8(leemem, 3); // We calculate the CRC of the commands we sent using the library function and store it + + if ( ccrc_calc != ccrc) { // Then we compare it to the value the ds250x calculated, if it fails, we print debug messages and abort + Serial.println("Invalid command CRC!"); + Serial.print("Calculated CRC:"); + Serial.println(ccrc_calc,HEX); // HEX makes it easier to observe and compare + Serial.print("DS250x readback CRC:"); + Serial.println(ccrc,HEX); + return; // Since CRC failed, we abort the rest of the loop and start over + } + Serial.println("Data is: "); // For the printout of the data + for ( i = 0; i < 32; i++) { // Now it's time to read the PROM data itself, each page is 32 bytes so we need 32 read commands + data[i] = ds.read(); // we store each read byte to a different position in the data array + Serial.print(data[i]); // printout in ASCII + Serial.print(" "); // blank space + } + Serial.println(); + delay(5000); // Delay so we don't saturate the serial output + } + else { // Nothing is connected in the bus + Serial.println("Nothing connected"); + delay(3000); + } +} + + + + + + + + + + + + + + + + + diff --git a/resources/arduino_files/libraries/OneWire/keywords.txt b/resources/arduino_files/libraries/OneWire/keywords.txt new file mode 100644 index 000000000..bee5d90b2 --- /dev/null +++ b/resources/arduino_files/libraries/OneWire/keywords.txt @@ -0,0 +1,38 @@ +####################################### +# Syntax Coloring Map For OneWire +####################################### + +####################################### +# Datatypes (KEYWORD1) +####################################### + +OneWire KEYWORD1 + +####################################### +# Methods and Functions (KEYWORD2) +####################################### + +reset KEYWORD2 +write_bit KEYWORD2 +read_bit KEYWORD2 +write KEYWORD2 +write_bytes KEYWORD2 +read KEYWORD2 +read_bytes KEYWORD2 +select KEYWORD2 +skip KEYWORD2 +depower KEYWORD2 +reset_search KEYWORD2 +search KEYWORD2 +crc8 KEYWORD2 +crc16 KEYWORD2 +check_crc16 KEYWORD2 + +####################################### +# Instances (KEYWORD2) +####################################### + + +####################################### +# Constants (LITERAL1) +####################################### diff --git a/resources/arduino_files/libraries/OneWire/library.json b/resources/arduino_files/libraries/OneWire/library.json new file mode 100644 index 000000000..ed232503e --- /dev/null +++ b/resources/arduino_files/libraries/OneWire/library.json @@ -0,0 +1,58 @@ +{ +"name": "OneWire", +"frameworks": "Arduino", +"keywords": "onewire, 1-wire, bus, sensor, temperature, ibutton", +"description": "Control 1-Wire protocol (DS18S20, DS18B20, DS2408 and etc)", +"authors": +[ + { + "name": "Paul Stoffregen", + "email": "paul@pjrc.com", + "url": "http://www.pjrc.com", + "maintainer": true + }, + { + "name": "Jim Studt" + }, + { + "name": "Tom Pollard", + "email": "pollard@alum.mit.edu" + }, + { + "name": "Derek Yerger" + }, + { + "name": "Josh Larios" + }, + { + "name": "Robin James" + }, + { + "name": "Glenn Trewitt" + }, + { + "name": "Jason Dangel", + "email": "dangel.jason AT gmail.com" + }, + { + "name": "Guillermo Lovato" + }, + { + "name": "Ken Butcher" + }, + { + "name": "Mark Tillotson" + }, + { + "name": "Bertrik Sikken" + }, + { + "name": "Scott Roberts" + } +], +"repository": +{ + "type": "git", + "url": "https://github.com/PaulStoffregen/OneWire" +} +} diff --git a/resources/arduino_files/libraries/OneWire/library.properties b/resources/arduino_files/libraries/OneWire/library.properties new file mode 100644 index 000000000..0946c9aa9 --- /dev/null +++ b/resources/arduino_files/libraries/OneWire/library.properties @@ -0,0 +1,10 @@ +name=OneWire +version=2.3.2 +author=Jim Studt, Tom Pollard, Robin James, Glenn Trewitt, Jason Dangel, Guillermo Lovato, Paul Stoffregen, Scott Roberts, Bertrik Sikken, Mark Tillotson, Ken Butcher, Roger Clark, Love Nystrom +maintainer=Paul Stoffregen +sentence=Access 1-wire temperature sensors, memory and other chips. +paragraph= +category=Communication +url=http://www.pjrc.com/teensy/td_libs_OneWire.html +architectures=* + diff --git a/resources/arduino_files/power_board/power_board.ino b/resources/arduino_files/power_board/power_board.ino new file mode 100644 index 000000000..dc8c79b85 --- /dev/null +++ b/resources/arduino_files/power_board/power_board.ino @@ -0,0 +1,239 @@ +#include + +#include +#include +#include + +#define DHTTYPE DHT22 // DHT 22 (AM2302) + +/* DECLARE PINS */ + +// Current Sense +const int IS_0 = A0; // PROFET-0 +const int IS_1 = A1; // PROFET-1 +const int IS_2 = A2; // PROFET-2 + +// Channel select +const int DSEL_0 = 2; // PROFET-0 +const int DSEL_1 = 6; // PROFET-1 + +const inst DEN_0 = A4; // PROFET-0 +const inst DEN_1 = 5; // PROFET-1 +const inst DEN_2 = 9; // PROFET-2 + +// Digital Pins +const int DS18_PIN = 10; // DS18B20 Temperature (OneWire) +const int DHT_PIN = 11; // DHT Temp & Humidity Pin + +// Relays +const int RELAY_1 = A3; // 0_0 PROFET-0 Channel 0 +const int RELAY_2 = 3; // 1_0 PROFET-0 Channel 1 +const int RELAY_3 = 4; // 0_1 PROFET-1 Channel 0 +const int RELAY_4 = 7; // 1_1 PROFET-1 Channel 1 +const int RELAY_5 = 8; // 0_2 PROFET-2 Channel 0 + +const int relayArray[] = {RELAY_1, RELAY_2, RELAY_3, RELAY_4, RELAY_5}; +const int numRelay = 5; + +const int NUM_DS18 = 3; // Number of DS18B20 Sensors + +uint8_t sensors_address[NUM_DS18][8]; + +// Temperature chip I/O +OneWire ds(DS18_PIN); +DallasTemperature sensors(&ds); + +// Setup DHT22 +DHT dht(DHT_PIN, DHTTYPE); + +int led_value = LOW; + +void setup() { + Serial.begin(9600); + Serial.flush(); + + pinMode(LED_BUILTIN, OUTPUT); + + sensors.begin(); + + pinMode(AC_PIN, INPUT); + + // Turn relays on to start + for (int i = 0; i < numRelay; i++) { + pinMode(relayArray[i], OUTPUT); + digitalWrite(relayArray[i], HIGH); + delay(250); + } + + dht.begin(); +} + +void loop() { + + // Read any serial input + // - Input will be two comma separated integers, the + // first specifying the pin and the second the status + // to change to (1/0). Only the fan and the debug led + // are currently supported. + // Example serial input: + // 4,1 # Turn relay 4 on + // 4,2 # Toggle relay 4 + // 4,3 # Toggle relay 4 w/ 30 sec delay + // 4,9 # Turn relay 4 off + while (Serial.available() > 0) { + int pin_num = Serial.parseInt(); + int pin_status = Serial.parseInt(); + + switch (pin_status) { + case 1: + turn_pin_on(pin_num); + break; + case 2: + toggle_pin(pin_num); + break; + case 3: + toggle_pin_delay(pin_num); + case 9: + turn_pin_off(pin_num); + break; + } + } + + get_readings(); + + // Simple heartbeat + toggle_led(); + delay(500); +} + +void get_readings() { + Serial.print("{"); + + read_voltages(); + + read_dht_temp(); + + read_ds18b20_temp(); + + Serial.print("\"name\":\"telemetry_board\""); Serial.print(","); + + Serial.print("\"count\":"); Serial.print(millis()); + + Serial.println("}"); +} + +/* Read Voltages + +Gets the AC probe as well as the values of the current on the AC I_ pins + +https://www.arduino.cc/en/Reference/AnalogRead + + */ +void read_voltages() { + int ac_reading = digitalRead(AC_PIN); + + int main_reading = analogRead(I_MAIN); + float main_amps = (main_reading / 1023.) * main_amps_mult; +// float main_amps = ((main_voltage - ACS_offset) / mV_per_amp); + + int fan_reading = analogRead(I_FAN); + float fan_amps = (fan_reading / 1023.) * fan_amps_mult; +// float fan_amps = ((fan_voltage - ACS_offset) / mV_per_amp); + + int mount_reading = analogRead(I_MOUNT); + float mount_amps = (mount_reading / 1023.) * mount_amps_mult; +// float mount_amps = ((mount_voltage - ACS_offset) / mV_per_amp); + + int camera_reading = analogRead(I_CAMERAS); + float camera_amps = (camera_reading / 1023.) * 1; +// float camera_amps = ((camera_voltage - ACS_offset) / mV_per_amp); + + Serial.print("\"power\":{"); + Serial.print("\"computer\":"); Serial.print(is_pin_on(COMP_RELAY)); Serial.print(','); + Serial.print("\"fan\":"); Serial.print(is_pin_on(FAN_RELAY)); Serial.print(','); + Serial.print("\"mount\":"); Serial.print(is_pin_on(MOUNT_RELAY)); Serial.print(','); + Serial.print("\"cameras\":"); Serial.print(is_pin_on(CAMERAS_RELAY)); Serial.print(','); + Serial.print("\"weather\":"); Serial.print(is_pin_on(WEATHER_RELAY)); Serial.print(','); + Serial.print("\"main\":"); Serial.print(ac_reading); Serial.print(','); + Serial.print("},"); + + Serial.print("\"current\":{"); + Serial.print("\"main\":"); Serial.print(main_reading); Serial.print(','); + Serial.print("\"fan\":"); Serial.print(fan_reading); Serial.print(','); + Serial.print("\"mount\":"); Serial.print(mount_reading); Serial.print(','); + Serial.print("\"cameras\":"); Serial.print(camera_reading); + Serial.print("},"); + +// Serial.print("\"volts\":{"); +// Serial.print("\"main\":"); Serial.print(main_voltage); Serial.print(','); +// Serial.print("\"fan\":"); Serial.print(fan_voltage); Serial.print(','); +// Serial.print("\"mount\":"); Serial.print(mount_voltage); Serial.print(','); +// Serial.print("\"cameras\":"); Serial.print(camera_voltage); +// Serial.print("},"); + + Serial.print("\"amps\":{"); + Serial.print("\"main\":"); Serial.print(main_amps); Serial.print(','); + Serial.print("\"fan\":"); Serial.print(fan_amps); Serial.print(','); + Serial.print("\"mount\":"); Serial.print(mount_amps); Serial.print(','); + Serial.print("\"cameras\":"); Serial.print(camera_amps); + Serial.print("},"); +} + +// Reading temperature or humidity takes about 250 milliseconds! +// Sensor readings may also be up to 2 seconds 'old' (its a very slow sensor) +void read_dht_temp() { + float h = dht.readHumidity(); + float c = dht.readTemperature(); // Celsius + + // Check if any reads failed and exit early (to try again). + // if (isnan(h) || isnan(t)) { + // Serial.println("Failed to read from DHT sensor!"); + // return; + // } + + Serial.print("\"humidity\":"); Serial.print(h); Serial.print(','); + Serial.print("\"temp_00\":"); Serial.print(c); Serial.print(','); +} + +void read_ds18b20_temp() { + + sensors.requestTemperatures(); + + Serial.print("\"temperature\":["); + + for (int x = 0; x < NUM_DS18; x++) { + Serial.print(sensors.getTempCByIndex(x)); Serial.print(","); + } + Serial.print("],"); +} + + +/************************************ +* Utitlity Methods +*************************************/ + +int is_pin_on(int pin_num) { + return digitalRead(pin_num); +} + +void turn_pin_on(int pin_num) { + digitalWrite(pin_num, HIGH); +} + +void turn_pin_off(int pin_num) { + digitalWrite(pin_num, LOW); +} + +void toggle_pin(int pin_num) { + digitalWrite(pin_num, !digitalRead(pin_num)); +} + +void toggle_pin_delay(int pin_num, int delay = 30) { + turn_pin_off(pin_num); + delay(1000 * delay); + turn_pin_on(pin_num); +} + +void toggle_led() { + toggle_pin(LED_BUILTIN); +} diff --git a/resources/arduino_files/telemetry_board/telemetry_board.ino b/resources/arduino_files/telemetry_board/telemetry_board.ino new file mode 100644 index 000000000..f4dc91910 --- /dev/null +++ b/resources/arduino_files/telemetry_board/telemetry_board.ino @@ -0,0 +1,260 @@ +#include +#include +#include + + +#include + +#define DHTTYPE DHT22 // DHT 22 (AM2302) + +/* DECLARE PINS */ + +// Analog Pins +const int I_MAIN = A1; +const int I_FAN = A2; +const int I_MOUNT = A3; +const int I_CAMERAS = A4; + +// Digital Pins +const int AC_PIN = 11; +const int DS18_PIN = 10; // DS18B20 Temperature (OneWire) +const int DHT_PIN = 9; // DHT Temp & Humidity Pin + +const int COMP_RELAY = 8; // Computer Relay +const int CAMERAS_RELAY = 7; // Cameras Relay Off: 70s Both On: 800s One On: 350 +const int FAN_RELAY = 6; // Fan Relay Off: 0 On: 80s +const int WEATHER_RELAY = 5; // Weather Relay 250mA upon init and 250mA to read +const int MOUNT_RELAY = 4; // Mount Relay + +const float main_amps_mult = 2.8; +const float fan_amps_mult = 1.8; +const float mount_amps_mult = 1.8; +const float camera_amps_mult = 1.0; + +const int NUM_DS18 = 3; // Number of DS18B20 Sensors + + +/* CONSTANTS */ +/* +For info on the current sensing, see: + http://henrysbench.capnfatz.com/henrys-bench/arduino-current-measurements/the-acs712-current-sensor-with-an-arduino/ + http://henrysbench.capnfatz.com/henrys-bench/arduino-current-measurements/acs712-current-sensor-user-manual/ +*/ +const float mV_per_amp = 0.185; +const float ACS_offset = 0.; + + +uint8_t sensors_address[NUM_DS18][8]; + +// Temperature chip I/O +OneWire ds(DS18_PIN); +DallasTemperature sensors(&ds); + +// Setup DHT22 +DHT dht(DHT_PIN, DHTTYPE); + +int led_value = LOW; + + +void setup() { + Serial.begin(9600); + Serial.flush(); + + pinMode(LED_BUILTIN, OUTPUT); + + sensors.begin(); + + pinMode(AC_PIN, INPUT); + + pinMode(COMP_RELAY, OUTPUT); + pinMode(CAMERAS_RELAY, OUTPUT); + pinMode(FAN_RELAY, OUTPUT); + pinMode(WEATHER_RELAY, OUTPUT); + pinMode(MOUNT_RELAY, OUTPUT); + + // Turn relays on to start + digitalWrite(COMP_RELAY, HIGH); + digitalWrite(CAMERAS_RELAY, HIGH); + digitalWrite(FAN_RELAY, HIGH); + digitalWrite(WEATHER_RELAY, HIGH); + digitalWrite(MOUNT_RELAY, HIGH); + + dht.begin(); + +} + +void loop() { + + // Read any serial input + // - Input will be two comma separated integers, the + // first specifying the pin and the second the status + // to change to (1/0). Only the fan and the debug led + // are currently supported. + // Example serial input: + // 4,1 # Turn fan on + // 13,0 # Turn led off + while (Serial.available() > 0) { + int pin_num = Serial.parseInt(); + int pin_status = Serial.parseInt(); + + switch (pin_num) { + case COMP_RELAY: + /* The computer shutting itself off: + * - Power down + * - Wait 30 seconds + * - Power up + */ + if (pin_status == 0){ + turn_pin_off(COMP_RELAY); + delay(1000 * 30); + turn_pin_on(COMP_RELAY); + } + break; + case CAMERAS_RELAY: + case FAN_RELAY: + case WEATHER_RELAY: + case MOUNT_RELAY: + if (pin_status == 1) { + turn_pin_on(pin_num); + } else if (pin_status == 0) { + turn_pin_off(pin_num); + } else if (pin_status == 9) { + toggle_pin(pin_num); + } + break; + case LED_BUILTIN: + digitalWrite(pin_num, pin_status); + break; + } + } + + Serial.print("{"); + + read_voltages(); + + read_dht_temp(); + + read_ds18b20_temp(); + + Serial.print("\"name\":\"telemetry_board\""); Serial.print(","); + + Serial.print("\"count\":"); Serial.print(millis()); + + Serial.println("}"); + + // Simple heartbeat + // toggle_led(); + delay(1000); +} + +/* Toggle Pin */ +void turn_pin_on(int camera_pin) { + digitalWrite(camera_pin, HIGH); +} + +void turn_pin_off(int camera_pin) { + digitalWrite(camera_pin, LOW); +} + +void toggle_pin(int pin_num) { + digitalWrite(pin_num, !digitalRead(pin_num)); +} + +int is_pin_on(int camera_pin) { + return digitalRead(camera_pin); +} + +/* Read Voltages + +Gets the AC probe as well as the values of the current on the AC I_ pins + +https://www.arduino.cc/en/Reference/AnalogRead + + */ +void read_voltages() { + int ac_reading = digitalRead(AC_PIN); + + int main_reading = analogRead(I_MAIN); + float main_amps = (main_reading / 1023.) * main_amps_mult; +// float main_amps = ((main_voltage - ACS_offset) / mV_per_amp); + + int fan_reading = analogRead(I_FAN); + float fan_amps = (fan_reading / 1023.) * fan_amps_mult; +// float fan_amps = ((fan_voltage - ACS_offset) / mV_per_amp); + + int mount_reading = analogRead(I_MOUNT); + float mount_amps = (mount_reading / 1023.) * mount_amps_mult; +// float mount_amps = ((mount_voltage - ACS_offset) / mV_per_amp); + + int camera_reading = analogRead(I_CAMERAS); + float camera_amps = (camera_reading / 1023.) * 1; +// float camera_amps = ((camera_voltage - ACS_offset) / mV_per_amp); + + Serial.print("\"power\":{"); + Serial.print("\"computer\":"); Serial.print(is_pin_on(COMP_RELAY)); Serial.print(','); + Serial.print("\"fan\":"); Serial.print(is_pin_on(FAN_RELAY)); Serial.print(','); + Serial.print("\"mount\":"); Serial.print(is_pin_on(MOUNT_RELAY)); Serial.print(','); + Serial.print("\"cameras\":"); Serial.print(is_pin_on(CAMERAS_RELAY)); Serial.print(','); + Serial.print("\"weather\":"); Serial.print(is_pin_on(WEATHER_RELAY)); Serial.print(','); + Serial.print("\"main\":"); Serial.print(ac_reading); Serial.print(','); + Serial.print("},"); + + Serial.print("\"current\":{"); + Serial.print("\"main\":"); Serial.print(main_reading); Serial.print(','); + Serial.print("\"fan\":"); Serial.print(fan_reading); Serial.print(','); + Serial.print("\"mount\":"); Serial.print(mount_reading); Serial.print(','); + Serial.print("\"cameras\":"); Serial.print(camera_reading); + Serial.print("},"); + +// Serial.print("\"volts\":{"); +// Serial.print("\"main\":"); Serial.print(main_voltage); Serial.print(','); +// Serial.print("\"fan\":"); Serial.print(fan_voltage); Serial.print(','); +// Serial.print("\"mount\":"); Serial.print(mount_voltage); Serial.print(','); +// Serial.print("\"cameras\":"); Serial.print(camera_voltage); +// Serial.print("},"); + + Serial.print("\"amps\":{"); + Serial.print("\"main\":"); Serial.print(main_amps); Serial.print(','); + Serial.print("\"fan\":"); Serial.print(fan_amps); Serial.print(','); + Serial.print("\"mount\":"); Serial.print(mount_amps); Serial.print(','); + Serial.print("\"cameras\":"); Serial.print(camera_amps); + Serial.print("},"); +} + +//// Reading temperature or humidity takes about 250 milliseconds! +//// Sensor readings may also be up to 2 seconds 'old' (its a very slow sensor) +void read_dht_temp() { + float h = dht.readHumidity(); + float c = dht.readTemperature(); // Celsius + + // Check if any reads failed and exit early (to try again). + // if (isnan(h) || isnan(t)) { + // Serial.println("Failed to read from DHT sensor!"); + // return; + // } + + Serial.print("\"humidity\":"); Serial.print(h); Serial.print(','); + Serial.print("\"temp_00\":"); Serial.print(c); Serial.print(','); +} + +void read_ds18b20_temp() { + + sensors.requestTemperatures(); + + Serial.print("\"temperature\":["); + + for (int x = 0; x < NUM_DS18; x++) { + Serial.print(sensors.getTempCByIndex(x)); Serial.print(","); + } + Serial.print("],"); +} + + +/************************************ +* Utitlity Methods +*************************************/ + +void toggle_led() { + led_value = ! led_value; + digitalWrite(LED_BUILTIN, led_value); +}