Introduce coderacerMKII library repository
This commit is contained in:
parent
c02f347518
commit
d5754d0a9f
14 changed files with 2034 additions and 0 deletions
63
readme.md.orig
Normal file
63
readme.md.orig
Normal file
|
@ -0,0 +1,63 @@
|
||||||
|
<<<<<<< HEAD
|
||||||
|
![Build Status](https://git.itsblue.de/Fenoglio/coderacer/badges/master/build.svg)
|
||||||
|
![Flyer](/Doku/Bilder/coderace_get_in_contact_pic.png)
|
||||||
|
## Repo Overview
|
||||||
|
This is fun in progress and for sure not covering all questions and topics.
|
||||||
|
Hopefully you will get an idea of what that project means and is able to do.
|
||||||
|
Have fun and let us know what you think.
|
||||||
|
|
||||||
|
Repo dir | Description
|
||||||
|
---------|--------------
|
||||||
|
Arduino/libraries | arduino stuff and libraries
|
||||||
|
Doku | HowTo as well as doxygen documentation. To view doxygen documentation repository has to be downloaded (no rendering through gitlab)
|
||||||
|
Install | Everything to get your dev IDE running on your PC
|
||||||
|
AppInventor | Module to load into AppInventor or directly to your phone.
|
||||||
|
Fritzing | Schematics and stuff
|
||||||
|
Bilder | Pictures of racers and events;-)
|
||||||
|
|
||||||
|
## Full API Docs
|
||||||
|
A full API Documentation is available [here](https://fenoglio.pages.itsblue.de/coderacer/)
|
||||||
|
|
||||||
|
## How to start
|
||||||
|
* Start reading the [{code}racer HowTo](https://git.itsblue.de/Fenoglio/coderacer/tree/master/Doku/coderacer_handbuch.pdf)
|
||||||
|
* Learn about the [{code}racer API](https://fenoglio.pages.itsblue.de/coderacer/)
|
||||||
|
* Download the {code}racer Repo and install the IDE on your PC (see [CodeRacer HowTo Page.8](https://git.itsblue.de/Fenoglio/coderacer/tree/master/Doku/coderacer_handbuch.pdf))
|
||||||
|
* Installation of used libraries (see [{code}racer HowTo Page.10](https://git.itsblue.de/Fenoglio/coderacer/tree/master/Doku/coderacer_handbuch.pdf))
|
||||||
|
* Compile example (esp32_coderacer_beispiel) (see [{code}racer HowTo Page.11](https://git.itsblue.de/Fenoglio/coderacer/tree/master/Doku/coderacer_handbuch.pdf))
|
||||||
|
* Work on your OWN CodeRacer Algo
|
||||||
|
|
||||||
|
## Feedback/Questions
|
||||||
|
* Please write your questions/feedback to development@itsblue.de
|
||||||
|
|
||||||
|
=======
|
||||||
|
![Build Status](https://git.itsblue.de/Fenoglio/coderacer/badges/master/build.svg)
|
||||||
|
![Flyer](/Doku/Bilder/coderace_get_in_contact_pic.png)
|
||||||
|
## Repo Overview
|
||||||
|
This is fun in progress and for sure not covering all questions and topics.
|
||||||
|
Hopefully you will get an idea of what that project means and is able to do.
|
||||||
|
Have fun and let us know what you think.
|
||||||
|
|
||||||
|
Repo dir | Description
|
||||||
|
---------|--------------
|
||||||
|
Arduino/libraries | arduino stuff and libraries
|
||||||
|
Doku | HowTo as well as doxygen documentation. View it [here](https://pages.itsblue.de/fenoglio/coderacer/)
|
||||||
|
Install | Everything to get your dev IDE running on your PC
|
||||||
|
AppInventor | Module to load into AppInventor or directly to your phone.
|
||||||
|
Fritzing | Schematics and stuff
|
||||||
|
Bilder | Pictures of racers and events;-)
|
||||||
|
|
||||||
|
## Full API Docs
|
||||||
|
A full API Documentation is available [here](https://pages.itsblue.de/fenoglio/coderacer/)
|
||||||
|
|
||||||
|
## How to start
|
||||||
|
* Start reading the [{code}racer HowTo](https://git.itsblue.de/Fenoglio/coderacer/tree/master/Doku/coderacer_handbuch.pdf)
|
||||||
|
* Learn about the [{code}racer API](https://pages.itsblue.de/fenoglio/coderacer/)
|
||||||
|
* Download the {code}racer Repo and install the IDE on your PC (see [CodeRacer HowTo Page.8](https://git.itsblue.de/Fenoglio/coderacer/tree/master/Doku/coderacer_handbuch.pdf))
|
||||||
|
* Installation of used libraries (see [{code}racer HowTo Page.10](https://git.itsblue.de/Fenoglio/coderacer/tree/master/Doku/coderacer_handbuch.pdf))
|
||||||
|
* Compile example (esp32_coderacer_beispiel) (see [{code}racer HowTo Page.11](https://git.itsblue.de/Fenoglio/coderacer/tree/master/Doku/coderacer_handbuch.pdf))
|
||||||
|
* Work on your OWN CodeRacer Algo
|
||||||
|
|
||||||
|
## Feedback/Questions
|
||||||
|
* Please write your questions/feedback to development@itsblue.de
|
||||||
|
|
||||||
|
>>>>>>> f6a79fe7b7828a529dc55c811b94e43f733e5aa2
|
5
vsode/coderacer_mkII/.gitignore
vendored
Normal file
5
vsode/coderacer_mkII/.gitignore
vendored
Normal file
|
@ -0,0 +1,5 @@
|
||||||
|
.pio
|
||||||
|
.vscode/.browse.c_cpp.db*
|
||||||
|
.vscode/c_cpp_properties.json
|
||||||
|
.vscode/launch.json
|
||||||
|
.vscode/ipch
|
67
vsode/coderacer_mkII/.travis.yml
Normal file
67
vsode/coderacer_mkII/.travis.yml
Normal file
|
@ -0,0 +1,67 @@
|
||||||
|
# Continuous Integration (CI) is the practice, in software
|
||||||
|
# engineering, of merging all developer working copies with a shared mainline
|
||||||
|
# several times a day < https://docs.platformio.org/page/ci/index.html >
|
||||||
|
#
|
||||||
|
# Documentation:
|
||||||
|
#
|
||||||
|
# * Travis CI Embedded Builds with PlatformIO
|
||||||
|
# < https://docs.travis-ci.com/user/integration/platformio/ >
|
||||||
|
#
|
||||||
|
# * PlatformIO integration with Travis CI
|
||||||
|
# < https://docs.platformio.org/page/ci/travis.html >
|
||||||
|
#
|
||||||
|
# * User Guide for `platformio ci` command
|
||||||
|
# < https://docs.platformio.org/page/userguide/cmd_ci.html >
|
||||||
|
#
|
||||||
|
#
|
||||||
|
# Please choose one of the following templates (proposed below) and uncomment
|
||||||
|
# it (remove "# " before each line) or use own configuration according to the
|
||||||
|
# Travis CI documentation (see above).
|
||||||
|
#
|
||||||
|
|
||||||
|
|
||||||
|
#
|
||||||
|
# Template #1: General project. Test it using existing `platformio.ini`.
|
||||||
|
#
|
||||||
|
|
||||||
|
# language: python
|
||||||
|
# python:
|
||||||
|
# - "2.7"
|
||||||
|
#
|
||||||
|
# sudo: false
|
||||||
|
# cache:
|
||||||
|
# directories:
|
||||||
|
# - "~/.platformio"
|
||||||
|
#
|
||||||
|
# install:
|
||||||
|
# - pip install -U platformio
|
||||||
|
# - platformio update
|
||||||
|
#
|
||||||
|
# script:
|
||||||
|
# - platformio run
|
||||||
|
|
||||||
|
|
||||||
|
#
|
||||||
|
# Template #2: The project is intended to be used as a library with examples.
|
||||||
|
#
|
||||||
|
|
||||||
|
# language: python
|
||||||
|
# python:
|
||||||
|
# - "2.7"
|
||||||
|
#
|
||||||
|
# sudo: false
|
||||||
|
# cache:
|
||||||
|
# directories:
|
||||||
|
# - "~/.platformio"
|
||||||
|
#
|
||||||
|
# env:
|
||||||
|
# - PLATFORMIO_CI_SRC=path/to/test/file.c
|
||||||
|
# - PLATFORMIO_CI_SRC=examples/file.ino
|
||||||
|
# - PLATFORMIO_CI_SRC=path/to/test/directory
|
||||||
|
#
|
||||||
|
# install:
|
||||||
|
# - pip install -U platformio
|
||||||
|
# - platformio update
|
||||||
|
#
|
||||||
|
# script:
|
||||||
|
# - platformio ci --lib="." --board=ID_1 --board=ID_2 --board=ID_N
|
7
vsode/coderacer_mkII/.vscode/extensions.json
vendored
Normal file
7
vsode/coderacer_mkII/.vscode/extensions.json
vendored
Normal file
|
@ -0,0 +1,7 @@
|
||||||
|
{
|
||||||
|
// See http://go.microsoft.com/fwlink/?LinkId=827846
|
||||||
|
// for the documentation about the extensions.json format
|
||||||
|
"recommendations": [
|
||||||
|
"platformio.platformio-ide"
|
||||||
|
]
|
||||||
|
}
|
39
vsode/coderacer_mkII/include/README
Normal file
39
vsode/coderacer_mkII/include/README
Normal file
|
@ -0,0 +1,39 @@
|
||||||
|
|
||||||
|
This directory is intended for project header files.
|
||||||
|
|
||||||
|
A header file is a file containing C declarations and macro definitions
|
||||||
|
to be shared between several project source files. You request the use of a
|
||||||
|
header file in your project source file (C, C++, etc) located in `src` folder
|
||||||
|
by including it, with the C preprocessing directive `#include'.
|
||||||
|
|
||||||
|
```src/main.c
|
||||||
|
|
||||||
|
#include "header.h"
|
||||||
|
|
||||||
|
int main (void)
|
||||||
|
{
|
||||||
|
...
|
||||||
|
}
|
||||||
|
```
|
||||||
|
|
||||||
|
Including a header file produces the same results as copying the header file
|
||||||
|
into each source file that needs it. Such copying would be time-consuming
|
||||||
|
and error-prone. With a header file, the related declarations appear
|
||||||
|
in only one place. If they need to be changed, they can be changed in one
|
||||||
|
place, and programs that include the header file will automatically use the
|
||||||
|
new version when next recompiled. The header file eliminates the labor of
|
||||||
|
finding and changing all the copies as well as the risk that a failure to
|
||||||
|
find one copy will result in inconsistencies within a program.
|
||||||
|
|
||||||
|
In C, the usual convention is to give header files names that end with `.h'.
|
||||||
|
It is most portable to use only letters, digits, dashes, and underscores in
|
||||||
|
header file names, and at most one dot.
|
||||||
|
|
||||||
|
Read more about using header files in official GCC documentation:
|
||||||
|
|
||||||
|
* Include Syntax
|
||||||
|
* Include Operation
|
||||||
|
* Once-Only Headers
|
||||||
|
* Computed Includes
|
||||||
|
|
||||||
|
https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html
|
1230
vsode/coderacer_mkII/lib/CodeRacer_MKII/CodeRacer_MKII.cpp
Normal file
1230
vsode/coderacer_mkII/lib/CodeRacer_MKII/CodeRacer_MKII.cpp
Normal file
File diff suppressed because it is too large
Load diff
270
vsode/coderacer_mkII/lib/CodeRacer_MKII/CodeRacer_MKII.h
Normal file
270
vsode/coderacer_mkII/lib/CodeRacer_MKII/CodeRacer_MKII.h
Normal file
|
@ -0,0 +1,270 @@
|
||||||
|
#include "Arduino.h"
|
||||||
|
#include <algorithm> // std::swap
|
||||||
|
#include <ESP32Servo.h> // Servo drive support for ESP32
|
||||||
|
#include "esp32-hal-ledc.h" // Part of ESP32 board files - Analog output
|
||||||
|
#include "BluetoothSerial.h" // Bluetooth enablement - part of ESP or standart Arduino lib
|
||||||
|
#include <vector> // support for vectors
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
#if !defined(CONFIG_BT_ENABLED) || !defined(CONFIG_BLUEDROID_ENABLED)
|
||||||
|
#error Bluetooth is not enabled! Please run `make menuconfig` to and enable it
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef __CodeRacer_MKII_H__
|
||||||
|
#define __CodeRacer_MKII_H__
|
||||||
|
|
||||||
|
//----- Fun stuff ---------
|
||||||
|
#define FUN_MIN_PAUSE_MS 120000 // minimum and maximum pause between to rounds fun
|
||||||
|
#define FUN_MAX_PAUSE_MS 300000
|
||||||
|
#define LED_SWITCH_MS 50 // speed of knight rider lights
|
||||||
|
//----- Button ------------
|
||||||
|
#define H_BUTTON_PIN 17
|
||||||
|
#define BUTTON_BOUNCING_TIME_MS 200 // bouncing delay
|
||||||
|
//----- Servo -----
|
||||||
|
#define H_SERVO_PIN 16
|
||||||
|
#define H_SERVO_LEFT_POS 145 // left position of the servo
|
||||||
|
#define H_SERVO_CENTER_LEFT 100 // left-center position of the servo
|
||||||
|
#define H_SERVO_RIGHT_POS 35 // right position of the servo
|
||||||
|
#define H_SERVO_CENTER_RIGHT 80 // right-center position of the servo
|
||||||
|
#define H_SERVO_CENTER_POS 90 // center position of the servo
|
||||||
|
#define H_SERVO_SWEEP_LEFT_POS 140 // most left sweep position of the servo
|
||||||
|
#define H_SERVO_SWEEP_RIGHT_POS 40 // most right sweep position of the servo
|
||||||
|
#define SERVO_SWEEP_TO_LEFT_STEP 5 // sweep step to the left
|
||||||
|
#define SERVO_SWEEP_TO_RIGHT_STEP -5 // sweep step to the right
|
||||||
|
#define SERVO_SWEEP_MS 10 // duration of time betwee to sweep steps
|
||||||
|
#define SERVO_MAX_POSITION 170 // maximum servo position
|
||||||
|
#define SERVO_MIN_POSITION 10 // minimum servo position
|
||||||
|
#define SERVO_SET_1TICK_POSITION_DELAY_MS 3 // minimum duration of time between two servo steps
|
||||||
|
|
||||||
|
//----- Ultrasonic sensor -----
|
||||||
|
#define H_US_TRIG_PIN 12
|
||||||
|
#define H_US_ECHO_PIN 14
|
||||||
|
#define H_US_STOP_DISTANCE_CM 25 // if the measured distance is smaller the racer maybe stopped
|
||||||
|
#define US_MAX_ECHO_TIME_US 6000 // timeout for ultrasonic sensor measurements - this is about 100cm
|
||||||
|
|
||||||
|
//----- Drives -----
|
||||||
|
#define H_DRIVE_RIGHT_SPEED 255 // default speed of right side drive. 0 ...255
|
||||||
|
#define H_DRIVE_LEFT_SPEED 255 // default speed of left side drive. 0 ...255
|
||||||
|
#define H_DRIVE_RIGHT_ENABLE_PIN 2
|
||||||
|
#define H_DRIVE_RIGHT_FWRD_PIN 4
|
||||||
|
#define H_DRIVE_RIGHT_BACK_PIN 15
|
||||||
|
#define H_DRIVE_LEFT_ENABLE_PIN 21
|
||||||
|
#define H_DRIVE_LEFT_FWRD_PIN 22
|
||||||
|
#define H_DRIVE_LEFT_BACK_PIN 23
|
||||||
|
#define H_RACER_TURN_LEFT_FOR_MS 400 // duration of time the racer will turn to left
|
||||||
|
#define H_RACER_TURN_RIGHT_FOR_MS 400 // duration of time the racer will turn to right
|
||||||
|
|
||||||
|
#define DRIVE_PWM_LEFT_CHANNEL 5 // PWM-channel for left side drive
|
||||||
|
#define DRIVE_PWM_RIGHT_CHANNEL 6 // PWM-channel for right side drive
|
||||||
|
|
||||||
|
//----- LEDs -----
|
||||||
|
#define H_LED_FRWD_PIN 26
|
||||||
|
#define H_LED_STOP_PIN 25
|
||||||
|
#define H_LED_LEFT_PIN 33
|
||||||
|
#define H_LED_RIGHT_PIN 27
|
||||||
|
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
|
||||||
|
static volatile bool coderracer_activ = false;;
|
||||||
|
static volatile unsigned long button_last_pressed_at_ms = millis();
|
||||||
|
|
||||||
|
enum ledstate {
|
||||||
|
LEDOFF,
|
||||||
|
LEDON
|
||||||
|
};
|
||||||
|
|
||||||
|
enum drivestate {
|
||||||
|
DRIVESTOP,
|
||||||
|
DRIVEFRWD,
|
||||||
|
DRIVEBACK
|
||||||
|
};
|
||||||
|
|
||||||
|
//--- this is as preparation of the class creation
|
||||||
|
class CodeRacerMKII {
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
//bluetooth
|
||||||
|
std::vector<String> _bt_ignoremsgs;
|
||||||
|
std::vector<String> _bt_onlymsgs;
|
||||||
|
bool _bluetoothcreated;
|
||||||
|
unsigned long _bt_stopOnLostConnection_timeout_ms;
|
||||||
|
unsigned long _bt_lastmessagereceived;
|
||||||
|
BluetoothSerial* _BTSerial;
|
||||||
|
|
||||||
|
//pins
|
||||||
|
uint8_t _button_pin;
|
||||||
|
uint8_t _servo_pin;
|
||||||
|
uint8_t _us_trigger_pin;
|
||||||
|
uint8_t _us_echo_pin;
|
||||||
|
uint8_t _drive_left_frwd_pin;
|
||||||
|
uint8_t _drive_left_back_pin;
|
||||||
|
uint8_t _drive_left_enable_pin;
|
||||||
|
uint8_t _drive_right_frwd_pin;
|
||||||
|
uint8_t _drive_right_back_pin;
|
||||||
|
uint8_t _drive_right_enable_pin;
|
||||||
|
uint8_t _led_frwd_pin;
|
||||||
|
uint8_t _led_stop_pin;
|
||||||
|
uint8_t _led_left_pin;
|
||||||
|
uint8_t _led_right_pin;
|
||||||
|
|
||||||
|
//servo variables
|
||||||
|
int8_t _servo_sweep_step;
|
||||||
|
uint8_t _servo_position;
|
||||||
|
unsigned long _servo_position_set_at_ms;
|
||||||
|
unsigned long _servo_position_eta_in_ms;
|
||||||
|
|
||||||
|
//drives variables
|
||||||
|
uint8_t _drive_left_speed;
|
||||||
|
uint8_t _drive_right_speed;
|
||||||
|
unsigned long _turn_left_for_ms;
|
||||||
|
unsigned long _turn_right_for_ms;
|
||||||
|
|
||||||
|
// ultrasonic variables
|
||||||
|
bool _coderacer_stopped_at_min_distance;
|
||||||
|
bool _coderacer_stop_at_distance_enabled;
|
||||||
|
unsigned long _usonic_stop_distance_cm;
|
||||||
|
unsigned long _usonic_stop_distance_us;
|
||||||
|
unsigned long _usonic_distance_us;
|
||||||
|
unsigned long _usonic_distance_cm;
|
||||||
|
|
||||||
|
//fun stuff variables
|
||||||
|
unsigned long _last_led_switched_at_ms;
|
||||||
|
uint8_t _led_count;
|
||||||
|
uint8_t _last_led_on;
|
||||||
|
unsigned long _servo_look_around_at_ms;
|
||||||
|
|
||||||
|
|
||||||
|
unsigned long _min_distance_cm;
|
||||||
|
bool _drive;
|
||||||
|
unsigned long _drive_set_at_ms;
|
||||||
|
bool _servo_sweep;
|
||||||
|
bool _coderracer_activ;
|
||||||
|
|
||||||
|
//objects
|
||||||
|
Servo* _servo;
|
||||||
|
Servo* _servo_dummy;
|
||||||
|
|
||||||
|
static void _set_button_state();
|
||||||
|
void _analog_write(uint8_t pin, uint8_t speed);
|
||||||
|
unsigned long _servo_set_position(uint8_t position);
|
||||||
|
|
||||||
|
public:
|
||||||
|
//properties
|
||||||
|
bool coderacer_fun_enabled;
|
||||||
|
|
||||||
|
uint8_t servo_center_pos; /**< The position the servo is looking straight forward. Default is 90 . Allowed are values 10<=pos<=170 */
|
||||||
|
uint8_t servo_left_pos; /**< The position the servo is looking to the left. Default is 170 . Allowed are values 10<=pos<=170 */
|
||||||
|
uint8_t servo_right_pos; /**< The position the servo is looking to the right. Default is 0 . Allowed are values 10<=pos<=170 */
|
||||||
|
uint8_t servo_sweep_left_pos; /**< When the servo is sweeping this is the left most position */
|
||||||
|
uint8_t servo_sweep_right_pos; /**< When the servo is sweeping this is the right most position */
|
||||||
|
|
||||||
|
//methods
|
||||||
|
CodeRacerMKII();
|
||||||
|
|
||||||
|
CodeRacerMKII(uint8_t button_pin, uint8_t servo_pin,
|
||||||
|
uint8_t us_trigger_pin, uint8_t us_echo_pin,
|
||||||
|
uint8_t drive_left_frwd_pin, uint8_t drive_left_back_pin, uint8_t drive_left_enable_pin,
|
||||||
|
uint8_t drive_right_frwd_pin, uint8_t drive_right_back_pin, uint8_t drive_right_enable_pin,
|
||||||
|
uint8_t led_frwd_pin, uint8_t led_stop_pin, uint8_t led_left_pin, uint8_t led_right_pin);
|
||||||
|
|
||||||
|
void set_inactive();
|
||||||
|
void set_active();
|
||||||
|
|
||||||
|
void begin();
|
||||||
|
|
||||||
|
// getters
|
||||||
|
bool is_active();
|
||||||
|
bool is_driving();
|
||||||
|
bool stopped_at_min_distance();
|
||||||
|
unsigned long usonic_distance_cm();
|
||||||
|
unsigned long usonic_distance_us();
|
||||||
|
uint8_t servo_position();
|
||||||
|
unsigned long servo_position_set_at_ms();
|
||||||
|
unsigned long servo_position_eta_in_ms();
|
||||||
|
uint8_t drive_left_speed();
|
||||||
|
uint8_t drive_right_speed();
|
||||||
|
unsigned long turn_left_for_ms();
|
||||||
|
unsigned long turn_right_for_ms();
|
||||||
|
|
||||||
|
// higher level {code}racer services
|
||||||
|
void stop_driving();
|
||||||
|
void drive_forward();
|
||||||
|
void drive_forward(uint8_t left_speed, uint8_t right_speed);
|
||||||
|
void drive_backward();
|
||||||
|
void drive_backward(uint8_t left_speed, uint8_t right_speed);
|
||||||
|
void turn_left();
|
||||||
|
void turn_left(unsigned long turn_for_ms);
|
||||||
|
void turn_left(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed);
|
||||||
|
void turn_right();
|
||||||
|
void turn_right(unsigned long turn_for_ms);
|
||||||
|
void turn_right(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed);
|
||||||
|
|
||||||
|
void start_stop_at_min_distance();
|
||||||
|
void start_stop_at_min_distance(unsigned long min_distance_cm);
|
||||||
|
void stop_stop_at_min_distance();
|
||||||
|
bool start_stop();
|
||||||
|
|
||||||
|
// Bluetooth
|
||||||
|
void bt_enable_stopOnLostConnection();
|
||||||
|
void bt_enable_stopOnLostConnection(unsigned long timeout);
|
||||||
|
void bt_disable_stopOnLostConnection();
|
||||||
|
void bt_start(String name);
|
||||||
|
String bt_getString();
|
||||||
|
String bt_getString(uint8_t delimiterbyte);
|
||||||
|
bool bt_msgavailable();
|
||||||
|
void bt_addStringToIgnoreList(String stringtoignore);
|
||||||
|
void bt_clearIgnoreList();
|
||||||
|
void bt_removeStringFromIgnoreList(String stringtoignore);
|
||||||
|
|
||||||
|
// LEDs
|
||||||
|
void set_leds_left_stop_frwd_right(ledstate leftled, ledstate stopled, ledstate frwdled, ledstate rightled);
|
||||||
|
void set_leds_all(ledstate alleds);
|
||||||
|
void set_leds_all_off();
|
||||||
|
void set_leds_all_on();
|
||||||
|
|
||||||
|
// Drives
|
||||||
|
void drives_settings(uint8_t drive_left_speed, uint8_t drive_right_speed, unsigned long turn_left_ms, unsigned long turn_right_ms);
|
||||||
|
void set_drives_states_left_right(drivestate stateleft, drivestate stateright);
|
||||||
|
void set_drive_left_state(drivestate state);
|
||||||
|
void set_drive_right_state(drivestate state);
|
||||||
|
void set_drive_state(drivestate state, uint8_t frwdpin, uint8_t backpin);
|
||||||
|
void set_drives_speed_left_right(uint8_t speedleft, uint8_t speedright);
|
||||||
|
void set_drive_left_speed(uint8_t speed);
|
||||||
|
void set_drive_right_speed(uint8_t speed);
|
||||||
|
void set_drive_speed(uint8_t speed, uint8_t enablepin);
|
||||||
|
void set_drives_stop_left_right();
|
||||||
|
|
||||||
|
// Ultrasonic sensor
|
||||||
|
unsigned long usonic_measure_cm();
|
||||||
|
unsigned long usonic_measure_us();
|
||||||
|
unsigned long usonic_measure_cm(unsigned long max_echo_run_time_us);
|
||||||
|
unsigned long usonic_measure_us(unsigned long max_echo_run_time_us);
|
||||||
|
unsigned long usonic_measure_single_shot_cm();
|
||||||
|
unsigned long usonic_measure_single_shot_us();
|
||||||
|
unsigned long usonic_measure_single_shot_cm(unsigned long max_echo_run_time_us);
|
||||||
|
unsigned long usonic_measure_single_shot_us(unsigned long max_echo_run_time_us);
|
||||||
|
void usonic_set_stop_distance_cm(unsigned long stop_distance_cm);
|
||||||
|
void usonic_set_stop_distance_us(unsigned long stop_distance_us);
|
||||||
|
|
||||||
|
// Servo drive
|
||||||
|
void servo_settings(uint8_t pos_center, uint8_t pos_left, uint8_t pos_right, uint8_t sweep_left_pos, uint8_t sweep_right_pos);
|
||||||
|
uint8_t servo_set_position_wait(uint8_t position);
|
||||||
|
unsigned long servo_set_position(uint8_t position);
|
||||||
|
void servo_set_to_right();
|
||||||
|
void servo_set_to_left();
|
||||||
|
void servo_set_to_center();
|
||||||
|
void servo_sweep();
|
||||||
|
|
||||||
|
// just for fun
|
||||||
|
void kitt();
|
||||||
|
void look_around();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#endif
|
|
@ -0,0 +1,56 @@
|
||||||
|
|
||||||
|
// Full API description of the coderacer.h can be found here: https://fenoglio.pages.itsblue.de/coderacer/
|
||||||
|
// Repository with all needed data and users guide is here: https://git.itsblue.de/Fenoglio/coderacer/tree/master
|
||||||
|
// An example for a application to control the coderacer via bluetooth can be found here: https://git.itsblue.de/Fenoglio/coderacer/tree/master/AppInventor/SimpleBTCoderacer
|
||||||
|
// - this app was developed with MIT App Inventor and can be uploaded to your account to rework it.
|
||||||
|
|
||||||
|
#include <CodeRacer.h>
|
||||||
|
|
||||||
|
CodeRacer coderacer;
|
||||||
|
String recvddata = ""; //Variable in der der Bluetooth Befehl gespeichert wird
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
Serial.begin(115200);
|
||||||
|
coderacer.begin();
|
||||||
|
coderacer.bt_start("CodeRacer"); //Bluetooth für den Coderacer anschalten
|
||||||
|
coderacer.bt_enable_stopOnLostConnection(); //Coderacer anhalten, wenn 1 Sekunde nichts per Bluetooth empfangen wurde
|
||||||
|
coderacer.bt_addStringToIgnoreList("."); //das "." Zeichen wird beim empfangen ignoriert
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
// Prüfen ob Bluetooth Nachrichten angekommen sind und die gleich abholen ...
|
||||||
|
recvddata = coderacer.bt_getString(); //die Nachtricht merken (sie steht jetzt in recvdata und kann später benutzt werden)
|
||||||
|
if (recvddata != "") //wenn eine Nachricht empfangen wurde, in der was drin steht ...
|
||||||
|
{
|
||||||
|
Serial.println(recvddata);
|
||||||
|
|
||||||
|
if(recvddata == "stop")
|
||||||
|
{
|
||||||
|
coderacer.stop_driving();
|
||||||
|
}
|
||||||
|
|
||||||
|
if(recvddata == "vor")
|
||||||
|
{
|
||||||
|
coderacer.drive_forward(255,255);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(recvddata.startsWith("rueck"))
|
||||||
|
{
|
||||||
|
coderacer.drive_backward(255,255);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(recvddata.startsWith("links"))
|
||||||
|
{
|
||||||
|
coderacer.turn_left();
|
||||||
|
}
|
||||||
|
|
||||||
|
if(recvddata.startsWith("rechts"))
|
||||||
|
{
|
||||||
|
coderacer.turn_right();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
delay(20);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,82 @@
|
||||||
|
#include <CodeRacer.h>
|
||||||
|
|
||||||
|
//----- settings for the ultrasonic sensor -----
|
||||||
|
#define US_STOP_ABSTAND_CM 20 // if distance goes below that - stop the racer
|
||||||
|
|
||||||
|
//----- variables we need
|
||||||
|
unsigned long distance_cm = 0;
|
||||||
|
|
||||||
|
//---- construct the coderacer object
|
||||||
|
CodeRacer coderacer;
|
||||||
|
|
||||||
|
//---- set up code - executed ones
|
||||||
|
void setup() {
|
||||||
|
// start serial monitor
|
||||||
|
Serial.begin(115200);
|
||||||
|
// initialize the coderacer
|
||||||
|
coderacer.begin();
|
||||||
|
// enable fun stuff
|
||||||
|
coderacer.coderacer_fun_enabled = true;
|
||||||
|
// look to the left, to the right and to center... :-)
|
||||||
|
coderacer.servo_set_to_left();
|
||||||
|
delay(100);
|
||||||
|
coderacer.servo_set_to_right();
|
||||||
|
delay(100);
|
||||||
|
coderacer.servo_set_to_center();
|
||||||
|
delay(100);
|
||||||
|
}
|
||||||
|
|
||||||
|
//---- 'endless' loop
|
||||||
|
void loop() {
|
||||||
|
|
||||||
|
// check if the racer was started (button was toggled to coderacer active state
|
||||||
|
if(true == coderacer.start_stop()){
|
||||||
|
|
||||||
|
Serial.print("Speed of right side drive: ");
|
||||||
|
Serial.println(coderacer.drive_right_speed());
|
||||||
|
Serial.print("Speed of left side drive: ");
|
||||||
|
Serial.println(coderacer.drive_left_speed());
|
||||||
|
|
||||||
|
// measure the distance - at the position of the servo
|
||||||
|
distance_cm = coderacer.usonic_measure_cm();
|
||||||
|
|
||||||
|
coderacer.start_stop_at_min_distance(US_STOP_ABSTAND_CM);
|
||||||
|
while(!coderacer.stopped_at_min_distance()){
|
||||||
|
|
||||||
|
Serial.print("Distanc in cm: ");
|
||||||
|
Serial.println(distance_cm);
|
||||||
|
|
||||||
|
if(distance_cm > 50){
|
||||||
|
coderacer.drive_forward();
|
||||||
|
coderacer.servo_sweep();
|
||||||
|
}
|
||||||
|
else if(distance_cm > 40){
|
||||||
|
coderacer.turn_right();
|
||||||
|
}
|
||||||
|
else if(distance_cm > 30){
|
||||||
|
coderacer.turn_left();
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
|
||||||
|
coderacer.drive_backward();
|
||||||
|
}
|
||||||
|
|
||||||
|
// measure the distance - at the position of the servo
|
||||||
|
distance_cm = coderacer.usonic_measure_cm();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial.println("***** STOPPED ***** ");
|
||||||
|
Serial.print("Measured stop distanc of cm: ");
|
||||||
|
Serial.println(distance_cm);
|
||||||
|
Serial.print("Measured at servo position of: ");
|
||||||
|
Serial.println(coderacer.servo_position());
|
||||||
|
|
||||||
|
coderacer.set_inactive();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
15
vsode/coderacer_mkII/lib/CodeRacer_MKII/keywords.txt
Normal file
15
vsode/coderacer_mkII/lib/CodeRacer_MKII/keywords.txt
Normal file
|
@ -0,0 +1,15 @@
|
||||||
|
CodeRacer KEYWORD1
|
||||||
|
begin KEYWORD2
|
||||||
|
servo_einstellungen KEYWORD2
|
||||||
|
motor_einstellungen KEYWORD2
|
||||||
|
anhalten KEYWORD2
|
||||||
|
normal_tempo KEYWORD2
|
||||||
|
vorwaerts KEYWORD2
|
||||||
|
links KEYWORD2
|
||||||
|
rechts KEYWORD2
|
||||||
|
servo_rechts KEYWORD2
|
||||||
|
servo_links KEYWORD2
|
||||||
|
servo_mitte KEYWORD2
|
||||||
|
abstand_messen KEYWORD2
|
||||||
|
servo_schwenk KEYWORD2
|
||||||
|
start_stop KEYWORD2
|
46
vsode/coderacer_mkII/lib/README
Normal file
46
vsode/coderacer_mkII/lib/README
Normal file
|
@ -0,0 +1,46 @@
|
||||||
|
|
||||||
|
This directory is intended for project specific (private) libraries.
|
||||||
|
PlatformIO will compile them to static libraries and link into executable file.
|
||||||
|
|
||||||
|
The source code of each library should be placed in a an own separate directory
|
||||||
|
("lib/your_library_name/[here are source files]").
|
||||||
|
|
||||||
|
For example, see a structure of the following two libraries `Foo` and `Bar`:
|
||||||
|
|
||||||
|
|--lib
|
||||||
|
| |
|
||||||
|
| |--Bar
|
||||||
|
| | |--docs
|
||||||
|
| | |--examples
|
||||||
|
| | |--src
|
||||||
|
| | |- Bar.c
|
||||||
|
| | |- Bar.h
|
||||||
|
| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html
|
||||||
|
| |
|
||||||
|
| |--Foo
|
||||||
|
| | |- Foo.c
|
||||||
|
| | |- Foo.h
|
||||||
|
| |
|
||||||
|
| |- README --> THIS FILE
|
||||||
|
|
|
||||||
|
|- platformio.ini
|
||||||
|
|--src
|
||||||
|
|- main.c
|
||||||
|
|
||||||
|
and a contents of `src/main.c`:
|
||||||
|
```
|
||||||
|
#include <Foo.h>
|
||||||
|
#include <Bar.h>
|
||||||
|
|
||||||
|
int main (void)
|
||||||
|
{
|
||||||
|
...
|
||||||
|
}
|
||||||
|
|
||||||
|
```
|
||||||
|
|
||||||
|
PlatformIO Library Dependency Finder will find automatically dependent
|
||||||
|
libraries scanning project source files.
|
||||||
|
|
||||||
|
More information about PlatformIO Library Dependency Finder
|
||||||
|
- https://docs.platformio.org/page/librarymanager/ldf.html
|
15
vsode/coderacer_mkII/platformio.ini
Normal file
15
vsode/coderacer_mkII/platformio.ini
Normal file
|
@ -0,0 +1,15 @@
|
||||||
|
;PlatformIO Project Configuration File
|
||||||
|
;
|
||||||
|
; Build options: build flags, source filter
|
||||||
|
; Upload options: custom upload port, speed and extra flags
|
||||||
|
; Library options: dependencies, extra library storages
|
||||||
|
; Advanced options: extra scripting
|
||||||
|
;
|
||||||
|
; Please visit documentation for the other options and examples
|
||||||
|
; https://docs.platformio.org/page/projectconf.html
|
||||||
|
|
||||||
|
[env:esp32dev]
|
||||||
|
platform = espressif32
|
||||||
|
board = esp32dev
|
||||||
|
framework = arduino
|
||||||
|
|
128
vsode/coderacer_mkII/src/coderacer_main.cpp
Normal file
128
vsode/coderacer_mkII/src/coderacer_main.cpp
Normal file
|
@ -0,0 +1,128 @@
|
||||||
|
#include "CodeRacer_MKII.h"
|
||||||
|
|
||||||
|
#include <ESP32Servo.h>
|
||||||
|
#include "esp32-hal-ledc.h"
|
||||||
|
|
||||||
|
//----- Werte für den Ultraschallsensor -----
|
||||||
|
#define US_STOP_ABSTAND_CM 20 // Wenn der gemessene Abstand kleiner ist, hält der CodeRacer an
|
||||||
|
#define US_MIN_ABSTAND_LI_RE 8 // Wenn der Unterschied zwischen linkem und und rechtem Abstand kleiner ist, dann drehe in dieselbe Richtugn wie vorher weiter
|
||||||
|
#define MAX_ANZAHL_DREHUNGEN 10 // Wenn der Coderacer sich schon so oft gedreht hat ohne eine Stelle zu finden, wo es Platz gibt - fahren wir mal ein Stück rückwärts ...
|
||||||
|
|
||||||
|
//----- Variablen, die wir brauchen um uns Werte zu merken ----
|
||||||
|
long abstand_vorn_cm, abstand_links_cm, abstand_rechts_cm;
|
||||||
|
enum drehrichtung {links=0, rechts};
|
||||||
|
drehrichtung drehung = links;
|
||||||
|
unsigned int anzahl_drehung = 0;
|
||||||
|
CodeRacerMKII coderacer;
|
||||||
|
|
||||||
|
//---- Hier startet der Code zum Einstellen aller wichtigen Dinge. Setup() wird einmal ausgeführt. ----
|
||||||
|
void setup() {
|
||||||
|
// Monitor
|
||||||
|
Serial.begin(115200); // Serial Monitor aktivieren. Mit dem Monitor kann man sich Werte und Meldungen anzeigen lassen.
|
||||||
|
|
||||||
|
// CodeRacer initialisieren
|
||||||
|
coderacer.begin();
|
||||||
|
|
||||||
|
coderacer.servo_set_to_left();
|
||||||
|
delay(10);
|
||||||
|
coderacer.servo_set_to_right();
|
||||||
|
delay(10);
|
||||||
|
coderacer.servo_set_to_center();
|
||||||
|
|
||||||
|
anzahl_drehung = 0;
|
||||||
|
drehung = links;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
//---- Hier startet unsere endlose Schleife - die immer wieder von vorn angefangen wird, wenn wir am Ende angekommen sind. Da ist unser "Fahr"Code drin, der den CodeRacer steuert
|
||||||
|
void loop() {
|
||||||
|
|
||||||
|
|
||||||
|
// Abstand messen -> nach vorn ... um zu sehen, ob was passiert messen wir immer ... auch wenn der Racer nicht fahren soll
|
||||||
|
abstand_vorn_cm = coderacer.usonic_measure_cm();
|
||||||
|
|
||||||
|
// Abfragen ob der Racer fahren soll oder nicht ...
|
||||||
|
if(true == coderacer.start_stop()){
|
||||||
|
|
||||||
|
// Abstandssensor schon verstellen ... dann hat er das bis zur nächsten Messung auch geschafft
|
||||||
|
coderacer.servo_sweep();
|
||||||
|
|
||||||
|
// Ist die Bahn frei?
|
||||||
|
if(abstand_vorn_cm < US_STOP_ABSTAND_CM){
|
||||||
|
// Nein! Der Abstand nach vorn ist kleiner als erlaubt!
|
||||||
|
// Racer anhalten
|
||||||
|
coderacer.stop_driving();
|
||||||
|
// Nach links schauen!
|
||||||
|
coderacer.servo_set_to_left();
|
||||||
|
// Abstand messen und merken.
|
||||||
|
abstand_links_cm = coderacer.usonic_measure_cm();
|
||||||
|
// Nach rechts schauen!
|
||||||
|
coderacer.servo_set_to_right();
|
||||||
|
// Abstand messen und merken.
|
||||||
|
abstand_rechts_cm = coderacer.usonic_measure_cm();
|
||||||
|
|
||||||
|
|
||||||
|
// Ist der Abstand links oder rechts groß genug genug?
|
||||||
|
// Wenn nicht - wenn der Racer sich bisher noch nicht gedreht hat - fahre ein Stück rückwarts. Wenn der Racer sich gerade schon gedreht hat, drehe in dieselbe Richtung wie vorher.
|
||||||
|
if((abstand_links_cm < US_MIN_ABSTAND_LI_RE) && (abstand_rechts_cm < US_MIN_ABSTAND_LI_RE)){
|
||||||
|
if(anzahl_drehung == 0){
|
||||||
|
coderacer.drive_backward();
|
||||||
|
delay(300);
|
||||||
|
coderacer.stop_driving();
|
||||||
|
//noch mal Abstand messen ...
|
||||||
|
coderacer.servo_set_to_left();
|
||||||
|
// Abstand messen und merken.
|
||||||
|
abstand_links_cm = coderacer.usonic_measure_cm();
|
||||||
|
// Nach rechts schauen!
|
||||||
|
coderacer.servo_set_to_right();
|
||||||
|
// Abstand messen und merken.
|
||||||
|
abstand_rechts_cm = coderacer.usonic_measure_cm();
|
||||||
|
}
|
||||||
|
if( anzahl_drehung > MAX_ANZAHL_DREHUNGEN ){
|
||||||
|
anzahl_drehung = 0;
|
||||||
|
} else {
|
||||||
|
anzahl_drehung ++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// wenn der Racer sich noch nicht gedreht hat (anzahl_drehung == 0) - oder gerade rückwärts gefahren ist (anzahl_drehung == 1) drehe jetzt dahin wo mehr Platz ist;
|
||||||
|
if(anzahl_drehung <= 1){
|
||||||
|
// Welcher Abstand ist größer?
|
||||||
|
if(abstand_links_cm > abstand_rechts_cm){
|
||||||
|
// Links ist mehr Platz!
|
||||||
|
drehung = links;
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
// Rechts ist mehr Platz!
|
||||||
|
drehung = rechts;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
switch(drehung){
|
||||||
|
case links:
|
||||||
|
coderacer.turn_left();
|
||||||
|
coderacer.servo_set_to_center();
|
||||||
|
break;
|
||||||
|
case rechts:
|
||||||
|
coderacer.turn_right();
|
||||||
|
coderacer.servo_set_to_center();
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
// Ja! Die Bahn ist frei
|
||||||
|
// Wenn die Bahn richtig frei ist, dann können wir den Zähler fürs drehen auf 0 setzen ...
|
||||||
|
if( abstand_vorn_cm > (US_STOP_ABSTAND_CM + US_MIN_ABSTAND_LI_RE)){
|
||||||
|
anzahl_drehung = 0;
|
||||||
|
}
|
||||||
|
coderacer.drive_forward();
|
||||||
|
}
|
||||||
|
|
||||||
|
} else {
|
||||||
|
anzahl_drehung = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
11
vsode/coderacer_mkII/test/README
Normal file
11
vsode/coderacer_mkII/test/README
Normal file
|
@ -0,0 +1,11 @@
|
||||||
|
|
||||||
|
This directory is intended for PIO Unit Testing and project tests.
|
||||||
|
|
||||||
|
Unit Testing is a software testing method by which individual units of
|
||||||
|
source code, sets of one or more MCU program modules together with associated
|
||||||
|
control data, usage procedures, and operating procedures, are tested to
|
||||||
|
determine whether they are fit for use. Unit testing finds problems early
|
||||||
|
in the development cycle.
|
||||||
|
|
||||||
|
More information about PIO Unit Testing:
|
||||||
|
- https://docs.platformio.org/page/plus/unit-testing.html
|
Loading…
Reference in a new issue