ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

rosserial_mbed breaks SPI communication

asked 2020-11-01 11:57:00 -0500

Gualor gravatar image

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!

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2020-11-02 00:59:44 -0500

duck-development gravatar image

you may use diffrent threads and a mmutex. you may say threat the thread spi com has more priority so it is evertyme execudet.

you lock the communication between ros and spi with a mutex und you done.

otherwise i do not know why you are using thread because you could also code everything in the main loop.

and how mutch of the cpu time is allready used bei you update funktion is there enought cpu power for ros communication.

edit flag offensive delete link more
1

answered 2020-11-02 03:51:36 -0500

Gualor gravatar image

updated 2020-11-02 10:16:54 -0500

Hi @duck-development! Firstly thank you for your quick answear!

I moved the sendDataThread code inside the main loop since there wasn't any reason to do it. Then I tried using mutex to lock the SPI write function, but I had no luck with it and it always gives me the same error as before, which is:

Assert failed: g_spiHandle[1], file: /home/gualor/.platformio/packages/framework-gap_sdk/mbed-os/targets/TARGET_GWT/TARGET_GAP8

++ MbedOS Error Info ++

Error Status: 0x8001011D Code: 285 Module: 1

Error Message:

Pre main thread not created

The code now looks something like this:

#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
osThreadId threadID;

// Prototypes
void dataReadyISR(void);

// Interrupt pin
InterruptIn DRDY(GPIO_A5_B40);


// Signal data ready
void dataReadyISR(void)
{
    osSignalSet(threadID, 0x05);
}


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

    // Get thread ID
    threadID = osThreadGetId();
    uint8_t counter = 0;
    Mutex mutex;

    // Start data reayd ISR
    DRDY.fall(dataReadyISR);

    for(;;)
    {   
        // Wait for data ready signal
        osSignalWait(0x05, osWaitForever);

        // Read new data
        mutex.lock();
        ads.updateChannelData();
        mutex.unlock();

        // Publish message every 1s
        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++;
    }
}

I thought the error was due to SPI write being interrupted, but mutex lock should have solved at least this issue. Could it be that the mutex failed to lock properly and interruption occurred anyway? Do you have any idea how I could debug this?

Thank you again for the help!


UPDATE:

As suggested I tried having 2 threads running, one for acquiring data via SPI and one for publishing ROS messaging and calling spin once. Saddly it seems to behave exactly like before even with the use of mutexes inside the code:

#include "mbed.h"
#include "ADS1299.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);

// Threads
osThreadId id;
Thread thread1;
Thread thread2(osPriorityAboveNormal1);
void acquireThread(void);
void publishThread(void);
Mutex mutex;

// Interrupt
InterruptIn DRDY(GPIO_A5_B40);  
void dataReadyISR(void);


// Data ready interrupt
void dataReadyISR(void)
{
    osSignalSet(id, 0x01);
}

// Acquire data from ADS1299
void acquireThread(void)
{
    id = ThisThread::get_id();
    for(;;)
    {
        osSignalWait(0x01, osWaitForever);
        mutex.lock();
        ads.updateChannelData();
        mutex.unlock();
    }
}

// Publish ROS messages
void publishThread(void)
{
    for(;;)
    {
        // Update message data
        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 ...
(more)
edit flag offensive delete link more

Comments

If you have mutexs then you need more threads.

One ads read thread and one ros write thread.

Did you Software have an compile or runtime error?

duck-development gravatar image duck-development  ( 2020-11-02 07:43:27 -0500 )edit

Does you first Programm run without the ROS code?

duck-development gravatar image duck-development  ( 2020-11-02 07:46:50 -0500 )edit

Yes, before merging this code with the rosserial stuff for sending messages of data, I implemented the same code but using a simple UART serial protocol (using Mbed Serial library), and I encountered no issues.

The error is a runtime error, nothing happens if I don't start the serial_node.py for bridging with rosserial, then after execution the connection is always immediate and successful and messages are exchanged at a constant rate for about 10 seconds, then the MCU encounter this runtime error and stops execution (breaking of course the connection with the serial node on the computer).

The fact is that rosserial uses asynchronous UART, and without knowing when messages will arrive at some point one of them will interrupt the SPI read of the sensor causing the issue.

I tried your suggestion of using multi-threaded code with mutexes, but without any luck. Maybe I'm just doing ...(more)

Gualor gravatar image Gualor  ( 2020-11-02 08:19:12 -0500 )edit

you have to set the mutex in the ros thread arround the acces of you adc data.

and set the adc data thread to high prio Thread testSignal(outputSignal,0,osPriorityHigh);

as described here https://os.mbed.com/questions/2313/Pr...

duck-development gravatar image duck-development  ( 2020-11-02 11:02:57 -0500 )edit

I change the thread priority as you said, but I don't quite understand what you mean with "you have to set the mutex in the ros thread arround the acces of you adc data." The ROS thread only copies data already stored inside an array to the message payloads fields, and then publish the message. The actual data is read by the ads.updateChannelData() function. Can you be more specific about which line/s of code have to be locked by mutex?

For now, by locking the mutexes as I show in the updated question, the ROS connection lasts for about 10/15 seconds before causing the issue i described.

Sorry if I am wasting your time, you are very kind for taking the time to guide me through it.

Gualor gravatar image Gualor  ( 2020-11-02 13:52:15 -0500 )edit

you have to set the mutex erround the block

   mutex.lock();
        // 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];
  mutex.unlock();

because those are changed in the other thread.

and as log you have a singel core mcu you may add a sleep in the adc thread so the ros thread get some compuation time. the questen is osSignalWait(0x01, osWaitForever); an task or thread blocking call. it it is task bloking then you have to add the sleeping insede the adc thred otherwise it could help. but now it is a ros time out and not spi arror?

duck-development gravatar image duck-development  ( 2020-11-03 10:27:02 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-11-01 11:57:00 -0500

Seen: 243 times

Last updated: Nov 02 '20