String sharing between M7 cores and M4 cores

Hi,
as can be seen from the title I have to send a string containing ~ 1000 characters from the M7 core to the M4 core, I am using the RPC.print() function which works for a limited number of characters.
Below are the two sketches.
Sketch for m7:

#include <RPC.h>
void setup() {

  RPC.begin();
  Serial.begin(9600);
}

void loop() {


  if (Serial.available() > 0) {
    String bt = Serial.readStringUntil('!');
    if (bt.length() > 0) {
      if (bt.substring(bt.indexOf(";"), 0) == "check" || bt.substring(bt.indexOf(";"), 0) == "posizione") {
        RPC.print(bt);
      }
    }
  }

  if (RPC.available() > 0) {
    String buffer = RPC.readStringUntil('!');
    Serial.print(buffer);
  }
}

Sketch for m4:

#include <RPC.h>

void setup() {

  RPC.begin();
  Serial.begin(9600);
}

void loop() {
  if (RPC.available() > 0) {

    String usb = RPC.readStringUntil('!');

    RPC.print(usb);
  }
}

I also tried sending the characters individually but when I go to recompose them there is data missing and not in order because there is no logic that regulates everything.

I honestly don't know if this is the best solution for sharing information from one core to another so I ask you if you could give me a hand.

In addition I would like the exchange to take place as quickly as possible.

Thanks!

I would use SDRAM space to achieve this. DATA_FRAME_SEND and DATA_FRAME_RETURN are just structs. My solution below takes only a few clock cycles to send data back and fourth.

#include "SDRAM.h"

const uint32_t SDRAM_START_ADDRESS_4 = ((uint32_t)0x38000000);  //USING THE AHB SRAM4 DOMAIN SPACE
const uint32_t SDRAM_ALLOCATION_PROTECTED_BUFFER_SIZE = 10000;  //for my own use, malloc will allocate after the size of this variable, increase if we need more than 10KB for core to core variables

//Pointers to memory locations
byte *send_frame_ready_flag = (byte *)SDRAM_START_ADDRESS_4;
byte *return_frame_ready_flag = (byte *)SDRAM_START_ADDRESS_4 + sizeof(byte);
DATA_FRAME_SEND *data_frame_send_sdram = (DATA_FRAME_SEND *)SDRAM_START_ADDRESS_4 + (2 * sizeof(byte));
DATA_FRAME_RETURN *data_frame_return_sdram = (DATA_FRAME_RETURN *)SDRAM_START_ADDRESS_4 + (2 * sizeof(byte) + sizeof(DATA_FRAME_SEND)); 

//Somewhere in M7 setup->
SDRAM.begin(SDRAM_START_ADDRESS_4 + SDRAM_ALLOCATION_PROTECTED_BUFFER_SIZE);  

//SOMEWHERE IN M7
void sendDataToM4() {
  if (*send_frame_ready_flag == 0) {
    DATA_FRAME_SEND dataForM4;
    dataForM4.drone_settings = drone_settings;
    dataForM4.imu_data = imu_data;
    dataForM4.altitude_data = altitude_data;
    dataForM4.altitude_control_data = altitude_control_data;
    dataForM4.receiver_data = receiver_data;
    dataForM4.power_management_data = power_management_data;
    dataForM4.compass_data = compass_data;
    dataForM4.temperature_data = temperature_data;
    dataForM4.gps_data = gps_data;
    dataForM4.gps_status_data = gps_status_data;
    *data_frame_send_sdram = dataForM4;
    *send_frame_ready_flag = 1;
  }
}

void receiveDataFromM4() {
  if (*return_frame_ready_flag == 1) {  //1 indicates it can read
    DATA_FRAME_RETURN dataFromM4 = *data_frame_return_sdram;
    telemetry.printTelemetry(String(dataFromM4.debugStringData));
    *return_frame_ready_flag = 0;  //0 indicates data has been read
  }
}

//SOMEWHERE IN M4
void receiveDataFromM7() {
  if (*send_frame_ready_flag == 1) {  //data is available from M7
    DATA_FRAME_SEND dataFromM7 = *data_frame_send_sdram;
    drone_settings = dataFromM7.drone_settings;
    imu_data = dataFromM7.imu_data;
    altitude_data = dataFromM7.altitude_data;
    altitude_control_data = dataFromM7.altitude_control_data;
    receiver_data = dataFromM7.receiver_data;
    power_management_data = dataFromM7.power_management_data;
    compass_data = dataFromM7.compass_data;
    temperature_data = dataFromM7.temperature_data;
    gps_data = dataFromM7.gps_data;
    gps_status_data = dataFromM7.gps_status_data;
    *send_frame_ready_flag = 0;  //set to zero to let M7 know data has been read
  }
}

void sendDataToM7(String debugStringData, bool blocking) {
  do {
    if (*return_frame_ready_flag == 0) {  //if 0 can send data
      DATA_FRAME_RETURN dataForM7;
      debugStringData.toCharArray(dataForM7.debugStringData, sizeof(dataForM7.debugStringData));
      *data_frame_return_sdram = dataForM7;
      *return_frame_ready_flag = 1;  //1 lets m7 know it can read data
      return;                        //break out of do->while loop
    } else if (blocking) {
      delayMicroseconds(5);  //hang out and try again, in a little bit
    }
  } while (blocking);
}
1 Like

I'm trying to implement this and running into a error on setting up SDRAM:

D:\Users\Merli\Documents\Arduino\M7_data_receive_M4\M7_data_receive_M4.ino:12:1: error: 'DATA_FRAME_SEND' does not name a type
 DATA_FRAME_SEND *data_frame_send_sdram = (DATA_FRAME_SEND *)SDRAM_START_ADDRESS_4 + (2 * sizeof(byte));
 ^~~~~~~~~~~~~~~
D:\Users\Merli\Documents\Arduino\M7_data_receive_M4\M7_data_receive_M4.ino:13:1: error: 'DATA_FRAME_RETURN' does not name a type
 DATA_FRAME_RETURN *data_frame_return_sdram = (DATA_FRAME_RETURN *)SDRAM_START_ADDRESS_4 + (2 * sizeof(byte) + sizeof(DATA_FRAME_SEND));
 ^~~~~~~~~~~~~~~~~

Any ideas? even if I put a #define in front of it I just get another error later on about data_frame_return_sdram

Thanks
Mike

dude, you just quoted me as saying DATA_FRAME_SEND and DATA_FRAME_RETURN are just regular structs in c++, I created them. You can use any struct of your own design and it wont have any issues compiling. In case you dont know the syntax of a struct here is an example:

struct GPS_STATUS_DATA {
  bool POSITION_DATA_SAFE = false;
  bool ALTITUDE_DATA_SAFE = false;
  bool HEADING_SAFE = false;
  bool SYNCED_WITH_SATELITES = false;
  bool RTK_FIX = false;
} __attribute__((aligned(8)));

These are my exact structs from my program: first is a struct of more structs, the second is just holding a debug string for sending stuff back from M4, replace variables with anything you want:

struct DATA_FRAME_SEND {
  DRONE_SETTINGS drone_settings;
  IMU_DATA imu_data;
  ALTITUDE_DATA altitude_data;
  ALTITUDE_CONTROL_DATA altitude_control_data;
  RECEIVER_DATA receiver_data;
  POWER_MANAGEMENT_DATA power_management_data;
  TEMPERATURE_DATA temperature_data;
  GPS_DATA gps_data;
  GPS_STATUS_DATA gps_status_data;
  NAVIGATION_DATA navigation_data;
  HEADING_CONTROL_DATA heading_control_data;
  STEPPER_MOTOR_DATA stepper_motor_data;
  SAFETY_DATA safety_data;
} __attribute__((aligned(8)));

struct DATA_FRAME_RETURN {
  char debugStringData[100];
} __attribute__((aligned(8)));

struct SEND_FRAME_READY_FLAG {
  volatile bool frame_ready = false;
} __attribute__((aligned(8)));

struct RETURN_FRAME_READY_FLAG {
  volatile bool frame_ready = false;
} __attribute__((aligned(8)));

Also here is a slight revision to my previous code to make the memory more aligned and performant, again anything in caps is a struct:

const uint32_t SDRAM_START_ADDRESS_4 = ((uint32_t)0x38000000);  //USING THE AHB SRAM4 DOMAIN SPACE
volatile uint32_t *sdramMemory = (uint32_t*)0x38000000;

SEND_FRAME_READY_FLAG* send_frame_ready_sdram = (SEND_FRAME_READY_FLAG*)(sdramMemory);
RETURN_FRAME_READY_FLAG* return_frame_ready_sdram = (RETURN_FRAME_READY_FLAG*)(sdramMemory + sizeof(SEND_FRAME_READY_FLAG) / sizeof(uint32_t));
DATA_FRAME_SEND* data_frame_send_sdram = (DATA_FRAME_SEND*)(sdramMemory + (sizeof(SEND_FRAME_READY_FLAG) + sizeof(RETURN_FRAME_READY_FLAG)) / sizeof(uint32_t));
DATA_FRAME_RETURN* data_frame_return_sdram = (DATA_FRAME_RETURN*)(sdramMemory + (sizeof(SEND_FRAME_READY_FLAG) + sizeof(RETURN_FRAME_READY_FLAG) + sizeof(DATA_FRAME_SEND)) / sizeof(uint32_t));

//Somewhere in M7 setup->
SDRAM.begin(SDRAM_START_ADDRESS_4);

//M7

void sendDataToM4() {
  if (!send_frame_ready_sdram->frame_ready) { //if false it can be written to
    DATA_FRAME_SEND dataForM4;
    memcpy(&dataForM4.drone_settings, &drone_settings, sizeof(struct DRONE_SETTINGS));
    memcpy(&dataForM4.imu_data, &imu_data, sizeof(struct IMU_DATA));
    memcpy(&dataForM4.altitude_data, &altitude_data, sizeof(struct ALTITUDE_DATA));
    memcpy(&dataForM4.altitude_control_data, &altitude_control_data, sizeof(struct ALTITUDE_CONTROL_DATA));
    memcpy(&dataForM4.receiver_data, &receiver_data, sizeof(struct RECEIVER_DATA));
    memcpy(&dataForM4.power_management_data, &power_management_data, sizeof(struct POWER_MANAGEMENT_DATA));
    memcpy(&dataForM4.temperature_data, &temperature_data, sizeof(struct TEMPERATURE_DATA));
    memcpy(&dataForM4.gps_data, &gps_data, sizeof(struct GPS_DATA));
    memcpy(&dataForM4.gps_status_data, &gps_status_data, sizeof(struct GPS_STATUS_DATA));
    memcpy(&dataForM4.navigation_data, &navigation_data, sizeof(struct NAVIGATION_DATA));
    memcpy(&dataForM4.heading_control_data, &heading_control_data, sizeof(struct HEADING_CONTROL_DATA));
    memcpy(&dataForM4.stepper_motor_data, &stepper_motor_data, sizeof(struct STEPPER_MOTOR_DATA));
    memcpy(&dataForM4.safety_data, &safety_data, sizeof(struct SAFETY_DATA));
    *data_frame_send_sdram = dataForM4;
    send_frame_ready_sdram->frame_ready = true; //if true M4 can read from it
  }
}

void receiveDataFromM4() {
  if (return_frame_ready_sdram->frame_ready) {  //true indicates it can read by M7
    DATA_FRAME_RETURN dataFromM4 = *data_frame_return_sdram;
    telemetry.printTelemetry(String(dataFromM4.debugStringData), TELEMETRY_LOW_PRIORITY);
    return_frame_ready_sdram->frame_ready = false;  //false indicates data has been read by M7
  }
}

//M4

void receiveDataFromM7() {
  if (send_frame_ready_sdram->frame_ready) {  //data is available from M7
    DATA_FRAME_SEND dataFromM7 = *data_frame_send_sdram;
    memcpy(&drone_settings, &dataFromM7.drone_settings, sizeof(struct DRONE_SETTINGS));
    memcpy(&imu_data, &dataFromM7.imu_data, sizeof(struct IMU_DATA));
    memcpy(&altitude_data, &dataFromM7.altitude_data, sizeof(struct ALTITUDE_DATA));
    memcpy(&altitude_control_data, &dataFromM7.altitude_control_data, sizeof(struct ALTITUDE_CONTROL_DATA));
    memcpy(&receiver_data, &dataFromM7.receiver_data, sizeof(struct RECEIVER_DATA));
    memcpy(&power_management_data, &dataFromM7.power_management_data, sizeof(struct POWER_MANAGEMENT_DATA));
    memcpy(&temperature_data, &dataFromM7.temperature_data, sizeof(struct TEMPERATURE_DATA));
    memcpy(&gps_data, &dataFromM7.gps_data, sizeof(struct GPS_DATA));
    memcpy(&gps_status_data, &dataFromM7.gps_status_data, sizeof(struct GPS_STATUS_DATA));
    memcpy(&navigation_data, &dataFromM7.navigation_data, sizeof(struct NAVIGATION_DATA));
    memcpy(&heading_control_data, &dataFromM7.heading_control_data, sizeof(struct HEADING_CONTROL_DATA));
    memcpy(&stepper_motor_data, &dataFromM7.stepper_motor_data, sizeof(struct STEPPER_MOTOR_DATA));
    memcpy(&safety_data, &dataFromM7.safety_data, sizeof(struct SAFETY_DATA));
    send_frame_ready_sdram->frame_ready = false;  //set to false to let M7 know data has been read
    hasReceivedDataFromM7 = true;
  }
}

void sendDataToM7(String debugStringData, bool blocking) {
  do {
    if (!return_frame_ready_sdram->frame_ready) {  //if 0 can send data
      DATA_FRAME_RETURN dataForM7;
      debugStringData.toCharArray(dataForM7.debugStringData, sizeof(dataForM7.debugStringData));
      *data_frame_return_sdram = dataForM7;
      return_frame_ready_sdram->frame_ready = true;  //1 lets m7 know it can read data
      return;                        //break out of do->while loop
    } else if (blocking) {
      delayMicroseconds(5);  //hang out and try again, in a little bit
    }
  } while (blocking);
}

Man thats what you meant - didn't really register until just now.

Man am embarrased

No worries, I also changed a few things included in my response to make things run safer in the transfers, one more edit with a few more changes incoming :slight_smile: Done! If you need any more help I'd be glad to clarify things, data transfer between the cores quickly is certainly a hard thing to figure out. Make sure your structs are of a fixed size and aligned in memory. Once you've figured out your memory transfers I can show you how to pass threads from the M7 core to the M4 core and vice versa, allowing true dual core operation. Transferring local SRAM function pointers into SDRAM then executing on another core in SDRAM space using MBED OS and hardware memory protections. then can execute a call back to m7 with data, for example in my flight controller program I spin up threads on M4 passed in from M7 that runs my PID loops and PWM ESC controls. The Giga is a pretty capable machine. (Also look into MBED threading if you want to try something cool, fully supported on the Giga)

1 Like

@PCMaster2165
Started playing with this in earnest this morning (been distracted with other Giga issues). But having a problem on the M4 - doesn't seem to be starting for some reason. Have it blinking blue when it starts and getting data but thats now working.
Heres the M7 sketch:

#include <RPC.h>
Stream *USERIAL = nullptr;

#include "SDRAM.h"

// Data constructors
struct IMU_DATA {
  float ax = 0.0;
  float ay = 0.0;
  float az = 0.0;
  float gx = 0.0;
  float gy = 0.0;
  float gz = 0.0;
  float mx = 0.0;
  float my = 0.0;
  float mz = 0.0;
} __attribute__((aligned(8)));

struct DATA_FRAME_SEND {
    IMU_DATA imu_data;
} __attribute__((aligned(8)));

struct DATA_FRAME_RETURN {
  char debugStringData[100];
} __attribute__((aligned(8)));

struct SEND_FRAME_READY_FLAG {
  volatile bool frame_ready = false;
} __attribute__((aligned(8)));

struct RETURN_FRAME_READY_FLAG {
  volatile bool frame_ready = false;
} __attribute__((aligned(8)));

//SDRAM Pointers
const uint32_t SDRAM_START_ADDRESS_4 = ((uint32_t)0x38000000);  //USING THE AHB SRAM4 DOMAIN SPACE
volatile uint32_t *sdramMemory = (uint32_t*)0x38000000;

SEND_FRAME_READY_FLAG* send_frame_ready_sdram = (SEND_FRAME_READY_FLAG*)(sdramMemory);
RETURN_FRAME_READY_FLAG* return_frame_ready_sdram = (RETURN_FRAME_READY_FLAG*)(sdramMemory + sizeof(SEND_FRAME_READY_FLAG) / sizeof(uint32_t));
DATA_FRAME_SEND* data_frame_send_sdram = (DATA_FRAME_SEND*)(sdramMemory + (sizeof(SEND_FRAME_READY_FLAG) + sizeof(RETURN_FRAME_READY_FLAG)) / sizeof(uint32_t));
DATA_FRAME_RETURN* data_frame_return_sdram = (DATA_FRAME_RETURN*)(sdramMemory + (sizeof(SEND_FRAME_READY_FLAG) + sizeof(RETURN_FRAME_READY_FLAG) + sizeof(DATA_FRAME_SEND)) / sizeof(uint32_t));

#include "icm20948.h"

/* Mpu9250 object */
bfs::Icm20948 imu;
volatile bool isrFired = false;

void setup() {
 if (HAL_GetCurrentCPUID() == CM7_CPUID) {
  while (!Serial && millis() < 5000) {}
    Serial.begin(115200);
    USERIAL = &Serial;
  } else {
    RPC.begin();
    USERIAL = &RPC;
    delay(1000);
  }

  SDRAM.begin(SDRAM_START_ADDRESS_4);

  pinMode(LED_RED, OUTPUT);
  for (uint8_t i = 0; i < 5; i++ ) {
    digitalWrite(LED_RED, HIGH);
    delay(250);
    digitalWrite(LED_RED, LOW);
    delay(250);
  }

  USERIAL->println("M4 Started\n - now to start M4");
  delay(100);

  Wire1.begin();
  Wire1.setClock(400000);
  //delay(5000);
  /* I2C bus,  0x68 address */
  imu.Config(&Wire1, bfs::Icm20948::I2C_ADDR_SEC);
  /* Initialize and configure IMU */
  if (!imu.Begin()) {
    USERIAL->println("Error initializing communication with IMU");
    while(1) {}
  }
  /* Set the sample rate divider for both accelerometer and gyroscope*/
  /* 
    rate = 1125/(SRD + 1) HZ
    ==========================
    SRD 8  => rate = 125 HZ
    SRD 9  => rate = 112.5 HZ
    SRD 10 => rate = 102.3 HZ
    SRD 11 => rate = 93.75 HZ
    SRD 19 => rate = 56.25 HZ
    SRD 20 => rate = 53,57 HZ
    SRD 21 => rate = 51,14 HZ
    SRD 22 => rate = 48.91 HZ
    when using SRD to set sampling rate magnetometer is 
    automatically set to 50Hz for SRD's > 10 otherwise it
    is set to 100Hz.
   */
  if (!imu.ConfigSrd(21)) {
    USERIAL->println("Error configured SRD");
    while(1) {}
  }
  // enabling the data ready interrupt
  // currently only the data ready interrupt is supported
  imu.EnableDrdyInt();
  // attaching the interrupt to microcontroller pin 1
  pinMode(2,INPUT);
  attachInterrupt(digitalPinToInterrupt(2), sensorISR, RISING);
}

void loop() {
  if (isrFired)
  { // If our isr flag is set then clear the interrupts on the ICM
    isrFired = false;
    getIMU();
  }
  
  receiveDataFromM4();

}


void sensorISR(void)
{
  isrFired = true; // Can't use I2C within ISR on 328p, so just set a flag to know that data is available
}

float imu_values[9];
void getIMU() {
  /* Check if data read */
 {
    imu.Read(imu_values);
    //Function used to clear interrupts if necessary
    imu.clearInterrupts();

    send_frame_ready_sdram->frame_ready = false;
    sendDataToM4();
  }

}

void sendDataToM4() {
  if (!send_frame_ready_sdram->frame_ready) { //if false it can be written to
    //USERIAL->print(send_frame_ready_sdram->frame_ready);
    DATA_FRAME_SEND dataForM4;
    memcpy(&dataForM4.imu_data, &imu_values, sizeof(struct IMU_DATA));
    *data_frame_send_sdram = dataForM4;
    send_frame_ready_sdram->frame_ready = true; //if true M4 can read from it
    //USERIAL->println(send_frame_ready_sdram->frame_ready);
  }
}

void receiveDataFromM4() {
  if (return_frame_ready_sdram->frame_ready) {  //true indicates it can read by M7
    DATA_FRAME_RETURN dataFromM4 = *data_frame_return_sdram;
    //telemetry.printTelemetry(String(dataFromM4.debugStringData), TELEMETRY_LOW_PRIORITY);
    USERIAL->println(String(dataFromM4.debugStringData));
    return_frame_ready_sdram->frame_ready = false;  //false indicates data has been read by M7
  }
}

and heres the M4

#include <floatToString.h>

#include <RPC.h>
Stream *USERIAL = nullptr;

#include "SDRAM.h"

// Data constructors
struct IMU_DATA {
  float ax;
  float ay;
  float az;
  float gx;
  float gy;
  float gz;
  float mx;
  float my;
  float mz;
} __attribute__((aligned(8)));
IMU_DATA imu_data_recv;

struct DATA_FRAME_SEND {
    IMU_DATA imu_data;
} __attribute__((aligned(8)));

struct DATA_FRAME_RETURN {
  char debugStringData[100];
} __attribute__((aligned(8)));

struct SEND_FRAME_READY_FLAG {
  volatile bool frame_ready = false;
} __attribute__((aligned(8)));

struct RETURN_FRAME_READY_FLAG {
  volatile bool frame_ready = false;
} __attribute__((aligned(8)));

//SDRAM Pointers
const uint32_t SDRAM_START_ADDRESS_4 = ((uint32_t)0x38000000);  //USING THE AHB SRAM4 DOMAIN SPACE
volatile uint32_t *sdramMemory = (uint32_t*)0x38000000;

SEND_FRAME_READY_FLAG* send_frame_ready_sdram = (SEND_FRAME_READY_FLAG*)(sdramMemory);
RETURN_FRAME_READY_FLAG* return_frame_ready_sdram = (RETURN_FRAME_READY_FLAG*)(sdramMemory + sizeof(SEND_FRAME_READY_FLAG) / sizeof(uint32_t));
DATA_FRAME_SEND* data_frame_send_sdram = (DATA_FRAME_SEND*)(sdramMemory + (sizeof(SEND_FRAME_READY_FLAG) + sizeof(RETURN_FRAME_READY_FLAG)) / sizeof(uint32_t));
DATA_FRAME_RETURN* data_frame_return_sdram = (DATA_FRAME_RETURN*)(sdramMemory + (sizeof(SEND_FRAME_READY_FLAG) + sizeof(RETURN_FRAME_READY_FLAG) + sizeof(DATA_FRAME_SEND)) / sizeof(uint32_t));

bool hasReceivedDataFromM7 = false;

void setup() {
 if (HAL_GetCurrentCPUID() == CM7_CPUID) {
  while (!Serial && millis() < 5000) {}
    Serial.begin(115200);
    USERIAL = &Serial;
  } else {
    RPC.begin();
    USERIAL = &RPC;
  }

  delay(500);

  pinMode(LED_BLUE, OUTPUT);
  for (uint8_t i = 0; i < 5; i++ ) {
    digitalWrite(LED_BLUE, HIGH);
    delay(250);
    digitalWrite(LED_BLUE, LOW);
    delay(250);
  }

}

void loop() {
  digitalWrite(LED_BLUE, HIGH);
  delay(250);

  receiveDataFromM7();
  if(hasReceivedDataFromM7 == true){
    /*
    USERIAL->print("\t"); 
    USERIAL->print(imu_data_recv.ax); USERIAL->print(", ");
    USERIAL->print(imu_data_recv.ay); USERIAL->print(", ");
    USERIAL->print(imu_data_recv.az); USERIAL->print(", ");
    USERIAL->print(imu_data_recv.gx); USERIAL->print(", ");
    USERIAL->print(imu_data_recv.gy); USERIAL->print(", ");
    USERIAL->print(imu_data_recv.gz); USERIAL->print(", ");
    USERIAL->print(imu_data_recv.mx); USERIAL->print(", ");
    USERIAL->print(imu_data_recv.my); USERIAL->print(", ");
    USERIAL->print(imu_data_recv.mz); USERIAL->println();
    */
    //String buf = ""; char S[15];
    //buf = floatToString(imu_data_recv.ax, S, sizeof(S), 6); buf.concat(", ");
    //buf.concat(floatToString(imu_data_recv.ay, S, sizeof(S), 6));
    hasReceivedDataFromM7 = false;

    sendDataToM7("Received data", true);
  }
  digitalWrite(LED_BLUE, LOW);
  delay(250);
}

void receiveDataFromM7() {
  if (send_frame_ready_sdram->frame_ready) {  //data is available from M7
    digitalWrite(LED_BLUE, HIGH);
    DATA_FRAME_SEND dataFromM7 = *data_frame_send_sdram;
    memcpy(&imu_data_recv, &dataFromM7.imu_data, sizeof(struct IMU_DATA));
    send_frame_ready_sdram->frame_ready = false;  //set to false to let M7 know data has been read
    hasReceivedDataFromM7 = true;
    digitalWrite(LED_BLUE, LOW);
  }
}

void sendDataToM7(String debugStringData, bool blocking) {
  do {
    if (!return_frame_ready_sdram->frame_ready) {  //if 0 can send data
      DATA_FRAME_RETURN dataForM7;
      debugStringData.toCharArray(dataForM7.debugStringData, sizeof(dataForM7.debugStringData));
      *data_frame_return_sdram = dataForM7;
      return_frame_ready_sdram->frame_ready = true;  //1 lets m7 know it can read data
      return;                        //break out of do->while loop
    } else if (blocking) {
      delayMicroseconds(5);  //hang out and try again, in a little bit
    }
  } while (blocking);
}

Kind of messy since I was trying a few different things

@PCMaster2165
Ok - made really dumb mistake its now working - passed imu_data from the M7 to the M4 and then sent accel's back - looks good so far:

0.023942, 0.349559, -9.576953,

Well now that I got this working you want to tell me what you did with threads? Busy with ILI9341 stuff but want to get this working.

While I don't use a "flight controller" I do use alot of what you are showing for rovers.

1 Like

… for the record, the rx buffer on the receive side that RPC.available polls is a 256 byte ring buffer (at least it is on the source I am looking at). When data is pushed to that from the receive it is dropped when the buffer is full and the API doesn’t inform of you of this so you can’t retry. As a result, sending large chunks of bytes via RPC.print/println is likely to result in data loss.