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);
}