mirror of
https://gitlab.dit.htwk-leipzig.de/phillip.kuehne/dezibot.git
synced 2025-05-18 18:41:47 +02:00
Merge branch 'release' into main
This commit is contained in:
commit
87b9fbe66f
@ -2,11 +2,15 @@ image: alpine
|
||||
|
||||
pages:
|
||||
stage: deploy
|
||||
|
||||
script:
|
||||
- apk update && apk add doxygen graphviz ttf-freefont && apk add make
|
||||
- apk update && apk add doxygen graphviz ttf-freefont && apk add make && apk add lftp
|
||||
- doxygen doxygen.txt
|
||||
- mkdir public
|
||||
- cp -r docs/html public
|
||||
- cd ./public/html
|
||||
- lftp -e "open plesk.iaccam.com; user $FTP_USERNAME $FTP_PASSWORD; mirror -X .* -X .*/ --reverse --exclude node_modules --verbose --delete ./ ./; bye"
|
||||
|
||||
|
||||
#- mv docs/html/ public/
|
||||
artifacts:
|
||||
|
1002
LICENSE.txt
1002
LICENSE.txt
File diff suppressed because it is too large
Load Diff
37
README.md
37
README.md
@ -112,6 +112,8 @@ A german documentation will be provided but does not replace the english documen
|
||||
|
||||
### Documentation
|
||||
|
||||
Documentation of the Software and Hardware can be found at https://docs.dezibot.de/
|
||||
|
||||
#### .h Files
|
||||
|
||||
```C++
|
||||
@ -148,42 +150,21 @@ For instance, in `src/Dezibot.h`, to include `src/motion/Motion.h`, you should w
|
||||
* Upload Mode: "UART0 / Hardware CDC"
|
||||
* USB Mode: "Hardware CDC and JTAG"
|
||||
* Programmer: "Esptool"
|
||||
* USB CDC on Boot: Enabled
|
||||
|
||||
Using `arduino-cli` to compile and upload:
|
||||
`arduino-cli upload /Users/jo/Documents/Arduino/theSketch -p /dev/cu.usbmodem101 -b esp32:esp32:nora_w10`
|
||||
`arduino-cli compile /Users/jo/Documents/Arduino/theSketch -p /dev/cu.usbmodem101 -b esp32:esp32:nora_w10`
|
||||
|
||||
#### Display
|
||||
##### Including Library
|
||||
|
||||
It is important to specify the SDA and SCL ports by using `Wire.begin(SDA, SCL)`.
|
||||
Arduino IDE -> Sketch -> Include Library -> add .ZIP Library -> this library
|
||||
|
||||
```c++
|
||||
#include <Wire.h>
|
||||
#include <Adafruit_SSD1306.h>
|
||||
If there is any other error like 'Painless_Mesh' not found, you have to include this library also.
|
||||
|
||||
#define SCREEN_WIDTH 128
|
||||
#define SCREEN_HEIGHT 64
|
||||
Arduino IDE -> Sketch -> Manage Library -> Search for missing Library
|
||||
|
||||
#define OLED_RESET -1
|
||||
#define SCREEN_ADDRESS 0x3C
|
||||
#### Start from Scratch
|
||||
|
||||
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, OLED_RESET);
|
||||
It is important, before using any functions of Dezibot, to call ```dezibot.begin()``` once in the setup function.
|
||||
|
||||
void Dezibot::begin(void) {
|
||||
Wire.begin(1, 2);
|
||||
if (!display.begin(SSD1306_SWITCHCAPVCC, SCREEN_ADDRESS)) {
|
||||
// Serial.println("SSD1306 allocation failed");
|
||||
for (;;); // Don't proceed, loop forever
|
||||
}
|
||||
|
||||
|
||||
// Draw a single pixel in white
|
||||
display.drawPixel(10, 10, SSD1306_WHITE);
|
||||
|
||||
// Show the display buffer on the screen. You MUST call display() after
|
||||
// drawing commands to make them visible on screen!
|
||||
display.display();
|
||||
vTaskDelay(2000);
|
||||
}
|
||||
```
|
||||
In the examples folder, a sketch ``start`` is provided, that handles the initialization.
|
25
example/Fernbedienung/empfaenger/empfaenger.ino
Normal file
25
example/Fernbedienung/empfaenger/empfaenger.ino
Normal file
@ -0,0 +1,25 @@
|
||||
#include "Dezibot.h"
|
||||
|
||||
|
||||
Dezibot dezibot = Dezibot();
|
||||
|
||||
void receivedCallback(String &msg) {
|
||||
if (msg == "vorn") {
|
||||
dezibot.motion.move();
|
||||
} else if (msg == "links") {
|
||||
dezibot.motion.rotateAntiClockwise();
|
||||
} else if (msg == "rechts") {
|
||||
dezibot.motion.rotateClockwise();
|
||||
} else if (msg == "stop") {
|
||||
dezibot.motion.stop();
|
||||
}
|
||||
}
|
||||
void setup() {
|
||||
dezibot.begin();
|
||||
dezibot.communication.begin();
|
||||
dezibot.communication.setGroupNumber(5);
|
||||
dezibot.communication.onReceive(&receivedCallback);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
}
|
46
example/Fernbedienung/sender/sender.ino
Normal file
46
example/Fernbedienung/sender/sender.ino
Normal file
@ -0,0 +1,46 @@
|
||||
#include "Dezibot.h"
|
||||
|
||||
|
||||
Dezibot dezibot = Dezibot();
|
||||
|
||||
void setup() {
|
||||
dezibot.begin();
|
||||
dezibot.communication.begin();
|
||||
dezibot.communication.setGroupNumber(5);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
switch (dezibot.motion.detection.getTiltDirection()) {
|
||||
case Front:
|
||||
dezibot.multiColorLight.setTopLeds(GREEN);
|
||||
dezibot.communication.sendMessage("vorn");
|
||||
break;
|
||||
case Left:
|
||||
dezibot.multiColorLight.setTopLeds(YELLOW);
|
||||
dezibot.communication.sendMessage("links");
|
||||
break;
|
||||
case Right:
|
||||
dezibot.multiColorLight.setTopLeds(TURQUOISE);
|
||||
dezibot.communication.sendMessage("rechts");
|
||||
break;
|
||||
case Back:
|
||||
dezibot.multiColorLight.setTopLeds(BLUE);
|
||||
dezibot.communication.sendMessage("stop");
|
||||
break;
|
||||
case Flipped:
|
||||
dezibot.multiColorLight.setTopLeds(PINK);
|
||||
dezibot.communication.sendMessage("stop");
|
||||
break;
|
||||
case Neutral:
|
||||
dezibot.multiColorLight.turnOffLed();
|
||||
dezibot.communication.sendMessage("stop");
|
||||
break;
|
||||
|
||||
case Error:
|
||||
dezibot.multiColorLight.setTopLeds(RED);
|
||||
dezibot.communication.sendMessage("stop");
|
||||
break;
|
||||
}
|
||||
|
||||
delay(100);
|
||||
}
|
@ -1,48 +0,0 @@
|
||||
#include "Dezibot.h"
|
||||
|
||||
Dezibot dezibot = Dezibot();
|
||||
const int centeredThreshold = 50 ;
|
||||
|
||||
void setup() {
|
||||
// put your setup code here, to run once:
|
||||
dezibot.begin();
|
||||
Serial.begin(115200);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
int32_t leftValue = (int32_t)dezibot.lightDetection.getAverageValue(IR_LEFT, 20, 1);
|
||||
int32_t rightValue = (int32_t)dezibot.lightDetection.getAverageValue(IR_RIGHT, 20, 1);
|
||||
switch(dezibot.lightDetection.getBrightest(IR)){
|
||||
case IR_FRONT:
|
||||
//correct Stearing to be centered
|
||||
if( abs(leftValue-rightValue)
|
||||
< centeredThreshold){
|
||||
dezibot.motion.move();
|
||||
}else{
|
||||
if (leftValue > rightValue){
|
||||
dezibot.motion.rotateAntiClockwise();
|
||||
} else{
|
||||
dezibot.motion.rotateClockwise();
|
||||
}
|
||||
}
|
||||
dezibot.multiColorLight.setTopLeds(BLUE);
|
||||
break;
|
||||
case IR_LEFT:
|
||||
dezibot.motion.rotateAntiClockwise();
|
||||
dezibot.multiColorLight.setTopLeds(RED);
|
||||
break;
|
||||
case IR_RIGHT:
|
||||
dezibot.motion.rotateClockwise();
|
||||
dezibot.multiColorLight.setTopLeds(GREEN);
|
||||
break;
|
||||
case IR_BACK:
|
||||
if(leftValue > rightValue){
|
||||
dezibot.motion.rotateAntiClockwise();
|
||||
} else {
|
||||
dezibot.motion.rotateClockwise();
|
||||
}
|
||||
dezibot.multiColorLight.setTopLeds(YELLOW);
|
||||
break;
|
||||
}
|
||||
//delay(100);
|
||||
}
|
@ -18,7 +18,7 @@ void loop() {
|
||||
|
||||
int zvalue = 0;
|
||||
for(int i = 0; i<30;i++){
|
||||
zvalue += dezibot.motionDetection.getAcceleration().z;
|
||||
zvalue += dezibot.motion.detection.getAcceleration().z;
|
||||
}
|
||||
zvalue = zvalue/30;
|
||||
|
||||
|
@ -3,8 +3,8 @@ Dezibot dezibot;
|
||||
void setup() {
|
||||
|
||||
dezibot.begin();
|
||||
dezibot.motionDetection.begin();
|
||||
//dezibot.motionDetection.end();
|
||||
dezibot.motion.detection.begin();
|
||||
//dezibot.motion.detection.end();
|
||||
// put your setup code here, to run once:
|
||||
Serial.begin(115200);
|
||||
}
|
||||
@ -12,9 +12,9 @@ void setup() {
|
||||
void loop() {
|
||||
// put your main code here, to run repeatedly:
|
||||
|
||||
//Serial.println(dezibot.motionDetection.getTemperature());
|
||||
Serial.println(dezibot.motionDetection.getAcceleration().z);
|
||||
//Serial.println(dezibot.motionDetection.getRotation().x);
|
||||
Serial.println(dezibot.motionDetection.getWhoAmI());
|
||||
//Serial.println(dezibot.motion.detection.getTemperature());
|
||||
Serial.println(dezibot.motion.detection.getAcceleration().z);
|
||||
//Serial.println(dezibot.motion.detection.getRotation().x);
|
||||
Serial.println(dezibot.motion.detection.getWhoAmI());
|
||||
delay(5000);
|
||||
}
|
||||
|
@ -0,0 +1,8 @@
|
||||
{
|
||||
// Use IntelliSense to learn about possible attributes.
|
||||
// Hover to view descriptions of existing attributes.
|
||||
"version": "0.2.0",
|
||||
"configurations": [
|
||||
|
||||
]
|
||||
}
|
@ -0,0 +1,86 @@
|
||||
#include "Dezibot.h"
|
||||
Dezibot dezibot = Dezibot();
|
||||
#define maxDuty 6000
|
||||
#define minDuty 3500
|
||||
#define baseDuty 3900
|
||||
void setup() {
|
||||
// put your setup code here, to run once:
|
||||
dezibot.begin();
|
||||
Serial.begin(115200);
|
||||
//dezibot.motion.move();
|
||||
//analogWrite(11, 2000);
|
||||
//analogWrite(12, 2000);
|
||||
}
|
||||
uint16_t leftDuty= baseDuty;
|
||||
uint16_t rightDuty = baseDuty;
|
||||
unsigned long previous = millis();
|
||||
unsigned long current = millis();
|
||||
long averageZRotation = 0;
|
||||
long averageXAccel = 0;
|
||||
int left=0;
|
||||
int right=0;
|
||||
int difference = 0;
|
||||
int changerate = 0;
|
||||
int interval = 40;
|
||||
int threshold = 150;
|
||||
int resultcounter = 0;
|
||||
void loop() {
|
||||
// put your main code here, to run repeatedly:
|
||||
current = millis();
|
||||
IMUResult result = dezibot.motion.detection.getRotation();
|
||||
averageXAccel += dezibot.motion.detection.getAcceleration().x;
|
||||
averageZRotation += result.z;
|
||||
//Serial.println(result.z);
|
||||
if (result.z > threshold){
|
||||
right++;
|
||||
} else if(result.z < -threshold) {
|
||||
left++;
|
||||
}
|
||||
resultcounter++;
|
||||
if ((current - previous) > interval){
|
||||
//averageZRotation = averageZRotation / resultcounter;
|
||||
difference = abs(left-right);
|
||||
if (difference>25){
|
||||
changerate = 100;
|
||||
} else if(difference>20){
|
||||
changerate = 50;
|
||||
} else if(difference >15){
|
||||
changerate = 30;
|
||||
} else if(difference > 10){
|
||||
changerate = 10;
|
||||
} else{
|
||||
changerate = 5;
|
||||
}
|
||||
//Serial.print("Z:");
|
||||
//Serial.println(averageZRotation);
|
||||
dezibot.display.clearDisplay();
|
||||
dezibot.display.setCursor(0, 0);
|
||||
dezibot.display.setTextColor(WHITE);
|
||||
dezibot.display.setTextSize(2); // Draw 2X-scale text
|
||||
dezibot.display.println(averageZRotation);
|
||||
//dezibot.display.println(resultcounter);
|
||||
dezibot.display.print(left);
|
||||
dezibot.display.print(" ");
|
||||
dezibot.display.println(right);
|
||||
if(left>right){ //rotates anticlock
|
||||
leftDuty+=changerate;
|
||||
rightDuty-=changerate;
|
||||
} else if(left<right){
|
||||
leftDuty-=changerate;
|
||||
rightDuty+=changerate;
|
||||
}
|
||||
dezibot.motion.left.setSpeed(leftDuty);
|
||||
dezibot.motion.right.setSpeed(rightDuty);
|
||||
dezibot.display.println(leftDuty);
|
||||
dezibot.display.println(rightDuty);
|
||||
dezibot.display.display();
|
||||
|
||||
|
||||
averageZRotation = 0;
|
||||
averageXAccel = 0;
|
||||
resultcounter = 0;
|
||||
left = 0;
|
||||
right = 0;
|
||||
previous = current;
|
||||
}
|
||||
}
|
@ -11,9 +11,9 @@ dezibot.multiColorLight.turnOffLed();
|
||||
|
||||
void loop() {
|
||||
// put your main code here, to run repeatedly:
|
||||
if(dezibot.motionDetection.isShaken(1000,zAxis)){
|
||||
if(dezibot.motion.detection.isShaken(1000,zAxis)){
|
||||
dezibot.multiColorLight.setTopLeds(0xFF0000);
|
||||
} else if(dezibot.motionDetection.isShaken(1000,xAxis|yAxis)) {
|
||||
} else if(dezibot.motion.detection.isShaken(1000,xAxis|yAxis)) {
|
||||
dezibot.multiColorLight.setTopLeds(0x00FF00);
|
||||
}
|
||||
}
|
||||
|
@ -9,7 +9,7 @@ void setup() {
|
||||
}
|
||||
|
||||
void loop() {
|
||||
switch (dezibot.motionDetection.getTiltDirection()) {
|
||||
switch (dezibot.motion.detection.getTiltDirection()) {
|
||||
case Front:
|
||||
dezibot.multiColorLight.setTopLeds(GREEN);
|
||||
break;
|
||||
|
@ -13,7 +13,7 @@ void loop() {
|
||||
|
||||
int zvalue = 0;
|
||||
for(int i = 0; i<30;i++){
|
||||
zvalue += dezibot.motionDetection.getAcceleration().z;
|
||||
zvalue += dezibot.motion.detection.getAcceleration().z;
|
||||
}
|
||||
zvalue = zvalue/30;
|
||||
if(zvalue < -1700){
|
||||
|
19
example/advanced/Ampel1/Ampel1.ino
Normal file
19
example/advanced/Ampel1/Ampel1.ino
Normal file
@ -0,0 +1,19 @@
|
||||
#include "Dezibot.h"
|
||||
|
||||
Dezibot dezibot = Dezibot();
|
||||
void setup() {
|
||||
// put your setup code here, to run once:
|
||||
dezibot.begin();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// put your main code here, to run repeatedly:
|
||||
dezibot.multiColorLight.setLed(TOP, RED);
|
||||
delay(2000);
|
||||
dezibot.multiColorLight.setLed(TOP, YELLOW);
|
||||
delay(2000);
|
||||
dezibot.multiColorLight.setLed(TOP, GREEN);
|
||||
delay(2000);
|
||||
dezibot.multiColorLight.setLed(TOP, YELLOW);
|
||||
delay(2000);
|
||||
}
|
29
example/advanced/Ampel2/Ampel2.ino
Normal file
29
example/advanced/Ampel2/Ampel2.ino
Normal file
@ -0,0 +1,29 @@
|
||||
#include "Dezibot.h"
|
||||
|
||||
Dezibot dezibot = Dezibot();
|
||||
void setup() {
|
||||
// put your setup code here, to run once:
|
||||
dezibot.begin();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// put your main code here, to run repeatedly:
|
||||
dezibot.multiColorLight.setLed(TOP, RED);
|
||||
delay(2000);
|
||||
dezibot.multiColorLight.setLed(TOP, YELLOW);
|
||||
delay(2000);
|
||||
dezibot.multiColorLight.setLed(TOP, GREEN);
|
||||
delay(2000);
|
||||
dezibot.multiColorLight.turnOffLed();
|
||||
delay(1000);
|
||||
|
||||
for(int i=0; i<3; i++){
|
||||
dezibot.multiColorLight.setLed(TOP, GREEN);
|
||||
delay(500);
|
||||
dezibot.multiColorLight.turnOffLed();
|
||||
delay(500);
|
||||
}
|
||||
|
||||
dezibot.multiColorLight.setLed(TOP, YELLOW);
|
||||
delay(2000);
|
||||
}
|
34
example/advanced/Ampel3/Ampel3.ino
Normal file
34
example/advanced/Ampel3/Ampel3.ino
Normal file
@ -0,0 +1,34 @@
|
||||
#include "Dezibot.h"
|
||||
|
||||
Dezibot dezibot = Dezibot();
|
||||
void setup() {
|
||||
// put your setup code here, to run once:
|
||||
dezibot.begin();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// put your main code here, to run repeatedly:
|
||||
|
||||
if(dezibot.motion.detection.isShaken()){
|
||||
dezibot.multiColorLight.setLed(TOP, YELLOW);
|
||||
delay(2000);
|
||||
dezibot.multiColorLight.setLed(TOP, GREEN);
|
||||
delay(2000);
|
||||
dezibot.multiColorLight.turnOffLed();
|
||||
delay(1000);
|
||||
|
||||
for(int i=0; i<3; i++){
|
||||
dezibot.multiColorLight.setLed(TOP, GREEN);
|
||||
delay(500);
|
||||
dezibot.multiColorLight.turnOffLed();
|
||||
delay(500);
|
||||
}
|
||||
|
||||
dezibot.multiColorLight.setLed(TOP, YELLOW);
|
||||
delay(2000);
|
||||
}
|
||||
else{
|
||||
dezibot.multiColorLight.setLed(TOP, RED);
|
||||
}
|
||||
|
||||
}
|
@ -6,12 +6,43 @@ const int centeredThreshold = 50 ;
|
||||
void setup() {
|
||||
// put your setup code here, to run once:
|
||||
dezibot.begin();
|
||||
//Serial.begin(115200);
|
||||
dezibot.infraredLight.bottom.turnOn();
|
||||
dezibot.infraredLight.front.turnOn();
|
||||
Serial.begin(115200);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
|
||||
int32_t leftValue = (int32_t)dezibot.lightDetection.getAverageValue(IR_LEFT, 20, 1);
|
||||
int32_t rightValue = (int32_t)dezibot.lightDetection.getAverageValue(IR_RIGHT, 20, 1);
|
||||
switch(dezibot.lightDetection.getBrightest(IR)){
|
||||
case IR_FRONT:
|
||||
//correct Stearing to be centered
|
||||
if( abs(leftValue-rightValue)
|
||||
< centeredThreshold){
|
||||
dezibot.motion.move();
|
||||
}else{
|
||||
if (leftValue > rightValue){
|
||||
dezibot.motion.rotateAntiClockwise();
|
||||
} else{
|
||||
dezibot.motion.rotateClockwise();
|
||||
}
|
||||
}
|
||||
dezibot.multiColorLight.setTopLeds(BLUE);
|
||||
break;
|
||||
case IR_LEFT:
|
||||
dezibot.motion.rotateAntiClockwise();
|
||||
dezibot.multiColorLight.setTopLeds(RED);
|
||||
break;
|
||||
case IR_RIGHT:
|
||||
dezibot.motion.rotateClockwise();
|
||||
dezibot.multiColorLight.setTopLeds(GREEN);
|
||||
break;
|
||||
case IR_BACK:
|
||||
if(leftValue > rightValue){
|
||||
dezibot.motion.rotateAntiClockwise();
|
||||
} else {
|
||||
dezibot.motion.rotateClockwise();
|
||||
}
|
||||
dezibot.multiColorLight.setTopLeds(YELLOW);
|
||||
break;
|
||||
}
|
||||
//delay(100);
|
||||
}
|
||||
|
23
example/advanced/phototaxis/phototaxis.ino
Normal file
23
example/advanced/phototaxis/phototaxis.ino
Normal file
@ -0,0 +1,23 @@
|
||||
#include "Dezibot.h"
|
||||
|
||||
Dezibot dezibot = Dezibot();
|
||||
void setup() {
|
||||
// put your setup code here, to run once:
|
||||
dezibot.begin();
|
||||
dezibot.multiColorLight.turnOffLed();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// put your main code here, to run repeatedly:
|
||||
dezibot.display.clear();
|
||||
int light = dezibot.lightDetection.getValue(DL_FRONT);
|
||||
dezibot.display.print(light);
|
||||
|
||||
if(light > 2000) {
|
||||
dezibot.motion.move();
|
||||
} else {
|
||||
dezibot.motion.rotateClockwise();
|
||||
}
|
||||
delay(100);
|
||||
|
||||
}
|
@ -8,14 +8,9 @@ void setup() {
|
||||
|
||||
void loop() {
|
||||
// put your main code here, to run repeatedly:
|
||||
dezibot.display.print("Starte Nachricht!");
|
||||
delay(2000);
|
||||
dezibot.multiColorLight.setLed(ALL,dezibot.multiColorLight.color(100,0,0));
|
||||
delay(2000);
|
||||
dezibot.multiColorLight.turnOffLed(ALL);
|
||||
delay(2000);
|
||||
//dezibot.display.print("Starte Nachricht!");
|
||||
//delay(2000);
|
||||
//dezibot.display.clear();
|
||||
dezibot.display.clear();
|
||||
|
||||
// T
|
||||
longSignal(1);
|
||||
@ -46,13 +41,9 @@ void loop() {
|
||||
longSignal(1);
|
||||
shortSignal(1);
|
||||
|
||||
dezibot.display.print("Ende Nachricht!");
|
||||
delay(2000);
|
||||
dezibot.multiColorLight.setLed(ALL,dezibot.multiColorLight.color(0,255,0));
|
||||
delay(2000);
|
||||
dezibot.multiColorLight.turnOffLed(ALL);
|
||||
delay(2000);
|
||||
//dezibot.display.print("Ende Nachricht!");
|
||||
//dezibot.display.clear();
|
||||
dezibot.display.clear();
|
||||
}
|
||||
|
||||
void shortSignal(int count){
|
||||
|
14
example/advanced/wuerfeln/wuerfeln.ino
Normal file
14
example/advanced/wuerfeln/wuerfeln.ino
Normal file
@ -0,0 +1,14 @@
|
||||
#include <Dezibot.h>
|
||||
Dezibot dezibot = Dezibot();
|
||||
void setup() {
|
||||
dezibot.begin();
|
||||
}
|
||||
void loop() {
|
||||
if(dezibot.motion.detection.isShaken()){
|
||||
dezibot.display.clear();
|
||||
dezibot.display.print(random(1,7));
|
||||
delay(1000);
|
||||
}
|
||||
|
||||
}
|
||||
|
14
example/advanced/zaehlen/zaehlen.ino
Normal file
14
example/advanced/zaehlen/zaehlen.ino
Normal file
@ -0,0 +1,14 @@
|
||||
#include <Dezibot.h>
|
||||
Dezibot dezibot = Dezibot();
|
||||
void setup() {
|
||||
dezibot.begin();
|
||||
}
|
||||
void loop() {
|
||||
for (int i=1; i<=10; i++){
|
||||
dezibot.display.clear();
|
||||
dezibot.display.print(i);
|
||||
delay(1000);
|
||||
}
|
||||
|
||||
}
|
||||
|
@ -1,393 +0,0 @@
|
||||
/**************************************************************************
|
||||
This is an example for our Monochrome OLEDs based on SSD1306 drivers
|
||||
|
||||
Pick one up today in the adafruit shop!
|
||||
------> http://www.adafruit.com/category/63_98
|
||||
|
||||
This example is for a 128x32 pixel display using I2C to communicate
|
||||
3 pins are required to interface (two I2C and one reset).
|
||||
|
||||
Adafruit invests time and resources providing this open
|
||||
source code, please support Adafruit and open-source
|
||||
hardware by purchasing products from Adafruit!
|
||||
|
||||
Written by Limor Fried/Ladyada for Adafruit Industries,
|
||||
with contributions from the open source community.
|
||||
BSD license, check license.txt for more information
|
||||
All text above, and the splash screen below must be
|
||||
included in any redistribution.
|
||||
**************************************************************************/
|
||||
#include <Wire.h>
|
||||
#include <Adafruit_SSD1306.h>
|
||||
|
||||
#define SCREEN_WIDTH 128 // OLED display width, in pixels
|
||||
#define SCREEN_HEIGHT 64 // OLED display height, in pixels
|
||||
|
||||
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, -1);
|
||||
|
||||
|
||||
#define LOGO_HEIGHT 64
|
||||
#define LOGO_WIDTH 128
|
||||
const unsigned char logo_bmp [] = {
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE3, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE3, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE3, 0xFF, 0xF0, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE3, 0xFF, 0xF0, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE3, 0xFF, 0xE0, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE3, 0xFF, 0xE0, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE3, 0xFF, 0xE0, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE3, 0xFF, 0xE0, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE3, 0xFF, 0xF0, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE3, 0xFF, 0xF0, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE3, 0xFF, 0xFC, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE3, 0xFF, 0xFC, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE3, 0xFF, 0xFC, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE3, 0xFF, 0xFC, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xFF, 0xC3, 0xFF, 0xFF, 0xC7, 0xFF, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xFF, 0x40, 0x7F, 0xFF, 0x00, 0xFF, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xFE, 0x00, 0x3F, 0xFE, 0x00, 0x3F, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xFC, 0x3C, 0x3F, 0xFC, 0x3C, 0x3F, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xFC, 0x7F, 0x1F, 0xF8, 0x7E, 0x1F, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x83, 0xFC, 0xE7, 0x1F, 0xF8, 0xE7, 0x1F, 0xC1, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xF8, 0xE3, 0x9F, 0xF9, 0xC3, 0x9F, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xF8, 0xE3, 0x9F, 0xF8, 0xC3, 0x1F, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x23, 0xF8, 0xFF, 0x1F, 0xF8, 0xFF, 0x1F, 0xC4, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFC, 0x7F, 0x1F, 0xF8, 0x7E, 0x1F, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFC, 0x1C, 0x3F, 0xFC, 0x1C, 0x3F, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0x01, 0xFF, 0xFF, 0x00, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xFC, 0x62, 0x11, 0x8C, 0x42, 0x3F, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xFC, 0x62, 0x11, 0x8C, 0x42, 0x3F, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xC0, 0x62, 0x11, 0x8C, 0x42, 0x07, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x07, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x1F, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xC3, 0xFF, 0x80, 0x00, 0x00, 0x01, 0xFF, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xE3, 0xFF, 0xFF, 0xF8, 0x1F, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xE3, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x80, 0x00, 0x00, 0x00, 0x00, 0x01, 0x07, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF
|
||||
};
|
||||
const unsigned char Banner [] = {
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0x00, 0xFF, 0xFC, 0x00, 0x0C, 0x00, 0x00, 0x43, 0x00, 0x3F, 0xFF, 0xF8, 0x7F, 0x80, 0x00, 0x00,
|
||||
0x00, 0x1F, 0xFC, 0x00, 0x0C, 0x00, 0x00, 0x43, 0x00, 0x0F, 0xFF, 0x80, 0x07, 0x80, 0x00, 0x00,
|
||||
0x00, 0x07, 0xFC, 0x00, 0x0C, 0x00, 0x00, 0x43, 0x00, 0x07, 0xFE, 0x00, 0x03, 0x80, 0x00, 0x00,
|
||||
0x00, 0x01, 0xFC, 0x00, 0x0C, 0x00, 0x00, 0x43, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x80, 0x00, 0x00,
|
||||
0x0F, 0x00, 0xFC, 0x3F, 0xFF, 0xFF, 0xF0, 0x43, 0x0F, 0x03, 0xF8, 0x0F, 0x20, 0x7F, 0xE1, 0xFF,
|
||||
0x0F, 0xC0, 0x7C, 0x3F, 0xFF, 0xFF, 0xE0, 0x43, 0x0F, 0x83, 0xF0, 0x6F, 0x18, 0x3F, 0xE1, 0xFF,
|
||||
0x0F, 0xF0, 0x3C, 0x3F, 0xFF, 0xFF, 0xC0, 0xC3, 0x0F, 0xC1, 0xE0, 0xEF, 0x1C, 0x3F, 0xE1, 0xFF,
|
||||
0x0F, 0xF8, 0x1C, 0x3F, 0xFF, 0xFF, 0xC1, 0xC3, 0x0F, 0xC1, 0xE1, 0xEF, 0x3E, 0x1F, 0xE1, 0xFF,
|
||||
0x0F, 0xFC, 0x1C, 0x3F, 0xFF, 0xFF, 0x83, 0xC3, 0x0F, 0xC1, 0xC0, 0x00, 0x01, 0x0F, 0xE1, 0xFF,
|
||||
0x0F, 0xFE, 0x0C, 0x3F, 0xFF, 0xFF, 0x03, 0xC3, 0x0F, 0x81, 0xC4, 0x00, 0x00, 0x0F, 0xE1, 0xFF,
|
||||
0x0F, 0xFE, 0x0C, 0x3F, 0xFF, 0xFF, 0x07, 0xC3, 0x0F, 0x83, 0x85, 0xFF, 0xFE, 0x8F, 0xE1, 0xFF,
|
||||
0x0F, 0xFF, 0x0C, 0x3F, 0xFF, 0xFE, 0x0F, 0xC3, 0x0E, 0x03, 0x85, 0x87, 0x8E, 0x8F, 0xE1, 0xFF,
|
||||
0x0F, 0xFF, 0x0C, 0x00, 0x1F, 0xFC, 0x0F, 0xC3, 0x00, 0x07, 0x89, 0xA3, 0x06, 0x07, 0xE1, 0xFF,
|
||||
0x0F, 0xFF, 0x0C, 0x00, 0x1F, 0xF8, 0x1F, 0xC3, 0x00, 0x0F, 0x89, 0x83, 0x06, 0x07, 0xE1, 0xFF,
|
||||
0x0F, 0xFF, 0x0C, 0x00, 0x1F, 0xF8, 0x3F, 0xC3, 0x00, 0x07, 0x89, 0x87, 0x8E, 0x07, 0xE1, 0xFF,
|
||||
0x0F, 0xFF, 0x0C, 0x00, 0x1F, 0xF0, 0x3F, 0xC3, 0x00, 0x03, 0x89, 0xFF, 0xFE, 0x07, 0xE1, 0xFF,
|
||||
0x0F, 0xFF, 0x0C, 0x3F, 0xFF, 0xE0, 0x7F, 0xC3, 0x00, 0x01, 0x89, 0xFF, 0xFE, 0x07, 0xE1, 0xFF,
|
||||
0x0F, 0xFF, 0x0C, 0x3F, 0xFF, 0xE0, 0xFF, 0xC3, 0x0F, 0x80, 0x81, 0xFF, 0xFE, 0x0F, 0xE1, 0xFF,
|
||||
0x0F, 0xFE, 0x0C, 0x3F, 0xFF, 0xC1, 0xFF, 0xC3, 0x0F, 0xE0, 0xC5, 0x00, 0x06, 0x8F, 0xE1, 0xFF,
|
||||
0x0F, 0xFE, 0x1C, 0x3F, 0xFF, 0x81, 0xFF, 0xC3, 0x0F, 0xF0, 0x41, 0x00, 0x06, 0x0F, 0xE1, 0xFF,
|
||||
0x0F, 0xFC, 0x1C, 0x3F, 0xFF, 0x83, 0xFF, 0xC3, 0x0F, 0xF0, 0x40, 0xFF, 0xFC, 0x1F, 0xE1, 0xFF,
|
||||
0x0F, 0xF8, 0x3C, 0x3F, 0xFF, 0x07, 0xFF, 0xC3, 0x0F, 0xF0, 0x60, 0x00, 0x00, 0x1F, 0xE1, 0xFF,
|
||||
0x0F, 0xF0, 0x3C, 0x3F, 0xFE, 0x07, 0xFF, 0xC3, 0x0F, 0xF0, 0x70, 0xFF, 0xF8, 0x3F, 0xE1, 0xFF,
|
||||
0x0F, 0xC0, 0x7C, 0x3F, 0xFE, 0x0F, 0xFF, 0xC3, 0x0F, 0xE0, 0x70, 0x3F, 0xF0, 0x7F, 0xE1, 0xFF,
|
||||
0x00, 0x00, 0xFC, 0x00, 0x0C, 0x00, 0x00, 0x43, 0x0F, 0xC0, 0xF8, 0x0F, 0xC0, 0xFF, 0xE1, 0xFF,
|
||||
0x00, 0x01, 0xFC, 0x00, 0x0C, 0x00, 0x00, 0x43, 0x00, 0x00, 0xFC, 0x00, 0x01, 0xFF, 0xE1, 0xFF,
|
||||
0x00, 0x07, 0xFC, 0x00, 0x0C, 0x00, 0x00, 0x43, 0x00, 0x01, 0xFF, 0x00, 0x03, 0xFF, 0xE1, 0xFF,
|
||||
0x00, 0x1F, 0xFC, 0x00, 0x0C, 0x00, 0x00, 0x43, 0x00, 0x03, 0xFF, 0xC0, 0x1F, 0xFF, 0xE1, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF
|
||||
};
|
||||
|
||||
#define ICON_HEIGHT 64
|
||||
#define ICON_WIDTH 64
|
||||
|
||||
const unsigned char icon_1 [] = {
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xC1, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xFF, 0xC1, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0,
|
||||
0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0,
|
||||
0xFE, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0xFC, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x00,
|
||||
0xF8, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0xE0, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0x00,
|
||||
0xC0, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x00,
|
||||
0x00, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x20, 0x01, 0x81, 0xFF, 0xFE, 0x07, 0xFF, 0x80, 0x60,
|
||||
0x03, 0x81, 0xFF, 0xFE, 0x07, 0xFF, 0x81, 0xE0, 0x0F, 0x81, 0xFF, 0xFE, 0x07, 0xFF, 0x87, 0xE0,
|
||||
0x3F, 0x81, 0xFF, 0xFE, 0x07, 0xFF, 0x8F, 0xE0, 0xFF, 0x81, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, 0xE0,
|
||||
0xFF, 0x81, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, 0xE0, 0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0,
|
||||
0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0,
|
||||
0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0,
|
||||
0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0,
|
||||
0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0,
|
||||
0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0,
|
||||
0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0,
|
||||
0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0,
|
||||
0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0xFF, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0,
|
||||
0xFF, 0x81, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, 0xE0, 0xFF, 0x81, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, 0xE0,
|
||||
0xFF, 0x81, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, 0xE0, 0xFF, 0x81, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, 0xE0,
|
||||
0xFF, 0x81, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, 0xE0, 0xFF, 0x81, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, 0xE0,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF
|
||||
};
|
||||
const unsigned char icon_2 [] = {
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x3F, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0xFF, 0x87, 0xFF, 0xFF, 0xFF, 0xE0, 0x3F, 0xFF,
|
||||
0xFF, 0x03, 0xFF, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, 0xFF, 0xFB, 0xFF, 0xFF,
|
||||
0xFE, 0x01, 0xFF, 0xFF, 0xFF, 0xFB, 0xFF, 0xFF, 0xFE, 0x01, 0xFF, 0xFF, 0xFF, 0xF3, 0xFF, 0xFF,
|
||||
0xFE, 0x03, 0xFF, 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFF, 0xF3, 0xFF, 0xFF,
|
||||
0xFF, 0x87, 0xFF, 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, 0xFF, 0x9F, 0xFF, 0xFF, 0xFF, 0xF3, 0xFF, 0xFF,
|
||||
0xFF, 0x3F, 0xFF, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF,
|
||||
0xFE, 0x7F, 0xFF, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0xFE, 0x7F, 0xFF, 0xFF, 0xFF, 0xE7, 0xFF, 0xC1,
|
||||
0xFE, 0x7F, 0xFF, 0xFF, 0xFF, 0xE7, 0xFF, 0x80, 0xFC, 0xFF, 0xFF, 0xFF, 0xFF, 0xE7, 0xFF, 0x80,
|
||||
0xFC, 0xFF, 0xFF, 0xFF, 0xFF, 0xEF, 0xFF, 0x80, 0xFD, 0xFF, 0xFF, 0xFF, 0xFF, 0xEF, 0xFF, 0x00,
|
||||
0xF9, 0xFF, 0xFF, 0xFF, 0xFF, 0xEF, 0xFC, 0x00, 0xF9, 0xFF, 0xFF, 0xFF, 0xFF, 0xCF, 0xF0, 0xC1,
|
||||
0xF3, 0xFF, 0xFF, 0xFF, 0xFF, 0xCF, 0xC3, 0xFF, 0xF3, 0xFF, 0xFF, 0xFF, 0xFF, 0x87, 0x0F, 0xFF,
|
||||
0xF3, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x3F, 0xFF, 0xE7, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0xFF, 0xFF,
|
||||
0x83, 0xFF, 0xFF, 0xFF, 0xFE, 0x01, 0xFF, 0xFF, 0x01, 0xFF, 0xFF, 0xFF, 0xF8, 0x01, 0xFF, 0xFF,
|
||||
0x01, 0xFF, 0xFC, 0x0F, 0x80, 0x03, 0xFF, 0xFF, 0x01, 0xFF, 0xFC, 0x00, 0x0F, 0x03, 0xFF, 0xFF,
|
||||
0x01, 0xFF, 0xF8, 0x00, 0xFF, 0x8F, 0xFF, 0xFF, 0x01, 0xFF, 0xF8, 0x07, 0xFF, 0xCF, 0xFF, 0xFF,
|
||||
0x03, 0xFF, 0xF8, 0x07, 0xFF, 0xCF, 0xFF, 0xFF, 0xC7, 0xFF, 0xFC, 0x07, 0xFF, 0xCF, 0xFF, 0xFF,
|
||||
0xF3, 0xFF, 0xFE, 0x0F, 0xFF, 0xEF, 0xFF, 0xFF, 0xF3, 0xFF, 0xFC, 0xFF, 0xFF, 0xEF, 0xFF, 0xFF,
|
||||
0xF9, 0xFF, 0xFC, 0xFF, 0xFF, 0xEF, 0xFF, 0xFF, 0xF9, 0xFF, 0xF9, 0xFF, 0xFF, 0xEF, 0xFF, 0xFF,
|
||||
0xF9, 0xFF, 0xF9, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0xFC, 0xFF, 0xF3, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF,
|
||||
0xFC, 0xFF, 0xE3, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0xFE, 0x7F, 0xE7, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF,
|
||||
0xFE, 0x7F, 0xC7, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0xFE, 0x7F, 0xCF, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF,
|
||||
0xFF, 0x3F, 0x9F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0x3F, 0x9F, 0xFF, 0xFF, 0x80, 0x7F, 0xFF,
|
||||
0xFF, 0x9F, 0x3F, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xFF, 0x9F, 0x3F, 0xFF, 0xFF, 0x80, 0x7F, 0xFF,
|
||||
0xFF, 0x9E, 0x7F, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xFF, 0xCE, 0x7F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF,
|
||||
0xFF, 0xCC, 0xFF, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xC0, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xC0, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xC0, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF
|
||||
};
|
||||
|
||||
const unsigned char icon_3 [] = {
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x00, 0x00, 0x03, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xC0, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x00, 0x00, 0x07, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0x00, 0x00, 0x1F, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFC, 0x00, 0x00, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x00, 0x7F, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x01, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xC0, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x07, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0x1F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x7F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x01, 0xFF, 0xFF,
|
||||
0xFF, 0xFE, 0x00, 0x1C, 0x18, 0x00, 0xFF, 0xFF, 0xFF, 0xFE, 0x01, 0xFC, 0x1F, 0x00, 0x7F, 0xFF,
|
||||
0xFF, 0xFE, 0x03, 0xFC, 0x1F, 0x81, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0x00, 0x04, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x3F, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xF8, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x00, 0x7F, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0x00, 0x3F, 0xFF, 0xFF, 0xFF, 0x07, 0xFC, 0x1F, 0xC0, 0x3F, 0xFF,
|
||||
0xFF, 0xFC, 0x03, 0xFC, 0x1F, 0xC0, 0x3F, 0xFF, 0xFF, 0xFC, 0x00, 0xFC, 0x1F, 0x80, 0x3F, 0xFF,
|
||||
0xFF, 0xFE, 0x00, 0x0C, 0x10, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x01, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xF8, 0x00, 0x00, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF
|
||||
};
|
||||
const unsigned char icon_4 [] = {
|
||||
0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFD, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8,
|
||||
0x8F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF1, 0xC7, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE3,
|
||||
0xE3, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC7, 0xF1, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x8F,
|
||||
0xF8, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x1F, 0xFC, 0x7F, 0xF7, 0xFF, 0xFF, 0xEF, 0xFE, 0x3F,
|
||||
0xFE, 0x3F, 0xF7, 0xFF, 0xFF, 0xEF, 0xFC, 0x7F, 0xFF, 0x1F, 0xF7, 0xFF, 0xFF, 0xEF, 0xF8, 0xFF,
|
||||
0xFF, 0x8F, 0xF7, 0xFF, 0xFF, 0xEF, 0xF1, 0xFF, 0xFF, 0xC7, 0xF7, 0xFF, 0xFF, 0xEF, 0xE3, 0xFF,
|
||||
0xFF, 0xE3, 0xF7, 0xFF, 0xFF, 0xEF, 0xC7, 0xFF, 0xFF, 0xF1, 0xF7, 0xFF, 0xFF, 0xEF, 0x8F, 0xFF,
|
||||
0xFF, 0xF8, 0xF7, 0xFF, 0xFF, 0xEF, 0x1F, 0xFF, 0xFF, 0xFC, 0x77, 0xFF, 0xFF, 0xEE, 0x3F, 0xFF,
|
||||
0xFF, 0xFE, 0x37, 0xFF, 0xFF, 0xEC, 0x7F, 0xFF, 0xFF, 0xFF, 0x17, 0xFF, 0xFF, 0xE8, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0x87, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0xE3, 0xFF, 0xFF,
|
||||
0xFE, 0x00, 0x07, 0xFF, 0xFF, 0xC0, 0x00, 0x7F, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xEF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xF8, 0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x07, 0xFF, 0xFF, 0xE0, 0x00, 0x7F,
|
||||
0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0xFF, 0xFF, 0x87, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0x17, 0xFF, 0xFF, 0xE8, 0xFF, 0xFF, 0xFF, 0xFE, 0x37, 0xFF, 0xFF, 0xEC, 0x7F, 0xFF,
|
||||
0xFF, 0xFC, 0x77, 0xFF, 0xFF, 0xEE, 0x3F, 0xFF, 0xFF, 0xF8, 0xF7, 0xFF, 0xFF, 0xEF, 0x1F, 0xFF,
|
||||
0xFF, 0xF1, 0xF7, 0xFF, 0xFF, 0xEF, 0x8F, 0xFF, 0xFF, 0xE3, 0xF7, 0xFF, 0xFF, 0xEF, 0xC7, 0xFF,
|
||||
0xFF, 0xC7, 0xF7, 0xFF, 0xFF, 0xEF, 0xE3, 0xFF, 0xFF, 0x8F, 0xF7, 0xFF, 0xFF, 0xEF, 0xF1, 0xFF,
|
||||
0xFF, 0x1F, 0xF7, 0xFF, 0xFF, 0xEF, 0xF8, 0xFF, 0xFE, 0x3F, 0xF7, 0xFF, 0xFF, 0xEF, 0xFC, 0x7F,
|
||||
0xFC, 0x7F, 0xF7, 0xFF, 0xFF, 0xEF, 0xFE, 0x3F, 0xF8, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x1F,
|
||||
0xF1, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x8F, 0xE3, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC7,
|
||||
0xC7, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE3, 0x8F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF1,
|
||||
0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0xBF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFD
|
||||
};
|
||||
|
||||
void setup() {
|
||||
Wire.begin(1,2);
|
||||
display.begin(SSD1306_SWITCHCAPVCC, 0x3C);
|
||||
|
||||
}
|
||||
|
||||
void loop() {
|
||||
|
||||
display.invertDisplay(true);
|
||||
drawlogo();
|
||||
delay(3000);
|
||||
drawbanner();
|
||||
delay(3000);
|
||||
jiaText();
|
||||
|
||||
}
|
||||
|
||||
|
||||
void jiaText(void) {
|
||||
display.invertDisplay(false);
|
||||
display.clearDisplay();
|
||||
display.setCursor(0, 0);
|
||||
display.setTextColor(WHITE);
|
||||
display.setTextSize(2); // Draw 2X-scale text
|
||||
display.println("Hallo \nJunior-\nIngenieur-\nAkademie!");
|
||||
display.display(); // Show initial text
|
||||
delay(3000);
|
||||
|
||||
display.stopscroll();
|
||||
|
||||
|
||||
}
|
||||
|
||||
void drawlogo(void) {
|
||||
display.clearDisplay();
|
||||
|
||||
display.drawBitmap(
|
||||
(display.width() - LOGO_WIDTH ) / 2,
|
||||
(display.height() - LOGO_HEIGHT) / 2,
|
||||
logo_bmp, LOGO_WIDTH, LOGO_HEIGHT, 1);
|
||||
display.display();
|
||||
|
||||
}
|
||||
void drawbanner(void) {
|
||||
display.clearDisplay();
|
||||
|
||||
display.drawBitmap(
|
||||
(display.width() - LOGO_WIDTH ) / 2,
|
||||
(display.height() - LOGO_HEIGHT) / 2,
|
||||
Banner, LOGO_WIDTH, LOGO_HEIGHT, 1);
|
||||
display.display();
|
||||
|
||||
}
|
||||
void drawicon1(void){
|
||||
display.clearDisplay();
|
||||
|
||||
display.drawBitmap(
|
||||
(display.width() - ICON_WIDTH) / 2,
|
||||
(display.height() - ICON_HEIGHT) /2,
|
||||
icon_1, ICON_WIDTH, ICON_HEIGHT, 1);
|
||||
display.display();
|
||||
}
|
||||
void drawicon2(void){
|
||||
display.clearDisplay();
|
||||
|
||||
display.drawBitmap(
|
||||
(display.width() - ICON_WIDTH) / 2,
|
||||
(display.height() - ICON_HEIGHT) /2,
|
||||
icon_2, ICON_WIDTH, ICON_HEIGHT, 1);
|
||||
display.display();
|
||||
}
|
||||
void drawicon3(void){
|
||||
display.clearDisplay();
|
||||
|
||||
display.drawBitmap(
|
||||
(display.width() - ICON_WIDTH) / 2,
|
||||
(display.height() - ICON_HEIGHT) /2,
|
||||
icon_3, ICON_WIDTH, ICON_HEIGHT, 1);
|
||||
display.display();
|
||||
}
|
||||
void drawicon4(void){
|
||||
display.clearDisplay();
|
||||
|
||||
display.drawBitmap(
|
||||
(display.width() - ICON_WIDTH) / 2,
|
||||
(display.height() - ICON_HEIGHT) /2,
|
||||
icon_4, ICON_WIDTH, ICON_HEIGHT, 1);
|
||||
display.display();
|
||||
}
|
14
example/start/start.ino
Normal file
14
example/start/start.ino
Normal file
@ -0,0 +1,14 @@
|
||||
#include "Dezibot.h"
|
||||
|
||||
Dezibot dezibot = Dezibot();
|
||||
|
||||
void setup(){
|
||||
dezibot.begin();
|
||||
//comment in to use WIFI-Communication
|
||||
//dezibot.communication.begin();
|
||||
// put your setup code here, to run once:
|
||||
}
|
||||
|
||||
void loop(){
|
||||
// put your main code here, to run repeatedly:
|
||||
}
|
@ -5,7 +5,8 @@
|
||||
#include "Dezibot.h"
|
||||
#include <Wire.h>
|
||||
|
||||
#define GPIO_LED 48
|
||||
|
||||
Dezibot::Dezibot():multiColorLight(){};
|
||||
|
||||
void Dezibot::begin(void) {
|
||||
Wire.begin(SDA_PIN,SCL_PIN);
|
||||
@ -15,7 +16,6 @@ void Dezibot::begin(void) {
|
||||
lightDetection.begin();
|
||||
colorDetection.begin();
|
||||
multiColorLight.begin();
|
||||
motionDetection.begin();
|
||||
display.begin();
|
||||
};
|
||||
|
||||
|
@ -25,11 +25,11 @@ class Dezibot {
|
||||
protected:
|
||||
|
||||
public:
|
||||
Dezibot();
|
||||
Motion motion;
|
||||
LightDetection lightDetection;
|
||||
ColorDetection colorDetection;
|
||||
MultiColorLight multiColorLight;
|
||||
MotionDetection motionDetection;
|
||||
InfraredLight infraredLight;
|
||||
Communication communication;
|
||||
Display display;
|
||||
|
@ -11,11 +11,10 @@
|
||||
|
||||
#include "Motion.h"
|
||||
|
||||
TaskHandle_t xMoveTaskHandle = NULL;
|
||||
TaskHandle_t xClockwiseTaskHandle = NULL;
|
||||
TaskHandle_t xAntiClockwiseTaskHandle = NULL;
|
||||
|
||||
// Initialize the movement component.
|
||||
|
||||
|
||||
void Motion::begin(void) {
|
||||
ledc_timer_config_t motor_timer = {
|
||||
.speed_mode = LEDC_MODE,
|
||||
@ -27,37 +26,118 @@ void Motion::begin(void) {
|
||||
ledc_timer_config(&motor_timer);
|
||||
Motion::left.begin();
|
||||
Motion::right.begin();
|
||||
detection.begin();
|
||||
};
|
||||
void Motion::moveTask(void * args) {
|
||||
uint32_t runtime = (uint32_t)args;
|
||||
|
||||
Motion::left.setSpeed(LEFT_MOTOR_DUTY);
|
||||
Motion::right.setSpeed(RIGHT_MOTOR_DUTY);
|
||||
vTaskDelay((uint32_t) args / portTICK_PERIOD_MS);
|
||||
Motion::left.setSpeed(0);
|
||||
Motion::right.setSpeed(0);
|
||||
vTaskDelete(xMoveTaskHandle);
|
||||
};
|
||||
Motion::xLastWakeTime = xTaskGetTickCount();
|
||||
while(1){
|
||||
if(runtime>40||runtime==0){
|
||||
vTaskDelayUntil(&xLastWakeTime,40);
|
||||
runtime -= 40;
|
||||
//calc new parameters
|
||||
//set new parameters
|
||||
int fifocount = detection.getDataFromFIFO(buffer);
|
||||
int rightCounter = 0;
|
||||
int leftCounter = 0;
|
||||
int changerate = 0;
|
||||
for(int i = 0;i<fifocount;i++){
|
||||
if(buffer[i].gyro.z>correctionThreshold){
|
||||
rightCounter++;
|
||||
} else if(buffer[i].gyro.z<-correctionThreshold){
|
||||
leftCounter++;
|
||||
}
|
||||
}
|
||||
int difference = abs(leftCounter-rightCounter);
|
||||
if (difference>25){
|
||||
changerate = 200;
|
||||
} else if(difference>20){
|
||||
changerate = 100;
|
||||
} else if(difference >15){
|
||||
changerate = 50;
|
||||
} else if(difference > 10){
|
||||
changerate = 20;
|
||||
} else{
|
||||
changerate = 5;
|
||||
}
|
||||
|
||||
// Move forward for a certain amount of time.
|
||||
void Motion::move(uint32_t moveForMs) {
|
||||
if (moveForMs > 0){
|
||||
xTaskCreate(moveTask, "Move", 4096, (void*)moveForMs, 10, &xMoveTaskHandle);
|
||||
} else{
|
||||
Motion::left.setSpeed(LEFT_MOTOR_DUTY);
|
||||
Motion::right.setSpeed(RIGHT_MOTOR_DUTY);
|
||||
if(leftCounter>rightCounter){ //rotates anticlock
|
||||
LEFT_MOTOR_DUTY+=changerate;
|
||||
RIGHT_MOTOR_DUTY-=changerate;
|
||||
} else if(leftCounter<rightCounter){
|
||||
LEFT_MOTOR_DUTY-=changerate;
|
||||
RIGHT_MOTOR_DUTY+=changerate;
|
||||
}
|
||||
|
||||
Motion::left.setSpeed(LEFT_MOTOR_DUTY);
|
||||
Motion::right.setSpeed(RIGHT_MOTOR_DUTY);
|
||||
} else {
|
||||
vTaskDelayUntil(&xLastWakeTime,runtime);
|
||||
Motion::left.setSpeed(0);
|
||||
Motion::right.setSpeed(0);
|
||||
vTaskDelete(xMoveTaskHandle);
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
// Move forward for a certain amount of time.
|
||||
void Motion::move(uint32_t moveForMs, uint baseValue) {
|
||||
if(xMoveTaskHandle){
|
||||
vTaskDelete(xMoveTaskHandle);
|
||||
xMoveTaskHandle = NULL;
|
||||
}
|
||||
if(xClockwiseTaskHandle){
|
||||
|
||||
vTaskDelete(xClockwiseTaskHandle);
|
||||
xClockwiseTaskHandle = NULL;
|
||||
}
|
||||
if(xAntiClockwiseTaskHandle){
|
||||
vTaskDelete(xAntiClockwiseTaskHandle);
|
||||
xAntiClockwiseTaskHandle = NULL;
|
||||
|
||||
}
|
||||
LEFT_MOTOR_DUTY = baseValue;
|
||||
RIGHT_MOTOR_DUTY = baseValue;
|
||||
xTaskCreate(moveTask, "Move", 4096, (void*)moveForMs, 10, &xMoveTaskHandle);
|
||||
|
||||
};
|
||||
|
||||
void Motion::leftMotorTask(void * args) {
|
||||
Motion::left.setSpeed(LEFT_MOTOR_DUTY);
|
||||
uint32_t runtime = (uint32_t)args;
|
||||
if(xMoveTaskHandle){
|
||||
vTaskDelete(xMoveTaskHandle);
|
||||
xMoveTaskHandle = NULL;
|
||||
}
|
||||
if(xAntiClockwiseTaskHandle){
|
||||
vTaskDelete(xAntiClockwiseTaskHandle);
|
||||
xAntiClockwiseTaskHandle = NULL;
|
||||
}
|
||||
Motion::right.setSpeed(0);
|
||||
vTaskDelay((uint32_t) args / portTICK_PERIOD_MS);
|
||||
Motion::left.setSpeed(0);
|
||||
vTaskDelete(xClockwiseTaskHandle);
|
||||
Motion::left.setSpeed(LEFT_MOTOR_DUTY);
|
||||
while(1){
|
||||
if((runtime>40)||(runtime==0)){
|
||||
vTaskDelayUntil(&xLastWakeTime,40);
|
||||
runtime -=40;
|
||||
} else {
|
||||
vTaskDelayUntil(&xLastWakeTime,runtime);
|
||||
Motion::left.setSpeed(0);
|
||||
vTaskDelete(xClockwiseTaskHandle);
|
||||
}
|
||||
vTaskDelayUntil(&xLastWakeTime,40);
|
||||
}
|
||||
};
|
||||
|
||||
// Rotate clockwise for a certain amount of time.
|
||||
void Motion::rotateClockwise(uint32_t rotateForMs) {
|
||||
void Motion::rotateClockwise(uint32_t rotateForMs,uint baseValue) {
|
||||
LEFT_MOTOR_DUTY = baseValue;
|
||||
RIGHT_MOTOR_DUTY = baseValue;
|
||||
if (rotateForMs > 0){
|
||||
if(xClockwiseTaskHandle){
|
||||
vTaskDelete(xClockwiseTaskHandle);
|
||||
}
|
||||
xTaskCreate(leftMotorTask, "LeftMotor", 4096, (void*)rotateForMs, 10, &xClockwiseTaskHandle);
|
||||
} else {
|
||||
Motion::left.setSpeed(LEFT_MOTOR_DUTY);
|
||||
@ -66,16 +146,37 @@ void Motion::rotateClockwise(uint32_t rotateForMs) {
|
||||
};
|
||||
|
||||
void Motion::rightMotorTask(void * args) {
|
||||
uint32_t runtime = (uint32_t)args;
|
||||
if(xMoveTaskHandle){
|
||||
vTaskDelete(xMoveTaskHandle);
|
||||
xMoveTaskHandle = NULL;
|
||||
}
|
||||
if(xClockwiseTaskHandle){
|
||||
vTaskDelete(xClockwiseTaskHandle);
|
||||
xClockwiseTaskHandle = NULL;
|
||||
}
|
||||
Motion::right.setSpeed(RIGHT_MOTOR_DUTY);
|
||||
Motion::left.setSpeed(0);
|
||||
vTaskDelay((uint32_t) args / portTICK_PERIOD_MS);
|
||||
Motion::right.setSpeed(0);
|
||||
vTaskDelete(xAntiClockwiseTaskHandle);
|
||||
while(1){
|
||||
if(runtime>40||runtime==0){
|
||||
vTaskDelayUntil(&xLastWakeTime,40);
|
||||
runtime -= 40;
|
||||
} else {
|
||||
vTaskDelayUntil(&xLastWakeTime,runtime);
|
||||
Motion::right.setSpeed(0);
|
||||
vTaskDelete(xAntiClockwiseTaskHandle);
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
// Rotate anticlockwise for a certain amount of time.
|
||||
void Motion::rotateAntiClockwise(uint32_t rotateForMs) {
|
||||
void Motion::rotateAntiClockwise(uint32_t rotateForMs,uint baseValue) {
|
||||
LEFT_MOTOR_DUTY = baseValue;
|
||||
RIGHT_MOTOR_DUTY = baseValue;
|
||||
if(rotateForMs > 0){
|
||||
if(xAntiClockwiseTaskHandle){
|
||||
vTaskDelete(xAntiClockwiseTaskHandle);
|
||||
}
|
||||
xTaskCreate(rightMotorTask, "RightMotor", 4096, (void*)rotateForMs, 10, &xAntiClockwiseTaskHandle);
|
||||
} else {
|
||||
Motion::right.setSpeed(RIGHT_MOTOR_DUTY);
|
||||
@ -84,6 +185,18 @@ void Motion::rotateAntiClockwise(uint32_t rotateForMs) {
|
||||
};
|
||||
|
||||
void Motion::stop(void){
|
||||
if(xMoveTaskHandle){
|
||||
vTaskDelete(xMoveTaskHandle);
|
||||
xMoveTaskHandle = NULL;
|
||||
}
|
||||
if(xAntiClockwiseTaskHandle){
|
||||
vTaskDelete(xAntiClockwiseTaskHandle);
|
||||
xAntiClockwiseTaskHandle = NULL;
|
||||
}
|
||||
if(xClockwiseTaskHandle){
|
||||
vTaskDelete(xClockwiseTaskHandle);
|
||||
xClockwiseTaskHandle = NULL;
|
||||
}
|
||||
Motion::left.setSpeed(0);
|
||||
Motion::right.setSpeed(0);
|
||||
}
|
||||
|
@ -16,17 +16,37 @@
|
||||
#include <freertos/FreeRTOS.h>
|
||||
#include <freertos/task.h>
|
||||
#include "driver/ledc.h"
|
||||
#include "motionDetection/MotionDetection.h"
|
||||
#define LEDC_MODE LEDC_LOW_SPEED_MODE
|
||||
#define TIMER LEDC_TIMER_2
|
||||
#define CHANNEL_LEFT LEDC_CHANNEL_3
|
||||
#define CHANNEL_RIGHT LEDC_CHANNEL_4
|
||||
#define DUTY_RES LEDC_TIMER_13_BIT // Set duty resolution to 13 bits
|
||||
#define FREQUENCY (5000) // Frequency in Hertz. Set frequency at 5 kHz
|
||||
#define DEFAULT_BASE_VALUE 3900
|
||||
class Motor{
|
||||
public:
|
||||
Motor(uint8_t pin, ledc_timer_t timer, ledc_channel_t channel);
|
||||
|
||||
/**
|
||||
* @brief Initializes the motor
|
||||
*/
|
||||
void begin(void);
|
||||
|
||||
/**
|
||||
* @brief Set the Speed by changing the pwm. To avoid current peaks, a linear ramp-up is used.
|
||||
*
|
||||
* @attention it is requried at any time to use that method to access the motors or methods of the motionclass to avoid such peaks.
|
||||
*
|
||||
* @param duty the duty cyle that should be set, can be between 0-8192
|
||||
*/
|
||||
void setSpeed(uint16_t duty);
|
||||
|
||||
/**
|
||||
* @brief returns the currently activ speed
|
||||
*
|
||||
* @return current speedvalue of the motor
|
||||
*/
|
||||
uint16_t getSpeed(void);
|
||||
protected:
|
||||
uint8_t pin;
|
||||
@ -38,18 +58,28 @@ class Motor{
|
||||
|
||||
class Motion{
|
||||
protected:
|
||||
static const uint16_t RIGHT_MOTOR_DUTY = 4096;
|
||||
static const uint16_t LEFT_MOTOR_DUTY = 4096;
|
||||
static inline uint16_t RIGHT_MOTOR_DUTY = DEFAULT_BASE_VALUE;
|
||||
static inline uint16_t LEFT_MOTOR_DUTY = DEFAULT_BASE_VALUE;
|
||||
static const int MOTOR_RIGHT_PIN = 11;
|
||||
static const int MOTOR_LEFT_PIN = 12;
|
||||
static void moveTask(void * args);
|
||||
static void leftMotorTask(void * args);
|
||||
static void rightMotorTask(void * args);
|
||||
static inline TaskHandle_t xMoveTaskHandle = NULL;
|
||||
static inline TaskHandle_t xClockwiseTaskHandle = NULL;
|
||||
static inline TaskHandle_t xAntiClockwiseTaskHandle = NULL;
|
||||
static inline TickType_t xLastWakeTime;
|
||||
|
||||
static inline FIFO_Package* buffer = new FIFO_Package[64];
|
||||
static inline int correctionThreshold = 150;
|
||||
|
||||
public:
|
||||
//Shared Timer to sync movement
|
||||
//Instances of the motors, so they can also be used from outside to set values for the motors directly.
|
||||
static inline Motor left = Motor(MOTOR_LEFT_PIN,TIMER,CHANNEL_LEFT);
|
||||
static inline Motor right = Motor(MOTOR_RIGHT_PIN,TIMER,CHANNEL_RIGHT);
|
||||
|
||||
//MotionDetection instance, for motion Correction and user (access with dezibot.motion.detection)
|
||||
static inline MotionDetection detection;
|
||||
|
||||
/**
|
||||
* @brief Initialize the movement component.
|
||||
@ -60,23 +90,30 @@ public:
|
||||
/**
|
||||
* @brief Move forward for a certain amount of time.
|
||||
* Call with moveForMs 0 will start movement, that must be stopped explicit by call to stop().
|
||||
* The function applys a basic algorithm to improve the straigthness of the movement.
|
||||
* Lifting the robot from the desk may corrupt the results and is not recommended.
|
||||
*
|
||||
* @param moveForMs Representing the duration of forward moving in milliseconds.
|
||||
* @param baseValue The value that is used to start with the calibrated movement. Defaults to 3900.
|
||||
* If the Dezibot is not moving forward at all increasing the value may help. If the robot is just jumping up and down but not forward, try a lower value.
|
||||
*/
|
||||
static void move(uint32_t moveForMs=0);
|
||||
static void move(uint32_t moveForMs=0,uint baseValue=DEFAULT_BASE_VALUE);
|
||||
|
||||
/**
|
||||
* @brief Rotate clockwise for a certain amount of time.
|
||||
* Call with moveForMs 0 will start movement, that must be stopped explicit by call to stop().
|
||||
* @param rotateForMs Representing the duration of rotating clockwise in milliseconds.
|
||||
* @param rotateForMs Representing the duration of rotating clockwise in milliseconds, or 0 to rotate until another movecmd is issued. Default is 0
|
||||
* @param baseValue The value that is used to start with the calibrated movement (not released yet, currently just the used value)
|
||||
*/
|
||||
static void rotateClockwise(uint32_t rotateForMs=0);
|
||||
static void rotateClockwise(uint32_t rotateForMs=0,uint baseValue=DEFAULT_BASE_VALUE);
|
||||
|
||||
/**
|
||||
* @brief Rotate anticlockwise for a certain amount of time.
|
||||
* Call with moveForMs 0 will start movement, that must be stopped explicit by call to stop().
|
||||
* @param rotateForMs Representing the duration of rotating anticlockwise in milliseconds.
|
||||
* @param rotateForMs Representing the duration of rotating anticlockwise in milliseconds or 0 to let the robot turn until another movecommand is issued. Default is 0.
|
||||
* @param baseValue The value that is used to start with the calibrated movement (not released yet, currently just the used value).
|
||||
*/
|
||||
static void rotateAntiClockwise(uint32_t rotateForMs=0);
|
||||
static void rotateAntiClockwise(uint32_t rotateForMs=0,uint baseValue=DEFAULT_BASE_VALUE);
|
||||
|
||||
/**
|
||||
* @brief stops any current movement, no matter if timebased or endless
|
||||
@ -84,6 +121,14 @@ public:
|
||||
*/
|
||||
static void stop(void);
|
||||
|
||||
/**
|
||||
* @brief Does the same as the move function, but this function does not apply any kind of algorithm to improve the result.
|
||||
*
|
||||
* @param moveForMs how many ms should the robot move, or 0 to let the robot move until another move command is mentioned, default is 0
|
||||
* @param baseValue the duty value that is used for the movement, default is 0
|
||||
*/
|
||||
static void moveWithoutCorrection(uint32_t moveForMs=0, uint baseValue = DEFAULT_BASE_VALUE);
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
@ -23,9 +23,24 @@ void Motor::begin(void){
|
||||
};
|
||||
|
||||
void Motor::setSpeed(uint16_t duty){
|
||||
this->duty = duty;
|
||||
ledc_set_duty(LEDC_MODE,this->channel,duty);
|
||||
ledc_update_duty(LEDC_MODE,this->channel);
|
||||
|
||||
int difference = duty-this->getSpeed();
|
||||
if (difference > 0){
|
||||
for(int i = 0;i<difference;i+=difference/20){
|
||||
this->duty += difference/20;
|
||||
ledc_set_duty(LEDC_MODE,this->channel,duty);
|
||||
ledc_update_duty(LEDC_MODE,this->channel);
|
||||
delayMicroseconds(5);
|
||||
}
|
||||
} else {
|
||||
for(int i = 0;i>difference;i-=abs(difference/20)){
|
||||
this->duty -= abs(difference/20);
|
||||
ledc_set_duty(LEDC_MODE,this->channel,duty);
|
||||
ledc_update_duty(LEDC_MODE,this->channel);
|
||||
delayMicroseconds(5);
|
||||
}
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
uint16_t Motor::getSpeed(void){
|
||||
|
49
src/motionDetection/IMU_CMDs.h
Normal file
49
src/motionDetection/IMU_CMDs.h
Normal file
@ -0,0 +1,49 @@
|
||||
#ifndef IMU_CMDs
|
||||
#define IMU_CMDs
|
||||
|
||||
#define CMD_READ 0x80
|
||||
#define CMD_WRITE 0x00
|
||||
#define ADDR_MASK 0x7F
|
||||
|
||||
//Registers
|
||||
#define MCLK_RDY 0x00
|
||||
|
||||
#define REG_TEMP_LOW 0x0A
|
||||
#define REG_TEMP_HIGH 0X09
|
||||
|
||||
#define ACCEL_DATA_X_HIGH 0x0B
|
||||
#define ACCEL_DATA_X_LOW 0x0C
|
||||
#define ACCEL_DATA_Y_HIGH 0x0D
|
||||
#define ACCEL_DATA_Y_LOW 0x0E
|
||||
#define ACCEL_DATA_Z_HIGH 0x0F
|
||||
#define ACCEL_DATA_Z_LOW 0x10
|
||||
|
||||
#define GYRO_DATA_X_HIGH 0x11
|
||||
#define GYRO_DATA_X_LOW 0x12
|
||||
#define GYRO_DATA_Y_HIGH 0x13
|
||||
#define GYRO_DATA_Y_LOW 0x14
|
||||
#define GYRO_DATA_Z_HIGH 0x15
|
||||
#define GYRO_DATA_Z_LOW 0x16
|
||||
|
||||
#define PWR_MGMT0 0x1F
|
||||
#define WHO_AM_I 0x75
|
||||
|
||||
#define INTF_CONFIG0 0x35
|
||||
|
||||
#define BLK_SEL_W 0x79
|
||||
#define BLK_SEL_R 0x7C
|
||||
#define MADDR_W 0x7A
|
||||
#define MADDR_R 0x7D
|
||||
#define M_W 0x7B
|
||||
#define M_R 0x7E
|
||||
|
||||
#define FIFO_COUNTH 0x3D
|
||||
#define FIFO_COUNTL 0x3E
|
||||
#define FIFO_DATA 0x3F
|
||||
#define FIFO_CONFIG1 0x28
|
||||
#define FIFO_CONFIG2 0x29
|
||||
|
||||
//MREG1
|
||||
#define FIFO_CONFIG5 0x01
|
||||
#define TMST_CONFIG1 0x00
|
||||
#endif
|
@ -1,4 +1,5 @@
|
||||
#include "MotionDetection.h"
|
||||
#include <math.h>
|
||||
|
||||
MotionDetection::MotionDetection(){
|
||||
handler = new SPIClass(FSPI);
|
||||
@ -8,32 +9,21 @@ void MotionDetection::begin(void){
|
||||
pinMode(34,OUTPUT);
|
||||
digitalWrite(34,HIGH);
|
||||
handler->begin(36,37,35,34);
|
||||
|
||||
|
||||
handler->beginTransaction(SPISettings(frequency,SPI_MSBFIRST,SPI_MODE0));
|
||||
digitalWrite(34,LOW);
|
||||
// set Accel and Gyroscop to Low Noise
|
||||
handler->transfer(PWR_MGMT0);
|
||||
handler->transfer(0x1F);
|
||||
this->writeRegister(PWR_MGMT0,0x1F);
|
||||
//busy Wait for startup
|
||||
delayMicroseconds(250);
|
||||
//set accelconfig
|
||||
this->writeRegister(0x21,0x05);
|
||||
//set Gyroconfig
|
||||
handler->transfer(0x20);
|
||||
handler->transfer(0x25);
|
||||
this->writeRegister(0x20,0x25);
|
||||
//set Gyro Filter
|
||||
handler->transfer(0x23);
|
||||
handler->transfer(0x37);
|
||||
digitalWrite(34,HIGH);
|
||||
handler->endTransaction();
|
||||
this->writeRegister(0x23,0x37);
|
||||
//Enable Gyro and Acceldata in FIFO
|
||||
this->initFIFO();
|
||||
};
|
||||
void MotionDetection::end(void){
|
||||
handler->beginTransaction(SPISettings(frequency,SPI_MSBFIRST,SPI_MODE0));
|
||||
digitalWrite(34,LOW);
|
||||
handler->transfer(cmdWrite(PWR_MGMT0));
|
||||
//turn Accel and Gyroscope off
|
||||
handler->transfer(0x00);
|
||||
digitalWrite(34,HIGH);
|
||||
handler->end();
|
||||
this->writeRegister(PWR_MGMT0,0x00);
|
||||
};
|
||||
IMUResult MotionDetection::getAcceleration(){
|
||||
IMUResult result;
|
||||
@ -175,7 +165,123 @@ uint8_t MotionDetection::readRegister(uint8_t reg){
|
||||
uint8_t result;
|
||||
result = handler->transfer(cmdRead(reg));
|
||||
result = handler->transfer(0x00);
|
||||
digitalWrite(34,HIGH);
|
||||
digitalWrite(34,HIGH);
|
||||
handler->endTransaction();
|
||||
return result;
|
||||
};
|
||||
|
||||
uint8_t MotionDetection::readFromRegisterBank(registerBank bank,uint8_t reg){
|
||||
uint8_t result = 0;
|
||||
switch(bank){
|
||||
case(MREG1):
|
||||
this->writeRegister(BLK_SEL_R,0x00);
|
||||
break;
|
||||
case(MREG2):
|
||||
this->writeRegister(BLK_SEL_R,0x28);
|
||||
break;
|
||||
case(MREG3):
|
||||
this->writeRegister(BLK_SEL_R,0x50);
|
||||
break;
|
||||
}
|
||||
this->writeRegister(MADDR_R,reg);
|
||||
delayMicroseconds(10);
|
||||
result=this->readRegister(M_R);
|
||||
delayMicroseconds(10);
|
||||
this->resetRegisterBankAccess();
|
||||
return result;
|
||||
};
|
||||
|
||||
void MotionDetection::writeToRegisterBank(registerBank bank, uint8_t reg, uint8_t value){
|
||||
while((this->readRegister(MCLK_RDY))&0x08!=0x08){
|
||||
Serial.println("CLK not rdy");
|
||||
delay(100);
|
||||
}
|
||||
uint8_t result = this->readRegister(PWR_MGMT0);
|
||||
Serial.print("MADDR_W: ");
|
||||
Serial.println(readRegister(MADDR_W));
|
||||
//set Idle Bit
|
||||
this->writeRegister(PWR_MGMT0,result|0x10);
|
||||
switch(bank){
|
||||
case(MREG1):
|
||||
this->writeRegister(BLK_SEL_W,0x00);
|
||||
break;
|
||||
case(MREG2):
|
||||
this->writeRegister(BLK_SEL_W,0x28);
|
||||
break;
|
||||
case(MREG3):
|
||||
this->writeRegister(BLK_SEL_W,0x50);
|
||||
break;
|
||||
}
|
||||
this->writeRegister(MADDR_W,reg);
|
||||
this->writeRegister(M_W,value);
|
||||
delayMicroseconds(10);
|
||||
this->writeRegister(PWR_MGMT0,result&0xEF);
|
||||
Serial.print("MADDR_W: ");
|
||||
Serial.println(readRegister(MADDR_W));
|
||||
this->resetRegisterBankAccess();
|
||||
};
|
||||
|
||||
void MotionDetection::resetRegisterBankAccess(){
|
||||
this->writeRegister(BLK_SEL_R,0x00);
|
||||
this->writeRegister(BLK_SEL_W,0x00);
|
||||
this->writeRegister(MADDR_R,0x00);
|
||||
this->writeRegister(MADDR_W,0x00);
|
||||
};
|
||||
|
||||
void MotionDetection::initFIFO(){
|
||||
delay(60);
|
||||
//set INTF_CONFIG0 FIFO_COUNT_REC_RECORD und Little Endian
|
||||
this->writeRegister(INTF_CONFIG0,0x60);
|
||||
//set FIFO_CONFIG1 to Mode Snapshot and BYPASS Off
|
||||
this->writeRegister(FIFO_CONFIG1,0x00);
|
||||
//set TMST_CONFIG1_MREG1 TMST_CONFIIG1_TMST_EN
|
||||
this->writeToRegisterBank(MREG1,TMST_CONFIG1,0x00);
|
||||
//set FiFO config 5 GYRO_EN,TMST_FSYNC, ACCEL_EN, WM_GT_TH_EN
|
||||
this->writeToRegisterBank(MREG1,FIFO_CONFIG5,0x23);
|
||||
//set FOF_CONFIG2 0x1 (INT triggerd each packaged)
|
||||
this->writeRegister(FIFO_CONFIG2,0x0A);
|
||||
};
|
||||
|
||||
uint MotionDetection::getDataFromFIFO(FIFO_Package* buffer){
|
||||
int16_t fifocount = 0;
|
||||
int8_t fifohigh = this->readRegister(FIFO_COUNTH);
|
||||
int8_t fifolow = this->readRegister(FIFO_COUNTL);
|
||||
fifocount = (fifohigh<<8)|fifolow;
|
||||
//fifocount |= this->readRegister(FIFO_COUNTL);
|
||||
//fifocount = (this->readRegister(FIFO_COUNTH)<<8);
|
||||
Serial.println(fifolow);
|
||||
Serial.println(fifohigh);
|
||||
Serial.println(fifocount);
|
||||
handler->beginTransaction(SPISettings(frequency,SPI_MSBFIRST,SPI_MODE0));
|
||||
digitalWrite(34,LOW);
|
||||
handler->transfer(cmdRead(FIFO_DATA));
|
||||
handler->transfer(buf,16*fifocount);
|
||||
digitalWrite(34,HIGH);
|
||||
handler->endTransaction();
|
||||
|
||||
writeRegister(0x02,0x04);
|
||||
delayMicroseconds(10);
|
||||
|
||||
for(int i = 0; i<fifocount;i++){
|
||||
buffer[i].header = buf[0x00+16*i];
|
||||
buffer[i].accel.x = (buf[0x02+16*i]<<8)|buf[0x01+16*i];
|
||||
buffer[i].accel.y = (buf[0x04+16*i]<<8)|buf[0x03+16*i];
|
||||
buffer[i].accel.z = (buf[0x06+16*i]<<8)|buf[0x05+16*i];
|
||||
buffer[i].gyro.x = (buf[0x08+16*i]<<8)|buf[0x07+16*i];
|
||||
buffer[i].gyro.y = (buf[0x0A+16*i]<<8)|buf[0x09+16*i];
|
||||
buffer[i].gyro.z = (buf[0x0C+16*i]<<8)|buf[0x0B+16*i];
|
||||
buffer[i].temperature = buf[0x0D+16*i];
|
||||
buffer[i].timestamp = (buf[0x0F+16*i]<<8)|buf[0x0E +16*i];
|
||||
}
|
||||
return fifocount;
|
||||
};
|
||||
|
||||
void MotionDetection::writeRegister(uint8_t reg, uint8_t value){
|
||||
handler->beginTransaction(SPISettings(frequency,SPI_MSBFIRST,SPI_MODE0));
|
||||
digitalWrite(34,LOW);
|
||||
handler->transfer(reg);
|
||||
handler->transfer(value);
|
||||
digitalWrite(34,HIGH);
|
||||
delayMicroseconds(10);
|
||||
handler->endTransaction();
|
||||
};
|
@ -12,6 +12,7 @@
|
||||
#define MotionDetection_h
|
||||
#include <SPI.h>
|
||||
#include <Arduino.h>
|
||||
#include "IMU_CMDs.h"
|
||||
struct IMUResult{
|
||||
int16_t x;
|
||||
int16_t y;
|
||||
@ -38,36 +39,25 @@ enum Direction{
|
||||
Error
|
||||
};
|
||||
|
||||
struct FIFO_Package{
|
||||
int8_t header;
|
||||
IMUResult gyro;
|
||||
IMUResult accel;
|
||||
int16_t temperature;
|
||||
int16_t timestamp;
|
||||
};
|
||||
|
||||
|
||||
class MotionDetection{
|
||||
protected:
|
||||
|
||||
static const uint8_t CMD_READ = 0x80;
|
||||
static const uint8_t CMD_WRITE = 0x00;
|
||||
static const uint8_t ADDR_MASK = 0x7F;
|
||||
|
||||
//Registers
|
||||
static const uint8_t REG_TEMP_LOW = 0x0A;
|
||||
static const uint8_t REG_TEMP_HIGH = 0X09;
|
||||
|
||||
static const uint8_t ACCEL_DATA_X_HIGH = 0x0B;
|
||||
static const uint8_t ACCEL_DATA_X_LOW = 0x0C;
|
||||
static const uint8_t ACCEL_DATA_Y_HIGH = 0x0D;
|
||||
static const uint8_t ACCEL_DATA_Y_LOW = 0x0E;
|
||||
static const uint8_t ACCEL_DATA_Z_HIGH = 0x0F;
|
||||
static const uint8_t ACCEL_DATA_Z_LOW = 0x10;
|
||||
|
||||
static const uint8_t GYRO_DATA_X_HIGH = 0x11;
|
||||
static const uint8_t GYRO_DATA_X_LOW = 0x12;
|
||||
static const uint8_t GYRO_DATA_Y_HIGH = 0x13;
|
||||
static const uint8_t GYRO_DATA_Y_LOW = 0x14;
|
||||
static const uint8_t GYRO_DATA_Z_HIGH = 0x15;
|
||||
static const uint8_t GYRO_DATA_Z_LOW = 0x16;
|
||||
|
||||
static const uint8_t PWR_MGMT0 = 0x1F;
|
||||
static const uint8_t WHO_AM_I = 0x75;
|
||||
|
||||
static const uint frequency = 10000000;
|
||||
enum registerBank{MREG1,MREG2,MREG3};
|
||||
static const uint frequency = 24000000;
|
||||
static const uint16_t defaultShakeThreshold = 500;
|
||||
const uint bufferLength = 64*16;
|
||||
int8_t* buf = new int8_t[bufferLength];
|
||||
uint8_t readFromRegisterBank(registerBank bank,uint8_t reg);
|
||||
void writeToRegisterBank(registerBank bank, uint8_t reg, uint8_t value);
|
||||
void resetRegisterBankAccess();
|
||||
|
||||
uint16_t cmdRead(uint8_t regHigh,uint8_t regLow);
|
||||
uint16_t cmdWrite(uint8_t regHigh,uint8_t regLow);
|
||||
@ -76,6 +66,8 @@ protected:
|
||||
|
||||
uint8_t readRegister(uint8_t reg);
|
||||
int16_t readDoubleRegister(uint8_t lowerReg);
|
||||
void writeRegister(uint8_t reg, uint8_t value);
|
||||
void initFIFO();
|
||||
|
||||
SPIClass * handler = NULL;
|
||||
|
||||
@ -183,6 +175,13 @@ public:
|
||||
*/
|
||||
void calibrateZAxis(uint gforceValue);
|
||||
|
||||
|
||||
/**
|
||||
* @brief will read all availible packages from fifo, after 40ms Fifo is full
|
||||
*
|
||||
* @param buffer pointer to FIFO_Package Struct that at least must have size 64 (this is the max package count with APEX Enabled)
|
||||
*
|
||||
* @return the amount of acutally fetched packages
|
||||
*/
|
||||
uint getDataFromFIFO(FIFO_Package* buffer);
|
||||
};
|
||||
#endif //MotionDetection
|
Loading…
x
Reference in New Issue
Block a user