├── examples ├── Projects │ ├── WirelessJoystick │ │ ├── BluetoothControl │ │ │ └── BluetoothControl.ino │ │ └── Joystick_test │ │ │ └── Joystick_test.ino │ └── rssi_proximity │ │ └── README.md ├── Hardware │ ├── low_power │ │ └── low_power.ino │ ├── blinky │ │ └── blinky.ino │ ├── adc │ │ └── adc.ino │ ├── dfu_ota │ │ └── dfu_ota.ino │ ├── button │ │ └── button.ino │ ├── dfu_serial │ │ └── dfu_serial.ino │ ├── meminfo │ │ └── meminfo.ino │ ├── fwinfo │ │ └── fwinfo.ino │ ├── Servo │ │ ├── Knob │ │ │ └── Knob.ino │ │ ├── Sweep │ │ │ └── Sweep.ino │ │ └── Joystick_servo │ │ │ └── Joystick_servo.ino │ ├── digital_interrupt │ │ └── digital_interrupt.ino │ ├── Fading │ │ └── Fading.ino │ ├── rtos_scheduler │ │ └── rtos_scheduler.ino │ ├── SerialEcho │ │ └── SerialEcho.ino │ ├── hwinfo │ │ └── hwinfo.ino │ ├── gpstest_swuart │ │ └── gpstest_swuart.ino │ ├── nfc_to_gpio │ │ └── nfc_to_gpio.ino │ ├── software_timer │ │ └── software_timer.ino │ ├── hw_systick │ │ └── hw_systick.ino │ ├── hwpwm │ │ └── hwpwm.ino │ └── adc_vbat │ │ └── adc_vbat.ino ├── BMI160 │ ├── Interrupt │ │ └── Interrupt.ino │ ├── Temperature │ │ └── Temperature.ino │ ├── Accelerometer │ │ └── Accelerometer.ino │ ├── Gyro │ │ └── Gyro.ino │ ├── FreeFallDetect │ │ └── FreeFallDetect.ino │ ├── TapDetect │ │ └── TapDetect.ino │ ├── ShockDetect │ │ └── ShockDetect.ino │ ├── TapDoubleDetect │ │ └── TapDoubleDetect.ino │ ├── accelGyro │ │ └── accelGyro.ino │ ├── MotionDetect │ │ └── MotionDetect.ino │ ├── ZeroMotionDetect │ │ └── ZeroMotionDetect.ino │ ├── StepCount │ │ └── StepCount.ino │ └── AccelerometerOrientation │ │ └── AccelerometerOrientation.ino ├── PCA9685 │ ├── pwmtest │ │ └── pwmtest.ino │ ├── gpiotest │ │ └── gpiotest.ino │ ├── servo │ │ └── servo.ino │ ├── trajmove │ │ └── trajmove.ino │ └── SmartArm │ │ └── SmartArm.ino ├── Peripheral │ ├── LCD_Display │ │ └── testround │ │ │ └── testround.ino │ ├── clearbonds │ │ └── clearbonds.ino │ ├── blinky_ota │ │ └── blinky_ota.ino │ ├── eddystone_url │ │ └── eddystone_url.ino │ ├── beacon │ │ └── beacon.ino │ ├── adv_advanced │ │ └── adv_advanced.ino │ ├── custom_htm │ │ ├── IEEE11073float.h │ │ └── IEEE11073float.cpp │ ├── controller │ │ └── packetParser.cpp │ ├── rssi_callback │ │ └── rssi_callback.ino │ ├── rssi_poll │ │ └── rssi_poll.ino │ ├── hid_mouse │ │ └── hid_mouse.ino │ ├── hid_camerashutter │ │ └── hid_camerashutter.ino │ ├── hid_keyboard │ │ └── hid_keyboard.ino │ └── bleuart │ │ └── bleuart.ino ├── Display │ ├── TFT_Number │ │ └── TFT_Number.ino │ ├── TFT_Mandlebrot │ │ └── TFT_Mandlebrot.ino │ ├── TFT_Starfield │ │ └── TFT_Starfield.ino │ ├── TFT_Pie_Chart │ │ └── TFT_Pie_Chart.ino │ ├── TFT_Print_Test │ │ └── TFT_Print_Test.ino │ ├── TFT_ArcFill │ │ └── TFT_ArcFill.ino │ └── TFT_Clock │ │ └── TFT_Clock.ino └── Central │ └── central_scan │ └── central_scan.ino ├── tools └── tool_list.jpg ├── docs ├── images │ ├── git_cmd.jpg │ ├── shift_cmd.jpg │ ├── nRF52_pinout.jpg │ ├── nRF52_Pinout_v2.1.png │ ├── Bluefruit52_Pinout.png │ └── Bluefruit52_Pinconfig.png ├── arduino-ide │ ├── win-screenshots_cn │ │ ├── my_com.png │ │ ├── arduino_path.png │ │ ├── arduino_cc_package.png │ │ ├── select_arduino_lib.png │ │ ├── arduino_windows_installer.png │ │ └── select_arduino_install_path.png │ ├── fedora.md │ ├── opensuse.md │ ├── mac.md │ ├── debian_ubuntu.md │ └── windows.md ├── hardware │ ├── nRF52_Bluefruit52_Sch V2.1.pdf │ └── nRF52_Bluefruit52_Sch V3.0.pdf ├── getting_started_ja.md ├── getting_started_cn.md └── getting_started_setting.md ├── src ├── utility │ ├── fontconvert │ │ ├── Makefile │ │ ├── makefonts.sh │ │ └── fontconvert_win.md │ ├── config.h │ ├── BMI160Gen.h │ ├── gfxfont.h │ ├── button.h │ ├── BMI160Gen.cpp │ └── ST7789.h ├── pca9685.h ├── bluefruit52.cpp └── pca9685.cpp ├── library.properties ├── LICENSE └── README.md /examples/Projects/WirelessJoystick/BluetoothControl/BluetoothControl.ino: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /tools/tool_list.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Afantor/Afantor_Bluefruit52_Arduino/HEAD/tools/tool_list.jpg -------------------------------------------------------------------------------- /docs/images/git_cmd.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Afantor/Afantor_Bluefruit52_Arduino/HEAD/docs/images/git_cmd.jpg -------------------------------------------------------------------------------- /docs/images/shift_cmd.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Afantor/Afantor_Bluefruit52_Arduino/HEAD/docs/images/shift_cmd.jpg -------------------------------------------------------------------------------- /docs/images/nRF52_pinout.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Afantor/Afantor_Bluefruit52_Arduino/HEAD/docs/images/nRF52_pinout.jpg -------------------------------------------------------------------------------- /docs/images/nRF52_Pinout_v2.1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Afantor/Afantor_Bluefruit52_Arduino/HEAD/docs/images/nRF52_Pinout_v2.1.png -------------------------------------------------------------------------------- /docs/images/Bluefruit52_Pinout.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Afantor/Afantor_Bluefruit52_Arduino/HEAD/docs/images/Bluefruit52_Pinout.png -------------------------------------------------------------------------------- /docs/images/Bluefruit52_Pinconfig.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Afantor/Afantor_Bluefruit52_Arduino/HEAD/docs/images/Bluefruit52_Pinconfig.png -------------------------------------------------------------------------------- /docs/arduino-ide/win-screenshots_cn/my_com.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Afantor/Afantor_Bluefruit52_Arduino/HEAD/docs/arduino-ide/win-screenshots_cn/my_com.png -------------------------------------------------------------------------------- /docs/hardware/nRF52_Bluefruit52_Sch V2.1.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Afantor/Afantor_Bluefruit52_Arduino/HEAD/docs/hardware/nRF52_Bluefruit52_Sch V2.1.pdf -------------------------------------------------------------------------------- /docs/hardware/nRF52_Bluefruit52_Sch V3.0.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Afantor/Afantor_Bluefruit52_Arduino/HEAD/docs/hardware/nRF52_Bluefruit52_Sch V3.0.pdf -------------------------------------------------------------------------------- /docs/arduino-ide/win-screenshots_cn/arduino_path.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Afantor/Afantor_Bluefruit52_Arduino/HEAD/docs/arduino-ide/win-screenshots_cn/arduino_path.png -------------------------------------------------------------------------------- /docs/arduino-ide/win-screenshots_cn/arduino_cc_package.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Afantor/Afantor_Bluefruit52_Arduino/HEAD/docs/arduino-ide/win-screenshots_cn/arduino_cc_package.png -------------------------------------------------------------------------------- /docs/arduino-ide/win-screenshots_cn/select_arduino_lib.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Afantor/Afantor_Bluefruit52_Arduino/HEAD/docs/arduino-ide/win-screenshots_cn/select_arduino_lib.png -------------------------------------------------------------------------------- /docs/arduino-ide/win-screenshots_cn/arduino_windows_installer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Afantor/Afantor_Bluefruit52_Arduino/HEAD/docs/arduino-ide/win-screenshots_cn/arduino_windows_installer.png -------------------------------------------------------------------------------- /docs/arduino-ide/win-screenshots_cn/select_arduino_install_path.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Afantor/Afantor_Bluefruit52_Arduino/HEAD/docs/arduino-ide/win-screenshots_cn/select_arduino_install_path.png -------------------------------------------------------------------------------- /src/utility/fontconvert/Makefile: -------------------------------------------------------------------------------- 1 | all: fontconvert 2 | 3 | CC = gcc 4 | CFLAGS = -Wall -I/usr/local/include/freetype2 -I/usr/include/freetype2 -I/usr/include 5 | LIBS = -lfreetype 6 | 7 | fontconvert: fontconvert.c 8 | $(CC) $(CFLAGS) $< $(LIBS) -o $@ 9 | strip $@ 10 | 11 | clean: 12 | rm -f fontconvert 13 | -------------------------------------------------------------------------------- /library.properties: -------------------------------------------------------------------------------- 1 | name=Afantor Bluefruit52 2 | version=0.9.3 3 | author=Afantor 4 | maintainer=Afantor 5 | sentence=Arduino library for nRF52-based Bluefruit52 LE modules 6 | paragraph=Arduino library for nRF52-based Bluefruit52 LE modules 7 | category=Communication 8 | url=https://github.com/Afantor/Afantor_Bluefruit52_Arduino 9 | architectures=nrf52 10 | includes=bluefruit52.h 11 | -------------------------------------------------------------------------------- /examples/Hardware/low_power/low_power.ino: -------------------------------------------------------------------------------- 1 | /* 2 | low power mode, button for wakeup. 3 | 4 | This example code is in the public domain. 5 | 6 | 2019/05/27 7 | by Afantor 8 | */ 9 | 10 | 11 | #include 12 | 13 | int interruptPin = 18; 14 | 15 | void setup() 16 | { 17 | Serial.begin(115200); 18 | Serial.println("low power mode test!"); 19 | } 20 | 21 | void loop() 22 | { 23 | // Request CPU to enter low-power mode until an event/interrupt occurs 24 | waitForEvent(); 25 | systemOff(interruptPin, LOW); 26 | } 27 | 28 | 29 | -------------------------------------------------------------------------------- /examples/Hardware/blinky/blinky.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Blink 3 | Turns on an LED on for one second, then off for one second, repeatedly. 4 | 5 | This example code is in the public domain. 6 | 7 | 2019/01/01 8 | by Afantor 9 | */ 10 | #include 11 | // the setup function runs once when you press reset or power the board 12 | void setup() { 13 | // initialize digital pin LED_BUILTIN as an output. 14 | pinMode(LED_2, OUTPUT); 15 | } 16 | 17 | // the loop function runs over and over again forever 18 | void loop() { 19 | digitalToggle(LED_2); // turn the LED on (HIGH is the voltage level) 20 | delay(500); // wait for a second 21 | } 22 | -------------------------------------------------------------------------------- /examples/Hardware/adc/adc.ino: -------------------------------------------------------------------------------- 1 | /* 2 | ADC get input 3 | get adc value from pin and print value. 4 | 5 | This example code is in the public domain. 6 | 7 | 2019/01/02 8 | by Afantor 9 | */ 10 | int adc_pin = A5; 11 | int adc_value = 0; 12 | float mv_per_lsb = 3600.0F/1024.0F; // 10-bit ADC with 3.6V input range 13 | 14 | void setup() { 15 | Serial.begin(115200); 16 | } 17 | 18 | void loop() { 19 | // Get a fresh ADC value 20 | adc_value = analogRead(adc_pin); 21 | 22 | // Print the results 23 | Serial.print(adc_value); 24 | Serial.print(" ["); 25 | Serial.print((float)adc_value * mv_per_lsb); 26 | Serial.println(" mV]"); 27 | 28 | delay(100); 29 | } 30 | -------------------------------------------------------------------------------- /src/utility/config.h: -------------------------------------------------------------------------------- 1 | #ifndef _CONFIG_H_ 2 | #define _CONFIG_H_ 3 | 4 | 5 | #define PI 3.1415926 6 | // LCD Screen 7 | #define LCD_SDA_PIN (7) 8 | #define LCD_SCL_PIN (27) 9 | #define LCD_DC_PIN (16) 10 | #define LCD_RST_PIN (23) 11 | #define LCD_CS_PIN (24) 12 | 13 | // LEDs 14 | #define LED1_PIN (17) 15 | #define LED2_PIN (19) 16 | 17 | #define LED_RED LED1_PIN 18 | #define LED_BLUE LED2_PIN 19 | 20 | #define LED_1 LED1_PIN 21 | #define LED_2 LED2_PIN 22 | 23 | // Buttons 24 | #define BTN_A (0) 25 | #define BTN_B (1) 26 | #define BUTTON_A (0) 27 | #define BUTTON_B (1) 28 | #define BUTTON_A_PIN (18) 29 | #define BUTTON_B_PIN (11) 30 | 31 | 32 | #endif /* SETTINGS_C */ -------------------------------------------------------------------------------- /docs/arduino-ide/fedora.md: -------------------------------------------------------------------------------- 1 | Installation instructions for Fedora 2 | ===================================== 3 | 4 | - Install the latest Arduino IDE from [arduino.cc](https://www.arduino.cc/en/Main/Software). `$ sudo dnf -y install arduino` will most likely install an older release. 5 | - Open Terminal and execute the following command (copy->paste and hit enter): 6 | 7 | ```bash 8 | sudo usermod -a -G dialout $USER && \ 9 | sudo dnf install git python3-pip python3-pyserial && \ 10 | mkdir -p ~/Arduino/hardware/espressif && \ 11 | cd ~/Arduino/hardware/espressif && \ 12 | git clone https://github.com/espressif/arduino-esp32.git esp32 && \ 13 | cd esp32 && \ 14 | git submodule update --init --recursive && \ 15 | cd tools && \ 16 | python get.py 17 | ``` 18 | - Restart Arduino IDE 19 | -------------------------------------------------------------------------------- /examples/Hardware/dfu_ota/dfu_ota.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | 15 | /* This sketch invoke API to enter OTA dfu mode */ 16 | 17 | #include 18 | 19 | 20 | void setup() 21 | { 22 | enterOTADfu(); 23 | } 24 | 25 | 26 | void loop() 27 | { 28 | } 29 | -------------------------------------------------------------------------------- /examples/Hardware/button/button.ino: -------------------------------------------------------------------------------- 1 | /* 2 | button scan example. 3 | 4 | This example code is in the public domain. 5 | 6 | 2019/01/05 7 | by Afantor 8 | */ 9 | #include 10 | // The setup() function runs once each time the micro-controller starts 11 | void setup() { 12 | // init lcd, serial, IMU 13 | Bluefruit52.begin(true, true, false); 14 | 15 | } 16 | 17 | // Add the main program code into the continuous loop() function 18 | void loop() { 19 | Bluefruit52.update(); 20 | 21 | // if want use Releasefor; suggest use Release in press event 22 | if (Bluefruit52.BtnA.wasReleased()) { 23 | Serial.println('A'); 24 | } else if (Bluefruit52.BtnB.wasReleased()) { 25 | Serial.println('B'); 26 | } else if (Bluefruit52.BtnB.wasReleasefor(700)) { 27 | //Serial.println('AB'); 28 | } 29 | } -------------------------------------------------------------------------------- /examples/Hardware/dfu_serial/dfu_serial.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | 15 | #include 16 | 17 | /* 18 | * This sketch will reset the board into Serial DFU mode 19 | */ 20 | 21 | void setup() 22 | { 23 | enterSerialDfu(); 24 | } 25 | 26 | 27 | void loop() 28 | { 29 | } 30 | -------------------------------------------------------------------------------- /examples/BMI160/Interrupt/Interrupt.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | const int bmi160_i2c_addr = 0x69; 4 | const int bmi160_interrupt_pin = 30; 5 | 6 | void bmi160_intr(void) 7 | { 8 | Serial.println("BMI160 interrupt: TAP!"); 9 | } 10 | 11 | void setup() { 12 | Serial.begin(115200); // initialize Serial communication 13 | 14 | // initialize device 15 | Serial.println("Initializing IMU device..."); 16 | // BMI160.begin(BMI160GenClass::SPI_MODE, bmi160_select_pin, bmi160_interrupt_pin); 17 | BMI160.begin(BMI160GenClass::I2C_MODE, bmi160_i2c_addr, bmi160_interrupt_pin); 18 | uint8_t dev_id = BMI160.getDeviceID(); 19 | Serial.print("DEVICE ID: "); 20 | Serial.println(dev_id, HEX); 21 | 22 | BMI160.attachInterrupt(bmi160_intr); 23 | BMI160.setIntTapEnabled(true); 24 | Serial.println("Initializing IMU device...done."); 25 | } 26 | 27 | void loop() { 28 | } 29 | -------------------------------------------------------------------------------- /docs/arduino-ide/opensuse.md: -------------------------------------------------------------------------------- 1 | Installation instructions for openSUSE 2 | ====================================== 3 | 4 | - Install the latest Arduino IDE from [arduino.cc](https://www.arduino.cc/en/Main/Software). 5 | - Open Terminal and execute the following command (copy->paste and hit enter): 6 | 7 | ```bash 8 | sudo usermod -a -G dialout $USER && \ 9 | if [ `python --version 2>&1 | grep '2.7' | wc -l` = "1" ]; then \ 10 | sudo zypper install git python-pip python-pyserial; \ 11 | else \ 12 | sudo zypper install git python3-pip python3-pyserial; \ 13 | fi && \ 14 | mkdir -p ~/Arduino/hardware/espressif && \ 15 | cd ~/Arduino/hardware/espressif && \ 16 | git clone https://github.com/espressif/arduino-esp32.git esp32 && \ 17 | cd esp32 && \ 18 | git submodule update --init --recursive && \ 19 | cd tools && \ 20 | python get.py 21 | ``` 22 | - Restart Arduino IDE 23 | -------------------------------------------------------------------------------- /docs/arduino-ide/mac.md: -------------------------------------------------------------------------------- 1 | Installation instructions for Mac OS 2 | ===================================== 3 | 4 | - Install latest Arduino IDE from [arduino.cc](https://www.arduino.cc/en/Main/Software) 5 | - Open Terminal and execute the following command (copy->paste and hit enter): 6 | 7 | ```bash 8 | mkdir -p ~/Documents/Arduino/hardware/espressif && \ 9 | cd ~/Documents/Arduino/hardware/espressif && \ 10 | git clone https://github.com/espressif/arduino-esp32.git esp32 && \ 11 | cd esp32 && \ 12 | git submodule update --init --recursive && \ 13 | cd tools && \ 14 | python get.py 15 | ``` 16 | - If you get the error below. Install the command line dev tools with xcode-select --install and try the command above again: 17 | 18 | ```xcrun: error: invalid active developer path (/Library/Developer/CommandLineTools), missing xcrun at: /Library/Developer/CommandLineTools/usr/bin/xcrun``` 19 | 20 | ```xcode-select --install``` 21 | 22 | - Restart Arduino IDE 23 | 24 | -------------------------------------------------------------------------------- /examples/Hardware/meminfo/meminfo.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | 15 | #include 16 | 17 | 18 | void setup() 19 | { 20 | Serial.begin(115200); 21 | 22 | Serial.println("Bluefruit52 Memory Info Example"); 23 | Serial.println("-------------------------------\n"); 24 | } 25 | 26 | 27 | void loop() 28 | { 29 | dbgMemInfo(); 30 | digitalToggle(LED_RED); 31 | delay(5000); // wait for a second 32 | } 33 | -------------------------------------------------------------------------------- /examples/Hardware/fwinfo/fwinfo.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | 15 | #include 16 | 17 | 18 | void setup() 19 | { 20 | Serial.begin(115200); 21 | 22 | Serial.println("Bluefruit52 Firmware Info Example"); 23 | Serial.println("---------------------------------\n"); 24 | } 25 | 26 | 27 | void loop() 28 | { 29 | dbgPrintVersion(); 30 | digitalToggle(LED_RED); 31 | delay(5000); // wait for a second 32 | } 33 | -------------------------------------------------------------------------------- /src/utility/BMI160Gen.h: -------------------------------------------------------------------------------- 1 | #ifndef _BMI160GEN_H_ 2 | #define _BMI160GEN_H_ 3 | 4 | //#define BMI160GEN_USE_CURIEIMU 5 | #include "CurieIMU.h" 6 | 7 | class BMI160GenClass : public CurieIMUClass { 8 | public: 9 | typedef enum { INVALID_MODE = -1, I2C_MODE = 1, SPI_MODE = 2 } Mode; 10 | bool begin(const int spi_cs_pin = 10, const int intr_pin = 2); 11 | bool begin(Mode mode, const int arg1 = 0x69, const int arg2 = 30); 12 | void attachInterrupt(void (*callback)(void)); 13 | protected: 14 | int interrupt_pin = -1; 15 | int i2c_addr = -1; 16 | int spi_ss = -1; 17 | Mode mode; 18 | virtual void ss_init(); 19 | virtual int ss_xfer(uint8_t *buf, unsigned tx_cnt, unsigned rx_cnt); 20 | void i2c_init(); 21 | int i2c_xfer(uint8_t *buf, unsigned tx_cnt, unsigned rx_cnt); 22 | void spi_init(); 23 | int spi_xfer(uint8_t *buf, unsigned tx_cnt, unsigned rx_cnt); 24 | }; 25 | 26 | extern BMI160GenClass BMI160; 27 | 28 | #endif /* _BMI160GEN_H_ */ 29 | -------------------------------------------------------------------------------- /examples/Hardware/Servo/Knob/Knob.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Controlling a servo position using a potentiometer (variable resistor) 3 | by Michal Rinott 4 | 5 | modified on 8 Nov 2013 6 | by Scott Fitzgerald 7 | http://www.arduino.cc/en/Tutorial/Knob 8 | */ 9 | 10 | #include 11 | 12 | Servo myservo; // create servo object to control a servo 13 | 14 | int potpin = A0; // P0.02 Pin analog pin used to connect the potentiometer 15 | int val; // variable to read the value from the analog pin 16 | 17 | void setup() { 18 | myservo.attach(A1); // attaches the servo on P0.03 Pin to the servo object 19 | } 20 | 21 | void loop() { 22 | val = analogRead(potpin); // reads the value of the potentiometer (value between 0 and 1023) 23 | val = map(val, 0, 1023, 0, 180); // scale it to use it with the servo (value between 0 and 180) 24 | myservo.write(val); // sets the servo position according to the scaled value 25 | delay(15); // waits for the servo to get there 26 | } 27 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2019 Afantor Industries 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /examples/Hardware/digital_interrupt/digital_interrupt.ino: -------------------------------------------------------------------------------- 1 | /* 2 | ADC get battery value 3 | get adc value from pin and print value. 4 | 5 | This example code is in the public domain. 6 | 7 | 2019/01/04 8 | by Afantor 9 | */ 10 | 11 | /* 12 | * This sketch demonstrate how to pass ISR_DEFFERED as additional parameter 13 | * to defer callback from ISR context with attachInterrupt 14 | */ 15 | #include 16 | 17 | int interruptPin = A0; 18 | 19 | void setup() 20 | { 21 | Serial.begin(115200); 22 | 23 | pinMode(interruptPin, INPUT_PULLUP); 24 | 25 | // ISR_DEFERRED flag cause the callback to be deferred from ISR context 26 | // and invoked within a callback thread. 27 | // It is required to use ISR_DEFERRED if callback function take long time 28 | // to run e.g Serial.print() or using any of Bluefruit API() which will 29 | // potentially call rtos API 30 | attachInterrupt(interruptPin, digital_callback, ISR_DEFERRED | CHANGE); 31 | } 32 | 33 | void loop() 34 | { 35 | // nothing to do 36 | } 37 | 38 | void digital_callback(void) 39 | { 40 | Serial.print("Pin value: "); 41 | Serial.println(digitalRead(interruptPin)); 42 | } 43 | -------------------------------------------------------------------------------- /examples/Projects/rssi_proximity/README.md: -------------------------------------------------------------------------------- 1 | # RSSI Proximity Project 2 | 3 | This project demonstrates how you can use a single Bluefruit nRF52 device 4 | running in Central mode to listen for a specific signature in the advertising 5 | packets of nearby Bluefruit nRF52 devices running in peripheral mode. 6 | 7 | The Central mode device will sort those devices with the matching signature by 8 | proximity based on their RSSI (relative signal strength) value. 9 | 10 | Most of the Central mode advertising API is used in this demo, making it an 11 | excellent place to start if you want to create your own custom Central based 12 | project(s). 13 | 14 | ## Project Files 15 | 16 | This project consists of two parts: 17 | 18 | - `rssi_proximity_central`: This project should be run on one Bluefruit nRF52 19 | board and will configure the board as a Central device, actively scanning 20 | for any peripheral devices in listening range. 21 | - `rssi_proximity_peripheral`: This project should be run on one or more 22 | Bluefruit nRF52 boards and will configure the boards as peripheral devices, 23 | sending out a specifically formatted advertising packet at a regular 24 | interval. 25 | -------------------------------------------------------------------------------- /examples/Hardware/Servo/Sweep/Sweep.ino: -------------------------------------------------------------------------------- 1 | /* Sweep 2 | by BARRAGAN 3 | This example code is in the public domain. 4 | 5 | modified 8 Nov 2013 6 | by Scott Fitzgerald 7 | http://www.arduino.cc/en/Tutorial/Sweep 8 | */ 9 | 10 | #include 11 | 12 | Servo myservo; // create servo object to control a servo 13 | // twelve servo objects can be created on most boards 14 | 15 | int pos = 0; // variable to store the servo position 16 | 17 | void setup() { 18 | myservo.attach(A0); // attaches the servo on P0.02 pin to the servo object 19 | } 20 | 21 | void loop() { 22 | for (pos = 0; pos <= 180; pos += 1) { // goes from 0 degrees to 180 degrees 23 | // in steps of 1 degree 24 | myservo.write(pos); // tell servo to go to position in variable 'pos' 25 | delay(15); // waits 15ms for the servo to reach the position 26 | } 27 | for (pos = 180; pos >= 0; pos -= 1) { // goes from 180 degrees to 0 degrees 28 | myservo.write(pos); // tell servo to go to position in variable 'pos' 29 | delay(15); // waits 15ms for the servo to reach the position 30 | } 31 | } 32 | -------------------------------------------------------------------------------- /examples/Hardware/Fading/Fading.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Fading 3 | 4 | This example shows how to fade an LED using the analogWrite() function. 5 | 6 | The circuit: 7 | * LED attached from digital pin 9 to ground. 8 | 9 | Created 1 Nov 2008 10 | By David A. Mellis 11 | modified 30 Aug 2011 12 | By Tom Igoe 13 | 14 | http://www.arduino.cc/en/Tutorial/Fading 15 | 16 | This example code is in the public domain. 17 | 18 | */ 19 | 20 | 21 | int ledPin = LED_RED; // LED connected to digital pin 9 22 | 23 | void setup() { 24 | // nothing happens in setup 25 | } 26 | 27 | void loop() { 28 | // fade in from min to max in increments of 5 points: 29 | for (int fadeValue = 0 ; fadeValue <= 255; fadeValue += 5) { 30 | // sets the value (range from 0 to 255): 31 | analogWrite(ledPin, fadeValue); 32 | // wait for 30 milliseconds to see the dimming effect 33 | delay(30); 34 | } 35 | 36 | // fade out from max to min in increments of 5 points: 37 | for (int fadeValue = 255 ; fadeValue >= 0; fadeValue -= 5) { 38 | // sets the value (range from 0 to 255): 39 | analogWrite(ledPin, fadeValue); 40 | // wait for 30 milliseconds to see the dimming effect 41 | delay(30); 42 | } 43 | } 44 | 45 | 46 | -------------------------------------------------------------------------------- /src/utility/gfxfont.h: -------------------------------------------------------------------------------- 1 | // Font structures for newer Adafruit_GFX (1.1 and later). 2 | // Example fonts are included in 'Fonts' directory. 3 | // To use a font in your Arduino sketch, #include the corresponding .h 4 | // file and pass address of GFXfont struct to setFont(). Pass NULL to 5 | // revert to 'classic' fixed-space bitmap font. 6 | 7 | #ifndef _GFXFONT_H_ 8 | #define _GFXFONT_H_ 9 | 10 | /// Font data stored PER GLYPH 11 | typedef struct { 12 | uint16_t bitmapOffset; ///< Pointer into GFXfont->bitmap 13 | uint8_t width; ///< Bitmap dimensions in pixels 14 | uint8_t height; ///< Bitmap dimensions in pixels 15 | uint8_t xAdvance; ///< Distance to advance cursor (x axis) 16 | int8_t xOffset; ///< X dist from cursor pos to UL corner 17 | int8_t yOffset; ///< Y dist from cursor pos to UL corner 18 | } GFXglyph; 19 | 20 | /// Data stored for FONT AS A WHOLE 21 | typedef struct { 22 | uint8_t *bitmap; ///< Glyph bitmaps, concatenated 23 | GFXglyph *glyph; ///< Glyph array 24 | uint8_t first; ///< ASCII extents (first char) 25 | uint8_t last; ///< ASCII extents (last char) 26 | uint8_t yAdvance; ///< Newline distance (y axis) 27 | } GFXfont; 28 | 29 | #endif // _GFXFONT_H_ 30 | -------------------------------------------------------------------------------- /docs/arduino-ide/debian_ubuntu.md: -------------------------------------------------------------------------------- 1 | Installation instructions for Debian / Ubuntu OS 2 | ================================================= 3 | 4 | - Install latest Arduino IDE from [arduino.cc](https://www.arduino.cc/en/Main/Software) 5 | - Open Terminal and execute the following command (copy->paste and hit enter): 6 | 7 | ```bash 8 | sudo usermod -a -G dialout $USER && \ 9 | sudo apt-get install git && \ 10 | wget https://bootstrap.pypa.io/get-pip.py && \ 11 | sudo python get-pip.py && \ 12 | sudo pip install pyserial && \ 13 | mkdir -p ~/Arduino/hardware/espressif && \ 14 | cd ~/Arduino/hardware/espressif && \ 15 | git clone https://github.com/espressif/arduino-esp32.git esp32 && \ 16 | cd esp32 && \ 17 | git submodule update --init --recursive && \ 18 | cd tools && \ 19 | python2 get.py 20 | ``` 21 | - Restart Arduino IDE 22 | 23 | 24 | 25 | - If you have Arduino.app installed to /Applications/, modify the installation as follows, beginning at `mkdir -p ~/Arduino...`: 26 | 27 | ```bash 28 | cd /Applications/Arduino_*/Contents/java/hardware/ 29 | mkdir -p espressif && \ 30 | cd espressif && \ 31 | git clone https://github.com/espressif/arduino-esp32.git esp32 && \ 32 | cd esp32 && \ 33 | git submodule update --init --recursive && \ 34 | cd tools && \ 35 | python2 get.py``` 36 | -------------------------------------------------------------------------------- /examples/Projects/WirelessJoystick/Joystick_test/Joystick_test.ino: -------------------------------------------------------------------------------- 1 | /*************************************************** 2 | This is an example for Wireless Joystick Board. 3 | 4 | ****************************************************/ 5 | 6 | #include 7 | 8 | #define JOYSTICK_START 11 9 | #define JOYSTICK_MODE 18 10 | #define JOYSTICK_KL 14 11 | #define JOYSTICK_KR 13 12 | #define JOYSTICK_BTN_L 12 13 | #define JOYSTICK_BTN_R 20 14 | #define JOYSTICK_BEEP 19 15 | #define JOYSTICK_POT1 A4 16 | #define JOYSTICK_POT2 A5 17 | #define JOYSTICK_POT3 A6 18 | #define JOYSTICK_LX A1 19 | #define JOYSTICK_LY A0 20 | #define JOYSTICK_RX A3 21 | #define JOYSTICK_RY A2 22 | 23 | void setup() { 24 | 25 | BF52.begin(true, true, false); 26 | 27 | Serial.println(""); 28 | Serial.println(""); 29 | Serial.println("Joystick Board test!"); 30 | 31 | pinMode(JOYSTICK_START, INPUT); 32 | pinMode(JOYSTICK_MODE, INPUT); 33 | pinMode(JOYSTICK_KL, INPUT); 34 | pinMode(JOYSTICK_KR, INPUT); 35 | pinMode(JOYSTICK_BTN_L, INPUT); 36 | pinMode(JOYSTICK_BTN_R, INPUT); 37 | pinMode(JOYSTICK_BEEP, OUTPUT); 38 | 39 | delay(1000); 40 | } 41 | 42 | void loop() { 43 | // Serial.println(digitalRead(JOYSTICK_KL)); 44 | Serial.println(analogRead(JOYSTICK_LX)); 45 | delay(50); 46 | } 47 | 48 | -------------------------------------------------------------------------------- /examples/PCA9685/pwmtest/pwmtest.ino: -------------------------------------------------------------------------------- 1 | /*************************************************** 2 | This is an example for our PCA9685 16-channel PWM & Servo driver 3 | PWM test - this will drive 16 PWMs in a 'wave' 4 | 5 | These drivers use I2C to communicate, 2 pins are required to 6 | interface. 7 | 8 | ****************************************************/ 9 | 10 | #include 11 | #include 12 | 13 | // called this way, it uses the default address 0x40 14 | PCA9685 pwm = PCA9685(); 15 | // you can also call it with a different address you want 16 | //PCA9685 pwm = PCA9685(0x41); 17 | // you can also call it with a different address and I2C interface 18 | //PCA9685 pwm = PCA9685(&Wire, 0x40); 19 | 20 | void setup() { 21 | Serial.begin(115200); 22 | Serial.println("16 channel PWM test!"); 23 | 24 | pwm.begin(); 25 | pwm.setPWMFreq(50); // This is the maximum PWM frequency 26 | 27 | // if you want to really speed stuff up, you can go into 'fast 400khz I2C' mode 28 | // some i2c devices dont like this so much so if you're sharing the bus, watch 29 | // out for this! 30 | Wire.setClock(400000); 31 | } 32 | 33 | void loop() { 34 | // Drive each PWM in a 'wave' 35 | for (uint16_t i=0; i<4096; i += 8) { 36 | for (uint8_t pwmnum=0; pwmnum < 16; pwmnum++) { 37 | pwm.setPWM(pwmnum, 0, (i + (4096/16)*pwmnum) % 4096 ); 38 | } 39 | } 40 | } 41 | -------------------------------------------------------------------------------- /src/utility/fontconvert/makefonts.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | # Ugly little Bash script, generates a set of .h files for GFX using 4 | # GNU FreeFont sources. There are three fonts: 'Mono' (Courier-like), 5 | # 'Sans' (Helvetica-like) and 'Serif' (Times-like); four styles: regular, 6 | # bold, oblique or italic, and bold+oblique or bold+italic; and four 7 | # sizes: 9, 12, 18 and 24 point. No real error checking or anything, 8 | # this just powers through all the combinations, calling the fontconvert 9 | # utility and redirecting the output to a .h file for each combo. 10 | 11 | # Adafruit_GFX repository does not include the source outline fonts 12 | # (huge zipfile, different license) but they're easily acquired: 13 | # http://savannah.gnu.org/projects/freefont/ 14 | 15 | convert=./fontconvert 16 | inpath=~/Desktop/freefont/ 17 | outpath=../Fonts/ 18 | fonts=(FreeMono FreeSans FreeSerif) 19 | styles=("" Bold Italic BoldItalic Oblique BoldOblique) 20 | sizes=(9 12 18 24) 21 | 22 | for f in ${fonts[*]} 23 | do 24 | for index in ${!styles[*]} 25 | do 26 | st=${styles[$index]} 27 | for si in ${sizes[*]} 28 | do 29 | infile=$inpath$f$st".ttf" 30 | if [ -f $infile ] # Does source combination exist? 31 | then 32 | outfile=$outpath$f$st$si"pt7b.h" 33 | # printf "%s %s %s > %s\n" $convert $infile $si $outfile 34 | $convert $infile $si > $outfile 35 | fi 36 | done 37 | done 38 | done 39 | -------------------------------------------------------------------------------- /examples/PCA9685/gpiotest/gpiotest.ino: -------------------------------------------------------------------------------- 1 | /*************************************************** 2 | This is an example for our PCA9685 16-channel PWM & Servo driver 3 | GPIO test - this will set a pin high/low 4 | 5 | These drivers use I2C to communicate, 2 pins are required to 6 | interface. 7 | 8 | ****************************************************/ 9 | 10 | #include 11 | #include 12 | 13 | // called this way, it uses the default address 0x40 14 | PCA9685 pwm = PCA9685(); 15 | // you can also call it with a different address you want 16 | //PCA9685 pwm = PCA9685(0x41); 17 | // you can also call it with a different address and I2C interface 18 | //PCA9685 pwm = PCA9685(&Wire, 0x40); 19 | 20 | void setup() { 21 | Serial.begin(9600); 22 | Serial.println("GPIO test!"); 23 | 24 | pwm.begin(); 25 | pwm.setPWMFreq(1000); // Set to whatever you like, we don't use it in this demo! 26 | 27 | // if you want to really speed stuff up, you can go into 'fast 400khz I2C' mode 28 | // some i2c devices dont like this so much so if you're sharing the bus, watch 29 | // out for this! 30 | Wire.setClock(400000); 31 | } 32 | 33 | void loop() { 34 | // Drive each pin in a 'wave' 35 | for (uint8_t pin=0; pin<16; pin++) { 36 | pwm.setPWM(pin, 4096, 0); // turns pin fully on 37 | delay(100); 38 | pwm.setPWM(pin, 0, 4096); // turns pin fully off 39 | } 40 | } 41 | -------------------------------------------------------------------------------- /examples/Hardware/rtos_scheduler/rtos_scheduler.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | 15 | #include 16 | 17 | /* 18 | * Sketch demonstate mutli-task using Scheduler. Demo create loop2() that 19 | * run in 'parallel' with loop(). 20 | * - loop() toggle LED_RED every 1 second 21 | * - loop2() toggle LED_BLUE every half of second 22 | */ 23 | 24 | void setup() 25 | { 26 | // LED_RED & LED_BLUE pin already initialized as an output. 27 | 28 | // Create loop2() using Scheduler to run in 'parallel' with loop() 29 | Scheduler.startLoop(loop2); 30 | } 31 | 32 | /** 33 | * Toggle led1 every 1 second 34 | */ 35 | void loop() 36 | { 37 | digitalToggle(LED_RED); // Toggle LED 38 | delay(1000); // wait for a second 39 | } 40 | 41 | /** 42 | * Toggle led1 every 0.5 second 43 | */ 44 | void loop2() 45 | { 46 | digitalToggle(LED_BLUE); // Toggle LED 47 | delay(500); // wait for a half second 48 | } 49 | 50 | -------------------------------------------------------------------------------- /examples/Hardware/SerialEcho/SerialEcho.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our Feather Bluefruit modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | 15 | #include 16 | 17 | const int baudrate = 115200; 18 | 19 | /**************************************************************************/ 20 | /*! 21 | @brief The setup function runs once when reset the board 22 | */ 23 | /**************************************************************************/ 24 | void setup() 25 | { 26 | Serial.begin (baudrate); 27 | 28 | Serial.println("Serial Echo demo"); 29 | Serial.print("Badurate : "); 30 | Serial.println(baudrate); 31 | } 32 | 33 | /**************************************************************************/ 34 | /*! 35 | @brief The loop function runs over and over again forever 36 | */ 37 | /**************************************************************************/ 38 | void loop() 39 | { 40 | // From Serial monitor to All 41 | if ( Serial.available() ) 42 | { 43 | Serial.write( Serial.read() ); 44 | } 45 | } 46 | -------------------------------------------------------------------------------- /examples/Hardware/hwinfo/hwinfo.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | typedef volatile uint32_t REG32; 4 | #define pREG32 (REG32 *) 5 | 6 | #define DEVICE_ID_HIGH (*(pREG32 (0x10000060))) 7 | #define DEVICE_ID_LOW (*(pREG32 (0x10000064))) 8 | #define MAC_ADDRESS_HIGH (*(pREG32 (0x100000a8))) 9 | #define MAC_ADDRESS_LOW (*(pREG32 (0x100000a4))) 10 | 11 | void setup() { 12 | Serial.begin(115200); 13 | 14 | Serial.println("Bluefruit 52 HW Info"); 15 | Serial.println(""); 16 | 17 | // MAC Address 18 | uint32_t addr_high = ((MAC_ADDRESS_HIGH) & 0x0000ffff) | 0x0000c000; 19 | uint32_t addr_low = MAC_ADDRESS_LOW; 20 | Serial.print("MAC Address: "); 21 | Serial.print((addr_high >> 8) & 0xFF, HEX); Serial.print(":"); 22 | Serial.print((addr_high) & 0xFF, HEX); Serial.print(":"); 23 | Serial.print((addr_low >> 24) & 0xFF, HEX); Serial.print(":"); 24 | Serial.print((addr_low >> 16) & 0xFF, HEX); Serial.print(":"); 25 | Serial.print((addr_low >> 8) & 0xFF, HEX); Serial.print(":"); 26 | Serial.print((addr_low) & 0xFF, HEX); Serial.println(""); 27 | 28 | // Unique Device ID 29 | Serial.print("Device ID : "); 30 | Serial.print(DEVICE_ID_HIGH, HEX); 31 | Serial.println(DEVICE_ID_LOW, HEX); 32 | 33 | // MCU Variant; 34 | Serial.printf("MCU Variant: nRF%X 0x%08X\n",NRF_FICR->INFO.PART, NRF_FICR->INFO.VARIANT); 35 | Serial.printf("Memory : Flash = %d KB, RAM = %d KB\n", NRF_FICR->INFO.FLASH, NRF_FICR->INFO.RAM); 36 | } 37 | 38 | void loop() { 39 | // put your main code here, to run repeatedly: 40 | 41 | } 42 | -------------------------------------------------------------------------------- /examples/Peripheral/LCD_Display/testround/testround.ino: -------------------------------------------------------------------------------- 1 | /*************************************************** 2 | This is a library for the ST7789 IPS SPI display. 3 | 4 | This example code is in the public domain. 5 | 6 | 2019/01/05 7 | by Afantor 8 | ****************************************************/ 9 | 10 | 11 | #include // Hardware-specific library for ST7789 (with or without CS pin) 12 | 13 | 14 | float p = 3.1415926; 15 | 16 | void setup(void) { 17 | BF52.begin(true, true, false); 18 | Serial.print("Hello! ST7789 TFT Test"); 19 | 20 | Serial.println("Initialized"); 21 | 22 | uint16_t time = millis(); 23 | BF52.Lcd.fillScreen(BLACK); 24 | time = millis() - time; 25 | 26 | Serial.println(time, DEC); 27 | delay(500); 28 | 29 | // a single pixel 30 | BF52.Lcd.drawPixel(BF52.Lcd.width()/2, BF52.Lcd.height()/2, GREEN); 31 | delay(500); 32 | 33 | testroundrects(); 34 | delay(500); 35 | 36 | Serial.println("done"); 37 | delay(1000); 38 | } 39 | 40 | void loop() { 41 | delay(500); 42 | } 43 | 44 | 45 | void testroundrects() { 46 | BF52.Lcd.fillScreen(BLACK); 47 | int color = 100; 48 | int i; 49 | int t; 50 | for(t = 0 ; t <= 4; t+=1) { 51 | int x = 0; 52 | int y = 0; 53 | int w = BF52.Lcd.width()-2; 54 | int h = BF52.Lcd.height()-2; 55 | for(i = 0 ; i <= 16; i+=1) { 56 | BF52.Lcd.drawRoundRect(x, y, w, h, 5, color); 57 | x+=2; 58 | y+=3; 59 | w-=4; 60 | h-=6; 61 | color+=1100; 62 | } 63 | color+=100; 64 | } 65 | } 66 | 67 | -------------------------------------------------------------------------------- /src/pca9685.h: -------------------------------------------------------------------------------- 1 | 2 | #ifndef _PCA9685_H 3 | #define _PCA9685_H 4 | 5 | #include 6 | #include 7 | 8 | #define PCA9685_SUBADR1 0x2 /**< i2c bus address 1 */ 9 | #define PCA9685_SUBADR2 0x3 /**< i2c bus address 2 */ 10 | #define PCA9685_SUBADR3 0x4 /**< i2c bus address 3 */ 11 | 12 | #define PCA9685_MODE1 0x0 /**< Mode Register 1 */ 13 | #define PCA9685_PRESCALE 0xFE /**< Prescaler for PWM output frequency */ 14 | 15 | #define LED0_ON_L 0x6 /**< LED0 output and brightness control byte 0 */ 16 | #define LED0_ON_H 0x7 /**< LED0 output and brightness control byte 1 */ 17 | #define LED0_OFF_L 0x8 /**< LED0 output and brightness control byte 2 */ 18 | #define LED0_OFF_H 0x9 /**< LED0 output and brightness control byte 3 */ 19 | 20 | #define ALLLED_ON_L 0xFA /**< load all the LEDn_ON registers, byte 0 */ 21 | #define ALLLED_ON_H 0xFB /**< load all the LEDn_ON registers, byte 1 */ 22 | #define ALLLED_OFF_L 0xFC /**< load all the LEDn_OFF registers, byte 0 */ 23 | #define ALLLED_OFF_H 0xFD /**< load all the LEDn_OFF registers, byte 1 */ 24 | 25 | /*! 26 | * @brief Class that stores state and functions for interacting with PCA9685 PWM chip 27 | */ 28 | class PCA9685 { 29 | public: 30 | PCA9685(TwoWire *I2C = &Wire, uint8_t addr = 0x40); 31 | void begin(void); 32 | void reset(void); 33 | void setPWMFreq(float freq); 34 | void setPWM(uint8_t num, uint16_t on, uint16_t off); 35 | void setPin(uint8_t num, uint16_t val, bool invert=false); 36 | 37 | private: 38 | uint8_t _i2caddr; 39 | 40 | TwoWire *_i2c; 41 | 42 | uint8_t read8(uint8_t addr); 43 | void write8(uint8_t addr, uint8_t d); 44 | }; 45 | 46 | #endif 47 | -------------------------------------------------------------------------------- /examples/Peripheral/clearbonds/clearbonds.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | 15 | /* This sketch remove the folder that contains the bonding information 16 | * used by Bluefruit which is "/adafruit/bond" 17 | */ 18 | 19 | #include 20 | #include 21 | 22 | void setup() 23 | { 24 | Serial.begin(115200); 25 | while ( !Serial ) delay(10); // for nrf52840 with native usb 26 | 27 | Serial.println("Bluefruit52 Clear Bonds Example"); 28 | Serial.println("-------------------------------\n"); 29 | 30 | Bluefruit.begin(); 31 | 32 | Serial.println(); 33 | Serial.println("----- Before -----\n"); 34 | bond_print_list(BLE_GAP_ROLE_PERIPH); 35 | bond_print_list(BLE_GAP_ROLE_CENTRAL); 36 | 37 | Bluefruit.clearBonds(); 38 | Bluefruit.Central.clearBonds(); 39 | 40 | Serial.println(); 41 | Serial.println("----- After -----\n"); 42 | 43 | bond_print_list(BLE_GAP_ROLE_PERIPH); 44 | bond_print_list(BLE_GAP_ROLE_CENTRAL); 45 | } 46 | 47 | void loop() 48 | { 49 | // Toggle both LEDs every 1 second 50 | digitalToggle(LED_RED); 51 | 52 | delay(1000); 53 | } 54 | 55 | -------------------------------------------------------------------------------- /examples/Hardware/gpstest_swuart/gpstest_swuart.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | 15 | /* This example show how to use Software Serial on Bluefruit nRF52 16 | * to interact with GPS FeatherWing https://www.adafruit.com/product/3133 17 | * 18 | * Hardware Set up 19 | * - Connect 3V and GND to GPS wing 20 | * - 21 | */ 22 | 23 | #include 24 | 25 | #define SW_RXD A0 26 | #define SW_TXD A1 27 | 28 | // Declare an Software Serial instance 29 | SoftwareSerial mySerial(SW_RXD, SW_TXD); 30 | 31 | void setup() { 32 | 33 | // Init hardware UART <-> Serial Monitor 34 | Serial.begin(115200); 35 | 36 | Serial.println("GPS echo test"); 37 | 38 | // Init Software Uart <-> GPS FeatherWing 39 | mySerial.begin(9600); // default NMEA GPS baud 40 | } 41 | 42 | 43 | void loop() { 44 | 45 | // Pass data from Serial (HW uart) to GPS Wing (SW Uart) 46 | if (Serial.available()) { 47 | char c = Serial.read(); 48 | mySerial.write(c); 49 | } 50 | 51 | // Pass data from GPS Wing (SW Uart) to Serial (HW uart) 52 | if (mySerial.available()) { 53 | char c = mySerial.read(); 54 | Serial.write(c); 55 | } 56 | } 57 | -------------------------------------------------------------------------------- /examples/Hardware/Servo/Joystick_servo/Joystick_servo.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Controlling a servo position using a potentiometer (variable resistor) 3 | 4 | */ 5 | 6 | #include 7 | 8 | Servo servo0; // create servo object to control a servo 9 | Servo servo1; 10 | Servo servo2; 11 | 12 | int potpin = A0; // P0.28 Pin analog pin used to connect the potentiometer 13 | int Xpin = A2; 14 | int Ypin = A1; 15 | 16 | int valPot; // variable to read the value from the analog pin 17 | int valX; 18 | int valY; 19 | 20 | void setup() { 21 | Serial.begin(115200); 22 | servo0.attach(11); // attaches the servo on P0.11 Pin to the servo object 23 | servo1.attach(12); 24 | servo2.attach(13); 25 | } 26 | 27 | void loop() { 28 | valPot = analogRead(potpin); // reads the value of the potentiometer (value between 0 and 1023) 29 | Serial.print("Pot: "); 30 | Serial.println(valPot); 31 | valPot = map(valPot, 0, 1023, 0, 180); // scale it to use it with the servo (value between 0 and 180) 32 | 33 | valX = analogRead(Xpin); // reads the value of the potentiometer (value between 0 and 1023) 34 | Serial.print("Xval: "); 35 | Serial.println(valX); 36 | valX = map(valX, 0, 1023, 0, 180); // scale it to use it with the servo (value between 0 and 180) 37 | 38 | valY = analogRead(Ypin); // reads the value of the potentiometer (value between 0 and 1023) 39 | Serial.print("Yval: "); 40 | Serial.println(valY); 41 | valY = map(valY, 0, 1023, 0, 180); // scale it to use it with the servo (value between 0 and 180) 42 | 43 | servo0.write(valPot); // sets the servo position according to the scaled value 44 | servo1.write(valX); 45 | servo2.write(valY); 46 | delay(15); // waits for the servo to get there 47 | } 48 | -------------------------------------------------------------------------------- /examples/Hardware/nfc_to_gpio/nfc_to_gpio.ino: -------------------------------------------------------------------------------- 1 | // This sketch will check if the NFC pins are configured for NFC mode, 2 | // and if so it will switch them to operate in GPIO mode. A system 3 | // reset is required before this change takes effect since the CONFIG 4 | // memory is only read on power up. 5 | 6 | // !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! 7 | // !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! 8 | // !!!!! IMPORTANT NOTE ... READ BEFORE RUNNING THIS SKETCH !!!!! 9 | // !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! 10 | // !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! 11 | 12 | // UICR customer registers are meant to be stored with values 13 | // that are supposed to stay there during the life time of the softdevice. 14 | // You cannot erase them without erasing everything on chip, so setting the 15 | // NFC pins to GPIO mode is a ONE WAY OPERATION and you will need a debugger 16 | // like a Segger J-Link to set them back to NFC mode! 17 | 18 | void setup() { 19 | Serial.begin(115200); 20 | 21 | Serial.println("Bluefruit52 NFC to GPIO Pin Config"); 22 | Serial.println("----------------------------------\n"); 23 | if ((NRF_UICR->NFCPINS & UICR_NFCPINS_PROTECT_Msk) == (UICR_NFCPINS_PROTECT_NFC << UICR_NFCPINS_PROTECT_Pos)) 24 | { 25 | Serial.println("Fix NFC pins"); 26 | NRF_NVMC->CONFIG = NVMC_CONFIG_WEN_Wen << NVMC_CONFIG_WEN_Pos; 27 | while (NRF_NVMC->READY == NVMC_READY_READY_Busy); 28 | NRF_UICR->NFCPINS &= ~UICR_NFCPINS_PROTECT_Msk; 29 | while (NRF_NVMC->READY == NVMC_READY_READY_Busy); 30 | NRF_NVMC->CONFIG = NVMC_CONFIG_WEN_Ren << NVMC_CONFIG_WEN_Pos; 31 | while (NRF_NVMC->READY == NVMC_READY_READY_Busy); 32 | Serial.println("Done"); 33 | delay(500); 34 | NVIC_SystemReset(); 35 | } 36 | 37 | } 38 | void loop() { 39 | // put your main code here, to run repeatedly: 40 | } 41 | -------------------------------------------------------------------------------- /docs/getting_started_ja.md: -------------------------------------------------------------------------------- 1 | # nRF52832 Bluefruit Arduino Libraries 2 | 3 | These's examples for our nRF52832 based Bluefruit LE modules 4 | 5 | [English](../README.md) | [中文](getting_started_cn.md) | 日本語 6 | 7 | M5Stack Core のライブラリへようこそ 8 | 9 | ## 1. 始めよう 10 | 11 | #### M5Stackの開発環境を構築しよう 12 | 13 | *1.MacOS環境* 14 | 15 | * [Install the Bluefruit52 board for Arduino](https://www.afantor.cc/nRF52_bluefruit_Learning_Guide.html#arduino-bsp-setup) 16 | 17 | *2.Windows環境* 18 | 19 | Coming soon... 20 | 21 | 22 | ## 2. プログラム例 23 | 24 | https://github.com/Afantor/Afantor_Bluefruit52_Arduino/tree/master/examples 25 | 26 | ## 3. 関数リファレンス(API仕様) 27 | 28 | https://github.com/Afantor/Afantor_Bluefruit52_Arduino/blob/master/src/bluefruit52.h#L49 29 | 30 | ## 4. ハードウェア仕様 31 | 32 | #### I/Oインタフェイス 33 | 34 | *nRF52は複数のバリエーションがあります。違いは [こちら](https://github.com/Afantor/Afantor_Bluefruit52_Arduino/tree/master/docs/hardware)* 35 | 36 | **LCD** 37 | 38 | *LCD 解像度: 135x240* 39 | 40 | 41 | 42 | 43 | 44 |
nRF52 ChipP0.07P0.27P0.16P0.23P0.24~CS
ST7789SDASCLDCRSTCSBL
45 | 46 | **ボタン** 47 | 48 | 49 | 50 | 51 |
nRF52 ChipP0.18P0.11
Button PinBUTTON 1BUTTON 2
52 | 53 | **MPU6050** 54 | 55 | 56 | 57 | 58 |
nRF52 ChipP0.26P0.25
MPU6050SCLSDA
59 | 60 | 61 | ### M-バス 62 | ![image](images/Bluefruit52_Pinconfig.png) 63 | ![image](images/Bluefruit52_Pinout.png) 64 | 65 | ## 5. 素晴らしい応用例 66 | 67 | * [App-Controller](https://github.com/Afantor/Afantor_Bluefruit52_Arduino/tree/master/examples/Peripheral/controller) この例は、BLEUartヘルパークラスとBluefruit LE Connectアプリケーションを使用して、ベースのキーパッドとセンサーデータをnRF52に送信できることを示しています。 -------------------------------------------------------------------------------- /examples/BMI160/Temperature/Temperature.ino: -------------------------------------------------------------------------------- 1 | /* 2 | * Temperature.ino 3 | * 4 | * I2C addr: 5 | * 0x68: connect SDIO pin of the BMI160 to GND which means the default I2C address 6 | * 0x69: set I2C address by parameter 7 | * 8 | * Through the example, you can get the sensor data by using getSensorData: 9 | * get acell by paremeter onlyAccel; 10 | * get gyro by paremeter onlyGyro; 11 | * get both acell and gyro by paremeter bothAccelGyro. 12 | * 13 | * With the rotation of the sensor, data changes are visible. 14 | * 15 | * Copyright [Afantor](http://www.afantor.cc), 2019 16 | * Copyright MIT License 17 | * 18 | * version V1.0 19 | * date 2019-05-27 20 | */ 21 | 22 | #include 23 | 24 | const int irq_pin = 30; 25 | const int i2c_addr = 0x69; 26 | 27 | 28 | void setup() { 29 | Serial.begin(115200); // initialize Serial communication 30 | Wire.begin(); 31 | 32 | // initialize device 33 | Serial.println("Initializing IMU device..."); 34 | 35 | BMI160.begin(BMI160GenClass::I2C_MODE, i2c_addr, irq_pin); 36 | uint8_t dev_id = BMI160.getDeviceID(); 37 | Serial.print("DEVICE ID: "); 38 | Serial.println(dev_id, HEX); 39 | 40 | // Set the gyro range to 2000 degrees/second 41 | BMI160.setGyroRate(3200); 42 | BMI160.setGyroRange(2000); 43 | // Set the accelerometer range to 2g 44 | BMI160.setAccelerometerRate(1600); 45 | BMI160.setAccelerometerRange(2); 46 | Serial.println("Initializing BMI160 device...done."); 47 | } 48 | 49 | void loop() { 50 | int TempRaw; // raw temperature values 51 | float temp; 52 | 53 | 54 | // read raw temperature from device 55 | TempRaw = BMI160.getTemperature(); 56 | 57 | // convert the raw temp data to °C. 58 | temp = ((float) TempRaw) / 512.0 + 23.0; 59 | Serial.print("Temp:\t"); 60 | Serial.print(temp,1); 61 | Serial.println("°C"); 62 | delay(1000); 63 | } 64 | 65 | 66 | 67 | 68 | -------------------------------------------------------------------------------- /examples/Hardware/software_timer/software_timer.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | #include 15 | 16 | /* SoftwareTimer is a helper class that uses FreeRTOS software timer 17 | * to invoke callback. Its periodic timing is flexible as opposed to 18 | * hardware timer and cannot be faster than rtos's tick which is configured 19 | * at ~1 ms interval. 20 | * 21 | * If you need an strict interval timing, or faster frequency, check out 22 | * the hw_systick sketch example that use hardware systick timer. 23 | * 24 | * http://www.freertos.org/RTOS-software-timer.html 25 | */ 26 | SoftwareTimer blinkTimer; 27 | 28 | 29 | void setup() 30 | { 31 | // Configure the timer with 1000 ms interval, with our callback 32 | blinkTimer.begin(1000, blink_timer_callback); 33 | 34 | // Start the timer 35 | blinkTimer.start(); 36 | } 37 | 38 | void loop() 39 | { 40 | // do nothing here 41 | } 42 | 43 | 44 | /** 45 | * Software Timer callback is invoked via a built-in FreeRTOS thread with 46 | * minimal stack size. Therefore it should be as simple as possible. If 47 | * a periodically heavy task is needed, please use Scheduler.startLoop() to 48 | * create a dedicated task for it. 49 | * 50 | * More information http://www.freertos.org/RTOS-software-timer.html 51 | */ 52 | void blink_timer_callback(TimerHandle_t xTimerID) 53 | { 54 | // freeRTOS timer ID, ignored if not used 55 | (void) xTimerID; 56 | 57 | digitalToggle(LED_RED); 58 | } 59 | -------------------------------------------------------------------------------- /docs/getting_started_cn.md: -------------------------------------------------------------------------------- 1 | # nRF52832 Bluefruit 库 2 | 3 | [English](../README.md) | 中文 | [日本語](docs/getting_started_ja.md) 4 | 5 | ## 1. 上手指南 6 | 7 | *1.For MacOS* 8 | 9 | * [Install the Bluefruit52 board for Arduino](https://www.afantor.cc/nRF52_bluefruit_Learning_Guide.html#arduino-bsp-setup) 10 | 11 | *2. For Windows* 12 | 13 | * [Install the Bluefruit52 board for Arduino](https://github.com/Afantor/Afantor_Bluefruit52_Arduino/tree/master/docs/getting_started_setting.md) 14 | 15 | 16 | ## 2. 例程 17 | 18 | https://github.com/Afantor/Afantor_Bluefruit52_Arduino/tree/master/examples 19 | 20 | ## 3. API 参考 21 | 22 | https://github.com/Afantor/Afantor_Bluefruit52_Arduino/blob/master/src/bluefruit52.h#L49 23 | 24 | https://www.afantor.cc/nRF52_bluefruit_Learning_Guide.html 25 | 26 | ## 4. H/W 参考 27 | 28 | #### 管脚映射 29 | 30 | *我们有几个不同版本的主控,可以直接查看原理图[对比](https://github.com/Afantor/Afantor_Bluefruit52_Arduino/tree/master/docs/hardware).* 31 | 32 | **LCD & TF Card** 33 | 34 | *LCD 分辨率: 135x240* 35 | 36 | 37 | 38 | 39 | 40 |
nRF52 ChipP0.07P0.27P0.16P0.23P0.24~CS
ST7789SDASCLDCRSTCSBL
41 | 42 | **Button** 43 | 44 | 45 | 46 | 47 |
nRF52 ChipP0.18P0.11
Button PinBUTTON 1BUTTON 2
48 | 49 | **MPU6050** 50 | 51 | 52 | 53 | 54 |
nRF52 ChipP0.26P0.25
MPU6050SCLSDA
55 | 56 | 57 | ### M-BUS 58 | ![image](images/Bluefruit52_Pinconfig.png) 59 | ![image](images/Bluefruit52_Pinout.png) 60 | 61 | #### Note: 62 | 63 | * 如何安装 CP210x 串口驱动 64 | 65 | https://docs.m5stack.com/#/zh_CN/related_documents/establish_serial_connection 66 | 67 | * 如何升级 Adafruit_nRF52_Arduino 库和 Afantor_Bluefruit52_Arduino 库 68 | 69 | https://docs.m5stack.com/#/zh_CN/related_documents/upgrade_m5stack_lib 70 | -------------------------------------------------------------------------------- /examples/Hardware/hw_systick/hw_systick.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | #include 15 | 16 | // Interval between systick event 17 | #define TICK_INTERVAL_MS 50 18 | 19 | // Note: Extern "C" is required since all the IRQ hardware handler is 20 | // declared as "C function" within the startup (assembly) file. 21 | // Without it, our SysTick_Handler will be declared as "C++ function" 22 | // which is not the same as the "C function" in startup even it has 23 | // the same name. 24 | extern "C" 25 | { 26 | 27 | /* This is hardware interupt service function exectuing in non-RTOS thread 28 | * Function implementation should be quick and short if possible. 29 | * 30 | * WARNING: This function MUST NOT call any blocking FreeRTOS API 31 | * such as delay(), xSemaphoreTake() etc ... for more information 32 | * http://www.freertos.org/a00016.html 33 | */ 34 | void SysTick_Handler(void) 35 | { 36 | digitalToggle(LED_RED); 37 | } 38 | 39 | } // extern C 40 | 41 | void setup() 42 | { 43 | /* Input parameter is number of ticks between interrupts handler i.e SysTick_Handler 44 | * 1000 ms --> F_CPU ticks 45 | * T ms --> (F_CPU/1000)*T ticks 46 | * 47 | * Note: Since systick is 24-bit timer, the max tick value is 0xFFFFFF, F_CPU = 64 Mhz 48 | * --> our Tmax = 0xFFFFFF/64000 ~ 262 ms 49 | */ 50 | 51 | SysTick_Config( (F_CPU/1000)*TICK_INTERVAL_MS ); 52 | } 53 | 54 | void loop() 55 | { 56 | // do nothing here 57 | } 58 | -------------------------------------------------------------------------------- /examples/BMI160/Accelerometer/Accelerometer.ino: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2019 CallMeCode Corporation. All rights reserved. 3 | * See the bottom of this file for the license terms. 4 | */ 5 | 6 | /* 7 | This sketch example demonstrates how the BMI160 on the 8 | Intel(R) Curie(TM) module can be used to read accelerometer data 9 | */ 10 | 11 | #include 12 | 13 | const int irq_pin = 30; 14 | const int i2c_addr = 0x69; 15 | 16 | void setup() { 17 | Serial.begin(115200); // initialize Serial communication 18 | Wire.begin(); 19 | // initialize device 20 | Serial.println("Initializing IMU device..."); 21 | // BMI160.begin(BMI160GenClass::SPI_MODE, /* SS pin# = */10); 22 | BMI160.begin(BMI160GenClass::I2C_MODE, i2c_addr, irq_pin); 23 | uint8_t dev_id = BMI160.getDeviceID(); 24 | Serial.print("DEVICE ID: "); 25 | Serial.println(dev_id, HEX); 26 | 27 | // Set the accelerometer range to 2G 28 | BMI160.setAccelerometerRange(2); 29 | Serial.println("Initializing IMU device...done."); 30 | } 31 | 32 | void loop() { 33 | int axRaw, ayRaw, azRaw; // raw accel values 34 | float ax, ay, az; //scaled accelerometer values 35 | 36 | // read accelerometer measurements from device, scaled to the configured range 37 | // read raw accel measurements from device 38 | BMI160.readAccelerometer(axRaw, ayRaw, azRaw); 39 | // convert the raw accel data to g 40 | ax = convertRawAccel(axRaw); 41 | ay = convertRawAccel(ayRaw); 42 | az = convertRawAccel(azRaw); 43 | // display tab-separated accelerometer x/y/z values 44 | Serial.print("Accel:\t"); 45 | Serial.print(ax); 46 | Serial.print("\t"); 47 | Serial.print(ay); 48 | Serial.print("\t"); 49 | Serial.print(az); 50 | Serial.println(); 51 | delay(100); 52 | } 53 | 54 | float convertRawAccel(int aRaw) { 55 | // since we are using 2000 degrees/seconds range 56 | // -2g to a raw value of -32768 57 | // +2g to a raw value of 32767 58 | 59 | float a = ((aRaw * 2.0) / 32768.0) * 9.8; 60 | 61 | return a; 62 | } 63 | 64 | 65 | -------------------------------------------------------------------------------- /examples/Display/TFT_Number/TFT_Number.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Test the BF52.Lcd.print() viz embedded BF52.Lcd.write() function 3 | 4 | This sketch used font 2, 4, 7 5 | 6 | Make sure all the display driver and pin comnenctions are correct by 7 | editting the User_Setup.h file in the BF52.eSPI library folder. 8 | 9 | ######################################################################### 10 | ###### DON'T FORGET TO UPDATE THE User_Setup.h FILE IN THE LIBRARY ###### 11 | ######################################################################### 12 | */ 13 | 14 | #include 15 | 16 | int tempInt = 0; 17 | float tempF = 1.01; 18 | 19 | void setup(void) { 20 | BF52.begin(true, true, false); 21 | } 22 | 23 | void loop() { 24 | tempInt = 0; 25 | tempF = 1.01; 26 | // Fill screen with grey so we can see the effect of printing with and without 27 | // a background colour defined 28 | BF52.Lcd.fillScreen(BLACK); 29 | 30 | // Set "cursor" at top left corner of display (0,0) and select font 2 31 | // (cursor will move to next line automatically during printing with 'BF52.Lcd.println' 32 | // or stay on the line is there is room for the text with BF52.Lcd.print) 33 | BF52.Lcd.setCursor(0, 0); 34 | // Set the font colour to be white with a black background, set text size multiplier to 1 35 | BF52.Lcd.setTextColor(WHITE,BLACK); 36 | BF52.Lcd.setTextSize(1); 37 | // We can now plot text on screen using the "print" class 38 | BF52.Lcd.println("LCD draw Number Test!"); 39 | 40 | // Set the font colour to be yellow with no background, set to font 7 41 | BF52.Lcd.setTextColor(YELLOW); 42 | BF52.Lcd.setTextSize(2); 43 | BF52.Lcd.println(1234.56); 44 | 45 | BF52.Lcd.drawChar(0, 40, 'A', RED, BLACK, 2); 46 | BF52.Lcd.drawNumber(0, 80, 102, 3, BLUE, BLACK, 2); 47 | BF52.Lcd.drawFloat(0, 110, 10.89, 4, YELLOW, BLACK, 2); 48 | // BF52.Lcd.drawString(0, 80, "Hello BLE", WHITE, BLACK, 4); 49 | for(int i=0; i<900; i++){ 50 | tempInt++; 51 | tempF+=0.2; 52 | BF52.Lcd.drawNumber(100, 80, tempInt, 3, BLUE, BLACK, 2); 53 | BF52.Lcd.drawFloat(100, 110, tempF, 4, YELLOW, BLACK, 2); 54 | delay(100); 55 | } 56 | delay(1000); 57 | } 58 | 59 | 60 | 61 | -------------------------------------------------------------------------------- /src/utility/button.h: -------------------------------------------------------------------------------- 1 | /*----------------------------------------------------------------------* 2 | * Arduino Button Library v1.0 * 3 | * Jack Christensen Mar 2012 * 4 | * * 5 | * This work is licensed under the Creative Commons Attribution- * 6 | * ShareAlike 3.0 Unported License. To view a copy of this license, * 7 | * visit http://creativecommons.org/licenses/by-sa/3.0/ or send a * 8 | * letter to Creative Commons, 171 Second Street, Suite 300, * 9 | * San Francisco, California, 94105, USA. * 10 | *----------------------------------------------------------------------*/ 11 | #ifndef _button_h 12 | #define _button_h 13 | // #if ARDUINO >= 100 14 | #include 15 | // #else 16 | // #include 17 | // #endif 18 | class Button 19 | { 20 | public: 21 | Button(uint8_t pin, uint8_t invert, uint32_t dbTime); 22 | uint8_t read(); 23 | uint8_t isPressed(); 24 | uint8_t isReleased(); 25 | uint8_t wasPressed(); 26 | uint8_t wasReleased(); 27 | uint8_t pressedFor(uint32_t ms); 28 | uint8_t releasedFor(uint32_t ms); 29 | uint8_t wasReleasefor(uint32_t ms); 30 | uint32_t lastChange(); 31 | 32 | private: 33 | uint8_t _pin; //arduino pin number 34 | uint8_t _puEnable; //internal pullup resistor enabled 35 | uint8_t _invert; //if 0, interpret high state as pressed, else interpret low state as pressed 36 | uint8_t _state; //current button state 37 | uint8_t _lastState; //previous button state 38 | uint8_t _changed; //state changed since last read 39 | uint32_t _time; //time of current state (all times are in ms) 40 | uint32_t _lastTime; //time of previous state 41 | uint32_t _lastChange; //time of last state change 42 | uint32_t _dbTime; //debounce time 43 | uint32_t _pressTime; //press time 44 | uint32_t _hold_time; //hold time call wasreleasefor 45 | }; 46 | #endif 47 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # nRF52832 Bluefruit Arduino Libraries 2 | 3 | These's examples for our nRF52832 based Bluefruit LE modules 4 | 5 | English | [中文](docs/getting_started_cn.md) | [日本語](docs/getting_started_ja.md) 6 | 7 | Welcome to program with Bluefruit52 nRF52832 Core 8 | 9 | ## 1. Get Started 10 | 11 | #### Here is the article to get started 12 | 13 | *1.For MacOS* 14 | 15 | * [Install the Bluefruit52 board for Arduino](https://www.afantor.cc/nRF52_bluefruit_Learning_Guide.html#arduino-bsp-setup) 16 | 17 | *2. For Windows* 18 | 19 | * [Install the Bluefruit52 board for Arduino](https://github.com/Afantor/Afantor_Bluefruit52_Arduino/tree/master/docs/getting_started_setting.md) 20 | 21 | 22 | ## 2. Example 23 | 24 | https://github.com/Afantor/Afantor_Bluefruit52_Arduino/tree/master/examples 25 | 26 | ## 3. API Reference 27 | 28 | https://github.com/Afantor/Afantor_Bluefruit52_Arduino/blob/master/src/bluefruit52.h#L49 29 | 30 | ## 4. H/W Reference 31 | 32 | #### Pinout 33 | 34 | *We have several kinds of Boards, There is [their difference in schematic](https://github.com/Afantor/Afantor_Bluefruit52_Arduino/tree/master/docs/hardware).* 35 | 36 | **LCD** 37 | 38 | *LCD Resolution: 135x240* 39 | 40 | 41 | 42 | 43 | 44 |
nRF52 ChipP0.07P0.27P0.16P0.23P0.24~CS
ST7789SDASCLDCRSTCSBL
45 | 46 | **Button** 47 | 48 | 49 | 50 | 51 |
nRF52 ChipP0.18P0.11
Button PinBUTTON 1BUTTON 2
52 | 53 | **MPU6050** 54 | 55 | 56 | 57 | 58 |
nRF52 ChipP0.26P0.25
MPU6050SCLSDA
59 | 60 | 61 | ### M-BUS 62 | ![image](docs/images/Bluefruit52_Pinconfig.png) 63 | ![image](docs/images/Bluefruit52_Pinout.png) 64 | 65 | ## 5. Awesome Project 66 | 67 | * [App-Controller](https://github.com/Afantor/Afantor_Bluefruit52_Arduino/tree/master/examples/Peripheral/controller) This examples shows you you can use the BLEUart helper class and the Bluefruit LE Connect applications to send based keypad and sensor data to your nRF52. -------------------------------------------------------------------------------- /examples/Display/TFT_Mandlebrot/TFT_Mandlebrot.ino: -------------------------------------------------------------------------------- 1 | // Mandlebrot 2 | 3 | // This will run quite slowly due to the large number of floating point calculations per pixel 4 | 5 | #include 6 | 7 | #define GREY 0x7BEF 8 | 9 | unsigned long runTime = 0; 10 | 11 | float sx = 0, sy = 0; 12 | uint16_t x0 = 0, x1 = 0, yy0 = 0, yy1 = 0; 13 | 14 | void setup() 15 | { 16 | BF52.begin(true, true, false); 17 | } 18 | 19 | void loop() 20 | { 21 | runTime = millis(); 22 | 23 | BF52.Lcd.fillScreen(BLACK); 24 | for (int px = 1; px < 240; px++) 25 | { 26 | for (int py = 0; py < 135; py++) 27 | { 28 | float x0 = (map(px, 0, 240, -250000/2, -242500/2)) / 100000.0; //scaled x coordinate of pixel (scaled to lie in the Mandelbrot X scale (-2.5, 1)) 29 | float yy0 = (map(py, 0, 135, -75000/4, -61000/4)) / 100000.0; //scaled y coordinate of pixel (scaled to lie in the Mandelbrot Y scale (-1, 1)) 30 | float xx = 0.0; 31 | float yy = 0.0; 32 | int iteration = 0; 33 | int max_iteration = 128; 34 | while ( ((xx * xx + yy * yy) < 4) && (iteration < max_iteration) ) 35 | { 36 | float xtemp = xx * xx - yy * yy + x0; 37 | yy = 2 * xx * yy + yy0; 38 | xx = xtemp; 39 | iteration++; 40 | } 41 | int color = rainbow((3*iteration+64)%128); 42 | yield();BF52.Lcd.drawPixel(px, py, color); 43 | } 44 | } 45 | while(1) yield(); 46 | } 47 | 48 | unsigned int rainbow(int value) 49 | { 50 | // Value is expected to be in range 0-127 51 | // The value is converted to a spectrum colour from 0 = blue through to red = blue 52 | 53 | byte red = 0; // Red is the top 5 bits of a 16 bit colour value 54 | byte green = 0;// Green is the middle 6 bits 55 | byte blue = 0; // Blue is the bottom 5 bits 56 | 57 | byte quadrant = value / 32; 58 | 59 | if (quadrant == 0) { 60 | blue = 31; 61 | green = 2 * (value % 32); 62 | red = 0; 63 | } 64 | if (quadrant == 1) { 65 | blue = 31 - (value % 32); 66 | green = 63; 67 | red = 0; 68 | } 69 | if (quadrant == 2) { 70 | blue = 0; 71 | green = 63; 72 | red = value % 32; 73 | } 74 | if (quadrant == 3) { 75 | blue = 0; 76 | green = 63 - 2 * (value % 32); 77 | red = 31; 78 | } 79 | return (red << 11) + (green << 5) + blue; 80 | } 81 | 82 | 83 | -------------------------------------------------------------------------------- /examples/Peripheral/blinky_ota/blinky_ota.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | 15 | #include 16 | 17 | // OTA DFU service 18 | BLEDfu bledfu; 19 | 20 | void setup() 21 | { 22 | Serial.begin(115200); 23 | while ( !Serial ) delay(10); // for nrf52840 with native usb 24 | 25 | Serial.println("Bluefruit52 Blinky Example"); 26 | Serial.println("--------------------------\n"); 27 | 28 | Bluefruit.begin(); 29 | Bluefruit.setTxPower(4); // Check bluefruit.h for supported values 30 | Bluefruit.setName("Bluefruit52"); 31 | 32 | // To be consistent OTA DFU should be added first if it exists 33 | bledfu.begin(); 34 | 35 | // Set up and start advertising 36 | startAdv(); 37 | } 38 | 39 | void startAdv(void) 40 | { 41 | // Advertising packet 42 | Bluefruit.Advertising.addFlags(BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE); 43 | Bluefruit.Advertising.addTxPower(); 44 | Bluefruit.Advertising.addName(); 45 | 46 | /* Start Advertising 47 | * - Enable auto advertising if disconnected 48 | * - Interval: fast mode = 20 ms, slow mode = 152.5 ms 49 | * - Timeout for fast mode is 30 seconds 50 | * - Start(timeout) with timeout = 0 will advertise forever (until connected) 51 | * 52 | * For recommended advertising interval 53 | * https://developer.apple.com/library/content/qa/qa1931/_index.html 54 | */ 55 | Bluefruit.Advertising.restartOnDisconnect(true); 56 | Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms 57 | Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode 58 | Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds 59 | } 60 | 61 | void loop() 62 | { 63 | // Toggle both LEDs every 1 second 64 | digitalToggle(LED_RED); 65 | 66 | delay(1000); 67 | } 68 | 69 | -------------------------------------------------------------------------------- /examples/Central/central_scan/central_scan.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | 15 | #include 16 | 17 | void setup() 18 | { 19 | Serial.begin(115200); 20 | while ( !Serial ) delay(10); // for nrf52840 with native usb 21 | 22 | Serial.println("Bluefruit52 Central Scan Example"); 23 | Serial.println("--------------------------------\n"); 24 | 25 | // Initialize Bluefruit with maximum connections as Peripheral = 0, Central = 1 26 | // SRAM usage required by SoftDevice will increase dramatically with number of connections 27 | Bluefruit.begin(0, 1); 28 | Bluefruit.setTxPower(4); // Check bluefruit.h for supported values 29 | Bluefruit.setName("Bluefruit52"); 30 | 31 | // Start Central Scan 32 | Bluefruit.setConnLedInterval(250); 33 | Bluefruit.Scanner.setRxCallback(scan_callback); 34 | Bluefruit.Scanner.start(0); 35 | 36 | Serial.println("Scanning ..."); 37 | } 38 | 39 | void scan_callback(ble_gap_evt_adv_report_t* report) 40 | { 41 | Serial.println("Timestamp Addr Rssi Data"); 42 | 43 | Serial.printf("%09d ", millis()); 44 | 45 | // MAC is in little endian --> print reverse 46 | Serial.printBufferReverse(report->peer_addr.addr, 6, ':'); 47 | Serial.print(" "); 48 | 49 | Serial.print(report->rssi); 50 | Serial.print(" "); 51 | 52 | Serial.printBuffer(report->data.p_data, report->data.len, '-'); 53 | Serial.println(); 54 | 55 | // Check if advertising contain BleUart service 56 | if ( Bluefruit.Scanner.checkReportForUuid(report, BLEUART_UUID_SERVICE) ) 57 | { 58 | Serial.println(" BLE UART service detected"); 59 | } 60 | 61 | Serial.println(); 62 | 63 | // For Softdevice v6: after received a report, scanner will be paused 64 | // We need to call Scanner resume() to continue scanning 65 | Bluefruit.Scanner.resume(); 66 | } 67 | 68 | void loop() 69 | { 70 | // nothing to do 71 | } 72 | -------------------------------------------------------------------------------- /examples/Display/TFT_Starfield/TFT_Starfield.ino: -------------------------------------------------------------------------------- 1 | // Animates white pixels to simulate flying through a star field 2 | 3 | #include 4 | 5 | // With 1024 stars the update rate is ~65 frames per second 6 | #define NSTARS 1024 7 | uint8_t sx[NSTARS] = {}; 8 | uint8_t sy[NSTARS] = {}; 9 | uint8_t sz[NSTARS] = {}; 10 | 11 | uint8_t za, zb, zc, zx; 12 | 13 | // Fast 0-255 random number generator from http://eternityforest.com/Projects/rng.php: 14 | uint8_t __attribute__((always_inline)) rng() 15 | { 16 | zx++; 17 | za = (za^zc^zx); 18 | zb = (zb+za); 19 | zc = (zc+(zb>>1)^za); 20 | return zc; 21 | } 22 | 23 | void setup() { 24 | za = random(256); 25 | zb = random(256); 26 | zc = random(256); 27 | zx = random(256); 28 | 29 | BF52.begin(true, true, false); 30 | // BF52.Lcd.setRotation(1); 31 | BF52.Lcd.fillScreen(BLACK); 32 | 33 | // fastSetup() must be used immediately before fastPixel() to prepare screen 34 | // It must be called after any other graphics drawing function call if fastPixel() 35 | // is to be called again 36 | //BF52.Lcd.fastSetup(); // Prepare plot window range for fast pixel plotting 37 | } 38 | 39 | void loop() 40 | { 41 | unsigned long t0 = micros(); 42 | uint8_t spawnDepthVariation = 255; 43 | 44 | for(int i = 0; i < NSTARS; ++i) 45 | { 46 | if (sz[i] <= 1) 47 | { 48 | sx[i] = 160 - 120 + rng(); 49 | sy[i] = rng(); 50 | sz[i] = spawnDepthVariation--; 51 | } 52 | else 53 | { 54 | int old_screen_x = ((int)sx[i] - 160) * 256 / sz[i] + 160; 55 | int old_screen_y = ((int)sy[i] - 120) * 256 / sz[i] + 120; 56 | 57 | // This is a faster pixel drawing function for occassions where many single pixels must be drawn 58 | BF52.Lcd.drawPixel(old_screen_x, old_screen_y,BLACK); 59 | 60 | sz[i] -= 2; 61 | if (sz[i] > 1) 62 | { 63 | int screen_x = ((int)sx[i] - 160) * 256 / sz[i] + 160; 64 | int screen_y = ((int)sy[i] - 120) * 256 / sz[i] + 120; 65 | 66 | if (screen_x >= 0 && screen_y >= 0 && screen_x < 320 && screen_y < 240) 67 | { 68 | uint8_t r, g, b; 69 | r = g = b = 255 - sz[i]; 70 | BF52.Lcd.drawPixel(screen_x, screen_y, BF52.Lcd.color565(r,g,b)); 71 | } 72 | else 73 | sz[i] = 0; // Out of screen, die. 74 | } 75 | } 76 | } 77 | unsigned long t1 = micros(); 78 | //static char timeMicros[8] = {}; 79 | 80 | // Calcualte frames per second 81 | Serial.println(1.0/((t1 - t0)/1000000.0)); 82 | } 83 | 84 | 85 | -------------------------------------------------------------------------------- /docs/arduino-ide/windows.md: -------------------------------------------------------------------------------- 1 | ## Steps to install Arduino ESP32 support on Windows 2 | ### Tested on 32 and 64 bit Windows 10 machines 3 | 4 | 1. Download and install the latest Arduino IDE ```Windows Installer``` from [arduino.cc](https://www.arduino.cc/en/Main/Software) 5 | 2. Download and install Git from [git-scm.com](https://git-scm.com/download/win) 6 | 3. Start ```Git GUI``` and run through the following steps: 7 | - Select ```Clone Existing Repository``` 8 | 9 | ![Step 1](win-screenshots/win-gui-1.png) 10 | 11 | - Select source and destination 12 | - Sketchbook Directory: Usually ```C:/Users/[YOUR_USER_NAME]/Documents/Arduino``` and is listed underneath the "Sketchbook location" in Arduino preferences. 13 | - Source Location: ```https://github.com/espressif/arduino-esp32.git``` 14 | - Target Directory: ```[ARDUINO_SKETCHBOOK_DIR]/hardware/espressif/esp32``` 15 | - Click ```Clone``` to start cloning the repository 16 | 17 | ![Step 2](win-screenshots/win-gui-2.png) 18 | ![Step 3](win-screenshots/win-gui-3.png) 19 | - open a `Git Bash` session pointing to ```[ARDUINO_SKETCHBOOK_DIR]/hardware/espressif/esp32``` and execute ```git submodule update --init --recursive``` 20 | - Open ```[ARDUINO_SKETCHBOOK_DIR]/hardware/espressif/esp32/tools``` and double-click ```get.exe``` 21 | 22 | ![Step 4](win-screenshots/win-gui-4.png) 23 | 24 | - When ```get.exe``` finishes, you should see the following files in the directory 25 | 26 | ![Step 5](win-screenshots/win-gui-5.png) 27 | 28 | 4. Plug your ESP32 board and wait for the drivers to install (or install manually any that might be required) 29 | 5. Start Arduino IDE 30 | 6. Select your board in ```Tools > Board``` menu 31 | 7. Select the COM port that the board is attached to 32 | 8. Compile and upload (You might need to hold the boot button while uploading) 33 | 34 | ![Arduino IDE Example](win-screenshots/arduino-ide.png) 35 | 36 | ### How to update to the latest code 37 | 38 | 1. Start ```Git GUI``` and you should see the repository under ```Open Recent Repository```. Click on it! 39 | 40 | ![Update Step 1](win-screenshots/win-gui-update-1.png) 41 | 42 | 2. From menu ```Remote``` select ```Fetch from``` > ```origin``` 43 | 44 | ![Update Step 2](win-screenshots/win-gui-update-2.png) 45 | 46 | 3. Wait for git to pull any changes and close ```Git GUI``` 47 | 4. Open ```[ARDUINO_SKETCHBOOK_DIR]/hardware/espressif/esp32/tools``` and double-click ```get.exe``` 48 | 49 | ![Step 4](win-screenshots/win-gui-4.png) 50 | -------------------------------------------------------------------------------- /examples/Display/TFT_Pie_Chart/TFT_Pie_Chart.ino: -------------------------------------------------------------------------------- 1 | // This sketch includes a function to draw circle segments 2 | // for pie charts in 1 degree increments 3 | 4 | #include 5 | 6 | #define DEG2RAD 0.0174532925 7 | 8 | byte inc = 0; 9 | unsigned int col = 0; 10 | 11 | 12 | void setup(void) 13 | { 14 | BF52.begin(true, true, false); 15 | 16 | // BF52.Lcd.setRotation(1); 17 | 18 | BF52.Lcd.fillScreen(BLACK); 19 | } 20 | 21 | void loop() { 22 | 23 | // Draw 4 pie chart segments 24 | fillSegment(120, 67, 0, 60, 64, RED); 25 | fillSegment(120, 67, 60, 30, 64, GREEN); 26 | fillSegment(120, 67, 60 + 30, 120, 64, BLUE); 27 | fillSegment(120, 67, 60 + 30 + 120, 150, 64, YELLOW); 28 | 29 | delay(4000); 30 | 31 | // Erase old chart with 360 degree black plot 32 | fillSegment(120, 67, 0, 360, 64, BLACK); 33 | } 34 | 35 | 36 | // ######################################################################### 37 | // Draw circle segments 38 | // ######################################################################### 39 | 40 | // x,y == coords of centre of circle 41 | // start_angle = 0 - 359 42 | // sub_angle = 0 - 360 = subtended angle 43 | // r = radius 44 | // colour = 16 bit colour value 45 | 46 | int fillSegment(int x, int y, int start_angle, int sub_angle, int r, unsigned int colour) 47 | { 48 | // Calculate first pair of coordinates for segment start 49 | float sx = cos((start_angle - 90) * DEG2RAD); 50 | float sy = sin((start_angle - 90) * DEG2RAD); 51 | uint16_t x1 = sx * r + x; 52 | uint16_t y1 = sy * r + y; 53 | 54 | // Draw colour blocks every inc degrees 55 | for (int i = start_angle; i < start_angle + sub_angle; i++) { 56 | 57 | // Calculate pair of coordinates for segment end 58 | int x2 = cos((i + 1 - 90) * DEG2RAD) * r + x; 59 | int y2 = sin((i + 1 - 90) * DEG2RAD) * r + y; 60 | 61 | BF52.Lcd.fillTriangle(x1, y1, x2, y2, x, y, colour); 62 | 63 | // Copy segment end to sgement start for next segment 64 | x1 = x2; 65 | y1 = y2; 66 | } 67 | } 68 | 69 | 70 | // ######################################################################### 71 | // Return the 16 bit colour with brightness 0-100% 72 | // ######################################################################### 73 | unsigned int brightness(unsigned int colour, int brightness) 74 | { 75 | byte red = colour >> 11; 76 | byte green = (colour & 0x7E0) >> 5; 77 | byte blue = colour & 0x1F; 78 | 79 | blue = (blue * brightness)/100; 80 | green = (green * brightness)/100; 81 | red = (red * brightness)/100; 82 | 83 | return (red << 11) + (green << 5) + blue; 84 | } 85 | 86 | -------------------------------------------------------------------------------- /examples/PCA9685/servo/servo.ino: -------------------------------------------------------------------------------- 1 | /*************************************************** 2 | This is an example for our PCA9685 16-channel PWM & Servo driver 3 | Servo test - this will drive 8 servos, one after the other on the 4 | first 8 pins of the PCA9685 5 | 6 | These drivers use I2C to communicate, 2 pins are required to 7 | interface. 8 | 9 | ****************************************************/ 10 | 11 | #include 12 | #include 13 | 14 | // called this way, it uses the default address 0x40 15 | PCA9685 pwm = PCA9685(); 16 | // you can also call it with a different address you want 17 | //PCA9685 pwm = PCA9685(0x41); 18 | // you can also call it with a different address and I2C interface 19 | //PCA9685 pwm = PCA9685(&Wire, 0x40); 20 | 21 | // Depending on your servo make, the pulse width min and max may vary, you 22 | // want these to be as small/large as possible without hitting the hard stop 23 | // for max range. You'll have to tweak them as necessary to match the servos you 24 | // have! 25 | #define SERVOMIN 150 // this is the 'minimum' pulse length count (out of 4096) 26 | #define SERVOMAX 600 // this is the 'maximum' pulse length count (out of 4096) 27 | 28 | // our servo # counter 29 | uint8_t servonum = 0; 30 | 31 | void setup() { 32 | Serial.begin(115200); 33 | Serial.println("4 channel Servo test!"); 34 | 35 | pwm.begin(); 36 | 37 | pwm.setPWMFreq(60); // Analog servos run at ~60 Hz updates 38 | 39 | delay(10); 40 | } 41 | 42 | // you can use this function if you'd like to set the pulse length in seconds 43 | // e.g. setServoPulse(0, 0.001) is a ~1 millisecond pulse width. its not precise! 44 | void setServoPulse(uint8_t n, double pulse) { 45 | double pulselength; 46 | 47 | pulselength = 1000000; // 1,000,000 us per second 48 | pulselength /= 60; // 60 Hz 49 | Serial.print(pulselength); Serial.println(" us per period"); 50 | pulselength /= 4096; // 12 bits of resolution 51 | Serial.print(pulselength); Serial.println(" us per bit"); 52 | pulse *= 1000000; // convert to us 53 | pulse /= pulselength; 54 | Serial.println(pulse); 55 | pwm.setPWM(n, 0, pulse); 56 | } 57 | 58 | void loop() { 59 | // Drive each servo one at a time 60 | Serial.println(servonum); 61 | for (uint16_t pulselen = SERVOMIN; pulselen < SERVOMAX; pulselen++) { 62 | pwm.setPWM(servonum, 0, pulselen); 63 | delay(2); 64 | } 65 | 66 | delay(1000); 67 | for (uint16_t pulselen = SERVOMAX; pulselen > SERVOMIN; pulselen--) { 68 | pwm.setPWM(servonum, 0, pulselen); 69 | delay(2); 70 | } 71 | 72 | delay(1000); 73 | 74 | servonum ++; 75 | if (servonum > 1) servonum = 0; 76 | } 77 | -------------------------------------------------------------------------------- /examples/Peripheral/eddystone_url/eddystone_url.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | #include 15 | 16 | #define URL "https://www.adafruit.com" 17 | 18 | // Create an EddyStone URL with rssi at 0m = -40 and URL as defined above 19 | EddyStoneUrl eddyUrl(-40, URL); 20 | 21 | void setup() 22 | { 23 | Serial.begin(115200); 24 | while ( !Serial ) delay(10); // for nrf52840 with native usb 25 | 26 | Serial.println("Bluefruit52 EddyStone URL Example"); 27 | Serial.println("---------------------------------\n"); 28 | 29 | Bluefruit.begin(); 30 | Bluefruit.setTxPower(4); // Check bluefruit.h for supported values 31 | Bluefruit.setName("Bluefruit52"); 32 | 33 | // Setup the advertising packet 34 | startAdv(); 35 | 36 | Serial.println("Broadcasting EddyStone URL, open Google Physical Web app to test"); 37 | } 38 | 39 | void startAdv(void) 40 | { 41 | // Advertising packet 42 | // Set the beacon payload using the BLEBeacon class populated 43 | // earlier in this example 44 | Bluefruit.Advertising.setBeacon(eddyUrl); 45 | 46 | // Secondary Scan Response packet (optional) 47 | // Since there is no room for 'Name' in Advertising packet 48 | Bluefruit.ScanResponse.addName(); 49 | 50 | /* Start Advertising 51 | * - Enable auto advertising if disconnected 52 | * - Timeout for fast mode is 30 seconds 53 | * - Start(timeout) with timeout = 0 will advertise forever (until connected) 54 | * 55 | * Apple Beacon specs 56 | * - Type: Non connectable, undirected 57 | * - Fixed interval: 100 ms -> fast = slow = 100 ms 58 | */ 59 | //Bluefruit.Advertising.setType(BLE_GAP_ADV_TYPE_ADV_NONCONN_IND); 60 | Bluefruit.Advertising.restartOnDisconnect(true); 61 | Bluefruit.Advertising.setInterval(160, 160); // in unit of 0.625 ms 62 | Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode 63 | Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds 64 | } 65 | 66 | void loop() 67 | { 68 | // Toggle both LEDs every second 69 | digitalToggle(LED_RED); 70 | delay(1000); 71 | } 72 | 73 | -------------------------------------------------------------------------------- /examples/BMI160/Gyro/Gyro.ino: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2019 CallMeCode Corporation. All rights reserved. 3 | * See the bottom of this file for the license terms. 4 | */ 5 | 6 | /* 7 | This sketch example demonstrates how the BMI160 on the 8 | Intel(R) Curie(TM) module can be used to read gyroscope data 9 | */ 10 | 11 | #include 12 | 13 | const int irq_pin = 30; 14 | const int i2c_addr = 0x69; 15 | 16 | 17 | void setup() { 18 | Serial.begin(115200); // initialize Serial communication 19 | Wire.begin(); 20 | 21 | // initialize device 22 | Serial.println("Initializing IMU device..."); 23 | // BMI160.begin(BMI160GenClass::SPI_MODE, /* SS pin# = */10); 24 | BMI160.begin(BMI160GenClass::I2C_MODE, i2c_addr, irq_pin); 25 | uint8_t dev_id = BMI160.getDeviceID(); 26 | Serial.print("DEVICE ID: "); 27 | Serial.println(dev_id, HEX); 28 | 29 | // Set the accelerometer range to 2000 degrees/second 30 | BMI160.setGyroRange(2000); 31 | Serial.println("Initializing IMU device...done."); 32 | } 33 | 34 | void loop() { 35 | int gxRaw, gyRaw, gzRaw; // raw gyro values 36 | float gx, gy, gz; 37 | 38 | // read raw gyro measurements from device 39 | BMI160.readGyro(gxRaw, gyRaw, gzRaw); 40 | 41 | // convert the raw gyro data to degrees/second 42 | gx = convertRawGyro(gxRaw); 43 | gy = convertRawGyro(gyRaw); 44 | gz = convertRawGyro(gzRaw); 45 | 46 | // display tab-separated gyro x/y/z values 47 | Serial.print("Gyro:\t"); 48 | Serial.print(gx); 49 | Serial.print("\t"); 50 | Serial.print(gy); 51 | Serial.print("\t"); 52 | Serial.print(gz); 53 | Serial.println(); 54 | 55 | delay(100); 56 | } 57 | 58 | float convertRawGyro(int gRaw) { 59 | // since we are using 2000 degrees/seconds range 60 | // -2000 maps to a raw value of -32768 61 | // +2000 maps to a raw value of 32767 62 | 63 | float g = (gRaw * 2000.0) / 32767.0; 64 | 65 | return g; 66 | } 67 | 68 | /* 69 | Copyright (c) 2016 Intel Corporation. All rights reserved. 70 | This library is free software; you can redistribute it and/or 71 | modify it under the terms of the GNU Lesser General Public 72 | License as published by the Free Software Foundation; either 73 | version 2.1 of the License, or (at your option) any later version. 74 | This library is distributed in the hope that it will be useful, 75 | but WITHOUT ANY WARRANTY; without even the implied warranty of 76 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 77 | Lesser General Public License for more details. 78 | You should have received a copy of the GNU Lesser General Public 79 | License along with this library; if not, write to the Free Software 80 | Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA 81 | */ 82 | -------------------------------------------------------------------------------- /examples/BMI160/FreeFallDetect/FreeFallDetect.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Copyright (c) 2019 CallMeCode Corporation. All rights reserved. 3 | See the bottom of this file for license terms. 4 | */ 5 | 6 | /* 7 | This sketch example demonstrates how the BMI160 accelerometer on the 8 | Intel(R) Curie(TM) module can be used to detect free fall events 9 | */ 10 | 11 | #include 12 | 13 | const int irq_pin = 30; 14 | const int i2c_addr = 0x69; 15 | 16 | bool blinkState = false; // state of the LED 17 | unsigned long loopTime = 0; // get the time since program started 18 | unsigned long interruptsTime = 0; // get the time when free fall event is detected 19 | 20 | 21 | void setup() { 22 | Serial.begin(115200); // initialize Serial communication 23 | Wire.begin(); 24 | pinMode(19, OUTPUT); 25 | // initialize device 26 | Serial.println("Initializing IMU device..."); 27 | // BMI160.begin(BMI160GenClass::SPI_MODE, /* SS pin# = */10); 28 | BMI160.begin(BMI160GenClass::I2C_MODE, i2c_addr, irq_pin); 29 | uint8_t dev_id = BMI160.getDeviceID(); 30 | Serial.print("DEVICE ID: "); 31 | Serial.println(dev_id, HEX); 32 | BMI160.attachInterrupt(eventCallback); 33 | 34 | /* Enable Free Fall Detection */ 35 | BMI160.setDetectionThreshold(CURIE_IMU_FREEFALL, 1000); // 1g=1000mg 36 | BMI160.setDetectionDuration(CURIE_IMU_FREEFALL, 50); // 50ms 37 | BMI160.setIntFreefallEnabled(true); 38 | 39 | Serial.println("IMU initialisation complete, waiting for events..."); 40 | } 41 | 42 | void loop() { 43 | // if free fall event is detected in 1000ms, LED will be turned up 44 | loopTime = millis(); 45 | if(abs(loopTime -interruptsTime) < 1000 ) 46 | blinkState = true; 47 | else 48 | blinkState = false; 49 | digitalWrite(19, blinkState); 50 | } 51 | 52 | static void eventCallback(){ 53 | if (BMI160.getInterruptStatus(CURIE_IMU_FREEFALL)) { 54 | Serial.println("free fall detected! "); 55 | interruptsTime = millis(); 56 | } 57 | } 58 | 59 | /* 60 | Copyright (c) 2016 Intel Corporation. All rights reserved. 61 | 62 | This library is free software; you can redistribute it and/or 63 | modify it under the terms of the GNU Lesser General Public 64 | License as published by the Free Software Foundation; either 65 | version 2.1 of the License, or (at your option) any later version. 66 | 67 | This library is distributed in the hope that it will be useful, 68 | but WITHOUT ANY WARRANTY; without even the implied warranty of 69 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 70 | Lesser General Public License for more details. 71 | 72 | You should have received a copy of the GNU Lesser General Public 73 | License along with this library; if not, write to the Free Software 74 | Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA 75 | 76 | */ 77 | -------------------------------------------------------------------------------- /examples/Peripheral/beacon/beacon.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | #include 15 | #include 16 | // Beacon使用广告中的制造商特定数据字段包 17 | // 这意味着您必须提供有效的制造商ID。 18 | // 更新下面的字段为适当的值。有关有效ID的列表,请参阅: 19 | // https://www.bluetooth.com/specifications/assigned-numbers/company-identifiers 20 | 21 | // 0x004C is Apple (示例) 22 | #define MANUFACTURER_ID 0x004C 23 | 24 | // AirLocate UUID: E2C56DB5-DFFB-48D2-B060-D0F5A71096E0 25 | uint8_t beaconUuid[16] = 26 | { 27 | 0xE2, 0xC5, 0x6D, 0xB5, 0xDF, 0xFB, 0x48, 0xD2, 28 | 0xB0, 0x60, 0xD0, 0xF5, 0xA7, 0x10, 0x96, 0xE0, 29 | }; 30 | 31 | // 有效的Beacon数据包包含以下信息: 32 | // UUID, Major, Minor, RSSI @ 1M 33 | BLEBeacon beacon(beaconUuid, 0x0000, 0x0000, -54); 34 | 35 | void setup() 36 | { 37 | Serial.begin(115200); 38 | 39 | Serial.println("Bluefruit52 Beacon Example"); 40 | Serial.println("--------------------------\n"); 41 | 42 | Bluefruit.begin(); 43 | 44 | //关闭蓝色LED以实现最低功耗 45 | Bluefruit.autoConnLed(false); 46 | 47 | //设置最大功率,可选值有:-40, -30, -20, -16, -12, -8, -4, 0, 4 48 | Bluefruit.setTxPower(0); 49 | Bluefruit.setName("Bluefruit52"); 50 | 51 | // 制造商特定数据需要制造商ID 52 | beacon.setManufacturer(MANUFACTURER_ID); 53 | 54 | // 设置广播包 55 | startAdv(); 56 | 57 | Serial.println("Broadcasting beacon, open your beacon app to test"); 58 | 59 | // 暂停循环以节省功耗,因为我们没有任何执行代码 60 | suspendLoop(); 61 | } 62 | 63 | void startAdv(void) 64 | { 65 | // 广告包 66 | // 使用填充的BLEBeacon类设置信标有效负载 67 | // 在此示例的前面 68 | Bluefruit.Advertising.setBeacon(beacon); 69 | 70 | // 二次扫描响应包(可选) 71 | // 由于广告包中没有“名称”的空间 72 | Bluefruit.ScanResponse.addName(); 73 | 74 | /* 开始做广告 75 | * - 如果断开连接则启用自动广告 76 | * - 快速模式超时为30秒 77 | * - 超时= 0的启动(超时)将永久通告(直到连接) 78 | * 79 | * Apple Beacon规格 80 | * - 类型:不可连接,无向 81 | * - 固定间隔: 100 ms -> fast = slow = 100 ms 82 | */ 83 | //Bluefruit.Advertising.setType(BLE_GAP_ADV_TYPE_ADV_NONCONN_IND); 84 | Bluefruit.Advertising.restartOnDisconnect(true); 85 | Bluefruit.Advertising.setInterval(160, 160); //以0.625毫秒为单位 86 | Bluefruit.Advertising.setFastTimeout(30); // 快速模式下的秒数 87 | Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds 88 | } 89 | 90 | void loop() 91 | { 92 | // loop is already suspended, CPU will not run loop() at all 93 | } 94 | -------------------------------------------------------------------------------- /examples/Hardware/hwpwm/hwpwm.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our Feather Bluefruit modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | 15 | /* 16 | * This sketch use different Hardware PWMs for LED Blue and Red 17 | * running with different frequency 18 | * - PWM0 : clock/1 ~ 16Mhz 19 | * - PWM1 : clock/16 ~ 1Mhz 20 | * 21 | * While LED RED looks solid, LED BLUE will blink while fading 22 | * (due to its lower freq). Furthermore LED RED is inverted 23 | * compared to LED BLUE (PWM2) --> They fade in opposite direction. 24 | */ 25 | 26 | #include 27 | 28 | /**************************************************************************/ 29 | /*! 30 | @brief The setup function runs once when reset the board 31 | */ 32 | /**************************************************************************/ 33 | void setup() 34 | { 35 | // Add LED RED to PWM0 36 | HwPWM0.addPin( LED_RED ); 37 | 38 | // Add LED BLUE to PWM1 39 | HwPWM1.addPin( LED_BLUE ); 40 | 41 | // Enable PWM modules with 15-bit resolutions(max) but different clock div 42 | HwPWM0.begin(); 43 | HwPWM0.setResolution(15); 44 | HwPWM0.setClockDiv(PWM_PRESCALER_PRESCALER_DIV_1); // freq = 16Mhz 45 | 46 | HwPWM1.begin(); 47 | HwPWM1.setResolution(15); 48 | HwPWM1.setClockDiv(PWM_PRESCALER_PRESCALER_DIV_16); // freq = 1Mhz 49 | } 50 | 51 | /**************************************************************************/ 52 | /*! 53 | @brief The loop function runs over and over again forever 54 | */ 55 | /**************************************************************************/ 56 | void loop() 57 | { 58 | const int maxValue = bit(15) - 1; 59 | 60 | // fade in from min to max 61 | for (int fadeValue = 0 ; fadeValue <= maxValue; fadeValue += 1024) 62 | { 63 | // Write same value but inverted for Led Blue 64 | HwPWM0.writePin(LED_RED, fadeValue, false); 65 | HwPWM1.writePin(LED_BLUE, fadeValue, true); 66 | 67 | // wait for 30 milliseconds to see the dimming effect 68 | delay(30); 69 | } 70 | 71 | // fade out from max to min 72 | for (int fadeValue = maxValue ; fadeValue >= 0; fadeValue -= 1024) 73 | { 74 | // Write same value but inverted for Led Blue 75 | HwPWM0.writePin(LED_RED, fadeValue, false); 76 | HwPWM1.writePin(LED_BLUE, fadeValue, true); 77 | 78 | // wait for 30 milliseconds to see the dimming effect 79 | delay(30); 80 | } 81 | } 82 | -------------------------------------------------------------------------------- /examples/Hardware/adc_vbat/adc_vbat.ino: -------------------------------------------------------------------------------- 1 | /* 2 | ADC get battery value 3 | get adc value from pin and print value. 4 | 5 | This example code is in the public domain. 6 | 7 | 2019/01/03 8 | by Afantor 9 | */ 10 | #define VBAT_PIN (A7) 11 | #define VBAT_MV_PER_LSB (0.73242188F) // 3.0V ADC range and 12-bit ADC resolution = 3000mV/4096 12 | #define VBAT_DIVIDER (0.71275837F) // 2M + 0.806M voltage divider on VBAT = (2M / (0.806M + 2M)) 13 | #define VBAT_DIVIDER_COMP (1.403F) // Compensation factor for the VBAT divider 14 | 15 | int readVBAT(void) { 16 | int raw; 17 | 18 | // Set the analog reference to 3.0V (default = 3.6V) 19 | analogReference(AR_INTERNAL_3_0); 20 | 21 | // Set the resolution to 12-bit (0..4095) 22 | analogReadResolution(12); // Can be 8, 10, 12 or 14 23 | 24 | // Let the ADC settle 25 | delay(1); 26 | 27 | // Get the raw 12-bit, 0..3000mV ADC value 28 | raw = analogRead(VBAT_PIN); 29 | 30 | // Set the ADC back to the default settings 31 | analogReference(AR_DEFAULT); 32 | analogReadResolution(10); 33 | 34 | return raw; 35 | } 36 | 37 | uint8_t mvToPercent(float mvolts) { 38 | uint8_t battery_level; 39 | if (mvolts >= 3000) 40 | { 41 | battery_level = 100; 42 | } 43 | else if (mvolts > 2900) 44 | { 45 | battery_level = 100 - ((3000 - mvolts) * 58) / 100; 46 | } 47 | else if (mvolts > 2740) 48 | { 49 | battery_level = 42 - ((2900 - mvolts) * 24) / 160; 50 | } 51 | else if (mvolts > 2440) 52 | { 53 | battery_level = 18 - ((2740 - mvolts) * 12) / 300; 54 | } 55 | else if (mvolts > 2100) 56 | { 57 | battery_level = 6 - ((2440 - mvolts) * 6) / 340; 58 | } 59 | else 60 | { 61 | battery_level = 0; 62 | } 63 | return battery_level; 64 | } 65 | 66 | void setup() { 67 | Serial.begin(115200); 68 | 69 | // Get a single ADC sample and throw it away 70 | readVBAT(); 71 | } 72 | 73 | void loop() { 74 | // Get a raw ADC reading 75 | int vbat_raw = readVBAT(); 76 | 77 | // Convert from raw mv to percentage (based on LIPO chemistry) 78 | uint8_t vbat_per = mvToPercent(vbat_raw * VBAT_MV_PER_LSB); 79 | 80 | // Convert the raw value to compensated mv, taking the resistor- 81 | // divider into account (providing the actual LIPO voltage) 82 | // ADC range is 0..3000mV and resolution is 12-bit (0..4095), 83 | // VBAT voltage divider is 2M + 0.806M, which needs to be added back 84 | float vbat_mv = (float)vbat_raw * VBAT_MV_PER_LSB * VBAT_DIVIDER_COMP; 85 | 86 | // Display the results 87 | Serial.print("ADC = "); 88 | Serial.print(vbat_raw * VBAT_MV_PER_LSB); 89 | Serial.print(" mV ("); 90 | Serial.print(vbat_raw); 91 | Serial.print(") "); 92 | Serial.print("LIPO = "); 93 | Serial.print(vbat_mv); 94 | Serial.print(" mV ("); 95 | Serial.print(vbat_per); 96 | Serial.println("%)"); 97 | 98 | delay(1000); 99 | } 100 | -------------------------------------------------------------------------------- /examples/BMI160/TapDetect/TapDetect.ino: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2019 CallMeCode Corporation. All rights reserved. 3 | * See the bottom of this file for the license terms. 4 | */ 5 | 6 | /* 7 | This sketch example demonstrates how the BMI160 accelerometer on the 8 | Intel(R) Curie(TM) module can be used to detect tap events 9 | */ 10 | 11 | #include 12 | 13 | const int irq_pin = 30; 14 | const int i2c_addr = 0x69; 15 | 16 | void setup() { 17 | Serial.begin(115200); // initialize Serial communication 18 | Wire.begin(); 19 | // initialize device 20 | Serial.println("Initializing IMU device..."); 21 | // BMI160.begin(BMI160GenClass::SPI_MODE, /* SS pin# = */10); 22 | BMI160.begin(BMI160GenClass::I2C_MODE, i2c_addr, irq_pin); 23 | uint8_t dev_id = BMI160.getDeviceID(); 24 | Serial.print("DEVICE ID: "); 25 | Serial.println(dev_id, HEX); 26 | BMI160.attachInterrupt(eventCallback); 27 | 28 | // Increase Accelerometer range to allow detection of stronger taps (< 4g) 29 | BMI160.setAccelerometerRange(4); 30 | 31 | // Reduce threshold to allow detection of weaker taps (>= 750mg) 32 | BMI160.setDetectionThreshold(CURIE_IMU_TAP, 750); // (750mg) 33 | 34 | // Enable Double-Tap detection 35 | BMI160.setIntTapEnabled(true); 36 | 37 | Serial.println("IMU initialization complete, waiting for events..."); 38 | } 39 | 40 | void loop() { 41 | // nothing happens in the loop because all the action happens 42 | // in the callback function. 43 | } 44 | 45 | static void eventCallback() 46 | { 47 | if (BMI160.getInterruptStatus(CURIE_IMU_TAP)) { 48 | if (BMI160.tapDetected(X_AXIS, NEGATIVE)) 49 | Serial.println("Tap detected on negative X-axis"); 50 | if (BMI160.tapDetected(X_AXIS, POSITIVE)) 51 | Serial.println("Tap detected on positive X-axis"); 52 | if (BMI160.tapDetected(Y_AXIS, NEGATIVE)) 53 | Serial.println("Tap detected on negative Y-axis"); 54 | if (BMI160.tapDetected(Y_AXIS, POSITIVE)) 55 | Serial.println("Tap detected on positive Y-axis"); 56 | if (BMI160.tapDetected(Z_AXIS, NEGATIVE)) 57 | Serial.println("Tap detected on negative Z-axis"); 58 | if (BMI160.tapDetected(Z_AXIS, POSITIVE)) 59 | Serial.println("Tap detected on positive Z-axis"); 60 | } 61 | } 62 | 63 | /* 64 | Copyright (c) 2016 Intel Corporation. All rights reserved. 65 | 66 | This library is free software; you can redistribute it and/or 67 | modify it under the terms of the GNU Lesser General Public 68 | License as published by the Free Software Foundation; either 69 | version 2.1 of the License, or (at your option) any later version. 70 | 71 | This library is distributed in the hope that it will be useful, 72 | but WITHOUT ANY WARRANTY; without even the implied warranty of 73 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 74 | Lesser General Public License for more details. 75 | 76 | You should have received a copy of the GNU Lesser General Public 77 | License along with this library; if not, write to the Free Software 78 | Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA 79 | */ 80 | -------------------------------------------------------------------------------- /docs/getting_started_setting.md: -------------------------------------------------------------------------------- 1 | # nRF52832 Bluefruit Arduino — 快速上手 2 | 3 | 4 | ## 一、安装 USB 驱动 5 | 6 | 点击以下链接,下载 nRF52832 Bluefruit52的 USB 转串口驱动CP2102 7 | 8 | https://www.silabs.com/products/development-tools/software/usb-to-uart-bridge-vcp-drivers 9 | 10 | 下载完之后,解压,根据系统位数,双击对应可执行文件 11 | 12 | (Windows 32位,执行 CP210xVCPInstaller_x68.exe;Windows 64位,执行 CP210xVCPInstaller_x64.exe;) 13 | 14 | *判断驱动安装是否成功:* 15 | 如果安装成功,在插入 Bluefruit52 主控之后,设备管理器如下图所示出现,Silicon Labs 的 CP21x 系列串口端口号 16 | (我的电脑当前串口号是 COM3) 17 | 18 | ![image](arduino-ide/win-screenshots_cn/my_com.png) 19 | 20 | 21 | ## 二、开发环境 22 | ## **Windows** 23 | ### 1、安装 Arduino IDE 24 | 25 | *下载地址* 26 | https://www.arduino.cc/en/Main/Software 27 | 28 | ![image](arduino-ide/win-screenshots_cn/arduino_cc_package.png) 29 | 30 | 31 | 如下图所示修改 Arduino 路径为 D:\Program Files 32 | 33 | ![image](arduino-ide/win-screenshots_cn/select_arduino_install_path.png) 34 | 35 | 36 | 此时,Arduino 的安装路径为 D:\Program Files\Arduino 37 | 38 | ![image](arduino-ide/win-screenshots_cn/arduino_path.png) 39 | 40 | 41 | ### 2、下载 Afantor nRF52832 支持包 42 | 43 | (我的 Arduino 当前路径是 D:\Program Files\arduino) 44 | 45 | 进入 Arduino 安装路径的 libraries 文件夹,按住 Shift 键的同时,右键选择“在此处打开命令窗口”,打开CMD命令窗口,使用“git clone ” 46 | 47 | 命令远程下载Afantor nRF52832库包。 48 | 49 | ![image](images/shift_cmd.jpg) 50 | ![image](images/git_cmd.jpg) 51 | 52 | 53 | ### 3、下载安装 nRF52832 编译链工具 54 | 55 | 打开Arduino IDE,进入“文件”菜单下的“首选项”; 56 | 57 | 在“附加开发板管理器网址”中增加 https://www.adafruit.com/package_adafruit_index.json 58 | 59 | 然后关闭IDE,重新打开Arduino IDE; 60 | 61 | 进入“工具”菜单栏,打开“开发板管理器”,等待联网更新数据,完成后在搜索框中搜索:nrf52 62 | 63 | 找到“Adafruit nRF52”,点击安装即可,等待时间会很久,请不要关闭Arduino。 64 | 65 | 安装完成后,打开“工具”菜单下,选择“开发板”,找到“Adafruit nRF52832 Boards” 下的 “Adafruit Bluefruit nRF52832 Feather”,环境即搭建完成。 66 | 67 | 68 | ### 4、打开Arduino IDE 验证Adafruit_nRF52_Arduino和Afantor_Bluefruit52_Arduino 的库 69 | 70 | 打开Arduino IDE,选择“Adafruit Bluefruit nRF52832 Feather”开发板,进入“文件”菜单下的“示例”,找到“Adafruit Bluefruit nRF52 Libraries” 和 “Afantor Bluefruit52” 里面即是例程库。 71 | 72 | ## 三、示例 73 | 74 | USB 线连接 Bluefruit52 主控,选择串口和一个示例程序,compile and upload 75 | 76 | ### 1、打开一个示例程序,如打开 blinky.ino 77 | 78 | 79 | 80 | 确认连接板子名称、和当前串口号分别:COM3(当前电脑串口号) 81 | 82 | 83 | 84 | 编译运行成功之后,串口监视窗口显示如下 85 | 86 | 87 | 88 | ### 2、新建一个 nRF52832 程序 89 | 90 | 打开 Arduino IDE 之后,新建 .ino 文件,并保存为 my_test.ino 91 | 92 | 将如下代码拷贝进文件中。 93 | 94 | ```cpp 95 | #include 96 | #include 97 | // the setup routine runs once when Bluefruit52 starts up 98 | void setup(){ 99 | 100 | // Initialize the Bluefruit52 object 101 | BF52.begin(true, true, false); 102 | 103 | // LCD display 104 | BF52.Lcd.fillScreen(BLACK); 105 | BF52.Lcd.setTextColor(YELLOW); 106 | BF52.Lcd.setTextSize(2); 107 | BF52.Lcd.println("Hello World!"); 108 | BF52.Lcd.println("Bluefruit52 is running"); 109 | BF52.Lcd.println(" successfully!"); 110 | } 111 | 112 | // the loop routine runs over and over again forever 113 | void loop() { 114 | 115 | } 116 | ``` 117 | 118 | 点击编译运行下载,此时 Bluefruit52 显示器显示 "Hello World!" "Bluefruit52 is running successfully!" 119 | 120 | 121 | -------------------------------------------------------------------------------- /examples/BMI160/ShockDetect/ShockDetect.ino: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2019 CallMeCode Corporation. All rights reserved. 3 | * See the bottom of this file for the license terms. 4 | */ 5 | 6 | /* 7 | This sketch example demonstrates how the BMI160 accelerometer on the 8 | Intel(R) Curie(TM) module can be used to detect shocks or sudden movements 9 | */ 10 | 11 | #include 12 | 13 | const int irq_pin = 30; 14 | const int i2c_addr = 0x69; 15 | 16 | bool blinkState = false; // state of the LED 17 | 18 | void setup() { 19 | Serial.begin(115200); // initialize Serial communication 20 | Wire.begin(); 21 | pinMode(19, OUTPUT); 22 | // initialize device 23 | Serial.println("Initializing IMU device..."); 24 | // BMI160.begin(BMI160GenClass::SPI_MODE, /* SS pin# = */10); 25 | BMI160.begin(BMI160GenClass::I2C_MODE, i2c_addr, irq_pin); 26 | uint8_t dev_id = BMI160.getDeviceID(); 27 | Serial.print("DEVICE ID: "); 28 | Serial.println(dev_id, HEX); 29 | BMI160.attachInterrupt(eventCallback); 30 | 31 | /* Enable Shock Detection */ 32 | BMI160.setDetectionThreshold(CURIE_IMU_SHOCK, 1500); // 1.5g = 1500 mg 33 | BMI160.setDetectionDuration(CURIE_IMU_SHOCK, 50); // 50ms 34 | BMI160.setIntShockEnabled(true); 35 | 36 | Serial.println("IMU initialisation complete, waiting for events..."); 37 | } 38 | 39 | void loop() { 40 | // blink the LED in the main loop: 41 | digitalWrite(19, blinkState); 42 | blinkState = !blinkState; 43 | delay(1000); 44 | } 45 | 46 | 47 | static void eventCallback(void) 48 | { 49 | if (BMI160.getInterruptStatus(CURIE_IMU_SHOCK)) { 50 | if (BMI160.shockDetected(X_AXIS, POSITIVE)) 51 | Serial.println("Negative shock detected on X-axis"); 52 | if (BMI160.shockDetected(X_AXIS, NEGATIVE)) 53 | Serial.println("Positive shock detected on X-axis"); 54 | if (BMI160.shockDetected(Y_AXIS, POSITIVE)) 55 | Serial.println("Negative shock detected on Y-axis"); 56 | if (BMI160.shockDetected(Y_AXIS, NEGATIVE)) 57 | Serial.println("Positive shock detected on Y-axis"); 58 | if (BMI160.shockDetected(Z_AXIS, POSITIVE)) 59 | Serial.println("Negative shock detected on Z-axis"); 60 | if (BMI160.shockDetected(Z_AXIS, NEGATIVE)) 61 | Serial.println("Positive shock detected on Z-axis"); 62 | } 63 | } 64 | 65 | /* 66 | Copyright (c) 2016 Intel Corporation. All rights reserved. 67 | 68 | This library is free software; you can redistribute it and/or 69 | modify it under the terms of the GNU Lesser General Public 70 | License as published by the Free Software Foundation; either 71 | version 2.1 of the License, or (at your option) any later version. 72 | 73 | This library is distributed in the hope that it will be useful, 74 | but WITHOUT ANY WARRANTY; without even the implied warranty of 75 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 76 | Lesser General Public License for more details. 77 | 78 | You should have received a copy of the GNU Lesser General Public 79 | License along with this library; if not, write to the Free Software 80 | Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA 81 | 82 | */ 83 | -------------------------------------------------------------------------------- /examples/Peripheral/adv_advanced/adv_advanced.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | 15 | /* This sketch demonstrates the Bluefruit.Advertising API(). When powered up, 16 | * the Bluefruit module will start advertising for ADV_TIMEOUT seconds (by 17 | * default 30 seconds in fast mode, the remaining time slow mode) and then 18 | * stop advertising completely. The module will start advertising again if 19 | * PIN_ADV is grounded. 20 | */ 21 | #include 22 | 23 | #define PIN_ADV A0 24 | #define ADV_TIMEOUT 60 // seconds 25 | 26 | void setup() 27 | { 28 | // configure PIN_ADV as input with a pullup (pin is active low) 29 | pinMode(PIN_ADV, INPUT_PULLUP); 30 | 31 | Serial.begin(115200); 32 | 33 | Serial.println("Bluefruit52 Advanced Advertising Example"); 34 | Serial.println("----------------------------------------\n"); 35 | 36 | Bluefruit.begin(); 37 | Bluefruit.setTxPower(4); // Check bluefruit.h for supported values 38 | Bluefruit.setName("Bluefruit52"); 39 | 40 | // Set up and start advertising 41 | startAdv(); 42 | 43 | Serial.println("Advertising is started"); 44 | } 45 | 46 | void startAdv(void) 47 | { 48 | // Advertising packet 49 | Bluefruit.Advertising.addFlags(BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE); 50 | Bluefruit.Advertising.addTxPower(); 51 | Bluefruit.Advertising.addName(); 52 | 53 | /* Start Advertising 54 | * - Enable auto advertising if disconnected 55 | * - Interval: fast mode = 20 ms, slow mode = 152.5 ms 56 | * - Timeout for fast mode is 30 seconds 57 | * - Start(timeout) with timeout = 0 will advertise forever (until connected) 58 | * 59 | * For recommended advertising interval 60 | * https://developer.apple.com/library/content/qa/qa1931/_index.html 61 | */ 62 | Bluefruit.Advertising.setStopCallback(adv_stop_callback); 63 | Bluefruit.Advertising.restartOnDisconnect(true); 64 | Bluefruit.Advertising.setInterval(32, 244); // in units of 0.625 ms 65 | Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode 66 | Bluefruit.Advertising.start(ADV_TIMEOUT); // Stop advertising entirely after ADV_TIMEOUT seconds 67 | } 68 | 69 | void loop() 70 | { 71 | // Only check pin when advertising has already stopped 72 | if ( !Bluefruit.Advertising.isRunning() ) 73 | { 74 | // Check if Pin is grounded 75 | if ( digitalRead(PIN_ADV) == 0 ) 76 | { 77 | Bluefruit.Advertising.start(ADV_TIMEOUT); 78 | Serial.println("Advertising is started"); 79 | } 80 | } 81 | } 82 | 83 | /** 84 | * Callback invoked when advertising is stopped by timeout 85 | */ 86 | void adv_stop_callback(void) 87 | { 88 | Serial.println("Advertising time passed, advertising will now stop."); 89 | } 90 | -------------------------------------------------------------------------------- /examples/Peripheral/custom_htm/IEEE11073float.h: -------------------------------------------------------------------------------- 1 | /**************************************************************************/ 2 | /*! 3 | @file IEEE11073float.h 4 | */ 5 | /**************************************************************************/ 6 | 7 | /** 8 | * \file bytelib.c 9 | * \brief Byte manipulation module implementation. 10 | * Copyright (C) 2010 Signove Tecnologia Corporation. 11 | * All rights reserved. 12 | * Contact: Signove Tecnologia Corporation (contact@signove.com) 13 | * 14 | * $LICENSE_TEXT:BEGIN$ 15 | * This library is free software; you can redistribute it and/or 16 | * modify it under the terms of the GNU Lesser General Public 17 | * License as published by the Free Software Foundation and appearing 18 | * in the file LICENSE included in the packaging of this file; either 19 | * version 2.1 of the License, or (at your option) any later version. 20 | * 21 | * This library is distributed in the hope that it will be useful, 22 | * but WITHOUT ANY WARRANTY; without even the implied warranty of 23 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 24 | * Lesser General Public License for more details. 25 | * 26 | * You should have received a copy of the GNU Lesser General Public 27 | * License along with this library; if not, write to the Free Software 28 | * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA 29 | * $LICENSE_TEXT:END$ 30 | * 31 | * \author Walter Guerra, Mateus Lima 32 | * \date Jun 14, 2010 33 | */ 34 | 35 | #ifndef _IEEE11073FLOAT_H_ 36 | #define _IEEE11073FLOAT_H_ 37 | 38 | #include 39 | 40 | typedef enum { 41 | MDER_POSITIVE_INFINITY = 0x007FFFFE, 42 | MDER_NaN = 0x007FFFFF, 43 | MDER_NRes = 0x00800000, 44 | MDER_RESERVED_VALUE = 0x00800001, 45 | MDER_NEGATIVE_INFINITY = 0x00800002 46 | } ReservedFloatValues; 47 | static const int32_t FIRST_RESERVED_VALUE = MDER_POSITIVE_INFINITY; 48 | 49 | // (2 ** 23 - 3) 50 | #define MDER_FLOAT_MANTISSA_MAX 0x007FFFFD 51 | // 2 ** 7 - 1 52 | #define MDER_FLOAT_EXPONENT_MAX 127 53 | #define MDER_FLOAT_EXPONENT_MIN -128 54 | // (2 ** 23 - 3) * 10 ** 127 55 | #define MDER_FLOAT_MAX 8.388604999999999e+133 56 | // -(2 ** 23 - 3) * 10 ** 127 57 | #define MDER_FLOAT_MIN (-MDER_FLOAT_MAX) 58 | // 10 ** -128 59 | #define MDER_FLOAT_EPSILON 1e-128 60 | // 10 ** upper(23 * log(2) / log(10)) 61 | // precision for a number 1.0000xxx 62 | #define MDER_FLOAT_PRECISION 10000000 63 | 64 | typedef enum { 65 | MDER_S_POSITIVE_INFINITY = 0x07FE, 66 | MDER_S_NaN = 0x07FF, 67 | MDER_S_NRes = 0x0800, 68 | MDER_S_RESERVED_VALUE = 0x0801, 69 | MDER_S_NEGATIVE_INFINITY = 0x0802 70 | } ReservedSFloatValues; 71 | static const uint32_t FIRST_S_RESERVED_VALUE = MDER_S_POSITIVE_INFINITY; 72 | 73 | // (2 ** 11 - 3) 74 | #define MDER_SFLOAT_MANTISSA_MAX 0x07FD 75 | // 2 ** 3 - 1 76 | #define MDER_SFLOAT_EXPONENT_MAX 7 77 | #define MDER_SFLOAT_EXPONENT_MIN -8 78 | // (2 ** 11 - 3) * 10 ** 7 79 | #define MDER_SFLOAT_MAX 20450000000.0 80 | // -(2 ** 11 - 3) * 10 ** 7 81 | #define MDER_SFLOAT_MIN (-MDER_SFLOAT_MAX) 82 | // 10 ** -8 83 | #define MDER_SFLOAT_EPSILON 1e-8 84 | // 10 ** upper(11 * log(2) / log(10)) 85 | #define MDER_SFLOAT_PRECISION 10000 86 | 87 | uint32_t float2IEEE11073(double data, uint8_t output[4]); 88 | 89 | #endif /* _IEEE11073FLOAT_H_ */ 90 | -------------------------------------------------------------------------------- /examples/Display/TFT_Print_Test/TFT_Print_Test.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Test the BF52.Lcd.print() viz embedded BF52.Lcd.write() function 3 | 4 | This sketch used font 2, 4, 7 5 | 6 | Make sure all the display driver and pin comnenctions are correct by 7 | editting the User_Setup.h file in the BF52.eSPI library folder. 8 | 9 | ######################################################################### 10 | ###### DON'T FORGET TO UPDATE THE User_Setup.h FILE IN THE LIBRARY ###### 11 | ######################################################################### 12 | */ 13 | 14 | #include 15 | 16 | 17 | void setup(void) { 18 | BF52.begin(true, true, false); 19 | } 20 | 21 | void loop() { 22 | 23 | // Fill screen with grey so we can see the effect of printing with and without 24 | // a background colour defined 25 | BF52.Lcd.fillScreen(BLACK); 26 | 27 | // Set "cursor" at top left corner of display (0,0) and select font 2 28 | // (cursor will move to next line automatically during printing with 'BF52.Lcd.println' 29 | // or stay on the line is there is room for the text with BF52.Lcd.print) 30 | BF52.Lcd.setCursor(0, 0); 31 | // Set the font colour to be white with a black background, set text size multiplier to 1 32 | BF52.Lcd.setTextColor(WHITE,BLACK); 33 | BF52.Lcd.setTextSize(1); 34 | // We can now plot text on screen using the "print" class 35 | BF52.Lcd.println("Hello World!"); 36 | 37 | // Set the font colour to be yellow with no background, set to font 7 38 | BF52.Lcd.setTextColor(YELLOW); 39 | BF52.Lcd.setTextSize(6); 40 | BF52.Lcd.println(1234.56); 41 | 42 | // Set the font colour to be red with black background, set to font 4 43 | BF52.Lcd.setTextColor(RED,BLACK); 44 | BF52.Lcd.setTextSize(3); 45 | BF52.Lcd.println(37359285L, HEX); // Should print 23A0EB5 46 | 47 | // Set the font colour to be green with black background, set to font 4 48 | BF52.Lcd.setTextColor(GREEN,BLACK); 49 | BF52.Lcd.setTextSize(3); 50 | BF52.Lcd.println("Groop"); 51 | BF52.Lcd.println("I implore thee,"); 52 | 53 | delay(5000); 54 | BF52.Lcd.fillScreen(BLACK); 55 | BF52.Lcd.setCursor(0, 0); 56 | // Change to font 2 57 | BF52.Lcd.setTextSize(1); 58 | BF52.Lcd.println("my foonting turlingdromes."); 59 | BF52.Lcd.println("And hooptiously drangle me"); 60 | BF52.Lcd.println("with crinkly bindlewurdles,"); 61 | // This next line is deliberately made too long for the display width to test 62 | // automatic text wrapping onto the next line 63 | BF52.Lcd.println("Or I will rend thee in the"); 64 | BF52.Lcd.println("gobberwarts with my blurglecruncheon,"); 65 | BF52.Lcd.println("see if I don't!"); 66 | 67 | delay(5000); 68 | BF52.Lcd.fillScreen(BLACK); 69 | BF52.Lcd.setCursor(0, 0); 70 | // Test some print formatting functions 71 | float fnumber = 123.45; 72 | // Set the font colour to be blue with no background, set to font 4 73 | BF52.Lcd.setTextColor(BLUE); 74 | BF52.Lcd.setTextSize(2); 75 | BF52.Lcd.print("Float = "); 76 | BF52.Lcd.println(fnumber); // Print floating point number 77 | BF52.Lcd.print("Binary = "); 78 | BF52.Lcd.println((int)fnumber, BIN); // Print as integer value in binary 79 | BF52.Lcd.print("Hexadecimal = "); 80 | BF52.Lcd.println((int)fnumber, HEX); // Print as integer number in Hexadecimal 81 | delay(5000); 82 | } 83 | 84 | 85 | 86 | -------------------------------------------------------------------------------- /examples/BMI160/TapDoubleDetect/TapDoubleDetect.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Copyright (c) 2019 CallMeCode Corporation. All rights reserved. 3 | See the bottom of this file for license terms. 4 | */ 5 | 6 | /* 7 | This sketch example demonstrates how the BMI160 accelerometer on the 8 | Intel(R) Curie(TM) module can be used to detect tap events 9 | */ 10 | 11 | #include 12 | 13 | const int irq_pin = 30; 14 | const int i2c_addr = 0x69; 15 | 16 | void setup() { 17 | Serial.begin(115200); // initialize Serial communication 18 | Wire.begin(); 19 | // initialize device 20 | Serial.println("Initializing IMU device..."); 21 | // BMI160.begin(BMI160GenClass::SPI_MODE, /* SS pin# = */10); 22 | BMI160.begin(BMI160GenClass::I2C_MODE, i2c_addr, irq_pin); 23 | uint8_t dev_id = BMI160.getDeviceID(); 24 | Serial.print("DEVICE ID: "); 25 | Serial.println(dev_id, HEX); 26 | BMI160.attachInterrupt(eventCallback); 27 | 28 | // Increase Accelerometer range to allow detection of stronger taps (< 4g) 29 | BMI160.setAccelerometerRange(4); 30 | 31 | // Reduce threshold to allow detection of weaker taps (>= 750mg) 32 | BMI160.setDetectionThreshold(CURIE_IMU_DOUBLE_TAP, 750); // (750mg) 33 | 34 | // Set the quite time window for 2 taps to be registered as a double-tap (Gap time between taps <= 1000 milliseconds) 35 | BMI160.setDetectionDuration(CURIE_IMU_DOUBLE_TAP, 1000); 36 | 37 | // Enable Double-Tap detection 38 | BMI160.setIntDoubleTapEnabled(true); 39 | 40 | Serial.println("IMU initialization complete, waiting for events..."); 41 | } 42 | 43 | void loop() { 44 | // nothing happens in the loop because all the action happens 45 | // in the callback function. 46 | } 47 | 48 | static void eventCallback() 49 | { 50 | if (BMI160.getInterruptStatus(CURIE_IMU_DOUBLE_TAP)) { 51 | if (BMI160.tapDetected(X_AXIS, NEGATIVE)) 52 | Serial.println("Double Tap detected on negative X-axis"); 53 | if (BMI160.tapDetected(X_AXIS, POSITIVE)) 54 | Serial.println("Double Tap detected on positive X-axis"); 55 | if (BMI160.tapDetected(Y_AXIS, NEGATIVE)) 56 | Serial.println("Double Tap detected on negative Y-axis"); 57 | if (BMI160.tapDetected(Y_AXIS, POSITIVE)) 58 | Serial.println("Double Tap detected on positive Y-axis"); 59 | if (BMI160.tapDetected(Z_AXIS, NEGATIVE)) 60 | Serial.println("Double Tap detected on negative Z-axis"); 61 | if (BMI160.tapDetected(Z_AXIS, POSITIVE)) 62 | Serial.println("Double Tap detected on positive Z-axis"); 63 | } 64 | } 65 | 66 | /* 67 | Copyright (c) 2016 Intel Corporation. All rights reserved. 68 | 69 | This library is free software; you can redistribute it and/or 70 | modify it under the terms of the GNU Lesser General Public 71 | License as published by the Free Software Foundation; either 72 | version 2.1 of the License, or (at your option) any later version. 73 | 74 | This library is distributed in the hope that it will be useful, 75 | but WITHOUT ANY WARRANTY; without even the implied warranty of 76 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 77 | Lesser General Public License for more details. 78 | 79 | You should have received a copy of the GNU Lesser General Public 80 | License along with this library; if not, write to the Free Software 81 | Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA 82 | 83 | */ 84 | -------------------------------------------------------------------------------- /examples/BMI160/accelGyro/accelGyro.ino: -------------------------------------------------------------------------------- 1 | /* 2 | * accelGyro.ino 3 | * 4 | * I2C addr: 5 | * 0x68: connect SDIO pin of the BMI160 to GND which means the default I2C address 6 | * 0x69: set I2C address by parameter 7 | * 8 | * Through the example, you can get the sensor data by using getSensorData: 9 | * get acell by paremeter onlyAccel; 10 | * get gyro by paremeter onlyGyro; 11 | * get both acell and gyro by paremeter bothAccelGyro. 12 | * 13 | * With the rotation of the sensor, data changes are visible. 14 | * 15 | * Copyright [Afantor](http://www.afantor.cc), 2019 16 | * Copyright MIT License 17 | * 18 | * version V1.0 19 | * date 2019-05-27 20 | */ 21 | 22 | #include 23 | 24 | const int irq_pin = 30; 25 | const int i2c_addr = 0x69; 26 | 27 | 28 | void setup() { 29 | Serial.begin(115200); // initialize Serial communication 30 | Wire.begin(); 31 | 32 | // initialize device 33 | Serial.println("Initializing IMU device..."); 34 | 35 | BMI160.begin(BMI160GenClass::I2C_MODE, i2c_addr, irq_pin); 36 | uint8_t dev_id = BMI160.getDeviceID(); 37 | Serial.print("DEVICE ID: "); 38 | Serial.println(dev_id, HEX); 39 | 40 | // Set the gyro range to 2000 degrees/second 41 | BMI160.setGyroRate(3200); 42 | BMI160.setGyroRange(2000); 43 | // Set the accelerometer range to 2g 44 | BMI160.setAccelerometerRate(1600); 45 | BMI160.setAccelerometerRange(2); 46 | Serial.println("Initializing BMI160 device...done."); 47 | } 48 | 49 | void loop() { 50 | int gxRaw, gyRaw, gzRaw; // raw gyro values 51 | float gx, gy, gz; 52 | 53 | int axRaw, ayRaw, azRaw; // raw accel values 54 | float ax, ay, az; 55 | 56 | // read raw gyro measurements from device 57 | BMI160.readGyro(gxRaw, gyRaw, gzRaw); 58 | 59 | // convert the raw gyro data to degrees/second 60 | gx = convertRawGyro(gxRaw); 61 | gy = convertRawGyro(gyRaw); 62 | gz = convertRawGyro(gzRaw); 63 | 64 | // display tab-separated gyro x/y/z values 65 | Serial.print("Gyro:\t"); 66 | Serial.print(gx); 67 | Serial.print("\t"); 68 | Serial.print(gy); 69 | Serial.print("\t"); 70 | Serial.print(gz); 71 | Serial.println(); 72 | 73 | // read raw accel measurements from device 74 | BMI160.readAccelerometer(axRaw, ayRaw, azRaw); 75 | 76 | // convert the raw accel data to g 77 | ax = convertRawAccel(axRaw); 78 | ay = convertRawAccel(ayRaw); 79 | az = convertRawAccel(azRaw); 80 | 81 | // display tab-separated accel x/y/z values 82 | Serial.print("Accel:\t"); 83 | Serial.print(ax); 84 | Serial.print("\t"); 85 | Serial.print(ay); 86 | Serial.print("\t"); 87 | Serial.print(az); 88 | Serial.println(); 89 | 90 | delay(100); 91 | } 92 | 93 | float convertRawGyro(int gRaw) { 94 | // since we are using 2000 degrees/seconds range 95 | // -2000 maps to a raw value of -32768 96 | // +2000 maps to a raw value of 32767 97 | 98 | float gyro = (gRaw * 2000.0) / (32767.0 * 57.29577); 99 | 100 | return gyro; 101 | } 102 | 103 | float convertRawAccel(int aRaw) { 104 | // since we are using 2g range 105 | // -2g to a raw value of -32768 106 | // +2g to a raw value of 32767 107 | 108 | float accel = ((aRaw * 2.0) / 32768.0) * 9.8; 109 | 110 | return accel; 111 | } 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | -------------------------------------------------------------------------------- /examples/BMI160/MotionDetect/MotionDetect.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Copyright (c) 2019 CallMeCode Corporation. All rights reserved. 3 | See the bottom of this file for license terms. 4 | */ 5 | 6 | /* 7 | This sketch example demonstrates how the BMI160 accelerometer on the 8 | Intel(R) Curie(TM) module can be used to detect motion events 9 | */ 10 | 11 | #include 12 | 13 | const int irq_pin = 30; 14 | const int i2c_addr = 0x69; 15 | 16 | bool blinkState = false; // state of the LED 17 | unsigned long loopTime = 0; // get the time since program started 18 | unsigned long interruptsTime = 0; // get the time when motion event is detected 19 | 20 | void setup() { 21 | Serial.begin(115200); // initialize Serial communication 22 | Wire.begin(); 23 | pinMode(19, OUTPUT); 24 | // initialize device 25 | Serial.println("Initializing IMU device..."); 26 | // BMI160.begin(BMI160GenClass::SPI_MODE, /* SS pin# = */10); 27 | BMI160.begin(BMI160GenClass::I2C_MODE, i2c_addr, irq_pin); 28 | uint8_t dev_id = BMI160.getDeviceID(); 29 | Serial.print("DEVICE ID: "); 30 | Serial.println(dev_id, HEX); 31 | BMI160.attachInterrupt(eventCallback); 32 | 33 | /* Enable Motion Detection */ 34 | BMI160.setDetectionThreshold(CURIE_IMU_MOTION, 20); // 20mg 35 | BMI160.setDetectionDuration(CURIE_IMU_MOTION, 10); // trigger times of consecutive slope data points 36 | BMI160.setIntMotionEnabled(true); 37 | 38 | Serial.println("IMU initialisation complete, waiting for events..."); 39 | } 40 | 41 | void loop() { 42 | // if motion is detected in 1000ms, LED will be turned up 43 | loopTime = millis(); 44 | if(abs(loopTime -interruptsTime) < 1000 ) 45 | blinkState = true; 46 | else 47 | blinkState = false; 48 | digitalWrite(19, blinkState); 49 | } 50 | 51 | 52 | static void eventCallback(void){ 53 | if (BMI160.getInterruptStatus(CURIE_IMU_MOTION)) { 54 | if (BMI160.motionDetected(X_AXIS, POSITIVE)) 55 | Serial.println("Negative motion detected on X-axis"); 56 | if (BMI160.motionDetected(X_AXIS, NEGATIVE)) 57 | Serial.println("Positive motion detected on X-axis"); 58 | if (BMI160.motionDetected(Y_AXIS, POSITIVE)) 59 | Serial.println("Negative motion detected on Y-axis"); 60 | if (BMI160.motionDetected(Y_AXIS, NEGATIVE)) 61 | Serial.println("Positive motion detected on Y-axis"); 62 | if (BMI160.motionDetected(Z_AXIS, POSITIVE)) 63 | Serial.println("Negative motion detected on Z-axis"); 64 | if (BMI160.motionDetected(Z_AXIS, NEGATIVE)) 65 | Serial.println("Positive motion detected on Z-axis"); 66 | interruptsTime = millis(); 67 | } 68 | } 69 | 70 | /* 71 | Copyright (c) 2016 Intel Corporation. All rights reserved. 72 | 73 | This library is free software; you can redistribute it and/or 74 | modify it under the terms of the GNU Lesser General Public 75 | License as published by the Free Software Foundation; either 76 | version 2.1 of the License, or (at your option) any later version. 77 | 78 | This library is distributed in the hope that it will be useful, 79 | but WITHOUT ANY WARRANTY; without even the implied warranty of 80 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 81 | Lesser General Public License for more details. 82 | 83 | You should have received a copy of the GNU Lesser General Public 84 | License along with this library; if not, write to the Free Software 85 | Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA 86 | 87 | */ 88 | -------------------------------------------------------------------------------- /examples/BMI160/ZeroMotionDetect/ZeroMotionDetect.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Copyright (c) 2019 CallMeCode Corporation. All rights reserved. 3 | See the bottom of this file for full license terms. 4 | */ 5 | 6 | /* 7 | This sketch example demonstrates how the BMI160 accelerometer on the 8 | Intel(R) Curie(TM) module can be used to detect zero motion events 9 | */ 10 | #include 11 | 12 | const int irq_pin = 30; 13 | const int i2c_addr = 0x69; 14 | bool ledState = false; // state of the LED 15 | 16 | void setup() { 17 | Serial.begin(115200); // initialize Serial communication 18 | Wire.begin(); 19 | 20 | // initialize device 21 | Serial.println("Initializing IMU device..."); 22 | // BMI160.begin(BMI160GenClass::SPI_MODE, /* SS pin# = */10); 23 | BMI160.begin(BMI160GenClass::I2C_MODE, i2c_addr, irq_pin); 24 | uint8_t dev_id = BMI160.getDeviceID(); 25 | Serial.print("DEVICE ID: "); 26 | Serial.println(dev_id, HEX); 27 | BMI160.attachInterrupt(eventCallback); 28 | 29 | /* Enable Zero Motion Detection */ 30 | BMI160.setDetectionThreshold(CURIE_IMU_ZERO_MOTION, 50); // 50mg 31 | BMI160.setDetectionDuration(CURIE_IMU_ZERO_MOTION, 2); // 2s 32 | BMI160.setIntZeroMotionEnabled(true); 33 | 34 | /* Enable Motion Detection */ 35 | BMI160.setDetectionThreshold(CURIE_IMU_MOTION, 20); // 20mg 36 | BMI160.setDetectionDuration(CURIE_IMU_MOTION, 10); // trigger times of consecutive slope data points 37 | BMI160.setIntMotionEnabled(true); 38 | 39 | Serial.println("IMU initialisation complete, waiting for events..."); 40 | } 41 | 42 | void loop() { 43 | // if zero motion is detected, LED will be turned up. 44 | digitalWrite(19, ledState); 45 | } 46 | 47 | static void eventCallback(void){ 48 | if (BMI160.getInterruptStatus(CURIE_IMU_ZERO_MOTION)) { 49 | ledState = true; 50 | Serial.println("zero motion detected..."); 51 | } 52 | if (BMI160.getInterruptStatus(CURIE_IMU_MOTION)) { 53 | ledState = false; 54 | if (BMI160.motionDetected(X_AXIS, POSITIVE)) 55 | Serial.println("Negative motion detected on X-axis"); 56 | if (BMI160.motionDetected(X_AXIS, NEGATIVE)) 57 | Serial.println("Positive motion detected on X-axis"); 58 | if (BMI160.motionDetected(Y_AXIS, POSITIVE)) 59 | Serial.println("Negative motion detected on Y-axis"); 60 | if (BMI160.motionDetected(Y_AXIS, NEGATIVE)) 61 | Serial.println("Positive motion detected on Y-axis"); 62 | if (BMI160.motionDetected(Z_AXIS, POSITIVE)) 63 | Serial.println("Negative motion detected on Z-axis"); 64 | if (BMI160.motionDetected(Z_AXIS, NEGATIVE)) 65 | Serial.println("Positive motion detected on Z-axis"); 66 | } 67 | } 68 | 69 | /* 70 | Copyright (c) 2016 Intel Corporation. All rights reserved. 71 | 72 | This library is free software; you can redistribute it and/or 73 | modify it under the terms of the GNU Lesser General Public 74 | License as published by the Free Software Foundation; either 75 | version 2.1 of the License, or (at your option) any later version. 76 | 77 | This library is distributed in the hope that it will be useful, 78 | but WITHOUT ANY WARRANTY; without even the implied warranty of 79 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 80 | Lesser General Public License for more details. 81 | 82 | You should have received a copy of the GNU Lesser General Public 83 | License along with this library; if not, write to the Free Software 84 | Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA 85 | 86 | */ 87 | -------------------------------------------------------------------------------- /examples/Peripheral/custom_htm/IEEE11073float.cpp: -------------------------------------------------------------------------------- 1 | /**************************************************************************/ 2 | /*! 3 | @file IEEE11073float.h 4 | */ 5 | /**************************************************************************/ 6 | 7 | /** 8 | * \file bytelib.c 9 | * \brief Byte manipulation module implementation. 10 | * Copyright (C) 2010 Signove Tecnologia Corporation. 11 | * All rights reserved. 12 | * Contact: Signove Tecnologia Corporation (contact@signove.com) 13 | * 14 | * $LICENSE_TEXT:BEGIN$ 15 | * This library is free software; you can redistribute it and/or 16 | * modify it under the terms of the GNU Lesser General Public 17 | * License as published by the Free Software Foundation and appearing 18 | * in the file LICENSE included in the packaging of this file; either 19 | * version 2.1 of the License, or (at your option) any later version. 20 | * 21 | * This library is distributed in the hope that it will be useful, 22 | * but WITHOUT ANY WARRANTY; without even the implied warranty of 23 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 24 | * Lesser General Public License for more details. 25 | * 26 | * You should have received a copy of the GNU Lesser General Public 27 | * License along with this library; if not, write to the Free Software 28 | * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA 29 | * $LICENSE_TEXT:END$ 30 | * 31 | * \author Walter Guerra, Mateus Lima 32 | * \date Jun 14, 2010 33 | */ 34 | 35 | #include 36 | #include "IEEE11073float.h" 37 | 38 | uint32_t float2IEEE11073(double data, uint8_t output[4]) 39 | { 40 | uint32_t result = MDER_NaN; 41 | 42 | 43 | if (isnan(data)) { 44 | goto finally; 45 | }/* else if (data > MDER_FLOAT_MAX) { 46 | result = MDER_POSITIVE_INFINITY; 47 | goto finally; 48 | } else if (data < MDER_FLOAT_MIN) { 49 | result = MDER_NEGATIVE_INFINITY; 50 | goto finally; 51 | } else if (data >= -MDER_FLOAT_EPSILON && 52 | data <= MDER_FLOAT_EPSILON) { 53 | result = 0; 54 | goto finally; 55 | }*/ 56 | 57 | double sgn; sgn = data > 0 ? +1 : -1; 58 | double mantissa; mantissa = fabs(data); 59 | int32_t exponent; exponent = 0; // Note: 10**x exponent, not 2**x 60 | 61 | // scale up if number is too big 62 | while (mantissa > MDER_FLOAT_MANTISSA_MAX) { 63 | mantissa /= 10.0; 64 | ++exponent; 65 | if (exponent > MDER_FLOAT_EXPONENT_MAX) { 66 | // argh, should not happen 67 | if (sgn > 0) { 68 | result = MDER_POSITIVE_INFINITY; 69 | } else { 70 | result = MDER_NEGATIVE_INFINITY; 71 | } 72 | goto finally; 73 | } 74 | } 75 | 76 | // scale down if number is too small 77 | while (mantissa < 1) { 78 | mantissa *= 10; 79 | --exponent; 80 | if (exponent < MDER_FLOAT_EXPONENT_MIN) { 81 | // argh, should not happen 82 | result = 0; 83 | goto finally; 84 | } 85 | } 86 | 87 | // scale down if number needs more precision 88 | double smantissa; smantissa = round(mantissa * MDER_FLOAT_PRECISION); 89 | double rmantissa; rmantissa = round(mantissa) * MDER_FLOAT_PRECISION; 90 | double mdiff; mdiff = abs(smantissa - rmantissa); 91 | while (mdiff > 0.5 && exponent > MDER_FLOAT_EXPONENT_MIN && 92 | (mantissa * 10) <= MDER_FLOAT_MANTISSA_MAX) { 93 | mantissa *= 10; 94 | --exponent; 95 | smantissa = round(mantissa * MDER_FLOAT_PRECISION); 96 | rmantissa = round(mantissa) * MDER_FLOAT_PRECISION; 97 | mdiff = abs(smantissa - rmantissa); 98 | } 99 | 100 | uint32_t int_mantissa; int_mantissa = (int) round(sgn * mantissa); 101 | result = (exponent << 24) | (int_mantissa & 0xFFFFFF); 102 | 103 | finally: 104 | if ( output ) memcpy(output, &result, 4); 105 | return result; 106 | } 107 | -------------------------------------------------------------------------------- /examples/BMI160/StepCount/StepCount.ino: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2019 CallMeCode Corporation. All rights reserved. 3 | * See the bottom of this file for the license terms. 4 | */ 5 | 6 | /* 7 | This sketch example demonstrates how the BMI160 accelerometer on the 8 | Intel(R) Curie(TM) module can be used as a Step Counter (pedometer) 9 | */ 10 | 11 | #include 12 | 13 | const int irq_pin = 30; 14 | const int i2c_addr = 0x69; 15 | 16 | /* To get an interrupt notification for every step detected, 17 | set stepEventsEnabeled to true. Otherwise, the main loop will 18 | poll for the current step count. 19 | 20 | By design, the step counter does not immediately update on every step detected. 21 | Please refer to Section 2.7 of the BMI160 IMU SensorData Sheet 22 | for more information on this feature. 23 | */ 24 | const int ledPin = 19; 25 | 26 | bool stepEventsEnabeled = true; // whether you're polling or using events 27 | long lastStepCount = 0; // step count on previous polling check 28 | bool blinkState = false; // state of the LED 29 | 30 | void setup() { 31 | Serial.begin(115200); // initialize Serial communication 32 | Wire.begin(); 33 | pinMode(ledPin, OUTPUT); 34 | // initialize device 35 | Serial.println("Initializing IMU device..."); 36 | // BMI160.begin(BMI160GenClass::SPI_MODE, /* SS pin# = */10); 37 | BMI160.begin(BMI160GenClass::I2C_MODE, i2c_addr, irq_pin); 38 | uint8_t dev_id = BMI160.getDeviceID(); 39 | Serial.print("DEVICE ID: "); 40 | Serial.println(dev_id, HEX); 41 | // turn on step detection mode: 42 | BMI160.setStepDetectionMode(CURIE_IMU_STEP_MODE_NORMAL); 43 | // enable step counting: 44 | BMI160.setStepCountEnabled(true); 45 | 46 | if (stepEventsEnabeled) { 47 | // attach the eventCallback function as the 48 | // step event handler: 49 | BMI160.attachInterrupt(eventCallback); 50 | // BMI160.interruptsEnabled(CURIE_IMU_STEP); // turn on step detection 51 | BMI160.setIntStepEnabled(true); 52 | Serial.println("IMU initialisation complete, waiting for events..."); 53 | } 54 | } 55 | 56 | void loop() { 57 | /* Instead of using step detection event notifications, 58 | we can check the step count periodically */ 59 | if (!stepEventsEnabeled) { 60 | updateStepCount(); 61 | } 62 | digitalWrite(ledPin, blinkState); 63 | blinkState = !blinkState; 64 | delay(1000); 65 | } 66 | 67 | static void updateStepCount() { 68 | // get the step count: 69 | int stepCount = BMI160.getStepCount(); 70 | 71 | // if the step count has changed, print it: 72 | if (stepCount != lastStepCount) { 73 | Serial.print("Step count: "); 74 | Serial.println(stepCount); 75 | // save the current count for comparison next check: 76 | lastStepCount = stepCount; 77 | } 78 | } 79 | 80 | static void eventCallback(void) { 81 | if (BMI160.stepsDetected()) 82 | updateStepCount(); 83 | } 84 | 85 | /* 86 | Copyright (c) 2016 Intel Corporation. All rights reserved. 87 | 88 | This library is free software; you can redistribute it and/or 89 | modify it under the terms of the GNU Lesser General Public 90 | License as published by the Free Software Foundation; either 91 | version 2.1 of the License, or (at your option) any later version. 92 | 93 | This library is distributed in the hope that it will be useful, 94 | but WITHOUT ANY WARRANTY; without even the implied warranty of 95 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 96 | Lesser General Public License for more details. 97 | 98 | You should have received a copy of the GNU Lesser General Public 99 | License along with this library; if not, write to the Free Software 100 | Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA 101 | 102 | */ 103 | -------------------------------------------------------------------------------- /examples/BMI160/AccelerometerOrientation/AccelerometerOrientation.ino: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2019 CallMeCode Corporation. All rights reserved. 3 | * See the bottom of this file for the license terms. 4 | */ 5 | 6 | /* 7 | This sketch example demonstrates how the BMI160 on the 8 | Intel(R) Curie(TM) module can be used to read accelerometer data 9 | and translate it to an orientation 10 | */ 11 | 12 | #include 13 | 14 | const int irq_pin = 30; 15 | const int i2c_addr = 0x69; 16 | 17 | int lastOrientation = - 1; // previous orientation (for comparison) 18 | 19 | void setup() { 20 | Serial.begin(115200); // initialize Serial communication 21 | Wire.begin(); 22 | 23 | // initialize device 24 | Serial.println("Initializing IMU device..."); 25 | // BMI160.begin(BMI160GenClass::SPI_MODE, /* SS pin# = */10); 26 | BMI160.begin(BMI160GenClass::I2C_MODE, i2c_addr, irq_pin); 27 | uint8_t dev_id = BMI160.getDeviceID(); 28 | Serial.print("DEVICE ID: "); 29 | Serial.println(dev_id, HEX); 30 | 31 | // Set the accelerometer range to 2G 32 | BMI160.setAccelerometerRange(2); 33 | Serial.println("Initializing IMU device...done."); 34 | } 35 | 36 | void loop() { 37 | int orientation = - 1; // the board's orientation 38 | String orientationString; // string for printing description of orientation 39 | /* 40 | The orientations of the board: 41 | 0: flat, processor facing up 42 | 1: flat, processor facing down 43 | 2: landscape, analog pins down 44 | 3: landscape, analog pins up 45 | 4: portrait, USB connector up 46 | 5: portrait, USB connector down 47 | */ 48 | // read accelerometer: 49 | int x = BMI160.readAccelerometer(X_AXIS); 50 | int y = BMI160.readAccelerometer(Y_AXIS); 51 | int z = BMI160.readAccelerometer(Z_AXIS); 52 | 53 | // calculate the absolute values, to determine the largest 54 | int absX = abs(x); 55 | int absY = abs(y); 56 | int absZ = abs(z); 57 | 58 | if ( (absZ > absX) && (absZ > absY)) { 59 | // base orientation on Z 60 | if (z > 0) { 61 | orientationString = "up"; 62 | orientation = 0; 63 | } else { 64 | orientationString = "down"; 65 | orientation = 1; 66 | } 67 | } else if ( (absY > absX) && (absY > absZ)) { 68 | // base orientation on Y 69 | if (y > 0) { 70 | orientationString = "digital pins up"; 71 | orientation = 2; 72 | } else { 73 | orientationString = "analog pins up"; 74 | orientation = 3; 75 | } 76 | } else { 77 | // base orientation on X 78 | if (x < 0) { 79 | orientationString = "connector up"; 80 | orientation = 4; 81 | } else { 82 | orientationString = "connector down"; 83 | orientation = 5; 84 | } 85 | } 86 | 87 | // if the orientation has changed, print out a description: 88 | if (orientation != lastOrientation) { 89 | Serial.println(orientationString); 90 | lastOrientation = orientation; 91 | } 92 | } 93 | 94 | /* 95 | Copyright (c) 2016 Intel Corporation. All rights reserved. 96 | 97 | This library is free software; you can redistribute it and/or 98 | modify it under the terms of the GNU Lesser General Public 99 | License as published by the Free Software Foundation; either 100 | version 2.1 of the License, or (at your option) any later version. 101 | 102 | This library is distributed in the hope that it will be useful, 103 | but WITHOUT ANY WARRANTY; without even the implied warranty of 104 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 105 | Lesser General Public License for more details. 106 | 107 | You should have received a copy of the GNU Lesser General Public 108 | License along with this library; if not, write to the Free Software 109 | Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA 110 | 111 | */ 112 | -------------------------------------------------------------------------------- /src/utility/fontconvert/fontconvert_win.md: -------------------------------------------------------------------------------- 1 | ### A short guide to use fontconvert.c to create your own fonts using MinGW. 2 | 3 | #### STEP 1: INSTALL MinGW 4 | 5 | Install MinGW (Minimalist GNU for Windows) from [MinGW.org](http://www.mingw.org/). 6 | Please read carefully the instructions found on [Getting started page](http://www.mingw.org/wiki/Getting_Started). 7 | I suggest installing with the "Graphical User Interface Installer". 8 | To complete your initial installation you should further install some "packages". 9 | For our purpose you should only install the "Basic Setup" packages. 10 | To do that: 11 | 12 | 1. Open the MinGW Installation Manager 13 | 2. From the left panel click "Basic Setup". 14 | 3. On the right panel choose "mingw32-base", "mingw-gcc-g++", "mingw-gcc-objc" and "msys-base" 15 | and click "Mark for installation" 16 | 4. From the Menu click "Installation" and then "Apply changes". In the pop-up window select "Apply". 17 | 18 | 19 | #### STEP 2: INSTALL Freetype Library 20 | 21 | To read about the freetype project visit [freetype.org](https://www.freetype.org/). 22 | To Download the latest version of freetype go to [download page](http://download.savannah.gnu.org/releases/freetype/) 23 | and choose "freetype-2.7.tar.gz" file (or a newer version if available). 24 | To avoid long cd commands later in the command prompt, I suggest you unzip the file in the C:\ directory. 25 | (I also renamed the folder to "ft27") 26 | Before you build the library it's good to read these articles: 27 | * [Using MSYS with MinGW](http://www.mingw.org/wiki/MSYS) 28 | * [Installation and Use of Supplementary Libraries with MinGW](http://www.mingw.org/wiki/LibraryPathHOWTO) 29 | * [Include Path](http://www.mingw.org/wiki/IncludePathHOWTO) 30 | 31 | Inside the unzipped folder there is another folder named "docs". Open it and read the INSTALL.UNIX (using notepad). 32 | Pay attention to paragraph 3 (Build and Install the Library). So, let's begin the installation. 33 | To give the appropriate commands we will use the MSYS command prompt (not cmd.exe of windows) which is UNIX like. 34 | Follow the path C:\MinGW\msys\1.0 and double click "msys.bat". The command prompt environment appears. 35 | Enter "ft27" directory using the cd commands: 36 | ``` 37 | cd /c 38 | cd ft27 39 | ``` 40 | 41 | and then type one by one the commands: 42 | ``` 43 | ./configure --prefix=/mingw 44 | make 45 | make install 46 | ``` 47 | Once you're finished, go inside "C:\MinGW\include" and there should be a new folder named "freetype2". 48 | That, hopefully, means that you have installed the library correctly !! 49 | 50 | #### STEP 3: Build fontconvert.c 51 | 52 | Before proceeding I suggest you make a copy of Adafruit_GFX_library folder in C:\ directory. 53 | Then, inside "fontconvert" folder open the "makefile" with an editor ( I used notepad++). 54 | Change the commands so in the end the program looks like : 55 | ``` 56 | all: fontconvert 57 | 58 | CC = gcc 59 | CFLAGS = -Wall -I c:/mingw/include/freetype2 60 | LIBS = -lfreetype 61 | 62 | fontconvert: fontconvert.c 63 | $(CC) $(CFLAGS) $< $(LIBS) -o $@ 64 | 65 | clean: 66 | rm -f fontconvert 67 | ``` 68 | Go back in the command prompt and with a cd command enter the fontconvert directory. 69 | ``` 70 | cd /c/adafruit_gfx_library\fontconvert 71 | ``` 72 | Give the command: 73 | ``` 74 | make 75 | ``` 76 | This command will, eventually, create a "fontconvert.exe" file inside fontconvert directory. 77 | 78 | #### STEP 4: Create your own font header files 79 | 80 | Now that you have an executable file, you can use it to create your own fonts to work with Adafruit GFX lib. 81 | So, if we suppose that you already have a .ttf file with your favorite fonts, jump to the command prompt and type: 82 | ``` 83 | ./fontconvert yourfonts.ttf 9 > yourfonts9pt7b.h 84 | ``` 85 | You can read more details at: [learn.adafruit](https://learn.adafruit.com/adafruit-gfx-graphics-library/using-fonts). 86 | 87 | Taraaaaaammm !! you've just created your new font header file. Put it inside the "Fonts" folder, grab a cup of coffee 88 | and start playing with your Arduino (or whatever else ....)+ display module project. 89 | -------------------------------------------------------------------------------- /examples/Peripheral/controller/packetParser.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | 5 | 6 | #define PACKET_ACC_LEN (15) 7 | #define PACKET_GYRO_LEN (15) 8 | #define PACKET_MAG_LEN (15) 9 | #define PACKET_QUAT_LEN (19) 10 | #define PACKET_BUTTON_LEN (5) 11 | #define PACKET_COLOR_LEN (6) 12 | #define PACKET_LOCATION_LEN (15) 13 | 14 | // READ_BUFSIZE Size of the read buffer for incoming packets 15 | #define READ_BUFSIZE (20) 16 | 17 | 18 | /* Buffer to hold incoming characters */ 19 | uint8_t packetbuffer[READ_BUFSIZE+1]; 20 | 21 | /**************************************************************************/ 22 | /*! 23 | @brief Casts the four bytes at the specified address to a float 24 | */ 25 | /**************************************************************************/ 26 | float parsefloat(uint8_t *buffer) 27 | { 28 | float f; 29 | memcpy(&f, buffer, 4); 30 | return f; 31 | } 32 | 33 | /**************************************************************************/ 34 | /*! 35 | @brief Prints a hexadecimal value in plain characters 36 | @param data Pointer to the byte data 37 | @param numBytes Data length in bytes 38 | */ 39 | /**************************************************************************/ 40 | void printHex(const uint8_t * data, const uint32_t numBytes) 41 | { 42 | uint32_t szPos; 43 | for (szPos=0; szPos < numBytes; szPos++) 44 | { 45 | Serial.print(F("0x")); 46 | // Append leading 0 for small values 47 | if (data[szPos] <= 0xF) 48 | { 49 | Serial.print(F("0")); 50 | Serial.print(data[szPos] & 0xf, HEX); 51 | } 52 | else 53 | { 54 | Serial.print(data[szPos] & 0xff, HEX); 55 | } 56 | // Add a trailing space if appropriate 57 | if ((numBytes > 1) && (szPos != numBytes - 1)) 58 | { 59 | Serial.print(F(" ")); 60 | } 61 | } 62 | Serial.println(); 63 | } 64 | 65 | /**************************************************************************/ 66 | /*! 67 | @brief Waits for incoming data and parses it 68 | */ 69 | /**************************************************************************/ 70 | uint8_t readPacket(BLEUart *ble_uart, uint16_t timeout) 71 | { 72 | uint16_t origtimeout = timeout, replyidx = 0; 73 | 74 | memset(packetbuffer, 0, READ_BUFSIZE); 75 | 76 | while (timeout--) { 77 | if (replyidx >= 20) break; 78 | if ((packetbuffer[1] == 'A') && (replyidx == PACKET_ACC_LEN)) 79 | break; 80 | if ((packetbuffer[1] == 'G') && (replyidx == PACKET_GYRO_LEN)) 81 | break; 82 | if ((packetbuffer[1] == 'M') && (replyidx == PACKET_MAG_LEN)) 83 | break; 84 | if ((packetbuffer[1] == 'Q') && (replyidx == PACKET_QUAT_LEN)) 85 | break; 86 | if ((packetbuffer[1] == 'B') && (replyidx == PACKET_BUTTON_LEN)) 87 | break; 88 | if ((packetbuffer[1] == 'C') && (replyidx == PACKET_COLOR_LEN)) 89 | break; 90 | if ((packetbuffer[1] == 'L') && (replyidx == PACKET_LOCATION_LEN)) 91 | break; 92 | 93 | while (ble_uart->available()) { 94 | char c = ble_uart->read(); 95 | if (c == '!') { 96 | replyidx = 0; 97 | } 98 | packetbuffer[replyidx] = c; 99 | replyidx++; 100 | timeout = origtimeout; 101 | } 102 | 103 | if (timeout == 0) break; 104 | delay(1); 105 | } 106 | 107 | packetbuffer[replyidx] = 0; // null term 108 | 109 | if (!replyidx) // no data or timeout 110 | return 0; 111 | if (packetbuffer[0] != '!') // doesn't start with '!' packet beginning 112 | return 0; 113 | 114 | // check checksum! 115 | uint8_t xsum = 0; 116 | uint8_t checksum = packetbuffer[replyidx-1]; 117 | 118 | for (uint8_t i=0; i 15 | 16 | BLEUart bleuart; // uart over ble 17 | 18 | void setup() 19 | { 20 | Serial.begin(115200); 21 | while ( !Serial ) delay(10); // for nrf52840 with native usb 22 | 23 | Serial.println("Bluefruit52 RSSI Example"); 24 | Serial.println("------------------------\n"); 25 | 26 | // Setup the BLE LED to be enabled on CONNECT 27 | // Note: This is actually the default behaviour, but provided 28 | // here in case you want to control this LED manually 29 | Bluefruit.autoConnLed(true); 30 | 31 | // Config the peripheral connection with maximum bandwidth 32 | // more SRAM required by SoftDevice 33 | // Note: All config***() function must be called before begin() 34 | Bluefruit.configPrphBandwidth(BANDWIDTH_MAX); 35 | 36 | Bluefruit.begin(); 37 | Bluefruit.setTxPower(4); // Check bluefruit.h for supported values 38 | Bluefruit.setName("Bluefruit52"); 39 | Bluefruit.Periph.setConnectCallback(connect_callback); 40 | Bluefruit.Periph.setDisconnectCallback(disconnect_callback); 41 | 42 | // Configure and Start BLE Uart Service 43 | bleuart.begin(); 44 | 45 | // Set up Rssi changed callback 46 | Bluefruit.setRssiCallback(rssi_changed_callback); 47 | 48 | // Set up and start advertising 49 | startAdv(); 50 | 51 | Serial.println("Please use Adafruit's Bluefruit LE app to connect"); 52 | } 53 | 54 | void startAdv(void) 55 | { 56 | // Advertising packet 57 | Bluefruit.Advertising.addFlags(BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE); 58 | Bluefruit.Advertising.addTxPower(); 59 | 60 | // Include bleuart 128-bit uuid 61 | Bluefruit.Advertising.addService(bleuart); 62 | 63 | // Secondary Scan Response packet (optional) 64 | // Since there is no room for 'Name' in Advertising packet 65 | Bluefruit.ScanResponse.addName(); 66 | 67 | /* Start Advertising 68 | * - Enable auto advertising if disconnected 69 | * - Interval: fast mode = 20 ms, slow mode = 152.5 ms 70 | * - Timeout for fast mode is 30 seconds 71 | * - Start(timeout) with timeout = 0 will advertise forever (until connected) 72 | * 73 | * For recommended advertising interval 74 | * https://developer.apple.com/library/content/qa/qa1931/_index.html 75 | */ 76 | Bluefruit.Advertising.restartOnDisconnect(true); 77 | Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms 78 | Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode 79 | Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds 80 | } 81 | 82 | void loop() 83 | { 84 | // do nothing 85 | } 86 | 87 | void connect_callback(uint16_t conn_handle) 88 | { 89 | Serial.println("Connected"); 90 | 91 | // Get the reference to current connection 92 | BLEConnection* connection = Bluefruit.Connection(conn_handle); 93 | 94 | // Start monitoring rssi of this connection 95 | // This function should be called in connect callback 96 | // Input argument is value difference (to current rssi) that triggers callback 97 | connection->monitorRssi(10); 98 | } 99 | 100 | void rssi_changed_callback(uint16_t conn_hdl, int8_t rssi) 101 | { 102 | (void) conn_hdl; 103 | Serial.printf("Rssi = %d", rssi); 104 | Serial.println(); 105 | } 106 | 107 | /** 108 | * Callback invoked when a connection is dropped 109 | * @param conn_handle connection where this event happens 110 | * @param reason is a BLE_HCI_STATUS_CODE which can be found in ble_hci.h 111 | */ 112 | void disconnect_callback(uint16_t conn_handle, uint8_t reason) 113 | { 114 | (void) conn_handle; 115 | (void) reason; 116 | 117 | Serial.println(); 118 | Serial.println("Disconnected"); 119 | } 120 | -------------------------------------------------------------------------------- /examples/PCA9685/trajmove/trajmove.ino: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | 5 | #define L1 135 //lengths are in mm 6 | #define L2 147 7 | #define L3 95 8 | #define PI 3.14159 9 | 10 | // called this way, it uses the default address 0x40 11 | PCA9685 pwm = PCA9685(); 12 | 13 | int potpinx = 0; // analog pin used to connect the potentiometer 14 | int valx; // variable to read the value from the analog pin 15 | int potpiny = 1; // analog pin used to connect the potentiometer 16 | int valy; // variable to read the value from the analog pin 17 | 18 | double x; 19 | double y; 20 | 21 | // our servo # counter 22 | uint8_t servonum = 0; 23 | 24 | int Bpin = 9; // P0.28 Pin analog pin used to connect the potentiometer 25 | int Xpin = A2; 26 | int Ypin = A1; 27 | 28 | int sAngle0 = 0; 29 | int sAngle1 = 0; 30 | int sAngle2 = 0; 31 | int sAngle90 = 0; 32 | 33 | int sAngle0_offset = 0; 34 | int sAngle1_offset = 0; 35 | int sAngle2_offset = 0; 36 | int sAngle90_offset = 0; 37 | 38 | int valB; // variable to read the value from the analog pin 39 | int valX; 40 | int valY; 41 | 42 | double horzA = 1.01; 43 | double vertA = 1.01; 44 | 45 | // you can use this function if you'd like to set the pulse length in seconds 46 | // e.g. setServoPulse(0, 0.001) is a ~1 millisecond pulse width. its not precise! 47 | void setServoPulse(uint8_t n, double pulse) { 48 | double pulselength; 49 | 50 | pulselength = 1000000; // 1,000,000 us per second 51 | pulselength /= 60; // 50 Hz 52 | // Serial.print(pulselength); Serial.println(" us per period"); 53 | pulselength /= 4096; // 12 bits of resolution 54 | // Serial.print(pulselength); Serial.println(" us per bit"); 55 | pulse *= 1000; // convert to us 56 | pulse /= pulselength; 57 | // Serial.println(pulse); 58 | pwm.setPWM(n, 0, pulse); 59 | } 60 | 61 | void setServoAngle(uint8_t n, float angle) { 62 | double pulse = angle; 63 | pulse = pulse/90.0 + 0.5; 64 | setServoPulse(n,pulse); 65 | } 66 | 67 | // move gripper to x,y,z,gripangle 68 | void movexy(double x1,double y1) 69 | { 70 | //inverse kinematics for joint angles (RADIANS) 71 | double t2 = PI - acos((L1 * L1 + L2 * L2 - x1 * x1 - y1 * y1 ) / (2 * L1 * L2)); 72 | double t1 = atan2(y1, x1) + atan2((L2*sin(t2)),(L1+(L2*cos(t2)))); 73 | 74 | //convert to degrees 75 | double t1deg = t1 / PI * 180; 76 | double t2deg = t2 / PI * 180; 77 | 78 | //convert joint angles to servo command angles 79 | int h = (360 - (2*t2deg))/2; 80 | int b = 15; 81 | int t1servo = 180 - t1deg; 82 | int t2servo = t1deg + h - b; 83 | 84 | setServoAngle(1, t1servo); 85 | setServoAngle(2, t2servo); 86 | // delay(20); // change this to make the motions faster or slower 87 | } 88 | 89 | void setup(){ 90 | Serial.begin(115200); 91 | Serial.println("4 channel Servo test!"); 92 | pinMode(Bpin, INPUT_PULLUP); 93 | 94 | pwm.begin(); 95 | 96 | pwm.setPWMFreq(60); // Analog servos run at ~50 Hz updates 97 | delay(100); 98 | valB = digitalRead(Bpin); 99 | valX = analogRead(Xpin); 100 | valY = analogRead(Ypin); 101 | // Serial.println(valX-10); 102 | // Serial.println(valY-20); 103 | sAngle0_offset = map(1000-valY, 0, 1000, 0, 180); 104 | sAngle1_offset = map(1000-valX, 0, 1000, 0, 180); 105 | sAngle2_offset = map(valX/2, 0, 1000, 0, 180); 106 | sAngle90_offset = 0; 107 | sAngle2_offset = sAngle2_offset + 100; 108 | setServoAngle(0, sAngle0_offset); 109 | setServoAngle(1, sAngle1_offset); 110 | setServoAngle(2, sAngle2_offset); 111 | setServoAngle(3, sAngle90_offset); 112 | Serial.println(atan(1.0)*180/PI); 113 | delay(500); 114 | 115 | } 116 | 117 | 118 | 119 | void loop() { 120 | valB = digitalRead(Bpin); 121 | valX = analogRead(Xpin); 122 | valY = analogRead(Ypin); 123 | 124 | // sAngle0 = map(1000-valY, 0, 1000, 0, 180); 125 | // sAngle1 = map(1000-valX, 0, 1000, 0, 180); 126 | // sAngle2 = map(valX/2, 0, 1000, 0, 180); 127 | // // Serial.println(sAngle0); 128 | // setServoAngle(0, sAngle0); 129 | // setServoAngle(1, sAngle1); 130 | // setServoAngle(2, sAngle2+100); 131 | 132 | sAngle0 = map(valY, 20, 1000, 0, 250); 133 | sAngle1 = map(valX, 20, 1000, 0, 225); 134 | 135 | movexy(sAngle0,sAngle1); 136 | 137 | if(valB == 1){ 138 | setServoAngle(3, 40); 139 | 140 | } 141 | else 142 | { 143 | setServoAngle(3, 170); 144 | Serial.println("Hello"); 145 | } 146 | delay(20); 147 | } 148 | -------------------------------------------------------------------------------- /examples/Peripheral/rssi_poll/rssi_poll.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | #include 15 | 16 | BLEUart bleuart; // uart over ble 17 | 18 | void setup() 19 | { 20 | Serial.begin(115200); 21 | while ( !Serial ) delay(10); // for nrf52840 with native usb 22 | 23 | Serial.println("Bluefruit52 RSSI Example"); 24 | Serial.println("------------------------\n"); 25 | 26 | // Setup the BLE LED to be enabled on CONNECT 27 | // Note: This is actually the default behaviour, but provided 28 | // here in case you want to control this LED manually 29 | Bluefruit.autoConnLed(true); 30 | 31 | // Config the peripheral connection with maximum bandwidth 32 | // more SRAM required by SoftDevice 33 | // Note: All config***() function must be called before begin() 34 | Bluefruit.configPrphBandwidth(BANDWIDTH_MAX); 35 | 36 | Bluefruit.begin(); 37 | Bluefruit.setTxPower(4); // Check bluefruit.h for supported values 38 | Bluefruit.setName("Bluefruit52"); 39 | Bluefruit.Periph.setConnectCallback(connect_callback); 40 | Bluefruit.Periph.setDisconnectCallback(disconnect_callback); 41 | 42 | // Configure and Start BLE Uart Service 43 | bleuart.begin(); 44 | 45 | // Set up and start advertising 46 | startAdv(); 47 | 48 | Serial.println("Please use Adafruit's Bluefruit LE app to connect"); 49 | } 50 | 51 | void startAdv(void) 52 | { 53 | // Advertising packet 54 | Bluefruit.Advertising.addFlags(BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE); 55 | Bluefruit.Advertising.addTxPower(); 56 | 57 | // Include bleuart 128-bit uuid 58 | Bluefruit.Advertising.addService(bleuart); 59 | 60 | // Secondary Scan Response packet (optional) 61 | // Since there is no room for 'Name' in Advertising packet 62 | Bluefruit.ScanResponse.addName(); 63 | 64 | /* Start Advertising 65 | * - Enable auto advertising if disconnected 66 | * - Interval: fast mode = 20 ms, slow mode = 152.5 ms 67 | * - Timeout for fast mode is 30 seconds 68 | * - Start(timeout) with timeout = 0 will advertise forever (until connected) 69 | * 70 | * For recommended advertising interval 71 | * https://developer.apple.com/library/content/qa/qa1931/_index.html 72 | */ 73 | Bluefruit.Advertising.restartOnDisconnect(true); 74 | Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms 75 | Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode 76 | Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds 77 | } 78 | 79 | void loop() 80 | { 81 | if ( Bluefruit.connected() ) 82 | { 83 | uint16_t conn_hdl = Bluefruit.connHandle(); 84 | 85 | // Get the reference to current connected connection 86 | BLEConnection* connection = Bluefruit.Connection(conn_hdl); 87 | 88 | // get the RSSI value of this connection 89 | // monitorRssi() must be called previously (in connect callback) 90 | int8_t rssi = connection->getRssi(); 91 | 92 | Serial.printf("Rssi = %d", rssi); 93 | Serial.println(); 94 | 95 | // print one per second 96 | delay(1000); 97 | } 98 | } 99 | 100 | void connect_callback(uint16_t conn_handle) 101 | { 102 | Serial.println("Connected"); 103 | 104 | // Get the reference to current connection 105 | BLEConnection* conn = Bluefruit.Connection(conn_handle); 106 | 107 | // Start monitoring rssi of this connection 108 | // This function should be called in connect callback 109 | // no parameters means we don't use rssi changed callback 110 | conn->monitorRssi(); 111 | } 112 | 113 | /** 114 | * Callback invoked when a connection is dropped 115 | * @param conn_handle connection where this event happens 116 | * @param reason is a BLE_HCI_STATUS_CODE which can be found in ble_hci.h 117 | */ 118 | void disconnect_callback(uint16_t conn_handle, uint8_t reason) 119 | { 120 | (void) conn_handle; 121 | (void) reason; 122 | 123 | Serial.println(); 124 | Serial.println("Disconnected"); 125 | } 126 | -------------------------------------------------------------------------------- /examples/PCA9685/SmartArm/SmartArm.ino: -------------------------------------------------------------------------------- 1 | /*************************************************** 2 | This is an example for our PCA9685 16-channel PWM & Servo driver 3 | Servo test - this will drive 8 servos, one after the other on the 4 | first 8 pins of the PCA9685 5 | 6 | These drivers use I2C to communicate, 2 pins are required to 7 | interface. 8 | 9 | ****************************************************/ 10 | 11 | #include 12 | #include 13 | 14 | 15 | 16 | // called this way, it uses the default address 0x40 17 | PCA9685 pwm = PCA9685(); 18 | 19 | 20 | // Depending on your servo make, the pulse width min and max may vary, you 21 | // want these to be as small/large as possible without hitting the hard stop 22 | // for max range. You'll have to tweak them as necessary to match the servos you 23 | // have! 24 | #define SERVOMIN 100 // this is the 'minimum' pulse length count (out of 4096) 25 | #define SERVOMAX 650 // this is the 'maximum' pulse length count (out of 4096) 26 | 27 | #define L1 135 28 | #define L5 147 29 | 30 | #define PI 3.1416 31 | 32 | // our servo # counter 33 | uint8_t servonum = 0; 34 | 35 | int Bpin = A0; // P0.28 Pin analog pin used to connect the potentiometer 36 | int Xpin = A2; 37 | int Ypin = A1; 38 | 39 | int sAngle0 = 0; 40 | int sAngle1 = 0; 41 | int sAngle2 = 0; 42 | int sAngle90 = 0; 43 | 44 | int sAngle0_offset = 0; 45 | int sAngle1_offset = 0; 46 | int sAngle2_offset = 0; 47 | int sAngle90_offset = 0; 48 | 49 | int valB; // variable to read the value from the analog pin 50 | int valX; 51 | int valY; 52 | 53 | double horzA = 1.01; 54 | double vertA = 1.01; 55 | 56 | // you can use this function if you'd like to set the pulse length in seconds 57 | // e.g. setServoPulse(0, 0.001) is a ~1 millisecond pulse width. its not precise! 58 | void setServoPulse(uint8_t n, double pulse) { 59 | double pulselength; 60 | 61 | pulselength = 1000000; // 1,000,000 us per second 62 | pulselength /= 53; // 50 Hz 63 | // Serial.print(pulselength); Serial.println(" us per period"); 64 | pulselength /= 4096; // 12 bits of resolution 65 | // Serial.print(pulselength); Serial.println(" us per bit"); 66 | pulse *= 1000; // convert to us 67 | pulse /= pulselength; 68 | // Serial.println(pulse); 69 | pwm.setPWM(n, 0, pulse); 70 | } 71 | 72 | void setup() { 73 | Serial.begin(115200); 74 | Serial.println("4 channel Servo test!"); 75 | pinMode(Bpin, INPUT_PULLUP); 76 | 77 | pwm.begin(); 78 | 79 | pwm.setPWMFreq(53); // Analog servos run at ~50 Hz updates 80 | delay(100); 81 | valB = digitalRead(Bpin); 82 | valX = analogRead(Xpin); 83 | valY = analogRead(Ypin); 84 | // Serial.println(valX-10); 85 | // Serial.println(valY-20); 86 | sAngle0_offset = map(1000-valY, 0, 1000, 0, 180); 87 | sAngle1_offset = map(1000-valX, 0, 1000, 0, 180); 88 | sAngle2_offset = map(valX/2, 0, 1000, 0, 180); 89 | sAngle90_offset = 0; 90 | sAngle2_offset = sAngle2_offset + 100; 91 | setServoAngle(0, sAngle0_offset); 92 | setServoAngle(1, sAngle1_offset); 93 | setServoAngle(2, sAngle2_offset); 94 | setServoAngle(3, sAngle90_offset); 95 | Serial.println(atan(1.0)*180/PI); 96 | delay(1000); 97 | } 98 | 99 | void loop() { 100 | valB = digitalRead(Bpin); 101 | valX = analogRead(Xpin); 102 | valY = analogRead(Ypin); 103 | 104 | // sAngle0 = map(1000-valY, 0, 1000, 0, 180); 105 | // sAngle1 = map(1000-valX, 0, 1000, 0, 180); 106 | // sAngle2 = map(valX/2, 0, 1000, 0, 180); 107 | // // Serial.println(sAngle0); 108 | // setServoAngle(0, sAngle0); 109 | // setServoAngle(1, sAngle1); 110 | // setServoAngle(2, sAngle2+100); 111 | 112 | sAngle0 = map(valY, 0, 1000, 0, 300); 113 | sAngle1 = map(valX, 0, 1000, 0, 290); 114 | 115 | pos_to_angle (&horzA,&vertA, sAngle0, sAngle1); 116 | Serial.println(vertA*180/PI); 117 | setServoAngle(1, sAngle1_offset + vertA*180/PI); 118 | setServoAngle(2, sAngle2_offset + horzA*180/PI); 119 | 120 | if(valB == 1){ 121 | setServoAngle(3, 40); 122 | } 123 | else 124 | { 125 | setServoAngle(3, 170); 126 | } 127 | delay(20); 128 | } 129 | 130 | void setServoAngle(uint8_t n, float angle) { 131 | double pulse = angle; 132 | pulse = pulse/90 + 0.5; 133 | setServoPulse(n,pulse); 134 | } 135 | 136 | void pos_to_angle (double * horz_angle,double * vert_angle,double radius,double height) 137 | { 138 | double alpha1 = atan(height/radius); 139 | double bf_2 = radius * radius + height * height; 140 | double alpha2 = acos((bf_2 + L1 * L1 - L5 * L5)/( 2 * sqrt(bf_2)* L1)); 141 | * horz_angle = PI/2 - (alpha1 + alpha2); 142 | double beta2 = acos((L1 * L1 + L5 * L5-bf_2)/(2 * L1 * L5)); 143 | * vert_angle = PI - beta2 - alpha1 - alpha2; 144 | } -------------------------------------------------------------------------------- /examples/Peripheral/hid_mouse/hid_mouse.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | #include 15 | 16 | BLEDis bledis; 17 | BLEHidAdafruit blehid; 18 | 19 | #define MOVE_STEP 10 20 | 21 | void setup() 22 | { 23 | Serial.begin(115200); 24 | while ( !Serial ) delay(10); // for nrf52840 with native usb 25 | 26 | Serial.println("Bluefruit52 HID Mouse Example"); 27 | Serial.println("-----------------------------\n"); 28 | Serial.println("Go to your phone's Bluetooth settings to pair your device"); 29 | Serial.println("then open an application that accepts mouse input"); 30 | Serial.println(); 31 | 32 | Serial.println("Enter following characters"); 33 | Serial.println("- 'WASD' to move mouse (up, left, down, right)"); 34 | Serial.println("- 'LRMBF' to press mouse button(s) (left, right, middle, backward, forward)"); 35 | Serial.println("- 'X' to release mouse button(s)"); 36 | 37 | Bluefruit.begin(); 38 | // HID Device can have a min connection interval of 9*1.25 = 11.25 ms 39 | Bluefruit.Periph.setConnInterval(9, 16); // min = 9*1.25=11.25 ms, max = 16*1.25=20ms 40 | Bluefruit.setTxPower(4); // Check bluefruit.h for supported values 41 | Bluefruit.setName("Bluefruit52"); 42 | 43 | // Configure and Start Device Information Service 44 | bledis.setManufacturer("Adafruit Industries"); 45 | bledis.setModel("Bluefruit Feather 52"); 46 | bledis.begin(); 47 | 48 | // BLE HID 49 | blehid.begin(); 50 | 51 | // Set up and start advertising 52 | startAdv(); 53 | } 54 | 55 | void startAdv(void) 56 | { 57 | // Advertising packet 58 | Bluefruit.Advertising.addFlags(BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE); 59 | Bluefruit.Advertising.addTxPower(); 60 | Bluefruit.Advertising.addAppearance(BLE_APPEARANCE_HID_MOUSE); 61 | 62 | // Include BLE HID service 63 | Bluefruit.Advertising.addService(blehid); 64 | 65 | // There is enough room for 'Name' in the advertising packet 66 | Bluefruit.Advertising.addName(); 67 | 68 | /* Start Advertising 69 | * - Enable auto advertising if disconnected 70 | * - Interval: fast mode = 20 ms, slow mode = 152.5 ms 71 | * - Timeout for fast mode is 30 seconds 72 | * - Start(timeout) with timeout = 0 will advertise forever (until connected) 73 | * 74 | * For recommended advertising interval 75 | * https://developer.apple.com/library/content/qa/qa1931/_index.html 76 | */ 77 | Bluefruit.Advertising.restartOnDisconnect(true); 78 | Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms 79 | Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode 80 | Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds 81 | } 82 | 83 | void loop() 84 | { 85 | if (Serial.available()) 86 | { 87 | char ch = (char) Serial.read(); 88 | 89 | // convert to upper case 90 | ch = (char) toupper(ch); 91 | 92 | // echo 93 | Serial.println(ch); 94 | 95 | switch(ch) 96 | { 97 | // WASD to move the mouse 98 | case 'W': 99 | blehid.mouseMove(0, -MOVE_STEP); 100 | break; 101 | 102 | case 'A': 103 | blehid.mouseMove(-MOVE_STEP, 0); 104 | break; 105 | 106 | case 'S': 107 | blehid.mouseMove(0, MOVE_STEP); 108 | break; 109 | 110 | case 'D': 111 | blehid.mouseMove(MOVE_STEP, 0); 112 | break; 113 | 114 | // LRMBF for mouse button(s) 115 | case 'L': 116 | blehid.mouseButtonPress(MOUSE_BUTTON_LEFT); 117 | break; 118 | 119 | case 'R': 120 | blehid.mouseButtonPress(MOUSE_BUTTON_RIGHT); 121 | break; 122 | 123 | case 'M': 124 | blehid.mouseButtonPress(MOUSE_BUTTON_MIDDLE); 125 | break; 126 | 127 | case 'B': 128 | blehid.mouseButtonPress(MOUSE_BUTTON_BACKWARD); 129 | break; 130 | 131 | case 'F': 132 | // This key is not always supported by every OS 133 | blehid.mouseButtonPress(MOUSE_BUTTON_FORWARD); 134 | break; 135 | 136 | case 'X': 137 | // X to release all buttons 138 | blehid.mouseButtonRelease(); 139 | break; 140 | 141 | default: break; 142 | } 143 | } 144 | } 145 | 146 | -------------------------------------------------------------------------------- /examples/Peripheral/hid_camerashutter/hid_camerashutter.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | 15 | /* 16 | * This sketch uses the HID Consumer Key API to send the Volume Down 17 | * key when PIN_SHUTTER is grounded. This will cause your mobile device 18 | * to capture a photo when you are in the camera app 19 | */ 20 | #include 21 | 22 | BLEDis bledis; 23 | BLEHidAdafruit blehid; 24 | 25 | #define PIN_SHUTTER A0 26 | 27 | void setup() 28 | { 29 | pinMode(PIN_SHUTTER, INPUT_PULLUP); 30 | 31 | Serial.begin(115200); 32 | while ( !Serial ) delay(10); // for nrf52840 with native usb 33 | 34 | Serial.println("Bluefruit52 HID Camera Shutter Example"); 35 | Serial.println("--------------------------------------\n"); 36 | 37 | Serial.println(); 38 | Serial.println("Go to your phone's Bluetooth settings to pair your device"); 39 | Serial.println("then open the camera application"); 40 | 41 | Serial.println(); 42 | Serial.printf("Set pin %d to GND to capture a photo\n", PIN_SHUTTER); 43 | Serial.println(); 44 | 45 | Bluefruit.begin(); 46 | Bluefruit.setTxPower(4); // Check bluefruit.h for supported values 47 | Bluefruit.setName("Bluefruit52"); 48 | 49 | // Configure and start DIS (Device Information Service) 50 | bledis.setManufacturer("Adafruit Industries"); 51 | bledis.setModel("Bluefruit Feather 52"); 52 | bledis.begin(); 53 | 54 | /* Start BLE HID 55 | * Note: Apple requires BLE devices to have a min connection interval >= 20m 56 | * (The smaller the connection interval the faster we can send data). 57 | * However, for HID and MIDI device Apple will accept a min connection 58 | * interval as low as 11.25 ms. Therefore BLEHidAdafruit::begin() will try to 59 | * set the min and max connection interval to 11.25 ms and 15 ms respectively 60 | * for the best performance. 61 | */ 62 | blehid.begin(); 63 | 64 | /* Set connection interval (min, max) to your perferred value. 65 | * Note: It is already set by BLEHidAdafruit::begin() to 11.25ms - 15ms 66 | * min = 9*1.25=11.25 ms, max = 12*1.25= 15 ms 67 | */ 68 | /* Bluefruit.Periph.setConnInterval(9, 12); */ 69 | 70 | // Set up and start advertising 71 | startAdv(); 72 | } 73 | 74 | void startAdv(void) 75 | { 76 | // Advertising packet 77 | Bluefruit.Advertising.addFlags(BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE); 78 | Bluefruit.Advertising.addTxPower(); 79 | Bluefruit.Advertising.addAppearance(BLE_APPEARANCE_HID_KEYBOARD); 80 | 81 | // Include BLE HID service 82 | Bluefruit.Advertising.addService(blehid); 83 | 84 | // There is enough room for the dev name in the advertising packet 85 | Bluefruit.Advertising.addName(); 86 | 87 | /* Start Advertising 88 | * - Enable auto advertising if disconnected 89 | * - Interval: fast mode = 20 ms, slow mode = 152.5 ms 90 | * - Timeout for fast mode is 30 seconds 91 | * - Start(timeout) with timeout = 0 will advertise forever (until connected) 92 | * 93 | * For recommended advertising interval 94 | * https://developer.apple.com/library/content/qa/qa1931/_index.html 95 | */ 96 | Bluefruit.Advertising.restartOnDisconnect(true); 97 | Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms 98 | Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode 99 | Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds 100 | } 101 | 102 | void loop() 103 | { 104 | // Make sure you are connected and bonded/paired 105 | if ( Bluefruit.connected() && Bluefruit.connPaired() ) 106 | { 107 | // Check if pin GND'ed 108 | if ( digitalRead(PIN_SHUTTER) == 0 ) 109 | { 110 | // Turn on red LED when we start sending data 111 | digitalWrite(LED_RED, 1); 112 | 113 | // Send the 'volume down' key press 114 | // Check BLEHidGeneric.h for a list of valid consumer usage codes 115 | blehid.consumerKeyPress(HID_USAGE_CONSUMER_VOLUME_DECREMENT); 116 | 117 | // Delay a bit between reports 118 | delay(10); 119 | 120 | // Send key release 121 | blehid.consumerKeyRelease(); 122 | 123 | // Turn off the red LED 124 | digitalWrite(LED_RED, 0); 125 | 126 | // Delay to avoid constant capturing 127 | delay(500); 128 | } 129 | } 130 | } 131 | -------------------------------------------------------------------------------- /examples/Peripheral/hid_keyboard/hid_keyboard.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | #include 15 | 16 | BLEDis bledis; 17 | BLEHidAdafruit blehid; 18 | 19 | bool hasKeyPressed = false; 20 | 21 | void setup() 22 | { 23 | Serial.begin(115200); 24 | while ( !Serial ) delay(10); // for nrf52840 with native usb 25 | 26 | Serial.println("Bluefruit52 HID Keyboard Example"); 27 | Serial.println("--------------------------------\n"); 28 | 29 | Serial.println(); 30 | Serial.println("Go to your phone's Bluetooth settings to pair your device"); 31 | Serial.println("then open an application that accepts keyboard input"); 32 | 33 | Serial.println(); 34 | Serial.println("Enter the character(s) to send:"); 35 | Serial.println(); 36 | 37 | Bluefruit.begin(); 38 | Bluefruit.setTxPower(4); // Check bluefruit.h for supported values 39 | Bluefruit.setName("Bluefruit52"); 40 | 41 | // Configure and Start Device Information Service 42 | bledis.setManufacturer("Adafruit Industries"); 43 | bledis.setModel("Bluefruit Feather 52"); 44 | bledis.begin(); 45 | 46 | /* Start BLE HID 47 | * Note: Apple requires BLE device must have min connection interval >= 20m 48 | * ( The smaller the connection interval the faster we could send data). 49 | * However for HID and MIDI device, Apple could accept min connection interval 50 | * up to 11.25 ms. Therefore BLEHidAdafruit::begin() will try to set the min and max 51 | * connection interval to 11.25 ms and 15 ms respectively for best performance. 52 | */ 53 | blehid.begin(); 54 | 55 | // Set callback for set LED from central 56 | blehid.setKeyboardLedCallback(set_keyboard_led); 57 | 58 | /* Set connection interval (min, max) to your perferred value. 59 | * Note: It is already set by BLEHidAdafruit::begin() to 11.25ms - 15ms 60 | * min = 9*1.25=11.25 ms, max = 12*1.25= 15 ms 61 | */ 62 | /* Bluefruit.Periph.setConnInterval(9, 12); */ 63 | 64 | // Set up and start advertising 65 | startAdv(); 66 | } 67 | 68 | void startAdv(void) 69 | { 70 | // Advertising packet 71 | Bluefruit.Advertising.addFlags(BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE); 72 | Bluefruit.Advertising.addTxPower(); 73 | Bluefruit.Advertising.addAppearance(BLE_APPEARANCE_HID_KEYBOARD); 74 | 75 | // Include BLE HID service 76 | Bluefruit.Advertising.addService(blehid); 77 | 78 | // There is enough room for the dev name in the advertising packet 79 | Bluefruit.Advertising.addName(); 80 | 81 | /* Start Advertising 82 | * - Enable auto advertising if disconnected 83 | * - Interval: fast mode = 20 ms, slow mode = 152.5 ms 84 | * - Timeout for fast mode is 30 seconds 85 | * - Start(timeout) with timeout = 0 will advertise forever (until connected) 86 | * 87 | * For recommended advertising interval 88 | * https://developer.apple.com/library/content/qa/qa1931/_index.html 89 | */ 90 | Bluefruit.Advertising.restartOnDisconnect(true); 91 | Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms 92 | Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode 93 | Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds 94 | } 95 | 96 | void loop() 97 | { 98 | // Only send KeyRelease if previously pressed to avoid sending 99 | // multiple keyRelease reports (that consume memory and bandwidth) 100 | if ( hasKeyPressed ) 101 | { 102 | hasKeyPressed = false; 103 | blehid.keyRelease(); 104 | 105 | // Delay a bit after a report 106 | delay(5); 107 | } 108 | 109 | if (Serial.available()) 110 | { 111 | char ch = (char) Serial.read(); 112 | 113 | // echo 114 | Serial.write(ch); 115 | 116 | blehid.keyPress(ch); 117 | hasKeyPressed = true; 118 | 119 | // Delay a bit after a report 120 | delay(5); 121 | } 122 | } 123 | 124 | /** 125 | * Callback invoked when received Set LED from central. 126 | * Must be set previously with setKeyboardLedCallback() 127 | * 128 | * The LED bit map is as follows: (also defined by KEYBOARD_LED_* ) 129 | * Kana (4) | Compose (3) | ScrollLock (2) | CapsLock (1) | Numlock (0) 130 | */ 131 | void set_keyboard_led(uint16_t conn_handle, uint8_t led_bitmap) 132 | { 133 | (void) conn_handle; 134 | 135 | // light up Red Led if any bits is set 136 | if ( led_bitmap ) 137 | { 138 | ledOn( LED_RED ); 139 | } 140 | else 141 | { 142 | ledOff( LED_RED ); 143 | } 144 | } 145 | -------------------------------------------------------------------------------- /examples/Display/TFT_ArcFill/TFT_ArcFill.ino: -------------------------------------------------------------------------------- 1 | // Demo using arcFill to draw ellipses and a segmented elipse 2 | #include 3 | 4 | #define DEG2RAD 0.0174532925 5 | 6 | #define LOOP_DELAY 10 // Loop delay to slow things down 7 | 8 | byte inc = 0; 9 | unsigned int col = 0; 10 | 11 | byte red = 31; // Red is the top 5 bits of a 16 bit colour value 12 | byte green = 0;// Green is the middle 6 bits 13 | byte blue = 0; // Blue is the bottom 5 bits 14 | byte state = 0; 15 | 16 | void setup(void) { 17 | BF52.begin(true, true, false); 18 | 19 | // BF52.Lcd.setRotation(1); 20 | 21 | BF52.Lcd.fillScreen(BLACK); 22 | 23 | } 24 | 25 | 26 | void loop() { 27 | 28 | // Continuous elliptical arc drawing 29 | fillArc(120, 68, inc * 6, 1, 100, 60, 10, rainbow(col)); 30 | 31 | // Continuous segmented (inc*2) elliptical arc drawing 32 | fillArc(120, 68, ((inc * 2) % 60) * 6, 1, 100, 60, 30, rainbow(col)); 33 | 34 | // Circle drawing using arc with arc width = radius 35 | fillArc(120, 68, inc * 6, 1, 30, 30, 42, rainbow(col)); 36 | 37 | inc++; 38 | col += 1; 39 | if (col > 191) col = 0; 40 | if (inc > 59) inc = 0; 41 | 42 | delay(LOOP_DELAY); 43 | } 44 | 45 | 46 | // ######################################################################### 47 | // Draw a circular or elliptical arc with a defined thickness 48 | // ######################################################################### 49 | 50 | // x,y == coords of centre of arc 51 | // start_angle = 0 - 359 52 | // seg_count = number of 6 degree segments to draw (60 => 360 degree arc) 53 | // rx = x axis outer radius 54 | // ry = y axis outer radius 55 | // w = width (thickness) of arc in pixels 56 | // colour = 16 bit colour value 57 | // Note if rx and ry are the same then an arc of a circle is drawn 58 | 59 | int fillArc(int x, int y, int start_angle, int seg_count, int rx, int ry, int w, unsigned int colour) 60 | { 61 | 62 | byte seg = 6; // Segments are 3 degrees wide = 120 segments for 360 degrees 63 | byte inc = 6; // Draw segments every 3 degrees, increase to 6 for segmented ring 64 | 65 | // Calculate first pair of coordinates for segment start 66 | float sx = cos((start_angle - 90) * DEG2RAD); 67 | float sy = sin((start_angle - 90) * DEG2RAD); 68 | uint16_t x0 = sx * (rx - w) + x; 69 | uint16_t y0 = sy * (ry - w) + y; 70 | uint16_t x1 = sx * rx + x; 71 | uint16_t y1 = sy * ry + y; 72 | 73 | // Draw colour blocks every inc degrees 74 | for (int i = start_angle; i < start_angle + seg * seg_count; i += inc) { 75 | 76 | // Calculate pair of coordinates for segment end 77 | float sx2 = cos((i + seg - 90) * DEG2RAD); 78 | float sy2 = sin((i + seg - 90) * DEG2RAD); 79 | int x2 = sx2 * (rx - w) + x; 80 | int y2 = sy2 * (ry - w) + y; 81 | int x3 = sx2 * rx + x; 82 | int y3 = sy2 * ry + y; 83 | 84 | BF52.Lcd.fillTriangle(x0, y0, x1, y1, x2, y2, colour); 85 | BF52.Lcd.fillTriangle(x1, y1, x2, y2, x3, y3, colour); 86 | 87 | // Copy segment end to sgement start for next segment 88 | x0 = x2; 89 | y0 = y2; 90 | x1 = x3; 91 | y1 = y3; 92 | } 93 | } 94 | 95 | // ######################################################################### 96 | // Return the 16 bit colour with brightness 0-100% 97 | // ######################################################################### 98 | unsigned int brightness(unsigned int colour, int brightness) 99 | { 100 | byte red = colour >> 11; 101 | byte green = (colour & 0x7E0) >> 5; 102 | byte blue = colour & 0x1F; 103 | 104 | blue = (blue * brightness) / 100; 105 | green = (green * brightness) / 100; 106 | red = (red * brightness) / 100; 107 | 108 | return (red << 11) + (green << 5) + blue; 109 | } 110 | 111 | // ######################################################################### 112 | // Return a 16 bit rainbow colour 113 | // ######################################################################### 114 | unsigned int rainbow(byte value) 115 | { 116 | // Value is expected to be in range 0-127 117 | // The value is converted to a spectrum colour from 0 = blue through to 127 = red 118 | 119 | switch (state) { 120 | case 0: 121 | green ++; 122 | if (green == 64) { 123 | green = 63; 124 | state = 1; 125 | } 126 | break; 127 | case 1: 128 | red--; 129 | if (red == 255) { 130 | red = 0; 131 | state = 2; 132 | } 133 | break; 134 | case 2: 135 | blue ++; 136 | if (blue == 32) { 137 | blue = 31; 138 | state = 3; 139 | } 140 | break; 141 | case 3: 142 | green --; 143 | if (green == 255) { 144 | green = 0; 145 | state = 4; 146 | } 147 | break; 148 | case 4: 149 | red ++; 150 | if (red == 32) { 151 | red = 31; 152 | state = 5; 153 | } 154 | break; 155 | case 5: 156 | blue --; 157 | if (blue == 255) { 158 | blue = 0; 159 | state = 0; 160 | } 161 | break; 162 | } 163 | return red << 11 | green << 5 | blue; 164 | } 165 | 166 | -------------------------------------------------------------------------------- /examples/Display/TFT_Clock/TFT_Clock.ino: -------------------------------------------------------------------------------- 1 | /* 2 | An example analogue clock using a TFT LCD screen to show the time 3 | use of some of the drawing commands with the library. 4 | 5 | For a more accurate clock, it would be better to use the RTClib library. 6 | But this is just a demo. 7 | 8 | This sketch uses font 4 only. 9 | 10 | Make sure all the display driver and pin comnenctions are correct by 11 | editting the User_Setup.h file in the eSPI library folder. 12 | 13 | ######################################################################### 14 | ###### DON'T FORGET TO UPDATE THE User_Setup.h FILE IN THE LIBRARY ###### 15 | ######################################################################### 16 | 17 | Based on a sketch by Gilchrist 6/2/2014 1.0 18 | */ 19 | 20 | #include 21 | 22 | #define GREY 0x5AEB 23 | 24 | float sx = 0, sy = 1, mx = 1, my = 0, hx = -1, hy = 0; // Saved H, M, S x & y multipliers 25 | float sdeg=0, mdeg=0, hdeg=0; 26 | uint16_t osx=67, osy=67, omx=67, omy=67, ohx=67, ohy=67; // Saved H, M, S x & y coords 27 | uint16_t x0=0, x1=0, yy0=0, yy1=0; 28 | uint32_t targetTime = 0; // for next 1 second timeout 29 | 30 | static uint8_t conv2d(const char* p); // Forward declaration needed for IDE 1.6.x 31 | uint8_t hh=conv2d(__TIME__), mm=conv2d(__TIME__+3), ss=conv2d(__TIME__+6); // Get H, M, S from compile time 32 | 33 | boolean initial = 1; 34 | 35 | void setup(void) { 36 | BF52.begin(true, true, false); 37 | // BF52.Lcd.setRotation(0); 38 | 39 | //BF52.Lcd.fillScreen(BLACK); 40 | //BF52.Lcd.fillScreen(RED); 41 | //BF52.Lcd.fillScreen(GREEN); 42 | //BF52.Lcd.fillScreen(BLUE); 43 | //BF52.Lcd.fillScreen(BLACK); 44 | BF52.Lcd.fillScreen(GREY); 45 | 46 | BF52.Lcd.setTextColor(WHITE, GREY); // Adding a background colour erases previous text automatically 47 | 48 | // Draw clock face 49 | BF52.Lcd.fillCircle(120, 67, 66, GREEN); 50 | BF52.Lcd.fillCircle(120, 67, 60, BLACK); 51 | 52 | // Draw 12 lines 53 | for(int i = 0; i<360; i+= 30) { 54 | sx = cos((i-90)*0.0174532925); 55 | sy = sin((i-90)*0.0174532925); 56 | x0 = sx*57+120; 57 | yy0 = sy*57+67; 58 | x1 = sx*50+120; 59 | yy1 = sy*50+67; 60 | 61 | BF52.Lcd.drawLine(x0, yy0, x1, yy1, GREEN); 62 | } 63 | 64 | // Draw 60 dots 65 | for(int i = 0; i<360; i+= 6) { 66 | sx = cos((i-90)*0.0174532925); 67 | sy = sin((i-90)*0.0174532925); 68 | x0 = sx*51+120; 69 | yy0 = sy*51+67; 70 | // Draw minute markers 71 | BF52.Lcd.drawPixel(x0, yy0, WHITE); 72 | 73 | // Draw main quadrant dots 74 | if(i==0 || i==180) BF52.Lcd.fillCircle(x0, yy0, 2, WHITE); 75 | if(i==90 || i==270) BF52.Lcd.fillCircle(x0, yy0, 2, WHITE); 76 | } 77 | 78 | BF52.Lcd.fillCircle(67, 68, 3, WHITE); 79 | 80 | // Draw text at position 120,260 using fonts 4 81 | // Only font numbers 2,4,6,7 are valid. Font 6 only contains characters [space] 0 1 2 3 4 5 6 7 8 9 : . - a p m 82 | // Font 7 is a 7 segment font and only contains characters [space] 0 1 2 3 4 5 6 7 8 9 : . 83 | 84 | targetTime = millis() + 1000; 85 | } 86 | 87 | void loop() { 88 | if (targetTime < millis()) { 89 | targetTime += 1000; 90 | ss++; // Advance second 91 | if (ss==60) { 92 | ss=0; 93 | mm++; // Advance minute 94 | if(mm>59) { 95 | mm=0; 96 | hh++; // Advance hour 97 | if (hh>23) { 98 | hh=0; 99 | } 100 | } 101 | } 102 | 103 | // Pre-compute hand degrees, x & y coords for a fast screen update 104 | sdeg = ss*6; // 0-59 -> 0-354 105 | mdeg = mm*6+sdeg*0.01666667; // 0-59 -> 0-360 - includes seconds 106 | hdeg = hh*30+mdeg*0.0833333; // 0-11 -> 0-360 - includes minutes and seconds 107 | hx = cos((hdeg-90)*0.0174532925); 108 | hy = sin((hdeg-90)*0.0174532925); 109 | mx = cos((mdeg-90)*0.0174532925); 110 | my = sin((mdeg-90)*0.0174532925); 111 | sx = cos((sdeg-90)*0.0174532925); 112 | sy = sin((sdeg-90)*0.0174532925); 113 | 114 | if (ss==0 || initial) { 115 | initial = 0; 116 | // Erase hour and minute hand positions every minute 117 | BF52.Lcd.drawLine(ohx, ohy, 120, 67, BLACK); 118 | ohx = hx*34+121; 119 | ohy = hy*34+67; 120 | BF52.Lcd.drawLine(omx, omy, 120, 67, BLACK); 121 | omx = mx*46+120; 122 | omy = my*46+67; 123 | } 124 | 125 | // Redraw new hand positions, hour and minute hands not erased here to avoid flicker 126 | BF52.Lcd.drawLine(osx, osy, 120, 67, BLACK); 127 | osx = sx*46+121; 128 | osy = sy*46+67; 129 | BF52.Lcd.drawLine(osx, osy, 120, 67, RED); 130 | BF52.Lcd.drawLine(ohx, ohy, 120, 67, WHITE); 131 | BF52.Lcd.drawLine(omx, omy, 120, 67, WHITE); 132 | BF52.Lcd.drawLine(osx, osy, 120, 67, RED); 133 | 134 | BF52.Lcd.fillCircle(120, 67, 3, RED); 135 | } 136 | } 137 | 138 | static uint8_t conv2d(const char* p) { 139 | uint8_t v = 0; 140 | if ('0' <= *p && *p <= '9') 141 | v = *p - '0'; 142 | return 10 * v + *++p - '0'; 143 | } 144 | 145 | -------------------------------------------------------------------------------- /src/bluefruit52.cpp: -------------------------------------------------------------------------------- 1 | /**************************************************************************/ 2 | /*! 3 | @file bluefruit52.cpp 4 | @author Afantor 5 | 6 | @section LICENSE 7 | 8 | Software License Agreement (BSD License) 9 | 10 | Copyright (c) 2019, Afantor Industries. 11 | All rights reserved. 12 | 13 | Redistribution and use in source and binary forms, with or without 14 | modification, are permitted provided that the following conditions are met: 15 | 1. Redistributions of source code must retain the above copyright 16 | notice, this list of conditions and the following disclaimer. 17 | 2. Redistributions in binary form must reproduce the above copyright 18 | notice, this list of conditions and the following disclaimer in the 19 | documentation and/or other materials provided with the distribution. 20 | 3. Neither the name of the copyright holders nor the 21 | names of its contributors may be used to endorse or promote products 22 | derived from this software without specific prior written permission. 23 | 24 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY 25 | EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 26 | WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 27 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY 28 | DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 29 | (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 30 | LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 31 | ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 32 | (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 33 | SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 34 | */ 35 | /**************************************************************************/ 36 | 37 | #include "bluefruit52.h" 38 | 39 | AfantorBluefruit52 Bluefruit52; 40 | 41 | /** 42 | * Constructor 43 | */ 44 | AfantorBluefruit52::AfantorBluefruit52(void):isInited(0){ 45 | 46 | } 47 | 48 | void AfantorBluefruit52::begin(bool SerialEnable, bool LCDEnable, bool IMUEnable) { 49 | 50 | // Correct init once 51 | if (isInited) return; 52 | else isInited = true; 53 | 54 | // UART 55 | if (SerialEnable) { 56 | Serial.begin(115200); 57 | Serial.flush(); 58 | delay(50); 59 | Serial.println("Bluefruit52 initializing..."); 60 | } 61 | 62 | // LCD INIT 63 | if (LCDEnable) { 64 | pinMode(LCD_CS_PIN, OUTPUT); 65 | Lcd.showEnable(); 66 | Lcd.init(240, 135); // initialize a ST7789 chip, 135x240 pixels 67 | Lcd.setRotation(1); 68 | Lcd.fillScreen(BLACK); 69 | delay(50); 70 | Lcd.setTextWrap(false); 71 | Lcd.fillScreen(BLACK); 72 | Lcd.setCursor(0, 0); 73 | Lcd.setTextColor(RED); 74 | Lcd.setTextSize(2); 75 | Lcd.println(" Hello Master!"); 76 | Lcd.setTextColor(WHITE); 77 | Lcd.setTextSize(2); 78 | Lcd.println("Wellcome to BLE."); 79 | Lcd.setTextColor(YELLOW); 80 | Lcd.setTextSize(1); 81 | Lcd.println("Hello Master, Welcome to the Bluetooth"); 82 | Lcd.setTextColor(GREEN); 83 | Lcd.setTextSize(1); 84 | Lcd.println("5.0 board, you can connect "); 85 | Lcd.setTextColor(BLUE); 86 | Lcd.setTextSize(1); 87 | Lcd.println("everything with Bluetooth."); 88 | Lcd.setTextColor(RED); 89 | Lcd.setTextSize(2); 90 | Lcd.println(" initializing......"); 91 | delay(500); 92 | } 93 | 94 | // I2C init 95 | Wire.begin(); 96 | delay(10); 97 | 98 | //BMI160 init 99 | if (IMUEnable) 100 | { 101 | Serial.println("BMI160 6-DOF 16-bit motion sensor 60 ug LSB!"); 102 | 103 | // initialize device 104 | Serial.println("Initializing IMU device..."); 105 | 106 | IMU.begin(BMI160GenClass::I2C_MODE, 0x69, 30); 107 | uint8_t dev_id = IMU.getDeviceID(); 108 | Serial.print("DEVICE ID: 0x"); 109 | Serial.println(dev_id, HEX); 110 | if (dev_id == 0xd1 ) 111 | { 112 | Serial.println("BMI160 device Online..."); 113 | } 114 | else 115 | { 116 | while(1) // Loop forever if communication doesn't happen 117 | { 118 | Serial.println("Could not connect to BMI160: 0xD1"); 119 | Serial.println("Please check if the hardware device is damaged."); 120 | } 121 | } 122 | 123 | // Set the accelerometer range to 2000 degrees/second 124 | IMU.setGyroRate(3200); 125 | IMU.setGyroRange(2000); 126 | // Set the accelerometer range to 2000 degrees/second 127 | IMU.setAccelerometerRate(1600); 128 | IMU.setAccelerometerRange(2); 129 | Serial.println("Initializing IMU device...done."); 130 | } 131 | 132 | if (LCDEnable) { 133 | Lcd.setTextColor(RED); 134 | Lcd.setTextSize(2); 135 | Lcd.println(" Initialize Done!"); 136 | delay(100); 137 | } 138 | if (SerialEnable) { 139 | Serial.println("Initialize Done!"); 140 | } 141 | } 142 | 143 | void AfantorBluefruit52::update() { 144 | 145 | //Button update 146 | BtnA.read(); 147 | BtnB.read(); 148 | 149 | } -------------------------------------------------------------------------------- /src/pca9685.cpp: -------------------------------------------------------------------------------- 1 | /*! 2 | * @file pca9685.cpp 3 | * 4 | * @mainpage pca9685 16-channel PWM & Servo driver 5 | * 6 | * @section intro_sec Introduction 7 | * 8 | * This is a library for the 16-channel PWM & Servo driver. 9 | * 10 | * These displays use I2C to communicate, 2 pins are required to interface. 11 | * 12 | */ 13 | 14 | #include "pca9685.h" 15 | #include 16 | 17 | /*! 18 | * @brief Instantiates a new PCA9685 PWM driver chip with the I2C address on a 19 | * TwoWire interface 20 | * @param i2c A pointer to a 'Wire' compatible object that we'll use to 21 | * communicate with 22 | * @param addr The 7-bit I2C address to locate this chip, default is 0x40 23 | */ 24 | PCA9685::PCA9685(TwoWire *i2c, uint8_t addr) { 25 | _i2c = i2c; 26 | _i2caddr = addr; 27 | } 28 | 29 | /*! 30 | * @brief Setups the I2C interface and hardware 31 | */ 32 | void PCA9685::begin(void) { 33 | _i2c->begin(); 34 | reset(); 35 | // set a default frequency 36 | setPWMFreq(1000); 37 | } 38 | 39 | /*! 40 | * @brief Sends a reset command to the PCA9685 chip over I2C 41 | */ 42 | void PCA9685::reset(void) { 43 | write8(PCA9685_MODE1, 0x80); 44 | delay(10); 45 | } 46 | 47 | /*! 48 | * @brief Sets the PWM frequency for the entire chip, up to ~1.6 KHz 49 | * @param freq Floating point frequency that we will attempt to match 50 | */ 51 | void PCA9685::setPWMFreq(float freq) { 52 | #ifdef ENABLE_DEBUG_OUTPUT 53 | Serial.print("Attempting to set freq "); 54 | Serial.println(freq); 55 | #endif 56 | 57 | freq *= 58 | 0.9; // Correct for overshoot in the frequency setting (see issue #11). 59 | float prescaleval = 25000000; 60 | prescaleval /= 4096; 61 | prescaleval /= freq; 62 | prescaleval -= 1; 63 | 64 | #ifdef ENABLE_DEBUG_OUTPUT 65 | Serial.print("Estimated pre-scale: "); 66 | Serial.println(prescaleval); 67 | #endif 68 | 69 | uint8_t prescale = floor(prescaleval + 0.5); 70 | #ifdef ENABLE_DEBUG_OUTPUT 71 | Serial.print("Final pre-scale: "); 72 | Serial.println(prescale); 73 | #endif 74 | 75 | uint8_t oldmode = read8(PCA9685_MODE1); 76 | uint8_t newmode = (oldmode & 0x7F) | 0x10; // sleep 77 | write8(PCA9685_MODE1, newmode); // go to sleep 78 | write8(PCA9685_PRESCALE, prescale); // set the prescaler 79 | write8(PCA9685_MODE1, oldmode); 80 | delay(5); 81 | write8(PCA9685_MODE1, 82 | oldmode | 83 | 0xa0); // This sets the MODE1 register to turn on auto increment. 84 | 85 | #ifdef ENABLE_DEBUG_OUTPUT 86 | Serial.print("Mode now 0x"); 87 | Serial.println(read8(PCA9685_MODE1), HEX); 88 | #endif 89 | } 90 | 91 | /*! 92 | * @brief Sets the PWM output of one of the PCA9685 pins 93 | * @param num One of the PWM output pins, from 0 to 15 94 | * @param on At what point in the 4096-part cycle to turn the PWM output ON 95 | * @param off At what point in the 4096-part cycle to turn the PWM output OFF 96 | */ 97 | void PCA9685::setPWM(uint8_t num, uint16_t on, uint16_t off) { 98 | #ifdef ENABLE_DEBUG_OUTPUT 99 | Serial.print("Setting PWM "); 100 | Serial.print(num); 101 | Serial.print(": "); 102 | Serial.print(on); 103 | Serial.print("->"); 104 | Serial.println(off); 105 | #endif 106 | 107 | _i2c->beginTransmission(_i2caddr); 108 | _i2c->write(LED0_ON_L + 4 * num); 109 | _i2c->write(on); 110 | _i2c->write(on >> 8); 111 | _i2c->write(off); 112 | _i2c->write(off >> 8); 113 | _i2c->endTransmission(); 114 | } 115 | 116 | /*! 117 | * @brief Helper to set pin PWM output. Sets pin without having to deal with 118 | * on/off tick placement and properly handles a zero value as completely off and 119 | * 4095 as completely on. Optional invert parameter supports inverting the 120 | * pulse for sinking to ground. 121 | * @param num One of the PWM output pins, from 0 to 15 122 | * @param val The number of ticks out of 4096 to be active, should be a value 123 | * from 0 to 4095 inclusive. 124 | * @param invert If true, inverts the output, defaults to 'false' 125 | */ 126 | void PCA9685::setPin(uint8_t num, uint16_t val, bool invert) { 127 | // Clamp value between 0 and 4095 inclusive. 128 | val = min(val, (uint16_t)4095); 129 | if (invert) { 130 | if (val == 0) { 131 | // Special value for signal fully on. 132 | setPWM(num, 4096, 0); 133 | } else if (val == 4095) { 134 | // Special value for signal fully off. 135 | setPWM(num, 0, 4096); 136 | } else { 137 | setPWM(num, 0, 4095 - val); 138 | } 139 | } else { 140 | if (val == 4095) { 141 | // Special value for signal fully on. 142 | setPWM(num, 4096, 0); 143 | } else if (val == 0) { 144 | // Special value for signal fully off. 145 | setPWM(num, 0, 4096); 146 | } else { 147 | setPWM(num, 0, val); 148 | } 149 | } 150 | } 151 | 152 | uint8_t PCA9685::read8(uint8_t addr) { 153 | _i2c->beginTransmission(_i2caddr); 154 | _i2c->write(addr); 155 | _i2c->endTransmission(); 156 | 157 | _i2c->requestFrom((uint8_t)_i2caddr, (uint8_t)1); 158 | return _i2c->read(); 159 | } 160 | 161 | void PCA9685::write8(uint8_t addr, uint8_t d) { 162 | _i2c->beginTransmission(_i2caddr); 163 | _i2c->write(addr); 164 | _i2c->write(d); 165 | _i2c->endTransmission(); 166 | } 167 | -------------------------------------------------------------------------------- /examples/Peripheral/bleuart/bleuart.ino: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | This is an example for our nRF52 based Bluefruit LE modules 3 | 4 | Pick one up today in the adafruit shop! 5 | 6 | Adafruit invests time and resources providing this open source code, 7 | please support Adafruit and open-source hardware by purchasing 8 | products from Adafruit! 9 | 10 | MIT license, check LICENSE for more information 11 | All text above, and the splash screen below must be included in 12 | any redistribution 13 | *********************************************************************/ 14 | #include 15 | #include 16 | #include 17 | #include 18 | // BLE Service 19 | BLEDfu bledfu; // OTA DFU service 20 | BLEDis bledis; // device information 21 | BLEUart bleuart; // uart over ble 22 | BLEBas blebas; // battery 23 | 24 | void setup() 25 | { 26 | Serial.begin(115200); 27 | 28 | Serial.println("Bluefruit52 BLEUART Example"); 29 | Serial.println("---------------------------\n"); 30 | 31 | // Setup the BLE LED to be enabled on CONNECT 32 | // Note: This is actually the default behaviour, but provided 33 | // here in case you want to control this LED manually via PIN 19 34 | Bluefruit.autoConnLed(true); 35 | 36 | // Config the peripheral connection with maximum bandwidth 37 | // more SRAM required by SoftDevice 38 | // Note: All config***() function must be called before begin() 39 | Bluefruit.configPrphBandwidth(BANDWIDTH_MAX); 40 | 41 | Bluefruit.begin(); 42 | Bluefruit.setTxPower(4); // Check bluefruit.h for supported values 43 | Bluefruit.setName("Bluefruit52"); 44 | //Bluefruit.setName(getMcuUniqueID()); // useful testing with multiple central connections 45 | Bluefruit.Periph.setConnectCallback(connect_callback); 46 | Bluefruit.Periph.setDisconnectCallback(disconnect_callback); 47 | 48 | // To be consistent OTA DFU should be added first if it exists 49 | bledfu.begin(); 50 | 51 | // Configure and Start Device Information Service 52 | bledis.setManufacturer("Adafruit Industries"); 53 | bledis.setModel("Bluefruit Feather52"); 54 | bledis.begin(); 55 | 56 | // Configure and Start BLE Uart Service 57 | bleuart.begin(); 58 | 59 | // Start BLE Battery Service 60 | blebas.begin(); 61 | blebas.write(100); 62 | 63 | // Set up and start advertising 64 | startAdv(); 65 | 66 | Serial.println("Please use Adafruit's Bluefruit LE app to connect in UART mode"); 67 | Serial.println("Once connected, enter character(s) that you wish to send"); 68 | } 69 | 70 | void startAdv(void) 71 | { 72 | // Advertising packet 73 | Bluefruit.Advertising.addFlags(BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE); 74 | Bluefruit.Advertising.addTxPower(); 75 | 76 | // Include bleuart 128-bit uuid 77 | Bluefruit.Advertising.addService(bleuart); 78 | 79 | // Secondary Scan Response packet (optional) 80 | // Since there is no room for 'Name' in Advertising packet 81 | Bluefruit.ScanResponse.addName(); 82 | 83 | /* Start Advertising 84 | * - Enable auto advertising if disconnected 85 | * - Interval: fast mode = 20 ms, slow mode = 152.5 ms 86 | * - Timeout for fast mode is 30 seconds 87 | * - Start(timeout) with timeout = 0 will advertise forever (until connected) 88 | * 89 | * For recommended advertising interval 90 | * https://developer.apple.com/library/content/qa/qa1931/_index.html 91 | */ 92 | Bluefruit.Advertising.restartOnDisconnect(true); 93 | Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms 94 | Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode 95 | Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds 96 | } 97 | 98 | void loop() 99 | { 100 | // Forward data from HW Serial to BLEUART 101 | while (Serial.available()) 102 | { 103 | // Delay to wait for enough input, since we have a limited transmission buffer 104 | delay(2); 105 | 106 | uint8_t buf[64]; 107 | int count = Serial.readBytes(buf, sizeof(buf)); 108 | bleuart.write( buf, count ); 109 | } 110 | 111 | // Forward from BLEUART to HW Serial 112 | while ( bleuart.available() ) 113 | { 114 | uint8_t ch; 115 | ch = (uint8_t) bleuart.read(); 116 | Serial.write(ch); 117 | } 118 | 119 | // Request CPU to enter low-power mode until an event/interrupt occurs 120 | //waitForEvent(); 121 | } 122 | 123 | // callback invoked when central connects 124 | void connect_callback(uint16_t conn_handle) 125 | { 126 | // Get the reference to current connection 127 | BLEConnection* connection = Bluefruit.Connection(conn_handle); 128 | 129 | char central_name[32] = { 0 }; 130 | connection->getPeerName(central_name, sizeof(central_name)); 131 | 132 | Serial.print("Connected to "); 133 | Serial.println(central_name); 134 | } 135 | 136 | /** 137 | * Callback invoked when a connection is dropped 138 | * @param conn_handle connection where this event happens 139 | * @param reason is a BLE_HCI_STATUS_CODE which can be found in ble_hci.h 140 | */ 141 | void disconnect_callback(uint16_t conn_handle, uint8_t reason) 142 | { 143 | (void) conn_handle; 144 | (void) reason; 145 | 146 | Serial.println(); 147 | Serial.println("Disconnected"); 148 | } 149 | -------------------------------------------------------------------------------- /src/utility/BMI160Gen.cpp: -------------------------------------------------------------------------------- 1 | #include "BMI160Gen.h" 2 | #include "SPI.h" 3 | #include "Wire.h" 4 | 5 | // #define DEBUG 6 | 7 | bool BMI160GenClass::begin(const int spi_cs_pin, const int intr_pin) 8 | { 9 | return begin(SPI_MODE, spi_cs_pin, intr_pin); 10 | } 11 | 12 | bool BMI160GenClass::begin(Mode mode, const int arg1, const int arg2) 13 | { 14 | this->mode = mode; 15 | switch (this->mode) { 16 | case INVALID_MODE: return false; 17 | case I2C_MODE: 18 | i2c_addr = arg1; 19 | break; 20 | case SPI_MODE: 21 | spi_ss = arg1; 22 | break; 23 | default: 24 | return false; 25 | } 26 | if (0 <= arg2) { 27 | interrupt_pin = digitalPinToInterrupt(arg2); 28 | #ifdef DEBUG 29 | Serial.print("BMI160GenClass::begin(): pin#="); 30 | Serial.print(arg2); 31 | Serial.print(" -> interrupt="); 32 | Serial.println(interrupt_pin); 33 | #endif 34 | } 35 | return CurieIMUClass::begin(); 36 | } 37 | 38 | void BMI160GenClass::attachInterrupt(void (*callback)(void)) 39 | { 40 | CurieIMUClass::attachInterrupt(NULL); 41 | if (0 <= interrupt_pin) { 42 | ::attachInterrupt(interrupt_pin, callback, FALLING); 43 | } else { 44 | Serial.println("BMI160GenClass::attachInterrupt: No valid interruption pin."); 45 | } 46 | } 47 | 48 | void BMI160GenClass::ss_init() 49 | { 50 | switch (this->mode) { 51 | case I2C_MODE: 52 | i2c_init(); 53 | break; 54 | case SPI_MODE: 55 | spi_init(); 56 | break; 57 | default: 58 | break; 59 | } 60 | } 61 | 62 | int BMI160GenClass::ss_xfer(uint8_t *buf, unsigned tx_cnt, unsigned rx_cnt) 63 | { 64 | switch (this->mode) { 65 | case I2C_MODE: 66 | return i2c_xfer(buf, tx_cnt, rx_cnt); 67 | case SPI_MODE: 68 | if (rx_cnt) /* For read transfers, assume 1st byte contains register address */ 69 | buf[0] |= (1 << BMI160_SPI_READ_BIT); 70 | return spi_xfer(buf, tx_cnt, rx_cnt); 71 | default: 72 | return 0; 73 | } 74 | } 75 | 76 | void BMI160GenClass::i2c_init() 77 | { 78 | #ifdef DEBUG 79 | Serial.println("BMI160GenClass::i2c_init()..."); 80 | #endif // DEBUG 81 | 82 | Wire.begin(); 83 | Wire.beginTransmission(i2c_addr); 84 | if( Wire.endTransmission() != 0 ) 85 | Serial.println("BMI160GenClass::i2c_init(): I2C failed."); 86 | 87 | #ifdef DEBUG 88 | int id = getDeviceID(); 89 | Serial.print("BMI160GenClass::i2c_init(): CHIP ID = 0x"); 90 | Serial.println(id, HEX); 91 | Serial.println("BMI160GenClass::i2c_init()...done"); 92 | #endif // DEBUG 93 | } 94 | 95 | int BMI160GenClass::i2c_xfer(uint8_t *buf, unsigned tx_cnt, unsigned rx_cnt) 96 | { 97 | uint8_t *p; 98 | 99 | #ifdef DEBUG 100 | Serial.print("i2c_xfer(offs=0x"); 101 | Serial.print(*buf, HEX); 102 | Serial.print(", tx="); 103 | Serial.print(tx_cnt); 104 | Serial.print(", rx="); 105 | Serial.print(rx_cnt); 106 | Serial.print("):"); 107 | #endif // DEBUG 108 | 109 | Wire.beginTransmission(i2c_addr); 110 | p = buf; 111 | while (0 < tx_cnt) { 112 | tx_cnt--; 113 | Wire.write(*p++); 114 | } 115 | if( Wire.endTransmission() != 0 ) { 116 | Serial.println("Wire.endTransmission() failed."); 117 | } 118 | if (0 < rx_cnt) { 119 | Wire.requestFrom(i2c_addr, rx_cnt); 120 | p = buf; 121 | while ( Wire.available() && 0 < rx_cnt) { 122 | rx_cnt--; 123 | #ifdef DEBUG 124 | int t = *p++ = Wire.read(); 125 | Serial.print(" "); 126 | Serial.print(t, HEX); 127 | #else 128 | *p++ = Wire.read();; 129 | #endif // DEBUG 130 | } 131 | } 132 | 133 | #ifdef DEBUG 134 | Serial.println(""); 135 | #endif // DEBUG 136 | 137 | return (0); 138 | } 139 | 140 | void BMI160GenClass::spi_init() 141 | { 142 | #ifdef DEBUG 143 | Serial.println("BMI160GenClass::spi_init()..."); 144 | #endif // DEBUG 145 | 146 | // start the SPI library: 147 | SPI.begin(); 148 | if (0 <= spi_ss) { 149 | pinMode(spi_ss, OUTPUT); 150 | } else { 151 | Serial.println("BMI160GenClass::spi_init(): WARNING: No chip select pin specified."); 152 | } 153 | 154 | #ifdef DEBUG 155 | Serial.println("BMI160GenClass::spi_init()...done"); 156 | #endif // DEBUG 157 | } 158 | 159 | int BMI160GenClass::spi_xfer(uint8_t *buf, unsigned tx_cnt, unsigned rx_cnt) 160 | { 161 | uint8_t *p; 162 | 163 | #ifdef DEBUG 164 | Serial.print("BMI160GenClass::spi_xfer("); 165 | Serial.print((unsigned long)buf, HEX); 166 | Serial.print("="); 167 | Serial.print(*buf, HEX); 168 | Serial.print(","); 169 | Serial.print(tx_cnt); 170 | Serial.print(","); 171 | Serial.print(rx_cnt); 172 | Serial.print("):"); 173 | #endif // DEBUG 174 | 175 | if (0 <= spi_ss) 176 | digitalWrite(spi_ss, LOW); 177 | p = buf; 178 | while (0 < tx_cnt) { 179 | tx_cnt--; 180 | SPI.transfer(*p++); 181 | } 182 | p = buf; 183 | while (0 < rx_cnt) { 184 | rx_cnt--; 185 | #ifdef DEBUG 186 | int t = *p++ = SPI.transfer(0); 187 | Serial.print(" "); 188 | Serial.print(t, HEX); 189 | #else 190 | *p++ = SPI.transfer(0); 191 | #endif // DEBUG 192 | } 193 | if (0 <= spi_ss) 194 | digitalWrite(spi_ss, HIGH); 195 | 196 | #ifdef DEBUG 197 | Serial.println(""); 198 | #endif // DEBUG 199 | 200 | return (0); 201 | } 202 | 203 | BMI160GenClass BMI160; 204 | -------------------------------------------------------------------------------- /src/utility/ST7789.h: -------------------------------------------------------------------------------- 1 | /*************************************************** 2 | This is a library for the ST7789 IPS SPI display. 3 | 4 | Written by Ananev Ilya. 5 | ****************************************************/ 6 | 7 | #ifndef _ST7789_H_ 8 | #define _ST7789_H_ 9 | 10 | #include "Arduino.h" 11 | #include "Print.h" 12 | #include "Afantor_GFX.h" 13 | 14 | #if defined(__AVR__) || defined(CORE_TEENSY) 15 | #include 16 | #define USE_FAST_IO 17 | typedef volatile uint8_t RwReg; 18 | #elif defined(ARDUINO_STM32_FEATHER) 19 | typedef volatile uint32_t RwReg; 20 | #define USE_FAST_IO 21 | #elif defined(NRF52) || defined(NRF52_SERIES) 22 | typedef volatile uint32_t RwReg; 23 | #define USE_FAST_IO 24 | #elif defined(ARDUINO_FEATHER52) 25 | typedef volatile uint32_t RwReg; 26 | #define USE_FAST_IO 27 | #elif defined(ESP8266) 28 | #include 29 | #elif defined(__SAM3X8E__) 30 | #undef __FlashStringHelper::F(string_literal) 31 | #define F(string_literal) string_literal 32 | #include 33 | #define PROGMEM 34 | #define pgm_read_byte(addr) (*(const unsigned char *)(addr)) 35 | #define pgm_read_word(addr) (*(const unsigned short *)(addr)) 36 | typedef unsigned char prog_uchar; 37 | #endif 38 | 39 | #define ST7789_TFTWIDTH 135 40 | #define ST7789_TFTHEIGHT 240 41 | 42 | #define ST7789_135x240_XSTART 52 43 | #define ST7789_135x240_YSTART 40 44 | 45 | #define ST7789_240x135_XSTART 53 46 | #define ST7789_240x135_YSTART 40 47 | 48 | #define ST_CMD_DELAY 0x80 // special signifier for command lists 49 | 50 | #define ST7789_NOP 0x00 51 | #define ST7789_SWRESET 0x01 52 | #define ST7789_RDDID 0x04 53 | #define ST7789_RDDST 0x09 54 | 55 | #define ST7789_SLPIN 0x10 56 | #define ST7789_SLPOUT 0x11 57 | #define ST7789_PTLON 0x12 58 | #define ST7789_NORON 0x13 59 | 60 | #define ST7789_INVOFF 0x20 61 | #define ST7789_INVON 0x21 62 | #define ST7789_DISPOFF 0x28 63 | #define ST7789_DISPON 0x29 64 | #define ST7789_CASET 0x2A 65 | #define ST7789_RASET 0x2B 66 | #define ST7789_RAMWR 0x2C 67 | #define ST7789_RAMRD 0x2E 68 | 69 | #define ST7789_PTLAR 0x30 70 | #define ST7789_COLMOD 0x3A 71 | #define ST7789_MADCTL 0x36 72 | 73 | #define ST7789_MADCTL_MY 0x80 74 | #define ST7789_MADCTL_MX 0x40 75 | #define ST7789_MADCTL_MV 0x20 76 | #define ST7789_MADCTL_ML 0x10 77 | #define ST7789_MADCTL_RGB 0x00 78 | 79 | #define ST7789_RDID1 0xDA 80 | #define ST7789_RDID2 0xDB 81 | #define ST7789_RDID3 0xDC 82 | #define ST7789_RDID4 0xDD 83 | 84 | // Color definitions 85 | #define BLACK 0x0000 86 | #define BLUE 0x001F 87 | #define BRED 0xF81F 88 | #define GRED 0xFFE0 89 | #define GBLUE 0x07FF 90 | #define RED 0xF800 91 | #define GREEN 0x07E0 92 | #define CYAN 0x07FF 93 | #define MAGENTA 0xF81F 94 | #define YELLOW 0xFFE0 95 | #define WHITE 0xFFFF 96 | #define BROWN 0XBC40 //棕色 97 | #define BRRED 0XFC07 //棕红色 98 | #define GRAY 0X8430 //灰色 99 | //GUI颜色 100 | 101 | #define DARKBLUE 0X01CF //深蓝色 102 | #define LIGHTBLUE 0X7D7C //浅蓝色 103 | #define GRAYBLUE 0X5458 //灰蓝色 104 | //以上三色为PANEL的颜色 105 | 106 | #define LIGHTGREEN 0X841F //浅绿色 107 | #define LGRAY 0XC618 //浅灰色(PANNEL),窗体背景色 108 | 109 | #define LGRAYBLUE 0XA651 //浅灰蓝色(中间层颜色) 110 | #define LBBLUE 0X2B12 //浅棕蓝色(选择条目的反色) 111 | 112 | class LCD_ST7789 : public Afantor_GFX { 113 | 114 | public: 115 | 116 | LCD_ST7789(int8_t DC, int8_t RST, int8_t SID, int8_t SCLK, int8_t CS = -1); 117 | LCD_ST7789(int8_t DC, int8_t RST, int8_t CS = -1); 118 | 119 | void setAddrWindow(uint8_t x0, uint8_t y0, uint8_t x1, uint8_t y1), 120 | pushColor(uint16_t color), 121 | fillScreen(uint16_t color), 122 | drawPixel(int16_t x, int16_t y, uint16_t color), 123 | drawFastVLine(int16_t x, int16_t y, int16_t h, uint16_t color), 124 | drawFastHLine(int16_t x, int16_t y, int16_t w, uint16_t color), 125 | fillRect(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color), 126 | setRotation(uint8_t r), 127 | invertDisplay(boolean i), 128 | init(uint16_t width, uint16_t height); 129 | uint16_t Color565(uint8_t r, uint8_t g, uint8_t b); 130 | uint16_t color565(uint8_t r, uint8_t g, uint8_t b) { return Color565(r, g, b); } 131 | void showEnable(void); 132 | void showDisable(void); 133 | protected: 134 | uint8_t _colstart, _rowstart, _xstart, _ystart; // some displays need this changed 135 | 136 | void displayInit(const uint8_t *addr); 137 | void spiwrite(uint8_t), 138 | writecommand(uint8_t c), 139 | writedata(uint8_t d), 140 | commonInit(const uint8_t *cmdList); 141 | 142 | private: 143 | 144 | inline void CS_HIGH(void); 145 | inline void CS_LOW(void); 146 | inline void DC_HIGH(void); 147 | inline void DC_LOW(void); 148 | 149 | boolean _hwSPI; 150 | 151 | int8_t _cs, _dc, _rst, _sid, _sclk; 152 | 153 | #if defined(USE_FAST_IO) 154 | volatile RwReg *dataport, *clkport, *csport, *dcport; 155 | 156 | #if defined(__AVR__) || defined(CORE_TEENSY) // 8 bit! 157 | uint8_t datapinmask, clkpinmask, cspinmask, dcpinmask; 158 | #else // 32 bit! 159 | uint32_t datapinmask, clkpinmask, cspinmask, dcpinmask; 160 | #endif 161 | #endif 162 | 163 | }; 164 | 165 | #endif 166 | --------------------------------------------------------------------------------