stm32 uavcan node idle

108 views
Skip to first unread message

Mohammed Talha

unread,
Jul 18, 2018, 10:04:26 PM7/18/18
to UAVCAN
Hello,

I'm trying to make stm32f429 uavcan node to work with an imx6sx node. I have simply configured the imx6 node as a time sync master as shown in the tutorials. The IMX6 board tham i am using has 2 can ifaces. One is a time sync master and the other is a time sync slave. Both are working fine without any issues. But the stm32 node for some reason does not sync. Here's my setup for stm32.
RTOS: Chibios + tickless mode
UAVCAN_STM32_TIMER_NUMBER: 3
Number of ifaces: 1 (only using can1 for now since i dont have an extra transceiver currently).

Here is the source for the stm32 node

#include <node.hpp>
#include <ch.hpp>
#include <uavcan_stm32/can.hpp>
#include <uavcan_stm32/clock.hpp>
#include <sys.hpp>
#include <unistd.h>
#include <timing/MicrosecondDelay.h>
#include <uavcan/protocol/global_time_sync_slave.hpp>
#include <uavcan/protocol/dynamic_node_id_client.hpp>

namespace can{

constexpr uint32_t MemoryPoolSize=16384;

using Node=uavcan::Node<MemoryPoolSize>;
auto node_status_mode = uavcan::protocol::NodeStatus::MODE_OPERATIONAL;
auto node_status_health = uavcan::protocol::NodeStatus::HEALTH_OK;
/*
* @template param: RxQueueCapacity
*     default value: 128
*/
uavcan_stm32::CanInitHelper<128> can;

static Node& getNode()
{
    static Node node(can.driver,uavcan_stm32::SystemClock::instance());
    return node;
}


void print_nodeInfo()
{
    sys::syslog("Can bitrate: %u\r\n",125000);
    sys::syslog("Node ID: %u\r\n",getNode().getNodeID());
    sys::syslog("Node mode: %u\r\n",node_status_mode);
    sys::syslog("Node Health: %u\r\n",node_status_health);

    const decltype(auto) perf= getNode().getDispatcher().getTransferPerfCounter();

    const auto pool_capacity = getNode().getAllocator().getBlockCapacity();
    const auto peak_usage = getNode().getAllocator().getPeakNumUsedBlocks();

    uavcan::CanIfacePerfCounters iface_perf;

    iface_perf = getNode().getDispatcher().getCanIOManager().getIfacePerfCounters(0);

    sys::syslog("Memory Pool Capacity: %u\r\n",pool_capacity);
    sys::syslog("Memory Peak Usage: %u\r\n",peak_usage);
       
    sys::syslog("Transfers Tx/Rx: %u / %u \r\n",perf.getTxTransferCount(),perf.getRxTransferCount());
    sys::syslog("Transfer Errors: %u\r\n",(unsigned)perf.getErrorCount());
       
    sys::syslog("Can Iface: %d\r\n",0);
    sys::syslog("Frames Tx/Rx: %u / %u \r\n", (unsigned)(iface_perf.frames_tx),(unsigned)(iface_perf.frames_tx));

    sys::syslog("Rx Overflows: %u\r\n",(unsigned)can.driver.getIface(0)->getRxQueueOverflowCount());
    sys::syslog("Iface errors: %u\r\n",(unsigned)iface_perf.errors);

    sys::syslog("------End of Block-------\r\n");
}

    void Init()
    {
        int res=0;
        //static const int self_node_id = 50;
        stm32plus::MicrosecondDelay timer;
        timer.initialise();
        do{
       
        uint32_t bitrate = 125000;
//        res= can.init([&](){timer.delay(can.getRecommendedListeningDelay().toUSec());},bitrate);
        res = can.init(bitrate);
        if(res >= 0)
        {
            sys::syslog("Inited can at bitrate: %u bps\r\n",bitrate);
        }
        else
        {
            sys::syslog("Failed to init Can: %d Bitrate:%u \r\n",res,bitrate);
        }
       
        }while(res < 0);
    }

class : public chibios_rt::BaseStaticThread<8192>
{
    void init_node()
    {
        getNode().setName("org.uavcan.Slave_sync");
        getNode().setNodeID(50);

        while(true)
        {
            int node_res = getNode().start();
            if(node_res < 0)
            {
                sys::syslog("Failed to Init Node: %d\r\n",node_res);
            }
            else
            {
                sys::syslog("Can Node Inited. Node ID %d\r\n",getNode().getNodeID().get());
                break;
            }
        }
    }

public:
   
    void main() override
    {
        Init();    //Can Driver Init
        init_node();
        chThdSleep(MS2ST(10));
       
        print_nodeInfo();

        uavcan::GlobalTimeSyncSlave slave(getNode());

        const int slave_res = slave.start();
        if(slave_res < 0)
        {
            sys::syslog("Failed to init time sync slave: %d\r\n",slave_res);
        }

        getNode().getNodeStatusProvider().setHealth(node_status_health);
        getNode().getNodeStatusProvider().setMode(node_status_mode);
       
        getNode().setModeOperational();
        while(true)
        {
            const int spin_res = getNode().spin(uavcan::MonotonicDuration::fromMSec(100));
            if(spin_res < 0)
            {
                sys::syslog("Spin Error: %d\r\n",spin_res);
            }

            const bool active = slave.isActive();
            const auto masterid = slave.getMasterNodeID().get();
            const float time_since_last_adj= (getNode().getMonotonicTime() - slave.getLastAdjustmentTime()).toMSec();

            sys::syslog("Slave Active: %d\r\n"
                                        "Master ID: %d\r\n"
                                        "Time since Last Adjustment: %f\r\n",active,masterid,time_since_last_adj);
        }
}
}test_node;


int init()
{
    (void)test_node.start(NORMALPRIO);
    return 0;
}
}

The thread only ever reaches the line "iface_perf = getNode().getDispatcher().getCanIOManager().getIfacePerfCounters(0);" in the print_nodeInfo() method and then never gets rescheduled. This is not an rtos issue since other threads are working fine. I have initialized the can peripheral properly and can confirm that the interface  is fully operational. One more thing that happens is after initialization. The node starts sending messages continuously non-stop overloading the bus. After some point the other  nodes (IMX6 master and slave) stop communicating. How do i proceed further with this issue?

Regards.


 
 

Pavel Kirienko

unread,
Jul 19, 2018, 4:40:38 AM7/19/18
to mohamme...@gmail.com, uav...@googlegroups.com
Hi Mohammed,

> This is not an rtos issue

This is an RTOS issue.

Either your sys tick timer is misconfigured, or the libuavcan hardware timer is not working properly (perhaps it is being reused by some other part of the firmware?). With a dysfunctional sys tick timer, a ChibiOS application may exhibit a confusing behavior where threads that block on IO and other conditions continue to function properly, whereas the threads that block on timers get stuck forever.

Also make sure you're not dealing with this issue: http://www.chibios.com/forum/viewtopic.php?f=3&t=3651

Pavel.

--
You received this message because you are subscribed to the Google Groups "UAVCAN" group.
To unsubscribe from this group and stop receiving emails from it, send an email to uavcan+un...@googlegroups.com.
To post to this group, send email to uav...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/uavcan/3b002157-7bed-4574-a7d1-3d0ffeb56b2f%40googlegroups.com.
For more options, visit https://groups.google.com/d/optout.

Mohammed Talha

unread,
Jul 22, 2018, 6:54:57 AM7/22/18
to UAVCAN


Hi Pavel,

Thank you for  the prompt reply. Turns out it was a trivial issue of mutex deadlock in the following code. i forgot to enable recursive mutex lock option. when multiple args were passed to the logger it called the variadic interface which tried to acquire the lock again held by the generic logger.

template<typename T,typename... Args>                                                                                  
void syslog(const char* fmt,T&& value,Args&&... args)                                                                  
{                                                                                                                      
     scoped_mutex mtx(_mutex);                                                                                            
    if(sizeof...(args) > 0)                                                                                              
       return syslog(fmt,traits::forward<Args>(args)...);                                                                 
    else                                                                                                                 
       chprintf(&STDIO_stream,fmt,traits::forward<T>(value));                                                             
}
 
However the issue regarding the node sending ("most likely") the node status msg continuously still bothers me. Here is the serial output of the program indicating interface error count.

 Can bitrate: 125000
Node ID: 50
Node mode: 0
Node Health: 0
Memory Pool Capacity: 292
Memory Peak Usage: 11
Transfers Tx/Rx: 0 \  0
Transfer Errors: 0
Can Iface: 0
Frames Tx/Rx: 0 \ 0
Rx Overflows: 0
Iface errors: 11857
Iface0 errors: 11822
Monotonic Time: 39110

I'm using stm32plus provided hal layer and following is my board::init file. The same code when used with standard can peripheral application works fine. Does uavcan require certain initialization sequence for the hardware?

namespace board
{
  void init()
   {
    using namespace stm32plus;
    //Initializing the System Timer
     //If USE_ALT_TIMER is defined Tickless timer mode is enabled
     //else Class Systick mode is enabled
 
     stInit();
    CanPinInitialiser<Can1DefaultPinPackage,PERIPHERAL_CAN1> _can1;
    CanPinInitialiser<Can2DefaultPinPackage,PERIPHERAL_CAN2> _can2;
    _can1.initialise();
    _can2.initialise();  
}
 
The class template initializer takes care of gpio clock initialization, AF selection, Mode, Output and speed selection. After this block the control reaches chibios_rt::System::init() and then CanInitHelper<>::init. Which i suppose takes care of can peripheral initialization. I have even tried initialising the peripheral in board::init() with default values but it doesnt effect the behavior. I'm attaching a CanTx CanRx signal image from a cheap hantek scope, so please ignore the sampling noise. Ch1 is Tx and Ch2 is Rx. Scope X-axis resolution is 1ms and Y-axis is 1.0 V.

Regards

s.PNG

Mohammed Talha

unread,
Jul 22, 2018, 11:23:43 AM7/22/18
to UAVCAN


P.S i have even tried the straightforward std periph method for hardware init.

void init()
{
using namespace stm32plus;
//Initializing the System Timer
 //If USE_ALT_TIMER is defined Tickless timer mode is enabled
//else Class Systick mode is enabled

stInit();
/*CanPinInitialiser<Can1Remap2PinPackage,PERIPHERAL_CAN1> _can1;
 CanPinInitialiser<Can2RemapPinPackage,PERIPHERAL_CAN2> _can2;
 _can1.initialise();
  _can2.initialise();
ClockControl<PERIPHERAL_CAN1>::On();
ClockControl<PERIPHERAL_CAN2>::On();*/
 
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOB,ENABLE);
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOD,ENABLE);
 
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5 | GPIO_Pin_6;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;   
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd  = GPIO_PuPd_UP;
   
GPIO_PinAFConfig(GPIOB,GPIO_PinSource5,GPIO_AF_CAN2);
GPIO_PinAFConfig(GPIOB,GPIO_PinSource6,GPIO_AF_CAN2);  
GPIO_Init(GPIOB, &GPIO_InitStructure);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_CAN2,ENABLE);
  
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd  = GPIO_PuPd_UP; 
GPIO_PinAFConfig(GPIOD,GPIO_PinSource0,GPIO_AF_CAN1);
GPIO_PinAFConfig(GPIOD,GPIO_PinSource1,GPIO_AF_CAN1);
GPIO_Init(GPIOD, &GPIO_InitStructure);
 
RCC_APB1PeriphClockCmd(RCC_APB1Periph_CAN1,ENABLE);
}

 

Pavel Kirienko

unread,
Jul 25, 2018, 5:09:50 AM7/25/18
to mohamme...@gmail.com, uav...@googlegroups.com
One of the possible reasons is that other nodes on the bus do not confirm reception of the frame, so the CAN controller on your local node attempts to retransmit it. Make sure that all nodes on the bus are using the same CAN bit rate.

Pavel.

--
You received this message because you are subscribed to the Google Groups "UAVCAN" group.
To unsubscribe from this group and stop receiving emails from it, send an email to uavcan+un...@googlegroups.com.
To post to this group, send email to uav...@googlegroups.com.
Reply all
Reply to author
Forward
0 new messages