9 _button_pin = H_BUTTON_PIN;
10 _servo_pin = H_SERVO_PIN;
11 _us_trigger_pin = H_US_TRIG_PIN;
12 _us_echo_pin = H_US_ECHO_PIN;
13 _drive_left_frwd_pin = H_DRIVE_LEFT_FWRD_PIN;
14 _drive_left_back_pin = H_DRIVE_LEFT_BACK_PIN;
15 _drive_left_enable_pin = H_DRIVE_LEFT_ENABLE_PIN;
16 _drive_right_frwd_pin = H_DRIVE_RIGHT_FWRD_PIN;
17 _drive_right_back_pin = H_DRIVE_RIGHT_BACK_PIN;
18 _drive_right_enable_pin = H_DRIVE_RIGHT_ENABLE_PIN;
19 _led_frwd_pin = H_LED_FRWD_PIN;
20 _led_stop_pin = H_LED_STOP_PIN;
21 _led_left_pin = H_LED_LEFT_PIN;
22 _led_right_pin = H_LED_RIGHT_PIN;
42 CodeRacer::CodeRacer(uint8_t button_pin , uint8_t servo_pin,
43 uint8_t us_trigger_pin, uint8_t us_echo_pin,
44 uint8_t drive_left_frwd_pin, uint8_t drive_left_back_pin, uint8_t drive_left_enable_pin,
45 uint8_t drive_right_frwd_pin, uint8_t drive_right_back_pin, uint8_t drive_right_enable_pin,
46 uint8_t led_frwd_pin, uint8_t led_stop_pin, uint8_t led_left_pin, uint8_t led_right_pin
49 _button_pin = button_pin;
50 _servo_pin = servo_pin;
51 _us_trigger_pin = us_trigger_pin;
52 _us_echo_pin = us_echo_pin;
53 _drive_left_frwd_pin = drive_left_frwd_pin;
54 _drive_left_back_pin = drive_left_back_pin;
55 _drive_left_enable_pin = drive_left_enable_pin;
56 _drive_right_frwd_pin = drive_right_frwd_pin;
57 _drive_right_back_pin = drive_right_back_pin;
58 _drive_right_enable_pin = drive_right_enable_pin;
59 _led_frwd_pin = led_frwd_pin;
60 _led_stop_pin = led_stop_pin;
61 _led_left_pin = led_left_pin;
62 _led_right_pin = led_right_pin;
68 void CodeRacer::begin() {
72 _servo_dummy =
new Servo();
74 servo_center_pos = H_SERVO_CENTER_POS;
75 servo_left_pos = H_SERVO_LEFT_POS;
76 servo_right_pos = H_SERVO_RIGHT_POS;
77 servo_sweep_left_pos = H_SERVO_SWEEP_LEFT_POS;
78 servo_sweep_right_pos = H_SERVO_SWEEP_RIGHT_POS;
79 _servo_position = servo_center_pos;
80 _servo_sweep_step = SERVO_SWEEP_TO_LEFT_STEP;
81 _servo_position_set_at_ms = millis();
82 _servo_position_eta_in_ms = 0;
84 _drive_left_speed = H_DRIVE_LEFT_SPEED;
85 _drive_right_speed = H_DRIVE_RIGHT_SPEED;
87 _turn_left_for_ms = H_RACER_TURN_LEFT_FOR_MS;
88 _turn_right_for_ms = H_RACER_TURN_RIGHT_FOR_MS;
90 coderracer_activ =
false;
91 _coderracer_activ =
true;
93 _drive_set_at_ms = millis();
96 _last_led_switched_at_ms = millis();
100 _servo_look_around_at_ms = millis() + random(FUN_MIN_PAUSE_MS, FUN_MAX_PAUSE_MS);
102 _usonic_stop_distance_cm = H_US_STOP_DISTANCE_CM;
103 usonic_set_stop_distance_cm(_usonic_stop_distance_cm);
104 _coderacer_stopped_at_min_distance =
false;
107 pinMode(_us_trigger_pin, OUTPUT);
108 pinMode(_us_echo_pin, INPUT);
111 _servo->attach(_servo_pin);
114 pinMode(_drive_left_frwd_pin, OUTPUT);
115 pinMode(_drive_left_back_pin, OUTPUT);
116 set_drive_left_state(DRIVESTOP);
117 ledcSetup(DRIVE_PWM_LEFT_CHANNEL, 5000, 8);
118 ledcAttachPin(_drive_left_enable_pin, DRIVE_PWM_LEFT_CHANNEL);
121 pinMode(_drive_right_frwd_pin, OUTPUT);
122 pinMode(_drive_right_back_pin, OUTPUT);
123 set_drive_right_state(DRIVESTOP);
124 ledcSetup(DRIVE_PWM_RIGHT_CHANNEL, 5000, 8);
125 ledcAttachPin(_drive_right_enable_pin, DRIVE_PWM_RIGHT_CHANNEL);
128 pinMode(_led_frwd_pin, OUTPUT);
129 pinMode(_led_stop_pin, OUTPUT);
130 pinMode(_led_left_pin, OUTPUT);
131 pinMode(_led_right_pin, OUTPUT);
136 button_last_pressed_at_ms = 0;
137 pinMode(_button_pin, INPUT_PULLUP);
138 attachInterrupt(digitalPinToInterrupt(_button_pin), _set_button_state, FALLING);
141 randomSeed(analogRead(0));
144 coderacer_fun_enabled =
false;
161 void CodeRacer::stop_driving() {
162 _servo_sweep =
false;
164 set_drives_stop_left_right();
165 set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF);
173 void CodeRacer::drive_forward()
185 void CodeRacer::drive_forward(uint8_t left_speed, uint8_t right_speed)
187 set_drives_states_left_right(DRIVEFRWD, DRIVEFRWD);
188 set_drives_speed_left_right(left_speed, right_speed);
189 set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF);
191 _drive_set_at_ms = millis();
199 void CodeRacer::drive_backward()
201 drive_backward(_drive_left_speed, _drive_right_speed);
211 void CodeRacer::drive_backward(uint8_t left_speed, uint8_t right_speed)
213 set_drives_states_left_right(DRIVEBACK, DRIVEBACK);
214 set_drives_speed_left_right(left_speed, right_speed);
215 set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDON, LEDOFF);
217 _drive_set_at_ms = millis();
226 void CodeRacer::turn_left()
228 turn_left(_turn_left_for_ms, _drive_left_speed, _drive_right_speed);
237 void CodeRacer::turn_left(
unsigned long turn_for_ms)
239 turn_left(turn_for_ms, _drive_left_speed, _drive_right_speed);
250 void CodeRacer::turn_left(
unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed)
253 set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF);
254 set_drives_states_left_right(DRIVEBACK, DRIVEFRWD);
255 set_drives_speed_left_right(left_speed, right_speed);
257 _turn_left_for_ms = turn_for_ms;
258 delay(_turn_left_for_ms);
260 set_drives_stop_left_right();
269 void CodeRacer::turn_right()
271 turn_right(_turn_right_for_ms, _drive_left_speed, _drive_right_speed);
280 void CodeRacer::turn_right(
unsigned long turn_for_ms)
282 turn_right(turn_for_ms, _drive_left_speed, _drive_right_speed);
293 void CodeRacer::turn_right(
unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed)
296 set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON);
297 set_drives_states_left_right(DRIVEFRWD, DRIVEBACK);
298 set_drives_speed_left_right(left_speed, right_speed);
300 _turn_right_for_ms = turn_for_ms;
301 delay(_turn_right_for_ms);
303 set_drives_stop_left_right();
314 void CodeRacer::start_stop_at_min_distance() {
315 start_stop_at_min_distance(_usonic_stop_distance_cm);
324 void CodeRacer::start_stop_at_min_distance(
unsigned long min_distance_cm) {
325 if (
false == _coderacer_stop_at_distance_enabled) {
326 _coderacer_stopped_at_min_distance =
false;
327 usonic_set_stop_distance_cm(min_distance_cm);
328 _coderacer_stop_at_distance_enabled =
true;
335 void CodeRacer::stop_stop_at_min_distance() {
336 _coderacer_stop_at_distance_enabled =
false;
348 bool CodeRacer::start_stop() {
349 if (_coderracer_activ != coderracer_activ) {
350 _coderracer_activ = coderracer_activ;
351 if (
true == _coderracer_activ) {
359 servo_set_to_center();
360 _servo_look_around_at_ms = millis() + random(20000, 120000);
364 if ((
false == _coderracer_activ) && (
true == coderacer_fun_enabled)) {
369 return(_coderracer_activ);
380 bool CodeRacer::stopped_at_min_distance() {
381 return(_coderacer_stopped_at_min_distance);
387 bool CodeRacer::is_driving() {
394 unsigned long CodeRacer::turn_left_for_ms() {
395 return(_turn_left_for_ms);
401 unsigned long CodeRacer::turn_right_for_ms() {
402 return(_turn_right_for_ms);
408 void CodeRacer::set_inactive() {
409 coderracer_activ =
false;
415 void CodeRacer::set_active() {
416 coderracer_activ =
true;
424 bool CodeRacer::is_active() {
425 return(coderracer_activ);
440 void CodeRacer::look_around()
442 if (_servo_look_around_at_ms < millis()) {
443 _servo_look_around_at_ms = millis() + random(FUN_MIN_PAUSE_MS, FUN_MAX_PAUSE_MS);
446 servo_set_to_right();
448 servo_set_to_center();
452 servo_set_to_center();
459 void CodeRacer::kitt()
461 if (millis() - _last_led_switched_at_ms > LED_SWITCH_MS) {
462 _last_led_switched_at_ms = millis();
463 if (_last_led_on >= 5) {
466 else if (_last_led_on <= 0) {
469 _last_led_on = _last_led_on + _led_count;
470 switch (_last_led_on) {
472 set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF);
475 set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF);
478 set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF);
481 set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF);
485 set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON);
510 void CodeRacer::servo_settings(uint8_t pos_center, uint8_t pos_left, uint8_t pos_right, uint8_t sweep_left_pos, uint8_t sweep_right_pos)
512 servo_center_pos = pos_center;
513 servo_left_pos = pos_left;
514 servo_right_pos = pos_right;
515 servo_sweep_left_pos = sweep_left_pos;
516 servo_sweep_right_pos = sweep_right_pos;
526 void CodeRacer::servo_sweep()
530 if (millis() - _servo_position_set_at_ms > SERVO_SWEEP_MS) {
531 position = _servo_position + _servo_sweep_step;
533 if ((position >= servo_sweep_left_pos) || (position >= SERVO_MAX_POSITION)) {
534 position = servo_sweep_left_pos;
535 _servo_sweep_step = SERVO_SWEEP_TO_RIGHT_STEP;
537 if ((position <= servo_sweep_right_pos) || (position <= SERVO_MIN_POSITION)) {
538 position = servo_sweep_right_pos;
539 _servo_sweep_step = SERVO_SWEEP_TO_LEFT_STEP;
541 _servo_set_position(position);
548 void CodeRacer::servo_set_to_right()
550 servo_set_position_wait(servo_right_pos);
556 void CodeRacer::servo_set_to_left()
558 servo_set_position_wait(servo_left_pos);
564 void CodeRacer::servo_set_to_center()
566 servo_set_position_wait(servo_center_pos);
575 uint8_t CodeRacer::servo_set_position_wait(uint8_t position)
577 _servo_sweep =
false;
578 unsigned long wait_time_ms = _servo_set_position(position);
580 return(_servo_position);
589 unsigned long CodeRacer::servo_set_position(uint8_t position)
591 _servo_sweep =
false;
592 unsigned long wait_time_ms = _servo_set_position(position);
593 return(wait_time_ms);
596 unsigned long CodeRacer::_servo_set_position(uint8_t position)
598 uint8_t _position = position;
601 if (position < SERVO_MIN_POSITION) {
602 _position = SERVO_MIN_POSITION;
604 else if (position > SERVO_MAX_POSITION) {
605 _position = SERVO_MAX_POSITION;
607 _servo->write(_position);
609 delay(SERVO_SET_1TICK_POSITION_DELAY_MS);
610 absdiff = abs(_servo_position - _position);
612 _servo_position_eta_in_ms = absdiff * SERVO_SET_1TICK_POSITION_DELAY_MS;
615 _servo_position_eta_in_ms = 0;
618 _servo_position_set_at_ms = millis();
619 _servo_position = _position;
621 return(_servo_position_eta_in_ms);
632 uint8_t CodeRacer::servo_position() {
633 return(_servo_position);
639 unsigned long CodeRacer::servo_position_set_at_ms() {
640 return(_servo_position_set_at_ms);
649 unsigned long CodeRacer::servo_position_eta_in_ms() {
650 return(_servo_position_eta_in_ms);
672 unsigned long CodeRacer::usonic_measure_cm()
674 return(usonic_measure_cm(US_MAX_ECHO_TIME_US));
682 unsigned long CodeRacer::usonic_measure_us()
684 return(usonic_measure_us(US_MAX_ECHO_TIME_US));
694 unsigned long CodeRacer::usonic_measure_cm(
unsigned long max_echo_run_time_us)
696 unsigned long echo_runtime_us = usonic_measure_us(max_echo_run_time_us);
697 unsigned long distance_cm = echo_runtime_us * 0.0172;
700 _usonic_distance_cm = distance_cm;
711 unsigned long CodeRacer::usonic_measure_us(
unsigned long max_echo_run_time_us)
713 unsigned long echo_runtime_us[3] = { 0,0,0 };
717 echo_runtime_us[measnr] = usonic_measure_single_shot_us(max_echo_run_time_us);
718 if (echo_runtime_us[measnr] > 200) {
721 }
while (measnr < 3);
724 if (echo_runtime_us[0] > echo_runtime_us[1]) { std::swap(echo_runtime_us[0], echo_runtime_us[1]); }
725 if (echo_runtime_us[1] > echo_runtime_us[2]) { std::swap(echo_runtime_us[1], echo_runtime_us[2]); }
726 if (echo_runtime_us[0] > echo_runtime_us[1]) { std::swap(echo_runtime_us[0], echo_runtime_us[1]); }
732 if (
true == _coderacer_stop_at_distance_enabled) {
733 if (echo_runtime_us[1] <= _usonic_stop_distance_us) {
734 _coderacer_stopped_at_min_distance =
true;
736 _coderacer_stop_at_distance_enabled =
false;
739 _usonic_distance_us = echo_runtime_us[1];
740 return(echo_runtime_us[1]);
748 unsigned long CodeRacer::usonic_measure_single_shot_cm()
750 return(usonic_measure_single_shot_cm(US_MAX_ECHO_TIME_US));
758 unsigned long CodeRacer::usonic_measure_single_shot_us()
760 return(usonic_measure_single_shot_us(US_MAX_ECHO_TIME_US));
770 unsigned long CodeRacer::usonic_measure_single_shot_cm(
unsigned long max_echo_run_time_us)
776 unsigned long echo_runtime_us = usonic_measure_single_shot_us(max_echo_run_time_us);
777 unsigned long distance_cm = echo_runtime_us * 0.0172;
780 _usonic_distance_cm = distance_cm;
791 unsigned long CodeRacer::usonic_measure_single_shot_us(
unsigned long max_echo_run_time_us)
793 unsigned long echo_runtime_us;
795 pinMode(_us_echo_pin, OUTPUT);
796 pinMode(_us_echo_pin, INPUT);
797 digitalWrite(_us_trigger_pin, LOW);
798 delayMicroseconds(2);
799 digitalWrite(_us_trigger_pin, HIGH);
800 delayMicroseconds(10);
801 digitalWrite(_us_trigger_pin, LOW);
803 echo_runtime_us = pulseInLong(_us_echo_pin, HIGH, max_echo_run_time_us);
804 if (echo_runtime_us == 0) {
805 echo_runtime_us = max_echo_run_time_us;
809 _usonic_distance_us = echo_runtime_us;
810 return(echo_runtime_us);
825 void CodeRacer::usonic_set_stop_distance_cm(
unsigned long stop_distance_cm)
827 _usonic_stop_distance_us = stop_distance_cm * 58.14;
837 void CodeRacer::usonic_set_stop_distance_us(
unsigned long stop_distance_us)
839 _usonic_stop_distance_us = stop_distance_us;
845 unsigned long CodeRacer::usonic_distance_us() {
846 return(_usonic_distance_us);
852 unsigned long CodeRacer::usonic_distance_cm() {
853 return(_usonic_distance_cm);
878 void CodeRacer::drives_settings(uint8_t drive_left_speed, uint8_t drive_right_speed,
unsigned long turn_left_for_ms,
unsigned long turn_right_for_ms)
880 _drive_left_speed = drive_left_speed;
881 _drive_right_speed = drive_right_speed;
882 _turn_left_for_ms = turn_left_for_ms;
883 _turn_right_for_ms = turn_right_for_ms;
889 void CodeRacer::set_drives_stop_left_right() {
890 set_drive_left_state(DRIVESTOP);
891 set_drive_right_state(DRIVESTOP);
899 void CodeRacer::set_drives_states_left_right(drivestate stateleft, drivestate stateright) {
900 set_drive_left_state(stateleft);
901 set_drive_right_state(stateright);
908 void CodeRacer::set_drive_left_state(drivestate state) {
909 set_drive_state(state, _drive_left_frwd_pin, _drive_left_back_pin);
916 void CodeRacer::set_drive_right_state(drivestate state) {
917 set_drive_state(state, _drive_right_frwd_pin, _drive_right_back_pin);
926 void CodeRacer::set_drive_state(drivestate state, uint8_t frwdpin, uint8_t backpin) {
929 digitalWrite(frwdpin, LOW);
930 digitalWrite(backpin, LOW);
933 digitalWrite(frwdpin, HIGH);
934 digitalWrite(backpin, LOW);
937 digitalWrite(frwdpin, LOW);
938 digitalWrite(backpin, HIGH);
950 void CodeRacer::set_drives_speed_left_right(uint8_t speedleft, uint8_t speedright) {
951 set_drive_left_speed(speedleft);
952 set_drive_right_speed(speedright);
961 void CodeRacer::set_drive_left_speed(uint8_t speed) {
962 set_drive_speed(speed, _drive_left_enable_pin);
971 void CodeRacer::set_drive_right_speed(uint8_t speed) {
972 set_drive_speed(speed, _drive_right_enable_pin);
982 void CodeRacer::set_drive_speed(uint8_t speed, uint8_t enablepin) {
983 _analog_write(enablepin, (
int)speed);
994 uint8_t CodeRacer::drive_right_speed() {
995 return _drive_right_speed;
1001 uint8_t CodeRacer::drive_left_speed() {
1002 return(_drive_left_speed);
1005 void CodeRacer::_analog_write(uint8_t pin, uint8_t speed) {
1006 if (pin == _drive_left_enable_pin) {
1007 _drive_left_speed = speed;
1008 ledcWrite(DRIVE_PWM_LEFT_CHANNEL, speed);
1010 if (pin == _drive_right_enable_pin) {
1011 _drive_right_speed = speed;
1012 ledcWrite(DRIVE_PWM_RIGHT_CHANNEL, speed);
1037 void CodeRacer::set_leds_left_stop_frwd_right(ledstate leftled, ledstate stopled, ledstate frwdled, ledstate rightled) {
1038 digitalWrite(_led_left_pin, leftled);
1039 digitalWrite(_led_frwd_pin, frwdled);
1040 digitalWrite(_led_right_pin, rightled);
1041 digitalWrite(_led_stop_pin, stopled);
1048 void CodeRacer::set_leds_all(ledstate alleds) {
1049 digitalWrite(_led_left_pin, alleds);
1050 digitalWrite(_led_frwd_pin, alleds);
1051 digitalWrite(_led_right_pin, alleds);
1052 digitalWrite(_led_stop_pin, alleds);
1058 void CodeRacer::set_leds_all_off() {
1059 set_leds_all(LEDOFF);
1065 void CodeRacer::set_leds_all_on() {
1066 set_leds_all(LEDON);
1077 void IRAM_ATTR CodeRacer::_set_button_state() {
1078 if ((millis() - button_last_pressed_at_ms) > BUTTON_BOUNCING_TIME_MS) {
1079 button_last_pressed_at_ms = millis();
1080 coderracer_activ = !coderracer_activ;
1088 void CodeRacer::motor_einstellungen(uint8_t drive_left_speed, uint8_t drive_right_speed,
unsigned long turn_left_for_ms,
unsigned long turn_right_for_ms)
1090 drives_settings(drive_left_speed, drive_right_speed, turn_left_for_ms, turn_right_for_ms);
1093 void CodeRacer::servo_einstellungen(uint8_t pos_center, uint8_t pos_left, uint8_t pos_right, uint8_t sweep_left_pos, uint8_t sweep_right_pos)
1095 servo_settings(pos_center, pos_left, pos_right, sweep_left_pos, sweep_right_pos);
1098 void CodeRacer::servo_rechts()
1100 Serial.println(
"SERVO_RECHTS");
1101 servo_set_to_right();
1104 void CodeRacer::servo_links()
1106 Serial.println(
"SERVO_LINKS");
1107 servo_set_to_left();
1110 void CodeRacer::servo_mitte()
1112 Serial.println(
"SERVO_MITTE");
1113 servo_set_to_center();
1116 void CodeRacer::servo_schwenk()
1121 void CodeRacer::links()
1123 Serial.println(
"CODERACER_LINKS");
1127 void CodeRacer::rechts()
1129 Serial.println(
"CODERACER_RECHTS");
1133 void CodeRacer::anhalten()
1135 Serial.println(
"CODERACER_ANHALTEN");
1139 void CodeRacer::vorwaerts()
1141 Serial.println(
"CODERACER_VORWAERTS");
1145 void CodeRacer::rueckwaerts()
1147 Serial.println(
"CODERACER_RUECKWAERTS");
1151 unsigned long CodeRacer::abstand_messen()
1155 unsigned long distance_cm = 0;
1156 unsigned long min_distance_cm = 1000;
1157 int8_t servo_turn_direction = 0;
1161 if (((
true == _drive) || (servo_center_pos == _servo_position) || _servo_sweep ==
true)) {
1164 min_distance_cm = usonic_measure_cm();
1169 if (servo_left_pos == _servo_position) {
1172 servo_turn_direction = SERVO_SWEEP_TO_RIGHT_STEP;
1174 if (servo_right_pos == _servo_position) {
1177 servo_turn_direction = SERVO_SWEEP_TO_LEFT_STEP;
1181 _servo_set_position(_servo_position + servo_turn_direction);
1184 distance_cm = usonic_measure_cm();
1185 if (distance_cm < min_distance_cm) {
1186 min_distance_cm = distance_cm;
1188 }
while ((_servo_position > H_SERVO_CENTER_LEFT) || (_servo_position < H_SERVO_CENTER_RIGHT));
1191 Serial.print(
"ABSTAND_MESSEN. Der Abstand in cm ist (mindestens):");
1192 Serial.println(min_distance_cm);
1195 return(min_distance_cm);
void drive_forward()
Sets the speed and the directions of both drives so that it will move forward.