Libuavcan CubeMX FreeRTOS SystemWorkbenchForSTM32

@Zarkopafilis would you be able to look into this, please?

Could you log a bug in GitHub against the AVL tree with details on what you observed? The code is very new and I’m excited to see we found an issue! Thanks so much.

mistake with working commit it’s 67da0aa. I just remember numbers 67.


I have pushed two working examples

https://github.com/raimapo/UAVCAN-examples

Is this related to the startup (before spinning)?

At first glance I can’t find anything wrong with the tree. The part of the code you pointed at is covered by TEST(AvlTree, MultipleEntriesPerKey) test. It should work properly. It’s ‘impossible’ for this to fail, unless you only add items for transfer in a while loop without spinning.

This condition may occur in a valid application on a limited time interval where multiple transfers are added between spins. Would this cause the tree to fail?

Not really. The point I wanted to make here is to double check for logical mistake in user-code. It’s designed to work specifically that way: schedule transfer, work to send on spin.

1 Like

Hi. I’ve got the same issue. There is a typo in the appendToEndOf method:

target = head->equal_keys;

should be

target = target->equal_keys;

The case happens when the driver is busy and all the frames produced from a single message are sent to a linked list.

2 Likes

Sorry for the delay on this. https://github.com/UAVCAN/libuavcan/pull/265 is in review. Will be fixed soon.

1 Like

Hello. I’m making a node on stm32 (Nucleo-F29ZI). Now I have a simple node code that broadcasts nodestatus. To initialize the kernel and clock, I used CubeMX. GPIO_CAN initialized on its own. I also assembled a slcan node and created a connection … And the UAVCAN gui tool does not see messages from my node. What could be the problem? My node functions exactly: I looked in the debugger and connected a logic analyzer to the bus. It constantly sends errors to the bus. I attach code without auto-generated:

/* Includes ------------------------------------------------------------------*/
#include "main.h"

/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "chip.h"
#include "uavcan_stm32.hpp"
/* USER CODE END Includes */


/* USER CODE BEGIN PV */
const int RxQueueSize = 128;
static std::uint32_t BitRate = 1000000;
const unsigned NodeMemoryPoolSize = 16384;
/* USER CODE END PV */

/* USER CODE BEGIN PFP */
static void USER_AFIO_CAN1_Init(void); //init the CAN1 pins
uavcan::ISystemClock& getSystemClock();
uavcan::ICanDriver& getCanDriver();
static uavcan::Node<NodeMemoryPoolSize>& getNode();
/* USER CODE END PFP */


int main(void)
{
  

  USER_AFIO_CAN1_Init();
  static uavcan::Node<NodeMemoryPoolSize>& node = getNode();
  if (node.setNodeID(10) == 0){
	  while(1);
  }
  node.setName("uavcan.equipment.actuator");

  uavcan::protocol::SoftwareVersion sw_version;
  sw_version.major = 1;
  node.setSoftwareVersion(sw_version);

  uavcan::protocol::HardwareVersion hw_version;
  hw_version.major = 1;
  node.setHardwareVersion(hw_version);

  node.setHealthOk();

 
  if (node.start() < 0){	//uavcan::TransferPriority::Default
	  while(1);
  }





  node.setModeOperational();
  
  /* Infinite loop */
  /* USER CODE BEGIN WHILE */
  
  while (1)
  {
	  if (node.spin(uavcan::MonotonicDuration::fromMSec(100)) < 0){
		  while(1);
	  }


    /* USER CODE END WHILE */

    /* USER CODE BEGIN 3 */
  }
  /* USER CODE END 3 */
}

/**
  * @brief System Clock Configuration
  * @retval None
  */

static void USER_AFIO_CAN1_Init(void){
	//gpiod clock is enabled before, because should not
	GPIO_InitTypeDef CAN1_AFIO;
	//Configure CAN1_RX_Pin
	CAN1_AFIO.Pin = CAN1_RX_Pin;
	CAN1_AFIO.Mode = GPIO_MODE_AF_PP;
	CAN1_AFIO.Pull = GPIO_NOPULL;
	CAN1_AFIO.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
	CAN1_AFIO.Alternate = GPIO_AF9_CAN1;
	HAL_GPIO_Init(CAN1_RX_GPIO, &CAN1_AFIO);

	//Configure CAN1_TX_Pin
	CAN1_AFIO.Pin = CAN1_TX_Pin;
	CAN1_AFIO.Mode = GPIO_MODE_AF_PP;
	CAN1_AFIO.Pull = GPIO_NOPULL;
	CAN1_AFIO.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
	CAN1_AFIO.Alternate = GPIO_AF9_CAN1;
	HAL_GPIO_Init(CAN1_TX_GPIO, &CAN1_AFIO);
}

uavcan::ISystemClock& getSystemClock(){
	return uavcan_stm32::SystemClock::instance();
}

uavcan::ICanDriver& getCanDriver(){
	static uavcan_stm32::CanInitHelper<RxQueueSize> can;
	static bool initialized = false;
	if (!initialized){
		initialized = true;
		int res = can.init(BitRate);
		if(res <0){
			while(1);
		}
	}
	return can.driver;
}

static uavcan::Node<NodeMemoryPoolSize>& getNode(){
	static uavcan::Node<NodeMemoryPoolSize> node(getCanDriver(), getSystemClock());
	return node;
}

Sorry, I can`t attach the schedule screenshot of logic analyzer(

This could be caused by a misconfigured (different) CAN bit rate.

Our anti-spam policies might be a bit overly paranoid. I have manually confirmed your trust level so you should be able to post pics now.

Pavel Kirienko, as I understand, the variable

static std::uint32_t BitRate = 1000000

determines CAN bitrate. The bitrate of slcan is the same.
Thank you) This is schedule of logic analyzer

With attached slcan and my node the schedule is same: only my node is publishing

In my Case I don’t used cubemx CAN configuration, because libuavcan has own configuration, I only making GPIO pins initalization. My main problem was, what newest version has issues what was discussed in this topic, I just tooked a little bit older version and it began working. Some working examples are at https://github.com/raimapo. Only server side in examples are not implemented, everything is in readme.md explained.

Thank you, Raimondas, I will see your repo)

Raimondas Pomarnacki,I watched. In your example, the same actions are described as in mine. The initialization of the GPIO is also the same. Perhaps there is a bug in the library, but I think I missed something or did something wrong. I’ll think more, but if I don’t solve the problem, I will switch to another version.)

Could be wiring. Could you show us a pic and/or a schematic diagram of your electrical connections?

For prototyping of my node I used:

  1. Nucleo-F429ZI
  2. WCMCU-2551 MCP2551 CAN BUS interface module
  3. 2 resistors 120 Om
  4. bread board

For prototyping of slcan I used:

  1. STM32F103C8T6
  2. WCMCU-2551 MCP2551 CAN BUS interface module
  3. USB-UART bridge
  4. bread board

All system:

Connecting of Nucleo and interface module:


Nucleo → CAN interface
can1_txo → ctx (“transmitter IN” logic)
can1_rxi → crx (“receive OUT” logic)

Photo with the bus between resistors (red line - CANH, blue line - CANL) :

I`m sorry for bad culture of manufacturing :grimacing::disappointed_relieved:. I have not the wiring diagrams, but can make if need.

Hi! Could you please try to remove terminating resistors at all, as they are placed weirdly and with your line length they are not really needed.
Also, I noticed one more thing.
image
Try removing these resistors in green ovel from your WCMCU-2551 boards in order to exclude all excessive components from the line.

Thanks for the answer, Alexander Sysoev) I tried to remove the terminators. Nodes (slcan and my node) was emitting frames of errors. The resistors on the board are needed to maintain a recessive state, I do not think that they need to be removed. slcan works well under these conditions.

If look at schedule of my nodes working (my post above), can see periodic short pauses. As I understanding, during these pauses a some reboot occurs. I cant capture it in debug.

And one more, mcp2551 has next logic:

  1. Dominant on the bus = 0 on the TxD/RxD
  2. Recessive on the bus = 1 on the TxD/RxD
    UAVCAN has the same logic, or this question needs addressing to stm32?

Yes. UAVCAN works on top of the standard CAN.

It’s hard to debug a hardware problem remotely. Perhaps you could arrange a video call with Alexander if he’s available, or ask for help at electronix.ru.

Hello everybody) I was absent for a long time. Today I continued my work and fixed my problem. I started over and opened “chip.h”, wich contains general defines for communication with hardware of a MCU. STM32_PCLK1 was defined by number from example (42000000), but was nor correct for work. I changed this number to “HAL_RCC_GetPCLK1Freq()” and slCAN reception has begun.Thanks to all for the help!) I continue to work.

1 Like