OP's code
// Auto mit 9 tracking sensoren
// über SoftSerial Bluetooth COM9 (Ports 11/10 RX, TX) werden Telemetriedaten / Regelparameter ausgetauscht
#include "configuration.h"
#include <Wire.h> // für I2C
#include <SoftwareSerial.h>
// I2C
byte PCF8574_Adr = 0x20;
byte daten = 0; // gelesenes Byte
// Variablen für die Sensoren - Positionsbestimmung
int sensor[10];
float ist_position;
float alt_position;
float soll_position;
float delta;
float delta_integral;
int n;
int drive_mode;
// Variable für Regelung
float Kp = 1.0;
float Ki = 0.0;
float Kd = 0.0;
int v = 100; // Anfangsgeschwindigkeit = 0
int notaus = 0;
int track_id = 1;
// Variablen für den PI Regler
float u;
float msf_r; // Motorspeed r - float wert - wird als int Wert der Motorsteuerung übergeben
float msf_l; // Motorspeed l
//serial comms
char serial_in[50] = "222222 \n";
int serial_index = 0;
String Eingabe;
int t = 0;
SoftwareSerial mySerial(11, 10); // RX, TX
//*** Unterprogramme Motoren
void go_Advance(void) //Forward
{
digitalWrite(dir1PinL, HIGH);
digitalWrite(dir2PinL, LOW);
digitalWrite(dir1PinR, HIGH);
digitalWrite(dir2PinR, LOW);
}
void go_Left(void) //Turn left
{
digitalWrite(dir1PinL, HIGH);
digitalWrite(dir2PinL, LOW);
digitalWrite(dir1PinR, LOW);
digitalWrite(dir2PinR, HIGH);
}
void go_Right(void) //Turn right
{
digitalWrite(dir1PinL, LOW);
digitalWrite(dir2PinL, HIGH);
digitalWrite(dir1PinR, HIGH);
digitalWrite(dir2PinR, LOW);
}
void go_Back(void) //Reverse
{
digitalWrite(dir1PinL, LOW);
digitalWrite(dir2PinL, HIGH);
digitalWrite(dir1PinR, LOW);
digitalWrite(dir2PinR, HIGH);
}
void stop_Stop() //Stop
{
digitalWrite(dir1PinL, LOW);
digitalWrite(dir2PinL, LOW);
digitalWrite(dir1PinR, LOW);
digitalWrite(dir2PinR, LOW);
}
void serial_comms()
{
char incomingByte;
char in;
String parameter;
String telemetrie;
while (mySerial.available() > 0) {
// read the incoming byte:
// Serial.print("I received: ");
in = mySerial.read();
Eingabe += in;
// Serial.println(in,DEC);
if (in == '\n')
{
Serial.print("I received: ");
Serial.println(Eingabe);
// track_id
parameter = split(Eingabe, ',', 0 );
track_id = parameter.toInt();
// v
parameter = split(Eingabe, ',', 1 );
v = parameter.toInt();
//Kp
parameter = split(Eingabe, ',', 2 );
Kp = parameter.toFloat();
//Ki
parameter = split(Eingabe, ',', 3 );
Ki = parameter.toFloat();
//Kd
parameter = split(Eingabe, ',', 4 );
Kd = parameter.toFloat();
//notaus
parameter = split(Eingabe, ',', 5 );
notaus = parameter.toInt();
telemetrie = "";
telemetrie = telemetrie + track_id + "," + v + "," + Kp + "," + Ki + "," + Kd + "," + notaus + "," + ist_position + "," + delta + "," + delta_integral + "," + u + "," + msf_r + "," + msf_l;
mySerial.println(telemetrie);
Eingabe = "";
}
}
}
void serial_comms_alt()
{
String serial_input;
int i, n, l;
int telemetrie;
String zeile;
String output;
String parameter;
// Serial.println("hallo");
// Serial lesen track_id, v, Kp, Ki, Kd, Notaus
while (mySerial.available()) {
serial_input = mySerial.readString();// read the incoming data as string
Serial.println(serial_input);
l = serial_input.length();
n = 0;
for (i = 0; i <= l; i++) {
// Serial.println(serial_input.charAt(i));
if (serial_input.charAt(i) == '\n') {
n = n + 1;
}
}
delta_integral = 0; // ** Integralteil zurücksetzen bei Änderung der Regel-Parameter
Serial.print("*********************************** ");
Serial.println(n);
if (n >= 1) {
zeile = split(serial_input, '\n', n - 1);
Serial.print("Zeile");
Serial.println(zeile);
// track_id
parameter = split(zeile, ',', 0 );
track_id = parameter.toInt();
// v
parameter = split(zeile, ',', 1 );
v = parameter.toInt();
//Kp
parameter = split(zeile, ',', 2 );
Kp = parameter.toFloat();
//Ki
parameter = split(zeile, ',', 3 );
Ki = parameter.toFloat();
//Kd
parameter = split(zeile, ',', 4 );
Kd = parameter.toFloat();
//notaus
parameter = split(zeile, ',', 5 );
notaus = parameter.toInt();
}
}
}
/*set motor speed */
void set_Motorspeed(int speed_L, int speed_R)
{
analogWrite(speedPinL, speed_L);
analogWrite(speedPinR, speed_R);
}
//*** split funktion Input von serieller Schnittstelle
String split(String s, char parser, int index) {
String rs = "";
int parserIndex = index;
int parserCnt = 0;
int rFromIndex = 0, rToIndex = -1;
while (index >= parserCnt) {
rFromIndex = rToIndex + 1;
rToIndex = s.indexOf(parser, rFromIndex);
if (index == parserCnt) {
if (rToIndex == 0 || rToIndex == -1) return "";
return s.substring(rFromIndex, rToIndex);
} else parserCnt++;
}
return rs;
}
//*** Telemetriedaten senden
// track_id, v, Kp, Ki, Kd, Notaus,ist_position, delta, delta_integral, msf_r, msf_l,
void sende_telemetrie()
{
String telemetrie;
telemetrie = "";
telemetrie = telemetrie + track_id + "," + v + "," + Kp + "," + Ki + "," + Kd + "," + notaus + "," + ist_position + "," + delta + "," + delta_integral + "," + u + "," + msf_r + "," + msf_l;
t = t + 1;
if (t > 100)
{
Serial.println(telemetrie);
mySerial.println(telemetrie);
t = 0;
}
}
//*** 9 Trackingsensoren einlesen
void read_sensor_values()
{
sensor[0] = digitalRead(LFSensor_0); // Sensor 0 ist direkt über D9 angschlossen!
Wire.requestFrom(PCF8574_Adr, 1); // Sensor 1-8 über I2C auslesen!
if (Wire.available()) {
daten = Wire.read();
}
if ((daten & 1) == 1) {
sensor[8] = HIGH;
}
else
sensor[8] = LOW;
if ((daten & 2) == 2) {
sensor[7] = HIGH;
}
else
sensor[7] = LOW;
if ((daten & 4) == 4) {
sensor[6] = HIGH;
}
else
sensor[6] = LOW;
if ((daten & 8) == 8) {
sensor[5] = HIGH;
}
else
sensor[5] = LOW;
if ((daten & 16) == 16)
sensor[4] = HIGH;
else
sensor[4] = LOW;
if ((daten & 32) == 32)
sensor[3] = HIGH;
else
sensor[3] = LOW;
if ((daten & 64) == 64)
sensor[1] = HIGH;
else
sensor[1] = LOW;
if ((daten & 128) == 128)
sensor[2] = HIGH;
else
sensor[2] = LOW;
}
// ************************************************* auto tracking **************************************************
void auto_tracking() {
//****** Sensorwerte einlesen
read_sensor_values();
//***** Ist Position aus Sensorwerten bestimmen
n = 0;
ist_position = 0;
if (sensor[0] == HIGH) {
ist_position = ist_position - 120;
n = n + 1;
}
if (sensor[1] == HIGH) {
ist_position = ist_position - 80;
n = n + 1;
}
if (sensor[2] == HIGH) {
ist_position = ist_position - 40;
n = n + 1;
}
if (sensor[3] == HIGH) {
ist_position = ist_position - 20;
n = n + 1;
}
if (sensor[4] == HIGH) {
n = n + 1;
}
if (sensor[5] == HIGH) {
ist_position = ist_position + 20;
n = n + 1;
}
if (sensor[6] == HIGH) {
ist_position = ist_position + 40;
n = n + 1;
}
if (sensor[7] == HIGH) {
ist_position = ist_position + 80;
n = n + 1;
}
if (sensor[8] == HIGH) {
ist_position = ist_position + 120;
n = n + 1;
}
// Fall mehrere Sensoren haben Kontakt zur Linie
if (n > 0) {
ist_position = ist_position / n;
}
// Falls kein Sensor hat Kontakt zur Linie
if (n == 0) {
ist_position = alt_position;
}
// Fall Stop
// if(n>4) {
// stop_Stop();
// delay(10000);
// }
alt_position = ist_position;
//*** PI Regler
delta = soll_position - ist_position;
delta_integral = delta_integral + delta;
u = Kp * delta + Ki * delta_integral;
if ( u < 0 ) // Abweichung nach links / Rechtskurve
{
msf_l = v;
msf_r = v + u;
}
else // Abweichung nach rechts / Linkskurve
{
msf_r = v;
msf_l = v - u;
}
if (msf_r < v / 2) {
msf_r = v / 2;
}
if (msf_l < v / 2) {
msf_l = v / 2;
}
//*** Motor ansteuern
go_Advance();
set_Motorspeed((int) msf_l, (int) msf_r);
}
void setup()
{
// Ports für Motoren konfigurieren
pinMode(speedPinL, OUTPUT); //left motor PWM pin
pinMode(speedPinR, OUTPUT); //rignt motor PWM pin
pinMode(dir1PinL, OUTPUT); //left motor direction pin1
pinMode(dir2PinL, OUTPUT); //left motor direction pin2
pinMode(dir1PinR, OUTPUT); //right motor direction Pin 1
pinMode(dir2PinR, OUTPUT); //right motor direction Pin 2
// Open serial communications and wait for port to open:
Serial.begin(38400);
while (!Serial) {
; // wait for serial port to connect. Needed for Native USB only
}
//Serial.println("Goodnight moon!");
// set the data rate for the SoftwareSerial port
mySerial.begin(9600);
mySerial.println("Hello, world?");
/* I2C communication */
Wire.begin();
/*line follow sensors */
pinMode(LFSensor_0, INPUT);
drive_mode = DRIVE_MODE_LINEFOLLOWER;
}
void loop() // run over and over
{
String test_str = "";
serial_comms();
switch (drive_mode) {
case DRIVE_MODE_LINEFOLLOWER:
auto_tracking();
sende_telemetrie();
break;
case DRIVE_MODE_STOP:
Serial.println(test_str);
break;
default:
break;
}
test_str = "";
test_str.concat(ist_position);
}
@mario123ggggggg, please post configuration.h
Your problem might be caused by the use of the String (capital S) concatenation that you use. I would just print the text instead of first creating a long String and see if it solves the issue. Change sende_telemetrie()
//*** Telemetriedaten senden
// track_id, v, Kp, Ki, Kd, Notaus,ist_position, delta, delta_integral, msf_r, msf_l,
void sende_telemetrie()
{
if (t > 100)
{
Serial.print(track_id);
Serial.print(",");
Serial.print(v);
Serial.print(",");
Serial.print(Kp);
Serial.print(",");
Serial.print(Ki);
Serial.print(",");
Serial.print(Kd);
Serial.print(",");
Serial.print(notaus);
Serial.print(",");
Serial.print(ist_position);
Serial.print(",");
Serial.print(delta);
Serial.print(",");
Serial.print(delta_integral);
Serial.print(",");
Serial.print(u);
Serial.print(",");
Serial.print(msf_r);
Serial.print(",");
Serial.println(msf_l);
// repeat for mySerial
...
...
t = 0;
}
}
Make a similar change in serial_comms.
Further I'm not sure why your code behaves as it does. There are other changes that I would make (get rid of String objects altogether and use a protocol that echoes received characters back over bluetooth to the sender; the sender is not allowed to send the next character before it has received the echo.