Arduino {code}racer API
... better know the details.
CodeRacer.cpp
1 // the compiler switch for an ESP8266 is looking like this: #elif defined(ARDUINO_ARCH_ESP8266)
2 #include "CodeRacer.h"
3 
7 CodeRacer::CodeRacer()
8 {
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;
23 }
24 
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
47 )
48 {
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;
63 }
64 
68 void CodeRacer::begin() {
69 
70  // init of variables and objects
71 
72  _servo_dummy = new Servo(); // the dummy is needed so far to avoid conflicts with analog write
73  _servo = 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;
83 
84  _drive_left_speed = H_DRIVE_LEFT_SPEED;
85  _drive_right_speed = H_DRIVE_RIGHT_SPEED;
86 
87  _turn_left_for_ms = H_RACER_TURN_LEFT_FOR_MS;
88  _turn_right_for_ms = H_RACER_TURN_RIGHT_FOR_MS;
89 
90  coderracer_activ = false;
91  _coderracer_activ = true;
92  _drive = false;
93  _drive_set_at_ms = millis();
94  _servo_sweep = false;
95 
96  _last_led_switched_at_ms = millis();
97  _last_led_on = 0;
98  _led_count = 3;
99 
100  _servo_look_around_at_ms = millis() + random(FUN_MIN_PAUSE_MS, FUN_MAX_PAUSE_MS);
101 
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;
105 
106  // Ultrasonic sensor
107  pinMode(_us_trigger_pin, OUTPUT);
108  pinMode(_us_echo_pin, INPUT);
109 
110  // Servo drive
111  _servo->attach(_servo_pin);
112 
113  // Left drive
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); // channel , 50 Hz, 8-bit width
118  ledcAttachPin(_drive_left_enable_pin, DRIVE_PWM_LEFT_CHANNEL); // connect left drive enable with PWM channel
119 
120  // Right drive
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); // channel , 50 Hz, 8-bit width
125  ledcAttachPin(_drive_right_enable_pin, DRIVE_PWM_RIGHT_CHANNEL); // connect right drive enable pin with PWM channel
126 
127  // LEDs
128  pinMode(_led_frwd_pin, OUTPUT);
129  pinMode(_led_stop_pin, OUTPUT);
130  pinMode(_led_left_pin, OUTPUT);
131  pinMode(_led_right_pin, OUTPUT);
132  // all LEDS off
133  set_leds_all_off();
134 
135  // Button & -interrupt
136  button_last_pressed_at_ms = 0;
137  pinMode(_button_pin, INPUT_PULLUP);
138  attachInterrupt(digitalPinToInterrupt(_button_pin), _set_button_state, FALLING);
139 
140  // Random
141  randomSeed(analogRead(0));
142 
143  //fun stuff
144  coderacer_fun_enabled = false;
145 
146 }
147 
148 //**************************************
149 //*** Coderacer hihger level methods ***
150 //**************************************
161 void CodeRacer::stop_driving() {
162  _servo_sweep = false;
163  _drive = false;
164  set_drives_stop_left_right();
165  set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF);
166 }
167 
173 void CodeRacer::drive_forward()
174 {
175  drive_forward(_drive_left_speed, _drive_right_speed);
176 }
177 
185 void CodeRacer::drive_forward(uint8_t left_speed, uint8_t right_speed)
186 {
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);
190  _drive = true;
191  _drive_set_at_ms = millis();
192 }
193 
199 void CodeRacer::drive_backward()
200 {
201  drive_backward(_drive_left_speed, _drive_right_speed);
202 }
203 
211 void CodeRacer::drive_backward(uint8_t left_speed, uint8_t right_speed)
212 {
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);
216  _drive = true;
217  _drive_set_at_ms = millis();
218 }
219 
226 void CodeRacer::turn_left()
227 {
228  turn_left(_turn_left_for_ms, _drive_left_speed, _drive_right_speed);
229 }
230 
237 void CodeRacer::turn_left(unsigned long turn_for_ms)
238 {
239  turn_left(turn_for_ms, _drive_left_speed, _drive_right_speed);
240 }
241 
250 void CodeRacer::turn_left(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed)
251 {
252  _drive = false;
253  set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF); // LEDs setzen
254  set_drives_states_left_right(DRIVEBACK, DRIVEFRWD);
255  set_drives_speed_left_right(left_speed, right_speed);
256  // wait set delay for the timed turn
257  _turn_left_for_ms = turn_for_ms;
258  delay(_turn_left_for_ms);
259  // stop drives again
260  set_drives_stop_left_right();
261 }
262 
269 void CodeRacer::turn_right()
270 {
271  turn_right(_turn_right_for_ms, _drive_left_speed, _drive_right_speed);
272 }
273 
280 void CodeRacer::turn_right(unsigned long turn_for_ms)
281 {
282  turn_right(turn_for_ms, _drive_left_speed, _drive_right_speed);
283 }
284 
293 void CodeRacer::turn_right(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed)
294 {
295  _drive = false;
296  set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON); // LEDs setzen
297  set_drives_states_left_right(DRIVEFRWD, DRIVEBACK);
298  set_drives_speed_left_right(left_speed, right_speed);
299  // wait set delay for the timed turn
300  _turn_right_for_ms = turn_for_ms;
301  delay(_turn_right_for_ms);
302  // stop drives again
303  set_drives_stop_left_right();
304 }
305 
314 void CodeRacer::start_stop_at_min_distance() {
315  start_stop_at_min_distance(_usonic_stop_distance_cm);
316 }
317 
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;
329  }
330 }
331 
335 void CodeRacer::stop_stop_at_min_distance() {
336  _coderacer_stop_at_distance_enabled = false;
337 }
338 
348 bool CodeRacer::start_stop() {
349  if (_coderracer_activ != coderracer_activ) {
350  _coderracer_activ = coderracer_activ;
351  if (true == _coderracer_activ) {
352  set_leds_all_off();
353  delay(500);
354  }
355  else {
356  stop_driving();
357  set_leds_all_on();
358  delay(200);
359  servo_set_to_center();
360  _servo_look_around_at_ms = millis() + random(20000, 120000);
361  }
362  }
363 
364  if ((false == _coderracer_activ) && (true == coderacer_fun_enabled)) {
365  kitt();
366  look_around();
367  }
368 
369  return(_coderracer_activ);
370 }
371  // end of group higherlevelmeths
380 bool CodeRacer::stopped_at_min_distance() {
381  return(_coderacer_stopped_at_min_distance);
382 }
383 
387 bool CodeRacer::is_driving() {
388  return(_drive);
389 }
390 
394 unsigned long CodeRacer::turn_left_for_ms() {
395  return(_turn_left_for_ms);
396 }
397 
401 unsigned long CodeRacer::turn_right_for_ms() {
402  return(_turn_right_for_ms);
403 }
404 
408 void CodeRacer::set_inactive() {
409  coderracer_activ = false;
410 }
411 
415 void CodeRacer::set_active() {
416  coderracer_activ = true;
417 }
418 
424 bool CodeRacer::is_active() {
425  return(coderracer_activ);
426 }
427  // end of group higherlevelgetters // end of group higherlevel
430 
431 //**************************************
432 //*** Just for fun ***
433 //**************************************
440 void CodeRacer::look_around()
441 {
442  if (_servo_look_around_at_ms < millis()) {
443  _servo_look_around_at_ms = millis() + random(FUN_MIN_PAUSE_MS, FUN_MAX_PAUSE_MS);
444  servo_set_to_left();
445  delay(500);
446  servo_set_to_right();
447  delay(800);
448  servo_set_to_center();
449  delay(300);
450  servo_set_to_left();
451  delay(100);
452  servo_set_to_center();
453  }
454 }
455 
459 void CodeRacer::kitt()
460 {
461  if (millis() - _last_led_switched_at_ms > LED_SWITCH_MS) {
462  _last_led_switched_at_ms = millis();
463  if (_last_led_on >= 5) {
464  _led_count = -1;
465  }
466  else if (_last_led_on <= 0) {
467  _led_count = 1;
468  }
469  _last_led_on = _last_led_on + _led_count;
470  switch (_last_led_on) {
471  case 0:
472  set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF);
473  break;
474  case 1:
475  set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF);
476  break;
477  case 2:
478  set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF);
479  break;
480  case 3:
481  set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF);
482  break;
483  case 4:
484  case 5:
485  set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON);
486  break;
487  }
488  }
489 }
490  // end of group lowerlevelfun
492 
493 //**************************************
494 //*** Servo drive lower level control ***
495 //**************************************
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)
511 {
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;
517 }
518 
526 void CodeRacer::servo_sweep()
527 {
528  uint8_t position;
529  _servo_sweep = true;
530  if (millis() - _servo_position_set_at_ms > SERVO_SWEEP_MS) {
531  position = _servo_position + _servo_sweep_step;
532  //sprintf(_debugmsg,"[%s] current position=%ld newpostion=%ld", __func__, _servo_position, position);
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;
536  }
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;
540  }
541  _servo_set_position(position);
542  }
543 }
544 
548 void CodeRacer::servo_set_to_right()
549 {
550  servo_set_position_wait(servo_right_pos);
551 }
552 
556 void CodeRacer::servo_set_to_left()
557 {
558  servo_set_position_wait(servo_left_pos);
559 }
560 
564 void CodeRacer::servo_set_to_center()
565 {
566  servo_set_position_wait(servo_center_pos);
567 }
568 
575 uint8_t CodeRacer::servo_set_position_wait(uint8_t position)
576 {
577  _servo_sweep = false;
578  unsigned long wait_time_ms = _servo_set_position(position);
579  delay(wait_time_ms);
580  return(_servo_position);
581 }
582 
589 unsigned long CodeRacer::servo_set_position(uint8_t position)
590 {
591  _servo_sweep = false;
592  unsigned long wait_time_ms = _servo_set_position(position);
593  return(wait_time_ms);
594 }
595 
596 unsigned long CodeRacer::_servo_set_position(uint8_t position)
597 {
598  uint8_t _position = position;
599  uint8_t absdiff;
600 
601  if (position < SERVO_MIN_POSITION) {
602  _position = SERVO_MIN_POSITION;
603  }
604  else if (position > SERVO_MAX_POSITION) {
605  _position = SERVO_MAX_POSITION;
606  }
607  _servo->write(_position);
608  // wait minimal delay to avoid code collaps
609  delay(SERVO_SET_1TICK_POSITION_DELAY_MS);
610  absdiff = abs(_servo_position - _position);
611  if (absdiff > 1) {
612  _servo_position_eta_in_ms = absdiff * SERVO_SET_1TICK_POSITION_DELAY_MS;
613  }
614  else {
615  _servo_position_eta_in_ms = 0;
616  }
617 
618  _servo_position_set_at_ms = millis();
619  _servo_position = _position;
620 
621  return(_servo_position_eta_in_ms);
622 }
623  // end of group lowerlevelservomeths
632 uint8_t CodeRacer::servo_position() {
633  return(_servo_position);
634 }
635 
639 unsigned long CodeRacer::servo_position_set_at_ms() {
640  return(_servo_position_set_at_ms);
641 }
642 
649 unsigned long CodeRacer::servo_position_eta_in_ms() {
650  return(_servo_position_eta_in_ms);
651 }
652  // end of group lowerlevelservogetters // end of group lowerlevelservo
655 
656 
657 //**************************************
658 //*** Ultrasonic lower level control ***
659 //**************************************
672 unsigned long CodeRacer::usonic_measure_cm()
673 {
674  return(usonic_measure_cm(US_MAX_ECHO_TIME_US));
675 }
676 
682 unsigned long CodeRacer::usonic_measure_us()
683  {
684  return(usonic_measure_us(US_MAX_ECHO_TIME_US));
685  }
686 
694 unsigned long CodeRacer::usonic_measure_cm(unsigned long max_echo_run_time_us)
695 {
696  unsigned long echo_runtime_us = usonic_measure_us(max_echo_run_time_us);
697  unsigned long distance_cm = echo_runtime_us * 0.0172;
698  //Serial.print("MEASURE_DISTANCE. Distance in cm is: ");
699  //Serial.println(distance_cm);
700  _usonic_distance_cm = distance_cm;
701  return(distance_cm);
702 }
703 
711 unsigned long CodeRacer::usonic_measure_us(unsigned long max_echo_run_time_us)
712 {
713  unsigned long echo_runtime_us[3] = { 0,0,0 };
714  uint8_t measnr = 0;
715 
716  do {
717  echo_runtime_us[measnr] = usonic_measure_single_shot_us(max_echo_run_time_us);
718  if (echo_runtime_us[measnr] > 200) {
719  measnr++;
720  }
721  } while (measnr < 3);
722 
723  // we will take the medium out of 3 values ...
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]); }
727 
728  //Serial.print("MEASURE_DISTANCE_US. Echo runtime in us is: ");
729  //Serial.println(echo_runtime_us[1]);
730 
731  // if the stop at minimal distance is enabeled - check for minimal distance is reached
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;
735  stop_driving();
736  _coderacer_stop_at_distance_enabled = false;
737  }
738  }
739  _usonic_distance_us = echo_runtime_us[1];
740  return(echo_runtime_us[1]);
741 }
742 
748 unsigned long CodeRacer::usonic_measure_single_shot_cm()
749 {
750  return(usonic_measure_single_shot_cm(US_MAX_ECHO_TIME_US));
751 }
752 
758 unsigned long CodeRacer::usonic_measure_single_shot_us()
759 {
760  return(usonic_measure_single_shot_us(US_MAX_ECHO_TIME_US));
761 }
762 
770 unsigned long CodeRacer::usonic_measure_single_shot_cm(unsigned long max_echo_run_time_us)
771 {
772  // convert into cm ... 344m/sec is the speed of noise - thus 34400cm/sec ... or 34,400cm/milisec ... or 0,0344cm/microsec
773  // the echo has to go the distance twice - forth and back - so the duration has to be the half of the measured one
774  // distance_cm = echo_duration/2 * 0,0344 or distance_cm = echo_duration/2 / 29,1 or distance_cm = echo_duration * 0,0172
775  // distance_cm = (echo_duration/2) / 29.1;
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;
778  //Serial.print("MEASURE_DISTANCE. Distance in cm is: ");
779  //Serial.println(distance_cm);
780  _usonic_distance_cm = distance_cm;
781  return(distance_cm);
782 }
783 
791 unsigned long CodeRacer::usonic_measure_single_shot_us(unsigned long max_echo_run_time_us)
792  {
793  unsigned long echo_runtime_us;
794  // start measurement - send a short pulse "HIGH" to the TRIG pin of the ultrasonic sensor
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);
802  // measure runtime in microseconds until the ECHO pin aof the sensor goes HIGH
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; // US_MAX_ECHO_TIME_US;
806  }
807  //Serial.print("MEASURE_DISTANCE_US. Echo runtime in us is: ");
808  //Serial.println(echo_runtime_us);
809  _usonic_distance_us = echo_runtime_us;
810  return(echo_runtime_us);
811  }
812  // end of group lowerlevelusmethods
825 void CodeRacer::usonic_set_stop_distance_cm(unsigned long stop_distance_cm)
826 {
827  _usonic_stop_distance_us = stop_distance_cm * 58.14;
828 }
829 
837 void CodeRacer::usonic_set_stop_distance_us(unsigned long stop_distance_us)
838 {
839  _usonic_stop_distance_us = stop_distance_us;
840 }
841 
845 unsigned long CodeRacer::usonic_distance_us() {
846  return(_usonic_distance_us);
847 }
848 
852 unsigned long CodeRacer::usonic_distance_cm() {
853  return(_usonic_distance_cm);
854 }
855  // end of group lowerlevelusgetters // end of group lowerlevelus
858 
859 
860 //**************************************
861 //*** Drives lower level control ***
862 //**************************************
863 
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)
879 {
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;
884 }
885 
889 void CodeRacer::set_drives_stop_left_right() {
890  set_drive_left_state(DRIVESTOP);
891  set_drive_right_state(DRIVESTOP);
892 }
893 
899 void CodeRacer::set_drives_states_left_right(drivestate stateleft, drivestate stateright) {
900  set_drive_left_state(stateleft);
901  set_drive_right_state(stateright);
902 }
903 
908 void CodeRacer::set_drive_left_state(drivestate state) {
909  set_drive_state(state, _drive_left_frwd_pin, _drive_left_back_pin);
910 }
911 
916 void CodeRacer::set_drive_right_state(drivestate state) {
917  set_drive_state(state, _drive_right_frwd_pin, _drive_right_back_pin);
918 }
919 
926 void CodeRacer::set_drive_state(drivestate state, uint8_t frwdpin, uint8_t backpin) {
927  switch (state) {
928  case DRIVESTOP:
929  digitalWrite(frwdpin, LOW);
930  digitalWrite(backpin, LOW);
931  break;
932  case DRIVEFRWD:
933  digitalWrite(frwdpin, HIGH);
934  digitalWrite(backpin, LOW);
935  break;
936  case DRIVEBACK:
937  digitalWrite(frwdpin, LOW);
938  digitalWrite(backpin, HIGH);
939  break;
940  }
941 }
942 
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);
953 }
954 
961 void CodeRacer::set_drive_left_speed(uint8_t speed) {
962  set_drive_speed(speed, _drive_left_enable_pin);
963 }
964 
971 void CodeRacer::set_drive_right_speed(uint8_t speed) {
972  set_drive_speed(speed, _drive_right_enable_pin);
973 }
974 
982 void CodeRacer::set_drive_speed(uint8_t speed, uint8_t enablepin) {
983  _analog_write(enablepin, (int)speed);
984 }
985  // end of group lowerleveldrivesmethods
994 uint8_t CodeRacer::drive_right_speed() {
995  return _drive_right_speed;
996 }
997 
1001 uint8_t CodeRacer::drive_left_speed() {
1002  return(_drive_left_speed);
1003 }
1004 
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);
1009  }
1010  if (pin == _drive_right_enable_pin) {
1011  _drive_right_speed = speed;
1012  ledcWrite(DRIVE_PWM_RIGHT_CHANNEL, speed);
1013  }
1014 }
1015  // end of group lowerleveldrivesgetters // end of group lowerleveldrives
1018 
1019 
1020 //**************************************
1021 //*** LED lower level control ***
1022 //**************************************
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);
1042 }
1043 
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);
1053 }
1054 
1058 void CodeRacer::set_leds_all_off() {
1059  set_leds_all(LEDOFF);
1060 }
1061 
1065 void CodeRacer::set_leds_all_on() {
1066  set_leds_all(LEDON);
1067 }
1068  // end of group lowerlevelledmets // end of group lowerlevelled
1071 
1072 
1073 //**************************************
1074 //*** ISRs ***
1075 //**************************************
1076 //IRAM_ATTR is used to load the code into DRAM and not to Flash to make it faster - required for ISRs
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(); // simplest debouncing - just wait ;-)
1080  coderracer_activ = !coderracer_activ;
1081  }
1082 }
1083 
1084 
1085 //**********************************************************************************************************************
1086 //** Methods below this are obsolete and only in here for compatiblity to other projects - do not use them anymore !!!
1087 //**********************************************************************************************************************
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)
1089 {
1090  drives_settings(drive_left_speed, drive_right_speed, turn_left_for_ms, turn_right_for_ms);
1091 }
1092 
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)
1094 {
1095  servo_settings(pos_center, pos_left, pos_right, sweep_left_pos, sweep_right_pos);
1096 }
1097 
1098 void CodeRacer::servo_rechts()
1099 {
1100  Serial.println("SERVO_RECHTS"); // Meldung am Monitor ausgeben
1101  servo_set_to_right(); // Servo auf den Winkel rechts drehen
1102 }
1103 
1104 void CodeRacer::servo_links()
1105 {
1106  Serial.println("SERVO_LINKS"); // Meldung am Monitor ausgeben
1107  servo_set_to_left(); // Servo auf den Winkel links drehen
1108 }
1109 
1110 void CodeRacer::servo_mitte()
1111 {
1112  Serial.println("SERVO_MITTE");
1113  servo_set_to_center();
1114 }
1115 
1116 void CodeRacer::servo_schwenk()
1117 {
1118  servo_sweep();
1119 }
1120 
1121 void CodeRacer::links()
1122 {
1123  Serial.println("CODERACER_LINKS");
1124  turn_left();
1125 }
1126 
1127 void CodeRacer::rechts()
1128 {
1129  Serial.println("CODERACER_RECHTS");
1130  turn_right();
1131 }
1132 
1133 void CodeRacer::anhalten()
1134 {
1135  Serial.println("CODERACER_ANHALTEN");
1136  stop_driving();
1137 }
1138 
1139 void CodeRacer::vorwaerts()
1140 {
1141  Serial.println("CODERACER_VORWAERTS");
1142  drive_forward();
1143 }
1144 
1145 void CodeRacer::rueckwaerts()
1146 {
1147  Serial.println("CODERACER_RUECKWAERTS");
1148  drive_backward();
1149 }
1150 
1151 unsigned long CodeRacer::abstand_messen()
1152 {
1153  return(0);
1154 
1155  unsigned long distance_cm = 0;
1156  unsigned long min_distance_cm = 1000;
1157  int8_t servo_turn_direction = 0;
1158 
1159 
1160  // while driving or sweeping there will be only one value be measured - else there will be mutiple measurements and the servor will be turning
1161  if (((true == _drive) || (servo_center_pos == _servo_position) || _servo_sweep == true)) {
1162  // while driving ...
1163  //Serial.println("ABSTAND_MESSEN im fahren, direkt nach vorn oder Schwenk() ist aktiv ...");
1164  min_distance_cm = usonic_measure_cm();
1165  } else {
1166  // no sweep, not driving ...
1167  //Serial.println("ABSTAND_MESSEN im Stand nach links oder rechts...");
1168  // are we already ath left or right with the servo ?
1169  if (servo_left_pos == _servo_position) {
1170  //Serial.println("ABSTAND_MESSEN. Linke Seite.");
1171  //left ...
1172  servo_turn_direction = SERVO_SWEEP_TO_RIGHT_STEP;
1173  }
1174  if (servo_right_pos == _servo_position) {
1175  //right ...
1176  //Serial.println("ABSTAND_MESSEN rechte Seite.");
1177  servo_turn_direction = SERVO_SWEEP_TO_LEFT_STEP;
1178  }
1179  // trun the servo and do measuring ... remember the smallest value
1180  do {
1181  _servo_set_position(_servo_position + servo_turn_direction);
1182  //Serial.print("ABSTAND_MESSEN. Servo position:");
1183  //Serial.println(_servo_position);
1184  distance_cm = usonic_measure_cm();
1185  if (distance_cm < min_distance_cm) {
1186  min_distance_cm = distance_cm;
1187  }
1188  } while ((_servo_position > H_SERVO_CENTER_LEFT) || (_servo_position < H_SERVO_CENTER_RIGHT));
1189  }
1190 
1191  Serial.print("ABSTAND_MESSEN. Der Abstand in cm ist (mindestens):");
1192  Serial.println(min_distance_cm);
1193  //_min_distance_cm = min_distance_cm;
1194 
1195  return(min_distance_cm);
1196 
1197 }
1198 
1199 //**********************************************************************************************************************
1200 //** Helper methods
1201 //**********************************************************************************************************************
1202 
void drive_forward()
Sets the speed and the directions of both drives so that it will move forward.
Definition: CodeRacer.cpp:173