Distanzsensoren_auswerten.ino 2.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122
  1. #include <Wire.h>
  2. #include <PPMReader.h>
  3. #include <drivers/PwmOut.h>
  4. //git add -A
  5. //git commit
  6. //git push origin master
  7. // Initialize a PPMReader on digital pin 3 with 6 expected channels.
  8. byte interruptPin = 11;
  9. byte channelAmount = 8;
  10. PPMReader ppm(interruptPin, channelAmount);
  11. #define PIN_TRIGGER 12
  12. #define PIN_ECHO 13
  13. int channel_ID_steering = 1;
  14. int channel_ID_speed = 3;
  15. const int SENSOR_MAX_RANGE = 300; // in cm
  16. unsigned long duration;
  17. unsigned int distance;
  18. class Motor{
  19. int _pina;
  20. int _pinb;
  21. bool _first = true;
  22. float _prev = 0;
  23. mbed::PwmOut* _pwm = NULL;
  24. public:
  25. void Setup(int a, int b)
  26. {
  27. _pina = a;
  28. _pinb = b;
  29. pinMode(_pina, OUTPUT);
  30. pinMode(_pinb, OUTPUT);
  31. }
  32. void SetPower(float pow)
  33. {
  34. if(_first){
  35. _first = false;
  36. _prev = pow;
  37. }
  38. if(_pwm != NULL)
  39. {
  40. delete _pwm;
  41. _pwm = NULL;
  42. }
  43. if(pow < 0)
  44. {
  45. if(_pwm == NULL)
  46. {
  47. _pwm = new mbed::PwmOut(digitalPinToPinName(_pinb));
  48. _pwm->period_ms(2); //500Hz
  49. }
  50. digitalWrite(_pina,0);
  51. _pwm->write(-pow);
  52. }
  53. else
  54. {
  55. if(_pwm == NULL)
  56. {
  57. _pwm = new mbed::PwmOut(digitalPinToPinName(_pina));
  58. _pwm->period_ms(2); //500Hz
  59. }
  60. digitalWrite(_pinb,0);
  61. _pwm->write(pow);
  62. }
  63. }
  64. }; // ; am Ende einer Klasse
  65. Motor motor_fl;
  66. Motor motor_fr;
  67. Motor motor_rl;
  68. Motor motor_rr;
  69. void setup() {
  70. Serial.begin(9600);
  71. motor_fl.Setup(2, 3);
  72. motor_fr.Setup(9, 8);
  73. motor_rl.Setup(5, 4);
  74. motor_rr.Setup(6, 7);
  75. Wire.begin(); // join i2c bus (address optional for master)
  76. pinMode(A4, INPUT_PULLUP);
  77. pinMode(A5, INPUT_PULLUP);
  78. }
  79. void loop() {
  80. int steering_value_raw = ppm.latestValidChannelValue(channel_ID_steering, 0);
  81. int speed_value_raw = ppm.latestValidChannelValue(channel_ID_speed, 0);
  82. float steering_value = (steering_value_raw == 0)? 1 : (1/500.0f) * steering_value_raw - 3; // == Bedingung, danach wenn True: wenn False
  83. float speed_value = (speed_value_raw == 0)? 1 : (1/500.0f) * speed_value_raw - 3;
  84. if (steering_value < -1)
  85. steering_value = -1;
  86. else if (steering_value > 1)
  87. steering_value = 1;
  88. float motor_right = (-steering_value + speed_value);
  89. float motor_left = (steering_value + speed_value);
  90. float factor = max (abs(motor_right), abs(motor_left));
  91. if (factor > 1) {
  92. motor_right = motor_right / factor;
  93. motor_left = motor_left / factor;
  94. }
  95. delay(20);
  96. motor_rr.SetPower(motor_right);
  97. motor_rl.SetPower(motor_left);
  98. motor_fr.SetPower(motor_right);
  99. motor_fl.SetPower(motor_left);
  100. Serial.println(String(motor_left) + "\t" + String(motor_right));
  101. //while(true);
  102. }