rosserial_mbed breaks SPI communication
Hi,
I'm working on a project on the Gapuino development board using Mbed OS. In my implementation I need to sample data from an SPI device (ADS1299) at a constant rate of 250Hz and without any data losses (this is done using a data ready interrupt coming from the device). Batches of data then needs to be sent to my computer using rosserial_mbed at a much slower rate.
Given the fact that rosserial mbed uses asynchronous UART communication, messages could arrive anytime and thus breaking the blocking SPI write functions when sampling data.
I will post the source code to give some context:
#include <mbed.h>
#include "ADS1299.h"
#include "Biquad.h"
#include "Definitions.h"
#include "ros.h"
#include "ads1299/ChannelData.h"
// ADS1299
ADS1299 ads;
// ROS stuff
ros::NodeHandle nh;
ads1299::ChannelData ads_msg;
ros::Publisher gap8("channel_data", &ads_msg);
// Thread
Thread thread;
osThreadId threadID;
// Prototypes
void sendDataThread(void);
void dataReadyISR(void);
// Interrupt pin
InterruptIn DRDY(GPIO_A5_B40);
// Signal data ready
void dataReadyISR(void)
{
osSignalSet(threadID, 0x05);
}
// Acquire and publish data
void sendDataThread(void)
{
// Get thread ID
threadID = osThreadGetId();
uint8_t counter = 0;
for(;;)
{
// Wait for data ready signal
osSignalWait(0x05, osWaitForever);
// Read new data
ads.updateChannelData(); // <-------- Here is used SPI::write
// Publish message every 100ms
if (counter == 25)
{
// Insert data inside payload
ads_msg.ch1 = ads.channelData[0];
ads_msg.ch2 = ads.channelData[1];
ads_msg.ch3 = ads.channelData[2];
ads_msg.ch4 = ads.channelData[3];
ads_msg.ch5 = ads.channelData[4];
ads_msg.ch6 = ads.channelData[5];
ads_msg.ch7 = ads.channelData[6];
ads_msg.ch8 = ads.channelData[7];
// Publish message
gap8.publish(&ads_msg);
nh.spinOnce();
counter = 0;
}
counter++;
}
}
int main(void)
{
// Setup ROS node
nh.getHardware()->setBaud(115200);
nh.initNode();
nh.advertise(gap8);
// Start connection
while(!nh.connected())
{
nh.spinOnce();
printf("Connecting...\n");
Thread::wait(1000);
}
printf("Connection enstablished.\n");
// Start thread
thread.start(callback(sendDataThread));
// Start data reayd ISR
DRDY.fall(dataReadyISR);
// Main thread wait forever
Thread::wait(osWaitForever);
}
I couldn't find any other questions regarding this incompatibility, I'm wondering if there is a way to make the SPI communication interrupt safe from ROS messages without disabling interrupts entirely (this will of course end with a lost connection).
I tried many approaches without any luck, I will sincerely appreciate anyone who could provide some help!