Merge branch 'feature/#20-communication' into 'main'

communication

See merge request wagner/dezibot!6
This commit is contained in:
Anton Jacker
2024-06-13 12:07:36 +00:00
41 changed files with 87563 additions and 225 deletions

5
.gitignore vendored
View File

@ -1,3 +1,6 @@
# automatic gernerated source
docs/*
# Prerequisites
*.d
@ -35,4 +38,4 @@
.vscode/*
.history/
*.vsix
*.workspace
*.workspace

View File

@ -1,9 +1,16 @@
# Dezibot4 Lib
## Links to external documentation
* [PDF-Doku Code](https://hardwarelabor.imn.htwk-leipzig.de/dezibot/dezibot.pdf)
* [PDF-Doku Device](https://hardwarelabor.imn.htwk-leipzig.de/dezibot/dezibot-4doku.pdf)
## Introduction
This repository contains the Library for the Dezibot4.<br>
It is ment to serve as an Arduino-Library. Therefore the rules for arduinolibrary develop apply:<br>
The project focuses on the software for the Dezibot4 robot and its use in the classroom.<br>
It includes libraries for use by students as well as guides for teachers. The hardware of the robot is not part of the project.<br>
The libraries and example programs are available under the GPL and are accessible as a repository.<br>
It is ment to serve as an Arduino-Library.<br>
Therefore the rules for arduinolibrary develop apply:<br>
* [Styleguide](https://docs.arduino.cc/learn/contributions/arduino-library-style-guide)
* [Libraryspecification](https://arduino.github.io/arduino-cli/0.35/library-specification/)

BIN
docs_edited/Banner.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 40 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 14 KiB

View File

@ -1,4 +1,4 @@
# Doxyfile 1.9.1
# Doxyfile 1.8.17
# This file describes the settings to be used by the documentation system
# doxygen (www.doxygen.org) for a project.
@ -51,7 +51,7 @@ PROJECT_BRIEF =
# pixels and the maximum width should not exceed 200 pixels. Doxygen will copy
# the logo to the output directory.
PROJECT_LOGO =
PROJECT_LOGO = /home/wagner/Git/dezibot/docs_edited/dezibot_banner.png
# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) path
# into which the generated documentation will be written. If a relative path is
@ -227,14 +227,6 @@ QT_AUTOBRIEF = NO
MULTILINE_CPP_IS_BRIEF = NO
# By default Python docstrings are displayed as preformatted text and doxygen's
# special commands cannot be used. By setting PYTHON_DOCSTRING to NO the
# doxygen's special commands can be used and the contents of the docstring
# documentation blocks is shown as doxygen documentation.
# The default value is: YES.
PYTHON_DOCSTRING = YES
# If the INHERIT_DOCS tag is set to YES then an undocumented member inherits the
# documentation from any documented member that it re-implements.
# The default value is: YES.
@ -271,13 +263,19 @@ TAB_SIZE = 4
ALIASES =
# This tag can be used to specify a number of word-keyword mappings (TCL only).
# A mapping has the form "name=value". For example adding "class=itcl::class"
# will allow you to use the command class in the itcl::class meaning.
TCL_SUBST =
# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C sources
# only. Doxygen will then generate output that is more tailored for C. For
# instance, some of the names that are used will be different. The list of all
# members will be omitted, etc.
# The default value is: NO.
OPTIMIZE_OUTPUT_FOR_C = YES
OPTIMIZE_OUTPUT_FOR_C = NO
# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java or
# Python sources only. Doxygen will then generate output that is more tailored
@ -312,21 +310,18 @@ OPTIMIZE_OUTPUT_SLICE = NO
# extension. Doxygen has a built-in mapping, but you can override or extend it
# using this tag. The format is ext=language, where ext is a file extension, and
# language is one of the parsers supported by doxygen: IDL, Java, JavaScript,
# Csharp (C#), C, C++, D, PHP, md (Markdown), Objective-C, Python, Slice, VHDL,
# Csharp (C#), C, C++, D, PHP, md (Markdown), Objective-C, Python, Slice,
# Fortran (fixed format Fortran: FortranFixed, free formatted Fortran:
# FortranFree, unknown formatted Fortran: Fortran. In the later case the parser
# tries to guess whether the code is fixed or free formatted code, this is the
# default for Fortran type files). For instance to make doxygen treat .inc files
# as Fortran files (default is PHP), and .f files as C (default is Fortran),
# use: inc=Fortran f=C.
# default for Fortran type files), VHDL, tcl. For instance to make doxygen treat
# .inc files as Fortran files (default is PHP), and .f files as C (default is
# Fortran), use: inc=Fortran f=C.
#
# Note: For files without extension you can use no_extension as a placeholder.
#
# Note that for custom extensions you also need to set FILE_PATTERNS otherwise
# the files are not read by doxygen. When specifying no_extension you should add
# * to the FILE_PATTERNS.
#
# Note see also the list of default file extension mappings.
# the files are not read by doxygen.
EXTENSION_MAPPING =
@ -460,19 +455,6 @@ TYPEDEF_HIDES_STRUCT = NO
LOOKUP_CACHE_SIZE = 0
# The NUM_PROC_THREADS specifies the number threads doxygen is allowed to use
# during processing. When set to 0 doxygen will based this on the number of
# cores available in the system. You can set it explicitly to a value larger
# than 0 to get more control over the balance between CPU load and processing
# speed. At this moment only the input processing can be done using multiple
# threads. Since this is still an experimental feature the default is set to 1,
# which efficively disables parallel processing. Please report any issues you
# encounter. Generating dot graphs in parallel is controlled by the
# DOT_NUM_THREADS setting.
# Minimum value: 0, maximum value: 32, default value: 1.
NUM_PROC_THREADS = 1
#---------------------------------------------------------------------------
# Build related configuration options
#---------------------------------------------------------------------------
@ -536,13 +518,6 @@ EXTRACT_LOCAL_METHODS = NO
EXTRACT_ANON_NSPACES = NO
# If this flag is set to YES, the name of an unnamed parameter in a declaration
# will be determined by the corresponding definition. By default unnamed
# parameters remain unnamed in the output.
# The default value is: YES.
RESOLVE_UNNAMED_PARAMS = YES
# If the HIDE_UNDOC_MEMBERS tag is set to YES, doxygen will hide all
# undocumented members inside documented classes or files. If set to NO these
# members will be included in the various overviews, but no documentation
@ -580,18 +555,11 @@ HIDE_IN_BODY_DOCS = NO
INTERNAL_DOCS = NO
# With the correct setting of option CASE_SENSE_NAMES doxygen will better be
# able to match the capabilities of the underlying filesystem. In case the
# filesystem is case sensitive (i.e. it supports files in the same directory
# whose names only differ in casing), the option must be set to YES to properly
# deal with such files in case they appear in the input. For filesystems that
# are not case sensitive the option should be be set to NO to properly deal with
# output files written for symbols that only differ in casing, such as for two
# classes, one named CLASS and the other named Class, and to also support
# references to files without having to specify the exact matching casing. On
# Windows (including Cygwin) and MacOS, users should typically set this option
# to NO, whereas on Linux or other Unix flavors it should typically be set to
# YES.
# If the CASE_SENSE_NAMES tag is set to NO then doxygen will only generate file
# names in lower-case letters. If set to YES, upper-case letters are also
# allowed. This is useful if you have classes or files whose names only differ
# in case and if your file system supports case sensitive file names. Windows
# (including Cygwin) ands Mac users are advised to set this option to NO.
# The default value is: system dependent.
CASE_SENSE_NAMES = NO
@ -830,10 +798,7 @@ WARN_IF_DOC_ERROR = YES
WARN_NO_PARAMDOC = NO
# If the WARN_AS_ERROR tag is set to YES then doxygen will immediately stop when
# a warning is encountered. If the WARN_AS_ERROR tag is set to FAIL_ON_WARNINGS
# then doxygen will continue running as if WARN_AS_ERROR tag is set to NO, but
# at the end of the doxygen process doxygen will return with a non-zero status.
# Possible values are: NO, YES and FAIL_ON_WARNINGS.
# a warning is encountered.
# The default value is: NO.
WARN_AS_ERROR = NO
@ -864,14 +829,14 @@ WARN_LOGFILE =
# spaces. See also FILE_PATTERNS and EXTENSION_MAPPING
# Note: If this tag is empty the current directory is searched.
INPUT = src \
doxymain.md
INPUT = . \
README.md
# This tag can be used to specify the character encoding of the source files
# that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses
# libiconv (or the iconv built into libc) for the transcoding. See the libiconv
# documentation (see:
# https://www.gnu.org/software/libiconv/) for the list of possible encodings.
# documentation (see: https://www.gnu.org/software/libiconv/) for the list of
# possible encodings.
# The default value is: UTF-8.
INPUT_ENCODING = UTF-8
@ -884,15 +849,13 @@ INPUT_ENCODING = UTF-8
# need to set EXTENSION_MAPPING for the extension otherwise the files are not
# read by doxygen.
#
# Note the list of default checked file patterns might differ from the list of
# default file extension mappings.
#
# If left blank the following patterns are tested:*.c, *.cc, *.cxx, *.cpp,
# *.c++, *.java, *.ii, *.ixx, *.ipp, *.i++, *.inl, *.idl, *.ddl, *.odl, *.h,
# *.hh, *.hxx, *.hpp, *.h++, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, *.inc,
# *.m, *.markdown, *.md, *.mm, *.dox (to be provided as doxygen C comment),
# *.py, *.pyw, *.f90, *.f95, *.f03, *.f08, *.f18, *.f, *.for, *.vhd, *.vhdl,
# *.ucf, *.qsf and *.ice.
# *.doc (to be provided as doxygen C comment), *.txt (to be provided as doxygen
# C comment), *.py, *.pyw, *.f90, *.f95, *.f03, *.f08, *.f, *.for, *.tcl, *.vhd,
# *.vhdl, *.ucf, *.qsf and *.ice.
FILE_PATTERNS = *.c \
*.cc \
@ -938,7 +901,8 @@ FILE_PATTERNS = *.c \
*.vhdl \
*.ucf \
*.qsf \
*.ice
*.ice \
*.ino
# The RECURSIVE tag can be used to specify whether or not subdirectories should
# be searched for input files as well.
@ -1062,7 +1026,7 @@ FILTER_SOURCE_PATTERNS =
# (index.html). This can be useful if you have a project on for instance GitHub
# and want to reuse the introduction page also for the doxygen output.
USE_MDFILE_AS_MAINPAGE = doxymain.md
USE_MDFILE_AS_MAINPAGE = README.md
#---------------------------------------------------------------------------
# Configuration options related to source browsing
@ -1151,22 +1115,16 @@ USE_HTAGS = NO
VERBATIM_HEADERS = YES
# If the CLANG_ASSISTED_PARSING tag is set to YES then doxygen will use the
# clang parser (see:
# http://clang.llvm.org/) for more accurate parsing at the cost of reduced
# performance. This can be particularly helpful with template rich C++ code for
# which doxygen's built-in parser lacks the necessary type information.
# clang parser (see: http://clang.llvm.org/) for more accurate parsing at the
# cost of reduced performance. This can be particularly helpful with template
# rich C++ code for which doxygen's built-in parser lacks the necessary type
# information.
# Note: The availability of this option depends on whether or not doxygen was
# generated with the -Duse_libclang=ON option for CMake.
# The default value is: NO.
CLANG_ASSISTED_PARSING = NO
# If clang assisted parsing is enabled and the CLANG_ADD_INC_PATHS tag is set to
# YES then doxygen will add the directory of each input to the include path.
# The default value is: YES.
CLANG_ADD_INC_PATHS = YES
# If clang assisted parsing is enabled you can provide the compiler with command
# line options that you would normally use when invoking the compiler. Note that
# the include paths will already be set by doxygen for the files and directories
@ -1176,13 +1134,10 @@ CLANG_ADD_INC_PATHS = YES
CLANG_OPTIONS =
# If clang assisted parsing is enabled you can provide the clang parser with the
# path to the directory containing a file called compile_commands.json. This
# file is the compilation database (see:
# http://clang.llvm.org/docs/HowToSetupToolingForLLVM.html) containing the
# options used when the source files were built. This is equivalent to
# specifying the -p option to a clang tool, such as clang-check. These options
# will then be passed to the parser. Any options specified with CLANG_OPTIONS
# will be added as well.
# path to the compilation database (see:
# http://clang.llvm.org/docs/HowToSetupToolingForLLVM.html) used when the files
# were built. This is equivalent to specifying the "-p" option to a clang tool,
# such as clang-check. These options will then be passed to the parser.
# Note: The availability of this option depends on whether or not doxygen was
# generated with the -Duse_libclang=ON option for CMake.
@ -1199,6 +1154,13 @@ CLANG_DATABASE_PATH =
ALPHABETICAL_INDEX = YES
# The COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns in
# which the alphabetical index list will be split.
# Minimum value: 1, maximum value: 20, default value: 5.
# This tag requires that the tag ALPHABETICAL_INDEX is set to YES.
COLS_IN_ALPHA_INDEX = 5
# In case all classes in a project start with a common prefix, all classes will
# be put under the same header in the alphabetical index. The IGNORE_PREFIX tag
# can be used to specify a prefix (or a list of prefixes) that should be ignored
@ -1369,11 +1331,10 @@ HTML_INDEX_NUM_ENTRIES = 100
# If the GENERATE_DOCSET tag is set to YES, additional index files will be
# generated that can be used as input for Apple's Xcode 3 integrated development
# environment (see:
# https://developer.apple.com/xcode/), introduced with OSX 10.5 (Leopard). To
# create a documentation set, doxygen will generate a Makefile in the HTML
# output directory. Running make will produce the docset in that directory and
# running make install will install the docset in
# environment (see: https://developer.apple.com/xcode/), introduced with OSX
# 10.5 (Leopard). To create a documentation set, doxygen will generate a
# Makefile in the HTML output directory. Running make will produce the docset in
# that directory and running make install will install the docset in
# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find it at
# startup. See https://developer.apple.com/library/archive/featuredarticles/Doxy
# genXcode/_index.html for more information.
@ -1415,8 +1376,8 @@ DOCSET_PUBLISHER_NAME = Publisher
# If the GENERATE_HTMLHELP tag is set to YES then doxygen generates three
# additional HTML index files: index.hhp, index.hhc, and index.hhk. The
# index.hhp is a project file that can be read by Microsoft's HTML Help Workshop
# (see:
# https://www.microsoft.com/en-us/download/details.aspx?id=21138) on Windows.
# (see: https://www.microsoft.com/en-us/download/details.aspx?id=21138) on
# Windows.
#
# The HTML Help Workshop contains a compiler that can convert all HTML output
# generated by doxygen into a single compiled HTML file (.chm). Compiled HTML
@ -1446,7 +1407,7 @@ CHM_FILE =
HHC_LOCATION =
# The GENERATE_CHI flag controls if a separate .chi index file is generated
# (YES) or that it should be included in the main .chm file (NO).
# (YES) or that it should be included in the master .chm file (NO).
# The default value is: NO.
# This tag requires that the tag GENERATE_HTMLHELP is set to YES.
@ -1491,8 +1452,7 @@ QCH_FILE =
# The QHP_NAMESPACE tag specifies the namespace to use when generating Qt Help
# Project output. For more information please see Qt Help Project / Namespace
# (see:
# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#namespace).
# (see: https://doc.qt.io/archives/qt-4.8/qthelpproject.html#namespace).
# The default value is: org.doxygen.Project.
# This tag requires that the tag GENERATE_QHP is set to YES.
@ -1500,8 +1460,8 @@ QHP_NAMESPACE = org.doxygen.Project
# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating Qt
# Help Project output. For more information please see Qt Help Project / Virtual
# Folders (see:
# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#virtual-folders).
# Folders (see: https://doc.qt.io/archives/qt-4.8/qthelpproject.html#virtual-
# folders).
# The default value is: doc.
# This tag requires that the tag GENERATE_QHP is set to YES.
@ -1509,16 +1469,16 @@ QHP_VIRTUAL_FOLDER = doc
# If the QHP_CUST_FILTER_NAME tag is set, it specifies the name of a custom
# filter to add. For more information please see Qt Help Project / Custom
# Filters (see:
# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom-filters).
# Filters (see: https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom-
# filters).
# This tag requires that the tag GENERATE_QHP is set to YES.
QHP_CUST_FILTER_NAME =
# The QHP_CUST_FILTER_ATTRS tag specifies the list of the attributes of the
# custom filter to add. For more information please see Qt Help Project / Custom
# Filters (see:
# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom-filters).
# Filters (see: https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom-
# filters).
# This tag requires that the tag GENERATE_QHP is set to YES.
QHP_CUST_FILTER_ATTRS =
@ -1530,9 +1490,9 @@ QHP_CUST_FILTER_ATTRS =
QHP_SECT_FILTER_ATTRS =
# The QHG_LOCATION tag can be used to specify the location (absolute path
# including file name) of Qt's qhelpgenerator. If non-empty doxygen will try to
# run qhelpgenerator on the generated .qhp file.
# The QHG_LOCATION tag can be used to specify the location of Qt's
# qhelpgenerator. If non-empty doxygen will try to run qhelpgenerator on the
# generated .qhp file.
# This tag requires that the tag GENERATE_QHP is set to YES.
QHG_LOCATION =
@ -1583,7 +1543,7 @@ DISABLE_INDEX = NO
# The default value is: NO.
# This tag requires that the tag GENERATE_HTML is set to YES.
GENERATE_TREEVIEW = NO
GENERATE_TREEVIEW = YES
# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values that
# doxygen will group on one line in the generated HTML documentation.
@ -1609,17 +1569,6 @@ TREEVIEW_WIDTH = 250
EXT_LINKS_IN_WINDOW = NO
# If the HTML_FORMULA_FORMAT option is set to svg, doxygen will use the pdf2svg
# tool (see https://github.com/dawbarton/pdf2svg) or inkscape (see
# https://inkscape.org) to generate formulas as SVG images instead of PNGs for
# the HTML output. These images will generally look nicer at scaled resolutions.
# Possible values are: png (the default) and svg (looks nicer but requires the
# pdf2svg or inkscape tool).
# The default value is: png.
# This tag requires that the tag GENERATE_HTML is set to YES.
HTML_FORMULA_FORMAT = png
# Use this tag to change the font size of LaTeX formulas included as images in
# the HTML documentation. When you change the font size after a successful
# doxygen run you need to manually remove any form_*.png images from the HTML
@ -1659,7 +1608,7 @@ USE_MATHJAX = NO
# When MathJax is enabled you can set the default output format to be used for
# the MathJax output. See the MathJax site (see:
# http://docs.mathjax.org/en/v2.7-latest/output.html) for more details.
# http://docs.mathjax.org/en/latest/output.html) for more details.
# Possible values are: HTML-CSS (which is slower, but has the best
# compatibility), NativeMML (i.e. MathML) and SVG.
# The default value is: HTML-CSS.
@ -1675,7 +1624,7 @@ MATHJAX_FORMAT = HTML-CSS
# Content Delivery Network so you can quickly see the result without installing
# MathJax. However, it is strongly recommended to install a local copy of
# MathJax from https://www.mathjax.org before deployment.
# The default value is: https://cdn.jsdelivr.net/npm/mathjax@2.
# The default value is: https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.5/.
# This tag requires that the tag USE_MATHJAX is set to YES.
MATHJAX_RELPATH = https://cdn.jsdelivr.net/npm/mathjax@2
@ -1689,8 +1638,7 @@ MATHJAX_EXTENSIONS =
# The MATHJAX_CODEFILE tag can be used to specify a file with javascript pieces
# of code that will be used on startup of the MathJax code. See the MathJax site
# (see:
# http://docs.mathjax.org/en/v2.7-latest/output.html) for more details. For an
# (see: http://docs.mathjax.org/en/latest/output.html) for more details. For an
# example see the documentation.
# This tag requires that the tag USE_MATHJAX is set to YES.
@ -1737,8 +1685,7 @@ SERVER_BASED_SEARCH = NO
#
# Doxygen ships with an example indexer (doxyindexer) and search engine
# (doxysearch.cgi) which are based on the open source search engine library
# Xapian (see:
# https://xapian.org/).
# Xapian (see: https://xapian.org/).
#
# See the section "External Indexing and Searching" for details.
# The default value is: NO.
@ -1751,9 +1698,8 @@ EXTERNAL_SEARCH = NO
#
# Doxygen ships with an example indexer (doxyindexer) and search engine
# (doxysearch.cgi) which are based on the open source search engine library
# Xapian (see:
# https://xapian.org/). See the section "External Indexing and Searching" for
# details.
# Xapian (see: https://xapian.org/). See the section "External Indexing and
# Searching" for details.
# This tag requires that the tag SEARCHENGINE is set to YES.
SEARCHENGINE_URL =
@ -1917,11 +1863,9 @@ LATEX_EXTRA_FILES =
PDF_HYPERLINKS = YES
# If the USE_PDFLATEX tag is set to YES, doxygen will use the engine as
# specified with LATEX_CMD_NAME to generate the PDF file directly from the LaTeX
# files. Set this option to YES, to get a higher quality PDF documentation.
#
# See also section LATEX_CMD_NAME for selecting the engine.
# If the USE_PDFLATEX tag is set to YES, doxygen will use pdflatex to generate
# the PDF file directly from the LaTeX files. Set this option to YES, to get a
# higher quality PDF documentation.
# The default value is: YES.
# This tag requires that the tag GENERATE_LATEX is set to YES.
@ -2160,10 +2104,6 @@ DOCBOOK_PROGRAMLISTING = NO
GENERATE_AUTOGEN_DEF = NO
#---------------------------------------------------------------------------
# Configuration options related to Sqlite3 output
#---------------------------------------------------------------------------
#---------------------------------------------------------------------------
# Configuration options related to the Perl module output
#---------------------------------------------------------------------------
@ -2436,31 +2376,9 @@ UML_LOOK = NO
# but if the number exceeds 15, the total amount of fields shown is limited to
# 10.
# Minimum value: 0, maximum value: 100, default value: 10.
# This tag requires that the tag UML_LOOK is set to YES.
UML_LIMIT_NUM_FIELDS = 10
# If the DOT_UML_DETAILS tag is set to NO, doxygen will show attributes and
# methods without types and arguments in the UML graphs. If the DOT_UML_DETAILS
# tag is set to YES, doxygen will add type and arguments for attributes and
# methods in the UML graphs. If the DOT_UML_DETAILS tag is set to NONE, doxygen
# will not generate fields with class member information in the UML graphs. The
# class diagrams will look similar to the default class diagrams but using UML
# notation for the relationships.
# Possible values are: NO, YES and NONE.
# The default value is: NO.
# This tag requires that the tag UML_LOOK is set to YES.
DOT_UML_DETAILS = NO
# The DOT_WRAP_THRESHOLD tag can be used to set the maximum number of characters
# to display on a single line. If the actual line length exceeds this threshold
# significantly it will wrapped across multiple lines. Some heuristics are apply
# to avoid ugly line breaks.
# Minimum value: 0, maximum value: 1000, default value: 17.
# This tag requires that the tag HAVE_DOT is set to YES.
DOT_WRAP_THRESHOLD = 17
UML_LIMIT_NUM_FIELDS = 10
# If the TEMPLATE_RELATIONS tag is set to YES then the inheritance and
# collaboration graphs will show the relations between templates and their
@ -2653,11 +2571,9 @@ DOT_MULTI_TARGETS = NO
GENERATE_LEGEND = YES
# If the DOT_CLEANUP tag is set to YES, doxygen will remove the intermediate
# If the DOT_CLEANUP tag is set to YES, doxygen will remove the intermediate dot
# files that are used to generate the various graphs.
#
# Note: This setting is not only used for dot files but also for msc and
# plantuml temporary files.
# The default value is: YES.
# This tag requires that the tag HAVE_DOT is set to YES.
DOT_CLEANUP = YES
DOT_CLEANUP = YES

View File

@ -0,0 +1,8 @@
{
// Use IntelliSense to learn about possible attributes.
// Hover to view descriptions of existing attributes.
"version": "0.2.0",
"configurations": [
]
}

View File

@ -0,0 +1,48 @@
#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);
}

View File

@ -0,0 +1,156 @@
#include <Dezibot.h>
#include <arduinoFFT.h>
#include <rom/ets_sys.h>
const uint16_t samples = 256; //This value MUST ALWAYS be a power of 2
const int centeredThreshold = 50 ;
//const float signalFrequency = 1000;
const float samplingFrequency = 4000;
float vReal[4][samples];
float vImag[4][samples];
#define SCL_INDEX 0x00
#define SCL_TIME 0x01
#define SCL_FREQUENCY 0x02
#define SCL_PLOT 0x03
ArduinoFFT<float> FFT = ArduinoFFT<float>(vReal[0], vImag[0], samples, samplingFrequency); /* Create FFT object */
Dezibot dezibot = Dezibot();
void setup() {
dezibot.begin();
Serial.begin(115200);
//dezibot.infraredLight.front.turnOn();
//dezibot.infraredLight.bottom.turnOn();
}
void loop() {
portDISABLE_INTERRUPTS();
for(int i = 0; i < samples; i++){
vReal[0][i] = dezibot.lightDetection.getValue(IR_FRONT);
vImag[0][i] = 0.0;
vReal[1][i] = dezibot.lightDetection.getValue(IR_LEFT);
vImag[1][i] = 0.0;
vReal[2][i] = dezibot.lightDetection.getValue(IR_RIGHT);
vImag[2][i] = 0.0;
vReal[3][i] = dezibot.lightDetection.getValue(IR_BACK);
vImag[3][i] = 0.0;
ets_delay_us(125);
}
portENABLE_INTERRUPTS();
//PrintVector(vReal, (samples>>1), 0);
//PrintVector(vReal, (samples>>1), 0);
float frequency[4];
float magnitude[4];
for(int index = 0; index <4; index++){
FFT.setArrays(vReal[index], vImag[index]);
FFT.windowing(FFTWindow::Rectangle, FFTDirection::Forward); /* Weigh data */
FFT.compute(FFTDirection::Forward); /* Compute FFT */
FFT.complexToMagnitude(); /* Compute magnitudes */
FFT.majorPeak(&frequency[index],&magnitude[index]);
if(abs(frequency[index]-1147)>10){
magnitude[index] = 0;
}
Serial.print(index);
Serial.print(":");
Serial.print(frequency[index]);
Serial.print(",");
Serial.print(index+4);
Serial.print(":");
Serial.print(magnitude[index]);
if(index < 3){
Serial.print(",");
}
Serial.println();
}
//================================================
float leftValue = magnitude[1];
float rightValue = magnitude[2];
switch(brightest(magnitude)){
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;
}
}
photoTransistors brightest(float *magnitudes){
int pos;
float maxMagnitude = 0;
for(int index = 0; index <4; index++){
if (magnitudes[index] > maxMagnitude){
pos = index;
maxMagnitude = magnitudes[index];
}
}
switch (pos) {
case 0:
return IR_FRONT;
case 1:
return IR_LEFT;
case 2:
return IR_RIGHT;
case 3:
return IR_BACK;
}
}
void PrintVector(float *vData, uint16_t bufferSize, uint8_t scaleType)
{
for (uint16_t i = 0; i < bufferSize; i++)
{
float abscissa;
/* Print abscissa value */
switch (scaleType)
{
case SCL_INDEX:
abscissa = (i * 1.0);
break;
case SCL_TIME:
abscissa = ((i * 1.0) / samplingFrequency);
break;
case SCL_FREQUENCY:
abscissa = ((i * 1.0 * samplingFrequency) / samples);
break;
}
Serial.print(abscissa, 6);
if(scaleType==SCL_FREQUENCY)
Serial.print("Hz");
Serial.print(" ");
Serial.println(vData[i], 4);
}
Serial.println();
}

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,34 @@
#include "Dezibot.h"
Dezibot dezibot = Dezibot();
void setup() {
// put your setup code here, to run once:
dezibot.begin();
Serial.begin(115200);
Serial.println("AAA");
}
//https://esp32cube.com/basis/032_millis/
int indices = 0;
void loop() {
// put your main code here, to run repeatedly:
int zvalue = 0;
for(int i = 0; i<30;i++){
zvalue += dezibot.motionDetection.getAcceleration().z;
}
zvalue = zvalue/30;
if(zvalue < -1700){
dezibot.multiColorLight.setLed(ALL,0x004000);
Serial.println("AAA");
} else if(zvalue > 1700){
dezibot.multiColorLight.setLed(ALL,0x400000);
} else {
dezibot.multiColorLight.turnOffLed();
}
}

View File

@ -0,0 +1,19 @@
#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:
if(dezibot.motionDetection.isShaken(1000,zAxis)){
dezibot.multiColorLight.setTopLeds(0xFF0000);
} else if(dezibot.motionDetection.isShaken(1000,xAxis|yAxis)) {
dezibot.multiColorLight.setTopLeds(0x00FF00);
}
}

View File

@ -0,0 +1,37 @@
#include "Dezibot.h"
Dezibot dezibot = Dezibot();
void setup() {
// put your setup code here, to run once:
Serial.begin(115200);
dezibot.begin();
}
void loop() {
switch (dezibot.motionDetection.getTiltDirection()) {
case Front:
dezibot.multiColorLight.setTopLeds(GREEN);
break;
case Left:
dezibot.multiColorLight.setTopLeds(YELLOW);
break;
case Right:
dezibot.multiColorLight.setTopLeds(TURQUOISE);
break;
case Back:
dezibot.multiColorLight.setTopLeds(BLUE);
break;
case Flipped:
dezibot.multiColorLight.setTopLeds(PINK);
break;
case Neutral:
dezibot.multiColorLight.turnOffLed();
break;
case Error:
dezibot.multiColorLight.setTopLeds(RED);
break;
}
delay(100);
}

View File

@ -0,0 +1,35 @@
#include "Dezibot.h"
Dezibot dezibot = Dezibot();
void setup() {
// put your setup code here, to run once:
dezibot.begin();
Serial.begin(115200);
}
void loop() {
// put your main code here, to run repeatedly:
Serial.print("Front:");
Serial.print(dezibot.lightDetection.getAverageValue(IR_FRONT,20,1));
Serial.print(",Left:");
Serial.print(dezibot.lightDetection.getAverageValue(IR_LEFT,20,1));
Serial.print(",Right:");
Serial.print(dezibot.lightDetection.getAverageValue(IR_RIGHT,20,1));
Serial.print(",Back:");
Serial.println(dezibot.lightDetection.getAverageValue(IR_BACK,20,1));
switch(dezibot.lightDetection.getBrightest(IR)){
case IR_FRONT:
dezibot.multiColorLight.setTopLeds(BLUE);
break;
case IR_LEFT:
dezibot.multiColorLight.setTopLeds(RED);
break;
case IR_RIGHT:
dezibot.multiColorLight.setTopLeds(GREEN);
break;
case IR_BACK:
dezibot.multiColorLight.setTopLeds(YELLOW);
break;
}
//delay(100);
}

View File

@ -0,0 +1,17 @@
#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);
dezibot.infraredLight.bottom.turnOn();
dezibot.infraredLight.front.turnOn();
}
void loop() {
//delay(100);
}

View File

@ -0,0 +1,82 @@
#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:
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();
// T
longSignal(1);
pauseLetter();
// E
shortSignal(1);
pauseLetter();
// S
shortSignal(3);
pauseLetter();
// T
longSignal(1);
pauseLetter();
pauseWord();
//A
shortSignal(1);
longSignal(1);
pauseLetter();
//B
longSignal(1);
shortSignal(3);
pauseLetter();
//C
longSignal(1);
shortSignal(1);
longSignal(1);
shortSignal(1);
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();
}
void shortSignal(int count){
for(int i=0; i < count; i++){
dezibot.motion.move();
delay(1000);
dezibot.motion.stop();
delay(1000);
}
}
void longSignal(int count){
for(int i=0; i < count; i++){
dezibot.motion.move();
delay(3000);
dezibot.motion.stop();
delay(1000);
}
}
void pauseLetter(){
delay(2000);
}
void pauseWord(){
delay(6000);
}

View File

@ -0,0 +1,393 @@
/**************************************************************************
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();
}

View File

@ -0,0 +1,17 @@
#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.display.print("Hello from\nDezibot!");
delay(5000);
dezibot.display.clear();
dezibot.display.print("Bye!");
delay(5000);
dezibot.display.clear();
}

View File

@ -2,6 +2,10 @@
Dezibot dezibot = Dezibot();
void setup() {
dezibot.begin();
<<<<<<< HEAD:example/motion_indicating/motion_indicating.ino
=======
Serial.begin(115200);
>>>>>>> remotes/origin/feature/#9-display:example/motion/motion.ino
}
void loop() {
dezibot.motion.move(1000);

View File

@ -1,24 +1,22 @@
/**
* @file Dezibot.cpp
* @author Anton Jacker, Hans Haupt, Saskia Duebener
* @brief
* @version 0.1
* @date 2023-11-26
*
* @copyright Copyright (c) 2023
*
*/
#define SDA_PIN 1
#define SCL_PIN 2
#include "Dezibot.h"
#include <Wire.h>
Dezibot::Dezibot():multiColorLight(),motionDetection(){
};
#define GPIO_LED 48
void Dezibot::begin(void) {
motion.begin();
multiColorLight.begin();
Wire.begin(SDA_PIN,SCL_PIN);
infraredLight.begin();
lightDetection.begin();
motion.begin();
lightDetection.begin();
colorDetection.begin();
multiColorLight.begin();
motionDetection.begin();
display.begin();
};

View File

@ -1,6 +1,6 @@
/**
* @file Dezibot.h
* @author your name (you@domain.com)
* @author Hans Haupt, Jens Wagner, Anina Morgner, Anton Jacker, Saskia Dübener
* @brief
* @version 0.1
* @date 2023-11-19
@ -16,36 +16,24 @@
#include "colorDetection/ColorDetection.h"
#include "multiColorLight/MultiColorLight.h"
#include "motionDetection/MotionDetection.h"
#include "infraredLight/InfraredLight.h"
#include "communication/Communication.h"
#include "display/Display.h"
class Dezibot {
protected:
public:
Dezibot();
Motion motion;
LightDetection lightDetection;
ColorDetection colorDetection;
MultiColorLight multiColorLight;
MotionDetection motionDetection;
InfraredLight infraredLight;
Communication communication;
Display display;
void begin(void);
/*
Display display
IRCommuncation irCommuncation (beinhaltet Kommuniaktion / Annhärung...)
Battery battery
Extension extension
WiFi wifi //wie wird WiFi geschrieben?
//nur lesender Zugriff, in dieser Klasse sind andere Instanzen mit dem Dezibotinterface gekapselt
Friends friends
OperatingSystem operatingSystem
USBCommunication usbCommunication
Button button
//nicht unique, initzial Dezibot
String robotName
*/
};
#endif //Dezibot_h

View File

@ -0,0 +1,83 @@
#include "ColorDetection.h"
void ColorDetection::begin(void){
ColorDetection::configure(VEML_CONFIG{.mode = AUTO,.enabled = true,.exposureTime=MS40});
};
void ColorDetection::configure(VEML_CONFIG config){
uint8_t configRegister = 0;
switch(config.exposureTime)
{
case MS40:
configRegister = 0x00;break;
case MS80:
configRegister = 0x01;break;
case MS160:
configRegister = 0x02;break;
case MS320:
configRegister = 0x03;break;
case MS640:
configRegister = 0x04;break;
case MS1280:
configRegister = 0x05;break;
}
configRegister = configRegister << 4;
if(config.mode == MANUAL)
{
configRegister = configRegister | (0x01<<1);
}
if(!config.enabled)
{
configRegister = configRegister | 1;
}
ColorDetection::writeDoubleRegister(CMD_CONFIG,(uint16_t)configRegister);
};
uint16_t ColorDetection::getColorValue(color color){
switch(color)
{
case VEML_RED:
return readDoubleRegister(REG_RED);
break;
case VEML_GREEN:
return readDoubleRegister(REG_GREEN);
break;
case VEML_BLUE:
return readDoubleRegister(REG_BLUE);
break;
case VEML_WHITE:
return readDoubleRegister(REG_WHITE);
break;
default:
Serial.println("Color is not supported by the sensor");
return 0;
}
};
uint16_t ColorDetection::readDoubleRegister(uint8_t regAddr){
uint16_t result = 0;
Wire.beginTransmission(VEML_ADDR);
Wire.write(regAddr);
if(Wire.endTransmission() != 0){
Serial.printf("Reading Register %d failed",regAddr);
}
Wire.requestFrom(VEML_ADDR,2);
uint8_t offset = 0;
while(Wire.available()){
result = result << 8;
result = result | (Wire.read()<<offset);
offset = offset + 8;
}
return result;
};
void ColorDetection::writeDoubleRegister(uint8_t regAddr, uint16_t data){
//erst low dann high
Wire.beginTransmission(VEML_ADDR);
Wire.write(regAddr);
Wire.write((uint8_t)(data&0x00FF));
Wire.write((uint8_t)((data>>8)&0x00FF));
if(Wire.endTransmission() != 0){
Serial.printf("Reading Register %d failed",regAddr);
}
};

View File

@ -1,7 +1,68 @@
/**
* @file ColorDetecion.h
* @author Hans Haupt
* @brief Class that controls the colorsensor (VEML6040) of the dezibot.
* @version 0.1
* @date 2024-06-01
*
* @copyright Copyright (c) 2024
*
*/
#ifndef ColorDetection_h
#define ColorDetection_h
#include <stdint.h>
#include <Wire.h>
#include <Arduino.h>
//Definitions for I2c
#define I2C_MASTER_SCL_IO 2 /*!< GPIO number used for I2C master clock */
#define I2C_MASTER_SDA_IO 1 /*!< GPIO number used for I2C master data */
//Chipadress of the VEML6040
#define VEML_ADDR 0x10 /*!< Slave address of the MPU9250 sensor */
//CMDCodes for communicate with the VEML6040
#define CMD_CONFIG 0x00
#define REG_RED 0x08
#define REG_GREEN 0x09
#define REG_BLUE 0x0A
#define REG_WHITE 0x0B
enum duration{
MS40,
MS80,
MS160,
MS320,
MS640,
MS1280
};
enum vemlMode{
AUTO,
MANUAL
};
struct VEML_CONFIG{
vemlMode mode;
bool enabled;
duration exposureTime;
};
enum color{
VEML_RED,
VEML_GREEN,
VEML_BLUE,
VEML_WHITE
};
class ColorDetection{
public:
void begin(void);
void configure(VEML_CONFIG config);
uint16_t getColorValue(color color);
protected:
uint16_t readDoubleRegister(uint8_t regAddr);
void writeDoubleRegister(uint8_t regAddr, uint16_t data);
};
#endif //ColorDetection_h

View File

@ -0,0 +1,87 @@
#include "Communication.h"
Scheduler userScheduler; // to control your personal task
painlessMesh mesh;
uint32_t Communication::groupNumber = 0;
// User-defined callback function pointer
void (*Communication::userCallback)(String &msg) = nullptr;
void Communication::sendMessage(String msg)
{
String data = String(groupNumber) + "#" + msg;
mesh.sendBroadcast(data);
}
// Needed for painless library
void Communication::receivedCallback(uint32_t from, String &msg)
{
int separatorIndex = msg.indexOf('#');
if (separatorIndex != -1) {
String groupNumberStr = msg.substring(0, separatorIndex);
uint32_t num = groupNumberStr.toInt();
String restOfMsg = msg.substring(separatorIndex + 1);
Serial.printf("startHere: Received from %u groupNumber=%u msg=%s\n", from, num, restOfMsg.c_str());
if (groupNumber != num) return;
// Execute user-defined callback if it is set
if (userCallback) {
userCallback(restOfMsg);
}
}
}
void newConnectionCallback(uint32_t nodeId)
{
Serial.printf("--> startHere: New Connection, nodeId = %u\n", nodeId);
}
void changedConnectionCallback()
{
Serial.printf("Changed connections\n");
}
void nodeTimeAdjustedCallback(int32_t offset)
{
Serial.printf("Adjusted time %u. Offset = %d\n", mesh.getNodeTime(), offset);
}
void vTaskUpdate(void *pvParameters)
{
for (;;)
{
mesh.update();
}
}
void Communication::setGroupNumber(uint32_t number) {
groupNumber = number;
}
// Method to set the user-defined callback function
void Communication::onReceive(void (*callbackFunc)(String &msg))
{
userCallback = callbackFunc;
}
void Communication::begin(void)
{
Serial.begin(115200);
// mesh.setDebugMsgTypes( ERROR | MESH_STATUS | CONNECTION | SYNC | COMMUNICATION | GENERAL | MSG_TYPES | REMOTE ); // all types on
mesh.setDebugMsgTypes(ERROR | STARTUP); // set before init() so that you can see startup messages
mesh.init(MESH_PREFIX, MESH_PASSWORD, &userScheduler, MESH_PORT);
mesh.onReceive(&receivedCallback);
mesh.onNewConnection(&newConnectionCallback);
mesh.onChangedConnections(&changedConnectionCallback);
mesh.onNodeTimeAdjusted(&nodeTimeAdjustedCallback);
static uint8_t ucParameterToPass;
TaskHandle_t xHandle = NULL;
xTaskCreate(vTaskUpdate, "vTaskMeshUpdate", 4096, &ucParameterToPass, tskIDLE_PRIORITY, &xHandle);
configASSERT(xHandle);
};

View File

@ -0,0 +1,32 @@
#ifndef Communication_h
#define Communication_h
#include <stdint.h>
#include <Arduino.h>
#include <painlessMesh.h>
#define MESH_PREFIX "DEZIBOT_MESH"
#define MESH_PASSWORD "somethingSneaky"
#define MESH_PORT 5555
class Communication{
public:
/**
* @brief initialize the Mesh Compnent, must be called before the other methods are used.
*
*/
static void begin(void);
void setGroupNumber(uint32_t number);
void sendMessage(String msg);
void onReceive(void (*callbackFunc)(String &msg));
private:
static void (*userCallback)(String &msg);
static void receivedCallback(uint32_t from, String &msg);
static uint32_t groupNumber;
};
#endif //Communication_h

147
src/display/CharTable.h Normal file
View File

@ -0,0 +1,147 @@
/**
* @file CharTable.h
* @author Hans Haupt (hans.haupt@dezibot.de)
* @brief LookUpTable for 8x8 Pixel Characters for an SSD1306 Display
* @version 0.1
* @date 2024-05-24
*
* @copyright Copyright (c) 2024
*
*/
/**
* @brief First index specifies the index, where index equals the ascii encoding
* unprintable characters are encode as all zero
* the first byte in an entry is the cmd_byte for SSD1306 and therefore not printed
* Encoding is colum wise, so first byte is the first column of the char and so on
*
*/
const char font8x8_colwise[128][9] = {{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+0()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+1()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+2()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+3()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+4()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+5()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+6()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+7()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+8()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+9()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+a()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+b()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+c()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+d()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+e()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+f()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+10()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+11()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+12()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+13()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+14()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+15()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+16()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+17()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+18()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+19()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+1a()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+1b()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+1c()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+1d()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+1e()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+1f()
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // U+20( )
{ 0x40,0x00,0x00,0x06,0x5f,0x5f,0x06,0x00,0x00}, // U+21(!)
{ 0x40,0x00,0x03,0x03,0x00,0x03,0x03,0x00,0x00}, // U+22(")
{ 0x40,0x14,0x7f,0x7f,0x14,0x7f,0x7f,0x14,0x00}, // U+23(#)
{ 0x40,0x24,0x2e,0x6b,0x6b,0x3a,0x12,0x00,0x00}, // U+24($)
{ 0x40,0x46,0x66,0x30,0x18,0x0c,0x66,0x62,0x00}, // U+25(%)
{ 0x40,0x30,0x7a,0x4f,0x5d,0x37,0x7a,0x48,0x00}, // U+26(&)
{ 0x40,0x04,0x07,0x03,0x00,0x00,0x00,0x00,0x00}, // U+27(')
{ 0x40,0x00,0x1c,0x3e,0x63,0x41,0x00,0x00,0x00}, // U+28(()
{ 0x40,0x00,0x41,0x63,0x3e,0x1c,0x00,0x00,0x00}, // U+29())
{ 0x40,0x08,0x2a,0x3e,0x1c,0x1c,0x3e,0x2a,0x08}, // U+2a(*)
{ 0x40,0x08,0x08,0x3e,0x3e,0x08,0x08,0x00,0x00}, // U+2b(+)
{ 0x40,0x00,0x80,0xe0,0x60,0x00,0x00,0x00,0x00}, // U+2c(,)
{ 0x40,0x08,0x08,0x08,0x08,0x08,0x08,0x00,0x00}, // U+2d(-)
{ 0x40,0x00,0x00,0x60,0x60,0x00,0x00,0x00,0x00}, // U+2e(.)
{ 0x40,0x60,0x30,0x18,0x0c,0x06,0x03,0x01,0x00}, // U+2f(/)
{ 0x40,0x3e,0x7f,0x71,0x59,0x4d,0x7f,0x3e,0x00}, // U+30(0)
{ 0x40,0x40,0x42,0x7f,0x7f,0x40,0x40,0x00,0x00}, // U+31(1)
{ 0x40,0x62,0x73,0x59,0x49,0x6f,0x66,0x00,0x00}, // U+32(2)
{ 0x40,0x22,0x63,0x49,0x49,0x7f,0x36,0x00,0x00}, // U+33(3)
{ 0x40,0x18,0x1c,0x16,0x53,0x7f,0x7f,0x50,0x00}, // U+34(4)
{ 0x40,0x27,0x67,0x45,0x45,0x7d,0x39,0x00,0x00}, // U+35(5)
{ 0x40,0x3c,0x7e,0x4b,0x49,0x79,0x30,0x00,0x00}, // U+36(6)
{ 0x40,0x03,0x03,0x71,0x79,0x0f,0x07,0x00,0x00}, // U+37(7)
{ 0x40,0x36,0x7f,0x49,0x49,0x7f,0x36,0x00,0x00}, // U+38(8)
{ 0x40,0x06,0x4f,0x49,0x69,0x3f,0x1e,0x00,0x00}, // U+39(9)
{ 0x40,0x00,0x00,0x66,0x66,0x00,0x00,0x00,0x00}, // U+3a(:)
{ 0x40,0x00,0x80,0xe6,0x66,0x00,0x00,0x00,0x00}, // U+3b(;)
{ 0x40,0x08,0x1c,0x36,0x63,0x41,0x00,0x00,0x00}, // U+3c(<)
{ 0x40,0x24,0x24,0x24,0x24,0x24,0x24,0x00,0x00}, // U+3d(=)
{ 0x40,0x00,0x41,0x63,0x36,0x1c,0x08,0x00,0x00}, // U+3e(>)
{ 0x40,0x02,0x03,0x51,0x59,0x0f,0x06,0x00,0x00}, // U+3f(?)
{ 0x40,0x3e,0x7f,0x41,0x5d,0x5d,0x1f,0x1e,0x00}, // U+40(@)
{ 0x40,0x7c,0x7e,0x13,0x13,0x7e,0x7c,0x00,0x00}, // U+41(A)
{ 0x40,0x41,0x7f,0x7f,0x49,0x49,0x7f,0x36,0x00}, // U+42(B)
{ 0x40,0x1c,0x3e,0x63,0x41,0x41,0x63,0x22,0x00}, // U+43(C)
{ 0x40,0x41,0x7f,0x7f,0x41,0x63,0x3e,0x1c,0x00}, // U+44(D)
{ 0x40,0x41,0x7f,0x7f,0x49,0x5d,0x41,0x63,0x00}, // U+45(E)
{ 0x40,0x41,0x7f,0x7f,0x49,0x1d,0x01,0x03,0x00}, // U+46(F)
{ 0x40,0x1c,0x3e,0x63,0x41,0x51,0x73,0x72,0x00}, // U+47(G)
{ 0x40,0x7f,0x7f,0x08,0x08,0x7f,0x7f,0x00,0x00}, // U+48(H)
{ 0x40,0x00,0x41,0x7f,0x7f,0x41,0x00,0x00,0x00}, // U+49(I)
{ 0x40,0x30,0x70,0x40,0x41,0x7f,0x3f,0x01,0x00}, // U+4a(J)
{ 0x40,0x41,0x7f,0x7f,0x08,0x1c,0x77,0x63,0x00}, // U+4b(K)
{ 0x40,0x41,0x7f,0x7f,0x41,0x40,0x60,0x70,0x00}, // U+4c(L)
{ 0x40,0x7f,0x7f,0x0e,0x1c,0x0e,0x7f,0x7f,0x00}, // U+4d(M)
{ 0x40,0x7f,0x7f,0x06,0x0c,0x18,0x7f,0x7f,0x00}, // U+4e(N)
{ 0x40,0x1c,0x3e,0x63,0x41,0x63,0x3e,0x1c,0x00}, // U+4f(O)
{ 0x40,0x41,0x7f,0x7f,0x49,0x09,0x0f,0x06,0x00}, // U+50(P)
{ 0x40,0x1e,0x3f,0x21,0x71,0x7f,0x5e,0x00,0x00}, // U+51(Q)
{ 0x40,0x41,0x7f,0x7f,0x09,0x19,0x7f,0x66,0x00}, // U+52(R)
{ 0x40,0x26,0x6f,0x4d,0x59,0x73,0x32,0x00,0x00}, // U+53(S)
{ 0x40,0x03,0x41,0x7f,0x7f,0x41,0x03,0x00,0x00}, // U+54(T)
{ 0x40,0x7f,0x7f,0x40,0x40,0x7f,0x7f,0x00,0x00}, // U+55(U)
{ 0x40,0x1f,0x3f,0x60,0x60,0x3f,0x1f,0x00,0x00}, // U+56(V)
{ 0x40,0x7f,0x7f,0x30,0x18,0x30,0x7f,0x7f,0x00}, // U+57(W)
{ 0x40,0x43,0x67,0x3c,0x18,0x3c,0x67,0x43,0x00}, // U+58(X)
{ 0x40,0x07,0x4f,0x78,0x78,0x4f,0x07,0x00,0x00}, // U+59(Y)
{ 0x40,0x47,0x63,0x71,0x59,0x4d,0x67,0x73,0x00}, // U+5a(Z)
{ 0x40,0x00,0x7f,0x7f,0x41,0x41,0x00,0x00,0x00}, // U+5b([)
{ 0x40,0x01,0x03,0x06,0x0c,0x18,0x30,0x60,0x00}, // U+5c(\)
{ 0x40,0x00,0x41,0x41,0x7f,0x7f,0x00,0x00,0x00}, // U+5d(])
{ 0x40,0x08,0x0c,0x06,0x03,0x06,0x0c,0x08,0x00}, // U+5e(^)
{ 0x40,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80}, // U+5f(_)
{ 0x40,0x00,0x00,0x03,0x07,0x04,0x00,0x00,0x00}, // U+60(`)
{ 0x40,0x20,0x74,0x54,0x54,0x3c,0x78,0x40,0x00}, // U+61(a)
{ 0x40,0x41,0x7f,0x3f,0x48,0x48,0x78,0x30,0x00}, // U+62(b)
{ 0x40,0x38,0x7c,0x44,0x44,0x6c,0x28,0x00,0x00}, // U+63(c)
{ 0x40,0x30,0x78,0x48,0x49,0x3f,0x7f,0x40,0x00}, // U+64(d)
{ 0x40,0x38,0x7c,0x54,0x54,0x5c,0x18,0x00,0x00}, // U+65(e)
{ 0x40,0x48,0x7e,0x7f,0x49,0x03,0x02,0x00,0x00}, // U+66(f)
{ 0x40,0x98,0xbc,0xa4,0xa4,0xf8,0x7c,0x04,0x00}, // U+67(g)
{ 0x40,0x41,0x7f,0x7f,0x08,0x04,0x7c,0x78,0x00}, // U+68(h)
{ 0x40,0x00,0x44,0x7d,0x7d,0x40,0x00,0x00,0x00}, // U+69(i)
{ 0x40,0x60,0xe0,0x80,0x80,0xfd,0x7d,0x00,0x00}, // U+6a(j)
{ 0x40,0x41,0x7f,0x7f,0x10,0x38,0x6c,0x44,0x00}, // U+6b(k)
{ 0x40,0x00,0x41,0x7f,0x7f,0x40,0x00,0x00,0x00}, // U+6c(l)
{ 0x40,0x7c,0x7c,0x18,0x38,0x1c,0x7c,0x78,0x00}, // U+6d(m)
{ 0x40,0x7c,0x7c,0x04,0x04,0x7c,0x78,0x00,0x00}, // U+6e(n)
{ 0x40,0x38,0x7c,0x44,0x44,0x7c,0x38,0x00,0x00}, // U+6f(o)
{ 0x40,0x84,0xfc,0xf8,0xa4,0x24,0x3c,0x18,0x00}, // U+70(p)
{ 0x40,0x18,0x3c,0x24,0xa4,0xf8,0xfc,0x84,0x00}, // U+71(q)
{ 0x40,0x44,0x7c,0x78,0x4c,0x04,0x1c,0x18,0x00}, // U+72(r)
{ 0x40,0x48,0x5c,0x54,0x54,0x74,0x24,0x00,0x00}, // U+73(s)
{ 0x40,0x00,0x04,0x3e,0x7f,0x44,0x24,0x00,0x00}, // U+74(t)
{ 0x40,0x3c,0x7c,0x40,0x40,0x3c,0x7c,0x40,0x00}, // U+75(u)
{ 0x40,0x1c,0x3c,0x60,0x60,0x3c,0x1c,0x00,0x00}, // U+76(v)
{ 0x40,0x3c,0x7c,0x70,0x38,0x70,0x7c,0x3c,0x00}, // U+77(w)
{ 0x40,0x44,0x6c,0x38,0x10,0x38,0x6c,0x44,0x00}, // U+78(x)
{ 0x40,0x9c,0xbc,0xa0,0xa0,0xfc,0x7c,0x00,0x00}, // U+79(y)
{ 0x40,0x4c,0x64,0x74,0x5c,0x4c,0x64,0x00,0x00}, // U+7a(z)
{ 0x40,0x08,0x08,0x3e,0x77,0x41,0x41,0x00,0x00}, // U+7b({)
{ 0x40,0x00,0x00,0x00,0x77,0x77,0x00,0x00,0x00}, // U+7c(|)
{ 0x40,0x41,0x41,0x77,0x3e,0x08,0x08,0x00,0x00}, // U+7d(})
{ 0x40,0x02,0x03,0x01,0x03,0x02,0x03,0x01,0x00}, // U+7e(~)
{ 0x40,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}}; // U+7f(°)

175
src/display/Display.cpp Normal file
View File

@ -0,0 +1,175 @@
/**
* @file Display.cpp
* @author Hans Haupt (hans.haupt@dezibot.de)
* @brief Adds the ability to print to the display of the robot.
* @version 0.1
* @date 2024-06-05
*
* @copyright Copyright (c) 2024
*/
#include "Display.h"
#include "CharTable.h"
#include "Wire.h"
void Display::begin(void){
//set Mux Ratio
sendDisplayCMD(muxRatio);
sendDisplayCMD(0x3f);
sendDisplayCMD(setOffset);
sendDisplayCMD(0x00);
sendDisplayCMD(setStartLine);
sendDisplayCMD(stopCompleteOn);
/*which pixels are bright: normal = 1s are bright, inverese= 0s are bright*/
sendDisplayCMD( setNormalMode);
sendDisplayCMD( setOscFreq);
sendDisplayCMD(0x80);
sendDisplayCMD(setChargePump);
sendDisplayCMD(0x14);
sendDisplayCMD(activateDisplay);
this->clear();
return;
};
void Display::sendDisplayCMD(uint8_t cmd){
Wire.beginTransmission(DisplayAdress);
Wire.write(cmd_byte);
Wire.write(cmd);
Wire.endTransmission();
};
void Display::clear(void){
sendDisplayCMD(addressingMode);
sendDisplayCMD(0x00); //horizontal
sendDisplayCMD(colRange);
sendDisplayCMD(0x00);
sendDisplayCMD(0x7f);
sendDisplayCMD(pageRange);
sendDisplayCMD(0x00);
sendDisplayCMD(0x07);
for (int j=0;j<64;j++){
Wire.beginTransmission(DisplayAdress);
Wire.write(data_byte);
for(int i = 0;i<16;i++){
Wire.write(0x00);
}
Wire.endTransmission();
}
this -> charsOnCurrLine = 0;
this -> currLine = 0;
return;
};
void Display::updateLine(uint charAmount)
{
if(charAmount+this->charsOnCurrLine>16)
{
this->currLine = (this->currLine+((charAmount+this->charsOnCurrLine)/16))%8;
this->charsOnCurrLine = (charAmount+this->charsOnCurrLine)%17; //there can be 0-16 chars on one line, so the 17th char is on next line
}
else
{
this->charsOnCurrLine = charAmount+this->charsOnCurrLine;
}
};
void Display::print(char *value){
char *nextchar;
/* write data to the buffer */
while(value && *value != '\0') //check if pointer is still valid and string is not terminated
{
//check if next character is a linebreak
if(*value=='\n')
{
//fill the current line with blanks
while(this->charsOnCurrLine<16)
{
updateLine(1);
Wire.beginTransmission(DisplayAdress);
for(int i = 0;i<9;i++){
Wire.write(font8x8_colwise[0][i]);
}
Wire.endTransmission();
}
//make the linebreak
this->currLine=currLine+1;
this->charsOnCurrLine=0;
}
else
{
updateLine(1);
Wire.beginTransmission(DisplayAdress);
//print the character
for(int i = 0;i<9;i++){
Wire.write(font8x8_colwise[*value][i]);
}
Wire.endTransmission();
}
value++;
}
};
char Display::stringToCharArray(String value) {
const int len = value.length() + 1; // +1 for the null terminator
char msgBuffer[len]; // Create a buffer of the appropriate length
value.toCharArray(msgBuffer, len); // Copy the string into the buffer, including the null terminator
return *msgBuffer;
}
void Display::print(String value){
const int len = value.length() + 1; // +1 for the null terminator
char msgBuffer[len]; // Create a buffer of the appropriate length
value.toCharArray(msgBuffer, len);
this->print(msgBuffer);
};
void Display::println(String value){
const int len = value.length() + 1; // +1 for the null terminator
char msgBuffer[len]; // Create a buffer of the appropriate length
value.toCharArray(msgBuffer, len);
this->println(msgBuffer);
};
void Display::print(int value){
char cstr[16];
this->print(itoa(value, cstr, 10));
};
void Display::println(int value){
char cstr[16];
this->println(itoa(value, cstr, 10));
};
void Display::println(char *value){
this ->print(value);
this->print("\n");
};
void Display::flipOrientation(void){
if(this->orientationFlipped){
sendDisplayCMD(setComDirectionNormal);
sendDisplayCMD(setSegmentMap);
} else{
sendDisplayCMD(setComDirectionFlipped);
sendDisplayCMD(setSegmentReMap);
}
this->orientationFlipped = !this->orientationFlipped;
};
void Display::invertColor(void){
if(this->colorInverted){
sendDisplayCMD(setNormalMode);
} else {
sendDisplayCMD(setInverseMode);
}
this->colorInverted = !this->colorInverted;
};

127
src/display/Display.h Normal file
View File

@ -0,0 +1,127 @@
/**
* @file InfraredLight.h
* @author Hans Haupt (hans.haupt@dezibot.de)
* @brief Adds the ability to print to the display of the robot.
* @version 0.1
* @date 2024-05-24
*
* @copyright Copyright (c) 2024
*
*/
#ifndef Display_h
#define Display_h
#include <stdint.h>
#include <Arduino.h>
#include "DisplayCMDs.h"
class Display{
protected:
//how many chars are on current line
uint8_t charsOnCurrLine = 0;
//on which line are we currently printing
uint8_t currLine = 0;
//flag that marks if the y-orientation is currently flipped
bool orientationFlipped = false;
//flag thats marks if the color is currently inverted
bool colorInverted = false;
/**
* @brief sends the passed cmd to the display, cmd_byte is added as prefix by the function
*
* @param cmd the byte instruction that shold by sent
*/
void sendDisplayCMD(uint8_t cmd);
/**
* @brief should be called whenever characters where printed to the display.
* Updates the data of the class to handle linebreaks correctly
* @param charAmount How many characters where added to the screen
*/
void updateLine(uint charAmount);
public:
/**
* @brief initializes the display datastructures and sents the required cmds to start the display. Should only be called once.
* @warning doesn't initalize the I²C bus itself, therefore wire.begin(1,2) must be called elsewhere, before this method.
*/
void begin(void);
/**
* @brief delets all content from the display, resets the linecounter, new print will start at the top left.
* Orientationflip is not resetted
*/
void clear(void);
/**
* @brief prints the passed string right behind the current displaycontent
* the sequence "\n" can be used to make a linebreak on the display
*
* @param value the string "xyz" that should be printed to the display
*/
void print(char *value);
/**
* @brief same as the print method, but after the string a line break is inserted
*
* @param value the string that should be printed
*/
void println(char *value);
/**
* @brief prints the passed string right behind the current displaycontent
* the sequence "\n" can be used to make a linebreak on the display
*
* @param value the string "xyz" that should be printed to the display
*/
void print(String value);
/**
* @brief same as the print method, but after the string a line break is inserted
*
* @param value the string that should be printed
*/
void println(String value);
/**
* @brief prints the passed string right behind the current displaycontent
* the sequence "\n" can be used to make a linebreak on the display
*
* @param value the string "xyz" that should be printed to the display
*/
void print(int value);
/**
* @brief same as the print method, but after the string a line break is inserted
*
* @param value the string that should be printed
*/
void println(int value);
/**
* @brief string to char
*
* @param value the string that should be converted to char
*/
char stringToCharArray(String value);
/**
* @brief flips the horizontal orientation of all content on the display
*/
void flipOrientation(void);
/**
* @brief inverts the pixelcolors, so pixels on will be set to off and currently off pixels will be turned off.
* affects already printed content as well as future prints.
*
*/
void invertColor(void);
};
#endif //Display_h

24
src/display/DisplayCMDs.h Normal file
View File

@ -0,0 +1,24 @@
#define cmd_byte 0x80
#define data_byte 0x40
#define muxRatio 0xa8 //needs second argument ranging from 16-63
#define setOffset 0xd3 //needs second argument ranging from 0-63
#define setStartLine 0x40
#define setSegmentMap 0xa0
#define setSegmentReMap 0xa1
#define setComDirectionNormal 0xc0
#define setComDirectionFlipped 0xc8
#define setComHardwareConfig 0xda //needs second arg
#define setContrast 0x81 //needs second arg
#define completeOn 0xa5
#define stopCompleteOn 0xa4
#define setNormalMode 0xa6
#define setInverseMode 0xa7
#define setOscFreq 0xd5 //needs second arg
#define setChargePump 0x8d//needs second arg 0x14 for enable
#define activateDisplay 0xaf
#define disableDisplay 0xae
#define addressingMode 0x20
#define colRange 0x21
#define pageRange 0x22
#define DisplayAdress 0x3C

View File

@ -0,0 +1,57 @@
#include "InfraredLight.h"
#define pwmSpeedMode LEDC_LOW_SPEED_MODE
InfraredLED::InfraredLED(uint8_t pin,ledc_timer_t timer, ledc_channel_t channel){
this->ledPin = pin;
this->timer = timer;
this->channel = channel;
};
void InfraredLED::begin(void){
//we want to change frequency instead of
pwmTimer = ledc_timer_config_t{
.speed_mode = pwmSpeedMode,
.duty_resolution = LEDC_TIMER_10_BIT,
.timer_num = this->timer,
.freq_hz = 800,
.clk_cfg = LEDC_AUTO_CLK
};
ledc_timer_config(&pwmTimer);
pwmChannel = ledc_channel_config_t{
.gpio_num = this->ledPin,
.speed_mode =pwmSpeedMode,
.channel = this->channel,
.intr_type = LEDC_INTR_DISABLE,
.timer_sel = this->timer,
.duty = 0,
.hpoint = 0
};
ledc_channel_config(&pwmChannel);
};
void InfraredLED::turnOn(void){
InfraredLED::setState(true);
};
void InfraredLED::turnOff(void){
InfraredLED::setState(false);
};
void InfraredLED::setState(bool state){
ledc_set_freq(pwmSpeedMode,timer,1);
if (state) {
ledc_set_duty(pwmSpeedMode,channel,1023);
} else {
ledc_set_duty(pwmSpeedMode,channel,0);
}
ledc_update_duty(pwmSpeedMode,channel);
};
void InfraredLED::sendFrequency(uint16_t frequency){
ledc_set_freq(pwmSpeedMode,timer,frequency);
ledc_set_duty(pwmSpeedMode,channel,512);
ledc_update_duty(pwmSpeedMode,channel);
};

View File

@ -0,0 +1,6 @@
#include "InfraredLight.h"
void InfraredLight::begin(void){
bottom.begin();
front.begin();
}

View File

@ -0,0 +1,68 @@
/**
* @file InfraredLight.h
* @author Hans Haupt (hans.haupt@dezibot.de)
* @brief Provides basic controls for the infrared LEDs of the robot.
* @version 0.1
* @date 2024-04-27
*
* @copyright Copyright (c) 2024
*
*/
#ifndef InfraredLight_h
#define InfraredLight_h
#include <stdint.h>
#include <Arduino.h>
#include "driver/ledc.h"
class InfraredLED{
public:
InfraredLED(uint8_t pin, ledc_timer_t timer, ledc_channel_t channel);
void begin(void);
/**
* @brief enables selected LED
*
*/
void turnOn(void);
/**
* @brief disables selected LED
*
* @param led
*/
void turnOff(void);
/**
* @brief changes state of selected LED depending on the state
*
* @param led which led will be affected
* @param state true if led should be turned on, else false
*/
void setState(bool state);
/**
* @brief starts flashing the IRLed with a specific frequency
* Won't stop automatically, must be stopped by calling any other IR-Method
*
* @param frequency
*/
void sendFrequency(uint16_t frequency);
protected:
uint8_t ledPin;
ledc_timer_t timer;
ledc_channel_t channel;
ledc_timer_config_t pwmTimer;
ledc_channel_config_t pwmChannel;
};
class InfraredLight{
public:
//Do something for correct resource sharing
InfraredLED bottom = InfraredLED(IRBottomPin,LEDC_TIMER_0,LEDC_CHANNEL_0);
InfraredLED front = InfraredLED(IRFrontPin,LEDC_TIMER_1,LEDC_CHANNEL_1);
void begin(void);
protected:
static const uint8_t IRFrontPin = 14;
static const uint8_t IRBottomPin = 13;
};
#endif //InfraredLight_h

View File

@ -1,4 +1,5 @@
#include "LightDetection.h"
#include <limits.h>
void LightDetection::begin(void){
LightDetection::beginInfrared();
@ -6,7 +7,6 @@ void LightDetection::begin(void){
};
uint16_t LightDetection::getValue(photoTransistors sensor){
uint16_t result;
switch(sensor){
//Fall Through intended
case IR_FRONT:
@ -17,6 +17,9 @@ uint16_t LightDetection::getValue(photoTransistors sensor){
case DL_BOTTOM:
case DL_FRONT:
return readDLPT(sensor);
default:
//currently not reachable, just if enum will be extended in the future
return UINT16_MAX;
}
};
@ -26,6 +29,7 @@ photoTransistors LightDetection::getBrightest(ptType type){
uint16_t currentReading = 0;
if (type == IR){
maxSensor = IR_FRONT;
for(const auto pt : allIRPTs){
currentReading = LightDetection::getValue(pt);
if (currentReading > maxReading){
@ -34,6 +38,7 @@ photoTransistors LightDetection::getBrightest(ptType type){
}
}
} else {
maxSensor = DL_FRONT;
for(const auto pt : allDLPTs){
currentReading = LightDetection::getValue(pt);
if (currentReading > maxReading){
@ -47,6 +52,7 @@ photoTransistors LightDetection::getBrightest(ptType type){
};
uint32_t LightDetection::getAverageValue(photoTransistors sensor, uint32_t measurments, uint32_t timeBetween){
TickType_t xLastWakeTime = xTaskGetTickCount();
TickType_t frequency = timeBetween / portTICK_PERIOD_MS;
uint64_t cumulatedResult = 0;
@ -58,6 +64,7 @@ uint32_t LightDetection::getAverageValue(photoTransistors sensor, uint32_t measu
};
void LightDetection::beginInfrared(void){
digitalWrite(IR_PT_ENABLE,true);
pinMode(IR_PT_ENABLE, OUTPUT);
pinMode(IR_PT_FRONT_ADC, INPUT);
pinMode(IR_PT_LEFT_ADC, INPUT);
@ -66,13 +73,14 @@ void LightDetection::beginInfrared(void){
};
void LightDetection::beginDaylight(void){
digitalWrite(DL_PT_ENABLE,true);
pinMode(DL_PT_ENABLE, OUTPUT);
pinMode(DL_PT_BOTTOM_ADC, INPUT);
pinMode(DL_PT_FRONT_ADC, INPUT );
};
uint16_t LightDetection::readIRPT(photoTransistors sensor){
digitalWrite(IR_PT_ENABLE,HIGH);
//digitalWrite(IR_PT_ENABLE,HIGH);
uint16_t result = 0;
switch (sensor)
{
@ -91,7 +99,7 @@ uint16_t LightDetection::readIRPT(photoTransistors sensor){
default:
break;
}
digitalWrite(IR_PT_ENABLE,LOW);
//digitalWrite(IR_PT_ENABLE,LOW);
return result;
};

View File

@ -62,7 +62,7 @@ public:
* Can distingish between IR and Daylight
*
* @param type select which PTTransistors to compare
* @return photoTransistors which sensor is exposed to the greatest amount of light
* @return photoTransistors which sensor is exposed to the greatest amount of light, if all sensor read 0, the front sensor is returned
*/
static photoTransistors getBrightest(ptType type);
@ -91,13 +91,7 @@ protected:
static void beginInfrared(void);
static void beginDaylight(void);
static uint16_t readIRPT(photoTransistors sensor);
static uint16_t readDLPT(photoTransistors sensor);
static void averageMeasurmentTask(void * args);
static uint16_t readDLPT(photoTransistors sensor);
};
#endif //LightDetection_h

View File

@ -1,6 +1,6 @@
#include "MotionDetection.h"
MotionDetection::MotionDetection(){//:handler(FSPI){
MotionDetection::MotionDetection(){
handler = new SPIClass(FSPI);
};
@ -9,13 +9,20 @@ void MotionDetection::begin(void){
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);
handler->transfer(0x0F);
//busy Wait for startup
delayMicroseconds(200);
delayMicroseconds(250);
//set Gyroconfig
handler->transfer(0x20);
handler->transfer(0x25);
//set Gyro Filter
handler->transfer(0x23);
handler->transfer(0x37);
digitalWrite(34,HIGH);
handler->endTransaction();
};
@ -30,12 +37,9 @@ void MotionDetection::end(void){
};
IMUResult MotionDetection::getAcceleration(){
IMUResult result;
result.x = readRegister(ACCEL_DATA_X_HIGH)<<8;
result.x |= readRegister(ACCEL_DATA_X_LOW);
result.y = readRegister(ACCEL_DATA_Y_HIGH)<<8;
result.y |= readRegister(ACCEL_DATA_Y_LOW);
result.z = readRegister(ACCEL_DATA_Z_HIGH)<<8;
result.z |= readRegister(ACCEL_DATA_Z_LOW);
result.x = readRegister(ACCEL_DATA_X_HIGH)<<8 | readRegister(ACCEL_DATA_X_LOW);
result.y = readRegister(ACCEL_DATA_Y_HIGH)<<8 | readRegister(ACCEL_DATA_Y_LOW);
result.z = readRegister(ACCEL_DATA_Z_HIGH)<<8 | readRegister(ACCEL_DATA_Z_LOW);
return result;
};
IMUResult MotionDetection::getRotation(){
@ -58,6 +62,106 @@ int8_t MotionDetection::getWhoAmI(){
return readRegister(WHO_AM_I);
};
bool MotionDetection::isShaken(uint32_t threshold ,uint8_t axis){
IMUResult measurment1;
IMUResult measurment2;
uint count = 0;
for(uint i = 0;i<20;i++){
measurment1 = this->getAcceleration();
delayMicroseconds(10);
measurment2 = this->getAcceleration();
if(
(((axis && xAxis) > 0) && (abs(abs(measurment1.x)-abs(measurment2.x))>threshold)) ||
(((axis && yAxis) > 0) && (abs(abs(measurment1.y)-abs(measurment2.y))>threshold)) ||
(((axis && zAxis) > 0) && (abs(abs(measurment1.z)-abs(measurment2.z))>threshold))){
count++;
}
delayMicroseconds(15);
}
return (count > 6);
};
void MotionDetection::calibrateZAxis(uint gforceValue){
this->gForceCalib = gforceValue;
};
Orientation MotionDetection::getTilt(){
uint tolerance = 200;
IMUResult reading = this->getAcceleration();
bool flipped = reading.z < 0;
float accelrationStrenght = sqrt(reading.x*reading.x+reading.y*reading.y+reading.z*reading.z);
//check if reading is valid
if (abs(accelrationStrenght-this->gForceCalib) > tolerance ){
//total accelration is not gravitational force, error
return Orientation{INT_MAX,INT_MAX};
}
//calculates the angle between the two axis, therefore value between 0-90
int yAngle;
int xAngle;
if(reading.z != 0){
yAngle = atan(float(reading.x)/reading.z)*180/3.1415+0.5;
xAngle = atan(float(reading.y)/reading.z)*180/3.1415+0.5;
} else {
yAngle = 90*(reading.x > 0) - (reading.x < 0);
xAngle = 90*(reading.y > 0) - (reading.y < 0);
}
//shift quadrants depending on signum
//esp is facing down (normal position)
if (reading.z > 0){
if(reading.y < 0){
xAngle = xAngle+180;
} else{
xAngle = -1*(180-xAngle);
}
if(reading.x < 0){
yAngle = yAngle+180;
} else{
yAngle = -1*(180-yAngle);
}
//yAngle = -1*yAngle-90;
}
return Orientation{xAngle,yAngle};
};
Direction MotionDetection::getTiltDirection(uint tolerance){
if (this->getAcceleration().z > 0){
return Flipped;
}
Orientation Rot = this->getTilt();
Serial.println(Rot.xRotation);
Serial.println(Rot.xRotation == INT_MAX);
if ((Rot.xRotation == INT_MAX)){
return Error;
}
if(abs(abs(Rot.xRotation)-abs(Rot.yRotation))>tolerance){
//determine which axis is more tiltet
if (abs(Rot.xRotation)>abs(Rot.yRotation)){
//test if dezibot is tilted left or right
if (Rot.xRotation > 0){
return Right;
} else {
return Left;
}
} else {
//test if robot is tilted front or back
if (Rot.yRotation > 0){
return Front;
} else {
return Back;
}
}
} else {
//dezibot is (with tolerance) leveled
return Neutral;
}
};
uint8_t MotionDetection::cmdRead(uint8_t reg){
return (CMD_READ | (reg & ADDR_MASK));
};
@ -65,7 +169,7 @@ uint8_t MotionDetection::cmdWrite(uint8_t reg){
return (CMD_WRITE | (reg & ADDR_MASK));
};
int8_t MotionDetection::readRegister(uint8_t reg){
uint8_t MotionDetection::readRegister(uint8_t reg){
handler->beginTransaction(SPISettings(frequency,SPI_MSBFIRST,SPI_MODE0));
digitalWrite(34,LOW);
uint8_t result;

View File

@ -17,7 +17,26 @@ struct IMUResult{
int16_t y;
int16_t z;
};
enum Axis{
xAxis = 0x01,
yAxis = 0x02,
zAxis = 0x04
};
struct Orientation{
int xRotation;
int yRotation;
};
enum Direction{
Front,
Left,
Right,
Back,
Neutral,
Flipped,
Error
};
class MotionDetection{
protected:
@ -48,16 +67,19 @@ protected:
static const uint8_t WHO_AM_I = 0x75;
static const uint frequency = 10000000;
static const uint16_t defaultShakeThreshold = 500;
uint16_t cmdRead(uint8_t regHigh,uint8_t regLow);
uint16_t cmdWrite(uint8_t regHigh,uint8_t regLow);
uint8_t cmdRead(uint8_t reg);
uint8_t cmdWrite(uint8_t reg);
int8_t readRegister(uint8_t reg);
uint8_t readRegister(uint8_t reg);
int16_t readDoubleRegister(uint8_t lowerReg);
SPIClass * handler = NULL;
uint gForceCalib = 4050;
public:
@ -83,21 +105,21 @@ public:
*
* @return IMUResult that contains the new read values
*/
IMUResult getAcceleration();
IMUResult getAcceleration(void);
/**
* @brief Triggers a new reading of the gyroscope and reads the values from the imu
*
* @return IMUResult
*/
IMUResult getRotation();
IMUResult getRotation(void);
/**
* @brief Reads the current On Chip temperature of the IMU
*
* @return normalized temperature in degree Centigrade
*/
float getTemperature();
float getTemperature(void);
/**
* @brief Returns the value of reading the whoAmI register
@ -105,6 +127,62 @@ public:
*
* @return the value of the whoami register of the ICM-42670
*/
int8_t getWhoAmI();
int8_t getWhoAmI(void);
/**
* @brief Detects if at the time of calling is shaken. Therefore the sum over all accelerationvalues is calculated
* and checked against threshold. If sum > threshold a shake is detected, else not
*
* @param threshold (optional) the level of acceleration that must be reached to detect a shake
* @param axis (optional) select which axis should be used for detection. Possible values ar xAxis,yAxis,zAxis
* It's possible to combine multiple axis with the bitwise or Operator |
* For Example: to detect x and y axis: axis = xAxis|yAxis
*
* @return true if a shake is detected, false else
*/
bool isShaken(uint32_t threshold = defaultShakeThreshold,uint8_t axis = xAxis|yAxis|zAxis);
/**
* @brief calculates how the robot is tilted. It is set, that when the robot is placed normally on a flat table, the result will be (0,0)
* Tilting the robot, so that the front leg is deeper than the other to results in an increasing degrees, tilting the front leg up will increase negativ degrees
* Tilting the robot to the right will increase the degrees until 180° (upside down), tilting it left will result in increasing negativ degrees (-1,-2,...,-180).
* On the top there is a jump of the values from 180->-180 and vice versa.
*
* Precision is rounded to 1 deg steps
*
* @attention The results are only valid, if the robot is not moved in any way during the measurment, as the calculation is made by using the accelration values.
* If it's detected, that the robot is accelerated while measuring, the method will return max(int).
* Please note that the imu is pretty sensitiv, even walking next to the table may influcene the result.
*
*/
Orientation getTilt();
/**
* @brief Checks in which direction (Front, Left, Right, Back) the robot is tilted.
*
* @attention Does only work if the robot is not moving
*
* @param tolerance (optional, default = 10) how many degrees can the robot be tilted, and still will be considerd as neutral.
*
*
* @return Direction the direction in that the robot is tilted most. Front is onsiderd as the direction of driving.
* If robot is not tilted more than the tolerance in any direction, return is Neutral.
* If Robot is upside down, return is Flipped.
* If Robot is moved, return is Error
*/
Direction getTiltDirection(uint tolerance = 10);
/**
* can be used to set a custom value for the gforceReading of the zaxis, which will improve the getTiltFunction.
*
* @attention this method is not persisten, so the value is not stored when the programm is restarted / the robot is powerd off
*
* @param gforceValue the value the IMU returns for the gravitationforce -> to get this value, place the robot on a leveled surface
* and read the value getAcceleration().z
*/
void calibrateZAxis(uint gforceValue);
};
#endif //MotionDetection

View File

@ -6,6 +6,7 @@ MultiColorLight::MultiColorLight():rgbLeds(ledAmount,ledPin){
void MultiColorLight::begin(void){
rgbLeds.begin();
this->turnOffLed();
};
void MultiColorLight::setLed(uint8_t index , uint32_t color){
@ -60,7 +61,6 @@ void MultiColorLight::blink(uint16_t amount,uint32_t color, leds leds, uint32_t
MultiColorLight::turnOffLed(leds);
vTaskDelay(interval);
}
};
void MultiColorLight::turnOffLed(leds leds){