New MKII version of library
This commit is contained in:
parent
d5754d0a9f
commit
462dbb3db4
3 changed files with 151 additions and 173 deletions
|
@ -8,20 +8,21 @@ using namespace std;
|
|||
*/
|
||||
CodeRacerMKII::CodeRacerMKII()
|
||||
{
|
||||
_button_pin = H_BUTTON_PIN;
|
||||
_button_pin_left = H_BUTTON_PIN_LEFT;
|
||||
_button_pin_right = H_BUTTON_PIN_RIGHT;
|
||||
_servo_pin = H_SERVO_PIN;
|
||||
_us_trigger_pin = H_US_TRIG_PIN;
|
||||
_us_echo_pin = H_US_ECHO_PIN;
|
||||
_drive_left_frwd_pin = H_DRIVE_LEFT_FWRD_PIN;
|
||||
_drive_left_back_pin = H_DRIVE_LEFT_BACK_PIN;
|
||||
_drive_left_frwd_bkwrd_pin = H_DRIVE_LEFT_FWRD_BKWRD_PIN;
|
||||
_drive_left_enable_pin = H_DRIVE_LEFT_ENABLE_PIN;
|
||||
_drive_right_frwd_pin = H_DRIVE_RIGHT_FWRD_PIN;
|
||||
_drive_right_back_pin = H_DRIVE_RIGHT_BACK_PIN;
|
||||
_drive_right_frwd_bkwrd_pin = H_DRIVE_RIGHT_FWRD_BKWRD_PIN;
|
||||
_drive_right_enable_pin = H_DRIVE_RIGHT_ENABLE_PIN;
|
||||
_led_frwd_pin = H_LED_FRWD_PIN;
|
||||
_led_stop_pin = H_LED_STOP_PIN;
|
||||
_led_left_pin = H_LED_LEFT_PIN;
|
||||
_led_right_pin = H_LED_RIGHT_PIN;
|
||||
_led_blue_pin = H_LED_BLUE_PIN;
|
||||
_led_white_pin = H_LED_WHITE_PIN;
|
||||
}
|
||||
|
||||
/** @brief CodeRace constructor with pins.This will overwrite the default settings taken from the header file.
|
||||
|
@ -39,29 +40,32 @@ CodeRacerMKII::CodeRacerMKII()
|
|||
* @param led_stop_pin Pin the led that signals that the drives are stopped is connected at
|
||||
* @param led_left_pin Pin the led that signals left side direction is connected at
|
||||
* @param led_right_pin Pin the led that signals right side direction is connected at
|
||||
* @param led_blue_pin Pin the blue led is connected at
|
||||
* @param led_white_pin Pin the white led is connected at
|
||||
* @return nothing
|
||||
*/
|
||||
CodeRacerMKII::CodeRacerMKII(uint8_t button_pin , uint8_t servo_pin,
|
||||
CodeRacerMKII::CodeRacerMKII(uint8_t button_pin_left , uint8_t button_pin_right, 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
|
||||
uint8_t drive_left_frwd_bkwrd_pin, uint8_t drive_left_enable_pin,
|
||||
uint8_t drive_right_frwd_bkwrd_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, uint8_t led_blue_pin, uint8_t led_white_pin
|
||||
)
|
||||
{
|
||||
_button_pin = button_pin;
|
||||
_button_pin_left = button_pin_left;
|
||||
_button_pin_right = button_pin_right;
|
||||
_servo_pin = servo_pin;
|
||||
_us_trigger_pin = us_trigger_pin;
|
||||
_us_echo_pin = us_echo_pin;
|
||||
_drive_left_frwd_pin = drive_left_frwd_pin;
|
||||
_drive_left_back_pin = drive_left_back_pin;
|
||||
_drive_left_frwd_bkwrd_pin = drive_left_frwd_bkwrd_pin;
|
||||
_drive_left_enable_pin = drive_left_enable_pin;
|
||||
_drive_right_frwd_pin = drive_right_frwd_pin;
|
||||
_drive_right_back_pin = drive_right_back_pin;
|
||||
_drive_right_frwd_bkwrd_pin = drive_right_frwd_bkwrd_pin;
|
||||
_drive_right_enable_pin = drive_right_enable_pin;
|
||||
_led_frwd_pin = led_frwd_pin;
|
||||
_led_stop_pin = led_stop_pin;
|
||||
_led_left_pin = led_left_pin;
|
||||
_led_right_pin = led_right_pin;
|
||||
_led_blue_pin = led_blue_pin;
|
||||
_led_white_pin= led_white_pin;
|
||||
}
|
||||
|
||||
/** @brief Initialisation of all attributes and settings of the coderacer. Defaults are taken from the header file.
|
||||
|
@ -90,7 +94,7 @@ void CodeRacerMKII::begin() {
|
|||
|
||||
_drive_left_speed = H_DRIVE_LEFT_SPEED;
|
||||
_drive_right_speed = H_DRIVE_RIGHT_SPEED;
|
||||
|
||||
Serial.printf("1 speed left %d , speed right %d\n", _drive_left_speed, _drive_right_speed);
|
||||
_turn_left_for_ms = H_RACER_TURN_LEFT_FOR_MS;
|
||||
_turn_right_for_ms = H_RACER_TURN_RIGHT_FOR_MS;
|
||||
|
||||
|
@ -102,7 +106,8 @@ void CodeRacerMKII::begin() {
|
|||
|
||||
_last_led_switched_at_ms = millis();
|
||||
_last_led_on = 0;
|
||||
_led_count = 3;
|
||||
_led_count = 6;
|
||||
right_button_pressed = 0;
|
||||
|
||||
_servo_look_around_at_ms = millis() + random(FUN_MIN_PAUSE_MS, FUN_MAX_PAUSE_MS);
|
||||
|
||||
|
@ -118,17 +123,15 @@ void CodeRacerMKII::begin() {
|
|||
_servo->attach(_servo_pin);
|
||||
|
||||
// Left drive
|
||||
pinMode(_drive_left_frwd_pin, OUTPUT);
|
||||
pinMode(_drive_left_back_pin, OUTPUT);
|
||||
pinMode(_drive_left_frwd_bkwrd_pin, OUTPUT);
|
||||
set_drive_left_state(DRIVESTOP);
|
||||
ledcSetup(DRIVE_PWM_LEFT_CHANNEL, 5000, 8); // channel , 50 Hz, 8-bit width
|
||||
ledcSetup(DRIVE_PWM_LEFT_CHANNEL, 100, 8); // channel , 50 Hz, 8-bit width
|
||||
ledcAttachPin(_drive_left_enable_pin, DRIVE_PWM_LEFT_CHANNEL); // connect left drive enable with PWM channel
|
||||
|
||||
// Right drive
|
||||
pinMode(_drive_right_frwd_pin, OUTPUT);
|
||||
pinMode(_drive_right_back_pin, OUTPUT);
|
||||
pinMode(_drive_right_frwd_bkwrd_pin, OUTPUT);
|
||||
set_drive_right_state(DRIVESTOP);
|
||||
ledcSetup(DRIVE_PWM_RIGHT_CHANNEL, 5000, 8); // channel , 50 Hz, 8-bit width
|
||||
ledcSetup(DRIVE_PWM_RIGHT_CHANNEL, 100, 8); // channel , 50 Hz, 8-bit width
|
||||
ledcAttachPin(_drive_right_enable_pin, DRIVE_PWM_RIGHT_CHANNEL); // connect right drive enable pin with PWM channel
|
||||
|
||||
// LEDs
|
||||
|
@ -136,24 +139,27 @@ void CodeRacerMKII::begin() {
|
|||
pinMode(_led_stop_pin, OUTPUT);
|
||||
pinMode(_led_left_pin, OUTPUT);
|
||||
pinMode(_led_right_pin, OUTPUT);
|
||||
// all LEDS off
|
||||
pinMode(_led_blue_pin, OUTPUT);
|
||||
pinMode(_led_white_pin, OUTPUT);
|
||||
set_leds_all_off();
|
||||
|
||||
// Button & -interrupt
|
||||
button_last_pressed_at_ms = 0;
|
||||
pinMode(_button_pin, INPUT_PULLUP);
|
||||
attachInterrupt(digitalPinToInterrupt(_button_pin), _set_button_state, FALLING);
|
||||
left_button_last_pressed_at_ms = 0;
|
||||
right_button_last_pressed_at_ms = 0;
|
||||
pinMode(_button_pin_left, INPUT_PULLUP);
|
||||
attachInterrupt(digitalPinToInterrupt(_button_pin_left), _set_button_state_left, FALLING);
|
||||
pinMode(_button_pin_right, INPUT_PULLUP);
|
||||
attachInterrupt(digitalPinToInterrupt(_button_pin_right), _set_button_state_right, FALLING);
|
||||
|
||||
// Random
|
||||
randomSeed(analogRead(0));
|
||||
|
||||
//fun stuff
|
||||
coderacer_fun_enabled = false;
|
||||
|
||||
}
|
||||
|
||||
//**************************************
|
||||
//*** Coderacer hihger level methods ***
|
||||
//*** Coderacer higher level methods ***
|
||||
//**************************************
|
||||
/** @defgroup higherlevel Higher level methods, setters and getters
|
||||
* @{
|
||||
|
@ -169,7 +175,7 @@ void CodeRacerMKII::stop_driving() {
|
|||
_servo_sweep = false;
|
||||
_drive = false;
|
||||
set_drives_stop_left_right();
|
||||
set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF);
|
||||
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF, LEDOFF, LEDOFF);
|
||||
}
|
||||
|
||||
/** @brief Sets the speed and the directions of both drives so that it will move forward.
|
||||
|
@ -193,7 +199,7 @@ void CodeRacerMKII::drive_forward(uint8_t left_speed, uint8_t right_speed)
|
|||
{
|
||||
set_drives_states_left_right(DRIVEFRWD, DRIVEFRWD);
|
||||
set_drives_speed_left_right(left_speed, right_speed);
|
||||
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF);
|
||||
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON, LEDOFF, LEDOFF);
|
||||
_drive = true;
|
||||
_drive_set_at_ms = millis();
|
||||
}
|
||||
|
@ -219,7 +225,7 @@ void CodeRacerMKII::drive_backward(uint8_t left_speed, uint8_t right_speed)
|
|||
{
|
||||
set_drives_states_left_right(DRIVEBACK, DRIVEBACK);
|
||||
set_drives_speed_left_right(left_speed, right_speed);
|
||||
set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDON, LEDOFF);
|
||||
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF, LEDOFF, LEDOFF);
|
||||
_drive = true;
|
||||
_drive_set_at_ms = millis();
|
||||
}
|
||||
|
@ -257,7 +263,7 @@ void CodeRacerMKII::turn_left(unsigned long turn_for_ms)
|
|||
void CodeRacerMKII::turn_left(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed)
|
||||
{
|
||||
_drive = false;
|
||||
set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF); // LEDs setzen
|
||||
set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDOFF); // LEDs setzen
|
||||
set_drives_states_left_right(DRIVEBACK, DRIVEFRWD);
|
||||
set_drives_speed_left_right(left_speed, right_speed);
|
||||
// wait set delay for the timed turn
|
||||
|
@ -300,7 +306,7 @@ void CodeRacerMKII::turn_right(unsigned long turn_for_ms)
|
|||
void CodeRacerMKII::turn_right(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed)
|
||||
{
|
||||
_drive = false;
|
||||
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON); // LEDs setzen
|
||||
set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF, LEDOFF, LEDOFF); // LEDs setzen
|
||||
set_drives_states_left_right(DRIVEFRWD, DRIVEBACK);
|
||||
set_drives_speed_left_right(left_speed, right_speed);
|
||||
// wait set delay for the timed turn
|
||||
|
@ -361,7 +367,7 @@ bool CodeRacerMKII::start_stop() {
|
|||
}
|
||||
else {
|
||||
stop_driving();
|
||||
set_leds_all_on();
|
||||
set_leds_all_off();
|
||||
delay(200);
|
||||
servo_set_to_center();
|
||||
_servo_look_around_at_ms = millis() + random(20000, 120000);
|
||||
|
@ -425,12 +431,25 @@ void CodeRacerMKII::set_active() {
|
|||
|
||||
/** @brief Checks if coderracer_activ is set.
|
||||
*
|
||||
* coderracer_activ is toggled each time the button is pressed. After power on coderracer_activ is set to False.
|
||||
* @return True id coderracer_activ is set - False if not.
|
||||
* coderracer_activ is toggled each time the left button is pressed. After power on coderracer_activ is set to False.
|
||||
* @return True if coderracer_activ is set - False if not.
|
||||
*/
|
||||
bool CodeRacerMKII::is_active() {
|
||||
return(coderracer_activ);
|
||||
}
|
||||
/** @brief returns the right button's current state
|
||||
* _right_button_state is toggled each time the right button is pressed. Is set false by default.
|
||||
* @return true if _right_button_pressed is set- False if not.
|
||||
*/
|
||||
bool CodeRacerMKII::right_button_state() {
|
||||
return(right_button_pressed);
|
||||
}
|
||||
|
||||
unsigned int CodeRacerMKII::button_count() {
|
||||
return(right_button_count);
|
||||
}
|
||||
|
||||
|
||||
|
||||
/** @} */ // end of group higherlevelgetters
|
||||
/** @} */ // end of group higherlevel
|
||||
|
@ -467,7 +486,7 @@ void CodeRacerMKII::kitt()
|
|||
{
|
||||
if (millis() - _last_led_switched_at_ms > LED_SWITCH_MS) {
|
||||
_last_led_switched_at_ms = millis();
|
||||
if (_last_led_on >= 5) {
|
||||
if (_last_led_on >= 6) {
|
||||
_led_count = -1;
|
||||
}
|
||||
else if (_last_led_on <= 0) {
|
||||
|
@ -476,21 +495,25 @@ void CodeRacerMKII::kitt()
|
|||
_last_led_on = _last_led_on + _led_count;
|
||||
switch (_last_led_on) {
|
||||
case 0:
|
||||
set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF);
|
||||
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDOFF);
|
||||
break;
|
||||
case 1:
|
||||
set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF);
|
||||
set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDOFF);
|
||||
break;
|
||||
case 2:
|
||||
set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF);
|
||||
set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF, LEDOFF, LEDOFF);
|
||||
break;
|
||||
case 3:
|
||||
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF);
|
||||
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF, LEDOFF, LEDOFF);
|
||||
break;
|
||||
case 4:
|
||||
case 5:
|
||||
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON);
|
||||
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON, LEDOFF, LEDOFF);
|
||||
break;
|
||||
case 5:
|
||||
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDON, LEDOFF);
|
||||
break;
|
||||
case 6:
|
||||
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDON);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -1049,7 +1072,7 @@ void CodeRacerMKII::set_drives_states_left_right(drivestate stateleft, drivestat
|
|||
* @return nothing
|
||||
*/
|
||||
void CodeRacerMKII::set_drive_left_state(drivestate state) {
|
||||
set_drive_state(state, _drive_left_frwd_pin, _drive_left_back_pin);
|
||||
set_drive_state(state, _drive_left_frwd_bkwrd_pin, _drive_left_enable_pin);
|
||||
}
|
||||
|
||||
/** @brief Sets the right side drive to the specified drivestate (DRIVESTOP, DRIVEFRWD, DRIVEBACK)
|
||||
|
@ -1057,7 +1080,7 @@ void CodeRacerMKII::set_drive_left_state(drivestate state) {
|
|||
* @return nothing
|
||||
*/
|
||||
void CodeRacerMKII::set_drive_right_state(drivestate state) {
|
||||
set_drive_state(state, _drive_right_frwd_pin, _drive_right_back_pin);
|
||||
set_drive_state(state, _drive_right_frwd_bkwrd_pin, _drive_right_enable_pin);
|
||||
}
|
||||
|
||||
/** @brief Sets the specified drivestate for the drive connected to the sepecified pins (DRIVESTOP, DRIVEFRWD, DRIVEBACK)
|
||||
|
@ -1066,19 +1089,16 @@ void CodeRacerMKII::set_drive_right_state(drivestate state) {
|
|||
* @param backpin Pin the backward signal of the drive device driver is connected at
|
||||
* @return nothing
|
||||
*/
|
||||
void CodeRacerMKII::set_drive_state(drivestate state, uint8_t frwdpin, uint8_t backpin) {
|
||||
void CodeRacerMKII::set_drive_state(drivestate state, uint8_t frwdbackpin, uint8_t enable_pin ) {
|
||||
switch (state) {
|
||||
case DRIVESTOP:
|
||||
digitalWrite(frwdpin, LOW);
|
||||
digitalWrite(backpin, LOW);
|
||||
set_drive_speed(0, enable_pin);
|
||||
break;
|
||||
case DRIVEFRWD:
|
||||
digitalWrite(frwdpin, HIGH);
|
||||
digitalWrite(backpin, LOW);
|
||||
digitalWrite(frwdbackpin, HIGH);
|
||||
break;
|
||||
case DRIVEBACK:
|
||||
digitalWrite(frwdpin, LOW);
|
||||
digitalWrite(backpin, HIGH);
|
||||
digitalWrite(frwdbackpin, LOW);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -1147,11 +1167,11 @@ uint8_t CodeRacerMKII::drive_left_speed() {
|
|||
|
||||
void CodeRacerMKII::_analog_write(uint8_t pin, uint8_t speed) {
|
||||
if (pin == _drive_left_enable_pin) {
|
||||
_drive_left_speed = speed;
|
||||
//_drive_left_speed = speed;
|
||||
ledcWrite(DRIVE_PWM_LEFT_CHANNEL, speed);
|
||||
}
|
||||
if (pin == _drive_right_enable_pin) {
|
||||
_drive_right_speed = speed;
|
||||
//_drive_right_speed = speed;
|
||||
ledcWrite(DRIVE_PWM_RIGHT_CHANNEL, speed);
|
||||
}
|
||||
}
|
||||
|
@ -1175,13 +1195,17 @@ void CodeRacerMKII::_analog_write(uint8_t pin, uint8_t speed) {
|
|||
* @param stopled set state of status stop LED (red led)
|
||||
* @param frwdled set state of status forward LED (green or blue led)
|
||||
* @param rightled set state of status right LED (most right yellow led)
|
||||
* @param blueled set state of blue LED
|
||||
* @param whiteled set state of white LED
|
||||
* @return nothing
|
||||
*/
|
||||
void CodeRacerMKII::set_leds_left_stop_frwd_right(ledstate leftled, ledstate stopled, ledstate frwdled, ledstate rightled) {
|
||||
void CodeRacerMKII::set_leds_left_stop_frwd_right(ledstate leftled, ledstate rightled, ledstate stopled, ledstate frwrdled, ledstate blueled, ledstate whiteled) {
|
||||
digitalWrite(_led_left_pin, leftled);
|
||||
digitalWrite(_led_frwd_pin, frwdled);
|
||||
digitalWrite(_led_right_pin, rightled);
|
||||
digitalWrite(_led_stop_pin, stopled);
|
||||
digitalWrite(_led_frwd_pin, frwrdled);
|
||||
digitalWrite(_led_blue_pin, blueled);
|
||||
digitalWrite(_led_white_pin, whiteled);
|
||||
}
|
||||
|
||||
/** @brief Sets all of the 4 LEDs to the same ledstate (LEDON, LEDOFF)
|
||||
|
@ -1190,9 +1214,11 @@ void CodeRacerMKII::set_leds_left_stop_frwd_right(ledstate leftled, ledstate sto
|
|||
*/
|
||||
void CodeRacerMKII::set_leds_all(ledstate alleds) {
|
||||
digitalWrite(_led_left_pin, alleds);
|
||||
digitalWrite(_led_frwd_pin, alleds);
|
||||
digitalWrite(_led_right_pin, alleds);
|
||||
digitalWrite(_led_stop_pin, alleds);
|
||||
digitalWrite(_led_frwd_pin, alleds);
|
||||
digitalWrite(_led_blue_pin, alleds);
|
||||
digitalWrite(_led_white_pin, alleds);
|
||||
}
|
||||
|
||||
/** @brief Sets all of the 4 LEDs to the ledstate LEDOFF
|
||||
|
@ -1217,12 +1243,20 @@ void CodeRacerMKII::set_leds_all_on() {
|
|||
//*** ISRs ***
|
||||
//**************************************
|
||||
//IRAM_ATTR is used to load the code into DRAM and not to Flash to make it faster - required for ISRs
|
||||
void IRAM_ATTR CodeRacerMKII::_set_button_state() {
|
||||
if ((millis() - button_last_pressed_at_ms) > BUTTON_BOUNCING_TIME_MS) {
|
||||
button_last_pressed_at_ms = millis(); // simplest debouncing - just wait ;-)
|
||||
void IRAM_ATTR CodeRacerMKII::_set_button_state_left() {
|
||||
if ((millis() - left_button_last_pressed_at_ms) > BUTTON_BOUNCING_TIME_MS) {
|
||||
left_button_last_pressed_at_ms = millis(); // simplest debouncing - just wait ;-)
|
||||
coderracer_activ = !coderracer_activ;
|
||||
}
|
||||
}
|
||||
void IRAM_ATTR CodeRacerMKII::_set_button_state_right() {
|
||||
if ((millis() - right_button_last_pressed_at_ms) > BUTTON_BOUNCING_TIME_MS) {
|
||||
right_button_last_pressed_at_ms = millis();
|
||||
right_button_pressed = !right_button_pressed;
|
||||
right_button_count++;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//**********************************************************************************************************************
|
||||
//** Helper methods
|
||||
|
|
|
@ -18,10 +18,11 @@
|
|||
#define FUN_MAX_PAUSE_MS 300000
|
||||
#define LED_SWITCH_MS 50 // speed of knight rider lights
|
||||
//----- Button ------------
|
||||
#define H_BUTTON_PIN 17
|
||||
#define H_BUTTON_PIN_LEFT 13
|
||||
#define H_BUTTON_PIN_RIGHT 16
|
||||
#define BUTTON_BOUNCING_TIME_MS 200 // bouncing delay
|
||||
//----- Servo -----
|
||||
#define H_SERVO_PIN 16
|
||||
#define H_SERVO_PIN 18
|
||||
#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
|
||||
|
@ -37,20 +38,18 @@
|
|||
#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_TRIG_PIN 21
|
||||
#define H_US_ECHO_PIN 17
|
||||
#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_DRIVE_RIGHT_SPEED 128 // default speed of right side drive. 0 ...255
|
||||
#define H_DRIVE_LEFT_SPEED 128 // default speed of left side drive. 0 ...255
|
||||
#define H_DRIVE_RIGHT_ENABLE_PIN 5
|
||||
#define H_DRIVE_RIGHT_FWRD_BKWRD_PIN 19
|
||||
#define H_DRIVE_LEFT_ENABLE_PIN 23
|
||||
#define H_DRIVE_LEFT_FWRD_BKWRD_PIN 22
|
||||
#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
|
||||
|
||||
|
@ -58,16 +57,21 @@
|
|||
#define DRIVE_PWM_RIGHT_CHANNEL 6 // PWM-channel for right side drive
|
||||
|
||||
//----- LEDs -----
|
||||
#define H_LED_FRWD_PIN 26
|
||||
#define H_LED_FRWD_PIN 27
|
||||
#define H_LED_STOP_PIN 25
|
||||
#define H_LED_LEFT_PIN 33
|
||||
#define H_LED_RIGHT_PIN 27
|
||||
#define H_LED_LEFT_PIN 32
|
||||
#define H_LED_RIGHT_PIN 33
|
||||
#define H_LED_BLUE_PIN 14
|
||||
#define H_LED_WHITE_PIN 12
|
||||
|
||||
|
||||
using namespace std;
|
||||
|
||||
static volatile bool coderracer_activ = false;;
|
||||
static volatile unsigned long button_last_pressed_at_ms = millis();
|
||||
static volatile bool coderracer_activ = false;
|
||||
static volatile bool right_button_pressed =false;
|
||||
static volatile unsigned int right_button_count=0;
|
||||
static volatile unsigned long left_button_last_pressed_at_ms = millis();
|
||||
static volatile unsigned long right_button_last_pressed_at_ms = millis();
|
||||
|
||||
enum ledstate {
|
||||
LEDOFF,
|
||||
|
@ -94,20 +98,21 @@ class CodeRacerMKII {
|
|||
BluetoothSerial* _BTSerial;
|
||||
|
||||
//pins
|
||||
uint8_t _button_pin;
|
||||
uint8_t _button_pin_left;
|
||||
uint8_t _button_pin_right;
|
||||
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_frwd_bkwrd_pin;
|
||||
uint8_t _drive_left_enable_pin;
|
||||
uint8_t _drive_right_frwd_pin;
|
||||
uint8_t _drive_right_back_pin;
|
||||
uint8_t _drive_right_frwd_bkwrd_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;
|
||||
uint8_t _led_blue_pin;
|
||||
uint8_t _led_white_pin;
|
||||
|
||||
//servo variables
|
||||
int8_t _servo_sweep_step;
|
||||
|
@ -135,7 +140,6 @@ class CodeRacerMKII {
|
|||
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;
|
||||
|
@ -146,7 +150,8 @@ class CodeRacerMKII {
|
|||
Servo* _servo;
|
||||
Servo* _servo_dummy;
|
||||
|
||||
static void _set_button_state();
|
||||
static void _set_button_state_left();
|
||||
static void _set_button_state_right();
|
||||
void _analog_write(uint8_t pin, uint8_t speed);
|
||||
unsigned long _servo_set_position(uint8_t position);
|
||||
|
||||
|
@ -163,11 +168,11 @@ class CodeRacerMKII {
|
|||
//methods
|
||||
CodeRacerMKII();
|
||||
|
||||
CodeRacerMKII(uint8_t button_pin, uint8_t servo_pin,
|
||||
CodeRacerMKII(uint8_t button_pin_left, uint8_t button_pin_right, 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);
|
||||
uint8_t drive_left_frwd_bkwrd_pin, uint8_t drive_left_enable_pin,
|
||||
uint8_t drive_right_frwd_bkwrd_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, uint8_t led_blue_pin, uint8_t led_white_pin);
|
||||
|
||||
void set_inactive();
|
||||
void set_active();
|
||||
|
@ -187,6 +192,9 @@ class CodeRacerMKII {
|
|||
uint8_t drive_right_speed();
|
||||
unsigned long turn_left_for_ms();
|
||||
unsigned long turn_right_for_ms();
|
||||
bool right_button_state();
|
||||
unsigned int button_count();
|
||||
|
||||
|
||||
// higher level {code}racer services
|
||||
void stop_driving();
|
||||
|
@ -205,7 +213,6 @@ class CodeRacerMKII {
|
|||
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);
|
||||
|
@ -219,7 +226,7 @@ class CodeRacerMKII {
|
|||
void bt_removeStringFromIgnoreList(String stringtoignore);
|
||||
|
||||
// LEDs
|
||||
void set_leds_left_stop_frwd_right(ledstate leftled, ledstate stopled, ledstate frwdled, ledstate rightled);
|
||||
void set_leds_left_stop_frwd_right(ledstate leftled, ledstate stopled, ledstate frwdled, ledstate rightled, ledstate blueled, ledstate whiteled);
|
||||
void set_leds_all(ledstate alleds);
|
||||
void set_leds_all_off();
|
||||
void set_leds_all_on();
|
||||
|
@ -229,7 +236,7 @@ class CodeRacerMKII {
|
|||
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_drive_state(drivestate state, uint8_t fwrdbackpin, uint8_t enable_pin);
|
||||
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);
|
||||
|
|
|
@ -18,7 +18,7 @@ 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.
|
||||
Serial.begin(9600); // Serial Monitor aktivieren. Mit dem Monitor kann man sich Werte und Meldungen anzeigen lassen.
|
||||
|
||||
// CodeRacer initialisieren
|
||||
coderacer.begin();
|
||||
|
@ -37,92 +37,29 @@ void setup() {
|
|||
//---- 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
|
||||
while(coderacer.start_stop()== 1)
|
||||
{
|
||||
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
|
||||
int iAbstand= coderacer.usonic_measure_cm();
|
||||
coderacer.drive_forward(130, 108);
|
||||
if (iAbstand<12)
|
||||
{
|
||||
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();
|
||||
delay(1000);
|
||||
iAbstand= 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){
|
||||
while (iAbstand<20)
|
||||
{
|
||||
coderacer.drive_backward();
|
||||
delay(300);
|
||||
iAbstand= coderacer.usonic_measure_cm();
|
||||
}
|
||||
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();
|
||||
delay(1000);
|
||||
coderacer.turn_left(300);
|
||||
delay(1000);
|
||||
}
|
||||
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;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
|
Loading…
Reference in a new issue