Unable to get the service uavcan.node.Getinfo to Work

Hello,

I am new to Libcanard. I am working on an MCU and was able to make the heartbeat message work properly.
Currently, i am trying to make the service uavcan.node.GetInfo (port id 430) to work.
I tried this command with yakut but i always get a timeout. My node ID = 95. Using the MCU debugger, I can hit correctly the CAN RX reception breakpoint and can see that the PC is sending me a CanardTransferKindRequest with uavcan_node_GetInfo_1_0_FIXED_PORT_ID_

void processReceivedTransfer(const CanardRxTransfer* const transfer)
{
    if (transfer->metadata.transfer_kind == CanardTransferKindMessage)
    {
    }
    else if (transfer->metadata.transfer_kind == CanardTransferKindRequest)
    {
        if (transfer->metadata.port_id == uavcan_node_GetInfo_1_0_FIXED_PORT_ID_)
        {
            // The request object is empty so we don't bother de-serializing it. Just send the response.
            const uavcan_node_GetInfo_Response_1_0 resp = processRequestNodeGetInfo();
            uint8_t      serialized[uavcan_node_GetInfo_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_] = {0};
            size_t       serialized_size = sizeof(serialized);
            const int8_t res = uavcan_node_GetInfo_Response_1_0_serialize_(&resp, &serialized[0], &serialized_size);
            if (res >= 0)
            {
                CanardTransferMetadata transfer_metadata = transfer->metadata;
                transfer_metadata.transfer_kind          = CanardTransferKindResponse;

                int32_t result = canardTxPush(&canard_Txqueue,
                                    &canard,
									transfer->timestamp_usec + (1000UL*1000UL),
									&transfer_metadata,
									serialized_size,
									serialized);

    			if (result < 0)
    			{
    				// An error has occurred: either an argument is invalid, the TX queue is full, or we've run out of memory.
    				// It is possible to statically prove that an out-of-memory will never occur for a given application if the
    				// heap is sized correctly; for background, refer to the Robson's Proof and the documentation for O1Heap.
    				  printf("processReceivedTransfer(): canardTxPush Error %ld \n", result);
    			}

            }
            else
            {
                //assert(false);
            }
        }
    }
}

This is what I see on the candump on Ubuntu PC when i sent this command:
yakut call 95 uavcan.node.getinfo -T3 -Pe
Error: The request has timed out after 3.0 seconds

Also attached yakut monitor screenshot.

Please can you tell me what is wrong by looking at this dump ?

$ candump -td -c -x can0
 (000.000000)  can0  TX - -  036BAF87   [1]  E5
 (000.000036)  can0  TX - -  107D5507   [8]  00 00 00 00 00 00 29 F2
 (000.000947)  can0  RX - -  026B83DF   [8]  01 00 00 00 08 01 07 A5
 (000.000395)  can0  RX - -  026B83DF   [8]  00 00 00 00 00 00 00 05
 (000.000166)  can0  RX - -  026B83DF   [8]  00 00 00 00 00 00 00 05
 (000.002803)  can0  RX - -  026B83DF   [8]  00 00 14 69 6F 2E 67 25
 (000.000032)  can0  RX - -  026B83DF   [8]  68 6F 73 74 72 6F 62 05
 (000.000032)  can0  RX - -  026B83DF   [8]  6F 74 69 63 73 2E 62 25
 (000.000032)  can0  RX - -  026B83DF   [7]  6D 73 00 00 26 D0 45
 (000.000031)  can0  RX - -  026B83DF   [8]  AA BB CC 00 00 00 00 25
 (000.998095)  can0  TX - -  1C7D5607   [8]  06 00 00 00 01 02 55 AC
 (000.000172)  can0  TX - -  1C7D5607   [8]  1D 56 1D 04 00 00 00 0C
 (000.000033)  can0  TX - -  1C7D5607   [8]  01 01 55 1D 40 00 00 2C
 (000.000270)  can0  TX - -  1C7D5607   [8]  00 00 00 00 00 00 00 0C
 (000.000031)  can0  TX - -  1C7D5607   [8]  00 00 00 00 00 00 00 2C
 (000.000031)  can0  TX - -  1C7D5607   [8]  00 00 00 00 00 00 00 0C
 (000.000157)  can0  TX - -  1C7D5607   [8]  00 00 00 00 00 00 00 2C
 (000.000031)  can0  TX - -  1C7D5607   [8]  00 00 00 00 00 00 00 0C
 (000.000031)  can0  TX - -  1C7D5607   [8]  00 00 00 00 00 00 00 2C
 (000.000965)  can0  TX - -  1C7D5607   [8]  00 00 00 00 00 00 00 0C
 (000.000145)  can0  TX - -  1C7D5607   [8]  00 00 00 00 00 40 00 2C
 (000.000032)  can0  TX - -  1C7D5607   [8]  00 00 00 00 00 00 00 0C
 (000.000031)  can0  TX - -  1C7D5607   [8]  00 00 40 00 00 00 00 2C
 (000.000288)  can0  TX - -  1C7D5607   [8]  00 00 00 00 00 00 00 0C
 (000.000208)  can0  TX - -  1C7D5607   [8]  00 00 00 00 00 00 00 2C
 (000.000224)  can0  TX - -  1C7D5607   [8]  00 00 00 00 00 00 00 0C
 (000.000392)  can0  TX - -  1C7D5607   [8]  00 00 00 00 00 00 00 2C
 (000.000405)  can0  TX - -  1C7D5607   [8]  00 00 00 00 00 00 00 0C
 (000.000254)  can0  TX - -  1C7D5607   [8]  00 00 00 00 00 00 00 2C
 (000.000262)  can0  TX - -  1C7D5607   [8]  00 00 00 00 00 03 00 0C
 (000.000272)  can0  TX - -  1C7D5607   [8]  00 00 00 40 00 00 00 2C
 (000.000485)  can0  TX - -  1C7D5607   [8]  00 00 00 00 00 00 00 0C
 (000.000040)  can0  TX - -  1C7D5607   [3]  45 F0 6C
 (000.000420)  can0  TX - -  107D5507   [8]  01 00 00 00 00 00 29 F3
 (000.995131)  can0  TX - -  107D5507   [8]  02 00 00 00 00 00 29 F4
 (001.000867)  can0  TX - -  107D5507   [8]  03 00 00 00 00 00 29 F5


Looking. Here’s what we see:

>>> from pycyphal.transport.can._identifier import CANID

>>> CANID.parse(0x036BAF87)
ServiceCANID(priority=<Priority.EXCEPTIONAL: 0>, source_node_id=7, destination_node_id=95, service_id=430, request_not_response=True)

>>> CANID.parse(0x026B83DF)
ServiceCANID(priority=<Priority.EXCEPTIONAL: 0>, source_node_id=95, destination_node_id=7, service_id=430, request_not_response=False)

The first line of your dump is the request. Lines 3…10 contain the response. The CAN ID appears to be correctly formed. Let’s check the payload then:

>>> from pycyphal.transport.can._frame import CyphalFrame
>>> from pycyphal.transport.can.media import DataFrame, FrameFormat

>>> CyphalFrame.parse(DataFrame(data=bytes([0x01,0x00,0x00,0x00,0x08,0x01,0x07,0xA5]),format=FrameFormat.EXTENDED,identifier=0x026B83DF))
CyphalFrame(identifier=0x026b83df, transfer_id=5, start_of_transfer=True, end_of_transfer=False, toggle_bit=True, padded_payload=01000000080107)

# <...>

>>> CyphalFrame.parse(DataFrame(data=bytes([0x6D,0x73,0x00,0x00,0x26,0xD0,0x45     ]),format=FrameFormat.EXTENDED,identifier=0x026B83DF))
CyphalFrame(identifier=0x026b83df, transfer_id=5, start_of_transfer=False, end_of_transfer=True, toggle_bit=False, padded_payload=6d73000026d0)

>>> CyphalFrame.parse(DataFrame(data=bytes([0xAA,0xBB,0xCC,0x00,0x00,0x00,0x00,0x25]),format=FrameFormat.EXTENDED,identifier=0x026B83DF))
CyphalFrame(identifier=0x026b83df, transfer_id=5, start_of_transfer=False, end_of_transfer=False, toggle_bit=True, padded_payload=aabbcc00000000)

Oops! The last two frames of your transfer are swapped! The CAN driver is apparently misbehaving.

Thanks, It seems the TX CAN frame of the MCU are not going out in order …
I do not know why…
I am just popping the canard_Txqueue.

void processReceivedTransfer(const CanardRxTransfer* const transfer)
{

	 static uint8_t msg_transfer_id =0;  // Must be static or heap-allocated to retain state between calls.

    if (transfer->metadata.transfer_kind == CanardTransferKindMessage)
    {
    }
    else if (transfer->metadata.transfer_kind == CanardTransferKindRequest)
    {
        if (transfer->metadata.port_id == uavcan_node_GetInfo_1_0_FIXED_PORT_ID_)
        {
          uavcan_node_GetInfo_Response_1_0 resp = processRequestNodeGetInfo();

      	  // buffer for serialization of a heartbeat message
      	  size_t ser_buf_size = uavcan_node_GetInfo_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_;
      	  uint8_t ser_buf[uavcan_node_GetInfo_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_]  = {0};

      	  // Serialize the previous heartbeat message
      	  int8_t result1 = uavcan_node_GetInfo_Response_1_0_serialize_(&resp, &ser_buf[0], &ser_buf_size);

      	  if(result1 == NUNAVUT_SUCCESS)
      	  {
               CanardTransferMetadata transfer_metadata = transfer->metadata;
               transfer_metadata.transfer_kind          = CanardTransferKindResponse;
               transfer_metadata.transfer_id			= msg_transfer_id;
               msg_transfer_id++;

               //memset(&ser_buf, 0xCC, ser_buf_size);

      		   int32_t result = canardTxPush(&canard_Txqueue,               // Call this once per redundant CAN interface (queue).
      										  &canard,
											  0,     						 // Zero if transmission deadline is not limited.
      										  &transfer_metadata,
      										  ser_buf_size,            // Size of the message payload (see Nunavut transpiler).
      										  (uint8_t*)ser_buf);
      			if (result < 0)
      			{
      				// An error has occurred: either an argument is invalid, the TX queue is full, or we've run out of memory.
      				// It is possible to statically prove that an out-of-memory will never occur for a given application if the
      				// heap is sized correctly; for background, refer to the Robson's Proof and the documentation for O1Heap.
      				  printf("canardTxPush Error %ld \n", result);
      			}
      	  }
      	  else
      	  {
      		  printf("uavcan_node_GetInfo_Response_1_0: failed to serialize ! \n");
      	  }
        }
    }
}


	//	Look at top of the TX queue of individual CAN frames
	for (const CanardTxQueueItem* txf = NULL; (txf = canardTxPeek(&canard_Txqueue)) != NULL;)
	{
		// Ensure TX deadline has not expired or not used
	    if ((0U == txf->tx_deadline_usec) || (txf->tx_deadline_usec > (HAL_GetTick()*1000U)))
	    {
			// Send the individual frame and break if no message buffers are available
	    	if((txf->frame.payload_size > 0) && (txf->frame.payload_size <= 8))
	    	{
	    		CAN_TxHeaderTypeDef   TxHeader;
	    		uint8_t               TxData[8] = {0};

	    		HAL_StatusTypeDef 	  CANTx_Status;

				TxHeader.ExtId = txf->frame.extended_can_id;
				TxHeader.RTR   = CAN_RTR_DATA;
				TxHeader.IDE   = CAN_ID_EXT;
				TxHeader.DLC   = CanardCANLengthToDLC[txf->frame.payload_size];//txf->frame.payload_size;
				TxHeader.TransmitGlobalTime = DISABLE;

				memcpy(TxData, (uint8_t*)txf->frame.payload, txf->frame.payload_size);

				CANTx_Status = HAL_CAN_AddTxMessage(&hcan1, &TxHeader, TxData, &TxMailbox);
				if(CANTx_Status != HAL_OK)
				{
					// If the driver is busy, break and retry later.
					break;
				}

	    	}
	    }


	    // After the frame is transmitted or if it has timed out while waiting,
	    // pop it from the queue and deallocate:
	    canard.memory_free(&canard, canardTxPop(&canard_Txqueue, txf));
	}

The problem is not in the queue but in your CAN driver. Look there.

This may be relevant:

Hello,
Setting hcan1.Init.TransmitFifoPriority = ENABLE;
fixed the problem.

No!

You did not really fix it, but rather replaced this problem with another one: the dreaded inner priority inversion. Please do read the section in the specification where this problem is reviewed (you can just search the text for “priority inversion”). Simply relying on the drivers from the chip vendor is a recipe for disaster.

Is implementing the pseudo code (page 65) in the specification good enough ?

Any idea why I am getting this warning:

yakut call 125 uavcan.node.getinfo +M -T1 -Pe
2022-09-06 22:35:21 0002717 WAR yakut.cmd.call: The transport implementation is misbehaving: feedback was never emitted; falling back to software timestamping. Please submit a bug report. Involved instances: client=Client(dtype=uavcan.node.GetInfo.1.0, input_transport_session=CANInputSession(InputSessionSpecifier(data_specifier=ServiceDataSpecifier(service_id=430, role=<Role.RESPONSE: 2>), remote_node_id=125), PayloadMetadata(extent_bytes=448))), result=(uavcan.node.GetInfo.Response.1.0(protocol_version=uavcan.node.Version.1.0(major=1, minor=0), hardware_version=uavcan.node.Version.1.0(major=0, minor=0), software_version=uavcan.node.Version.1.0(major=1, minor=0), software_vcs_revision_id=0, unique_id=[0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0], name='io.ghostrobotics.bms.mcu', software_image_crc=[], certificate_of_authenticity=''), TransferFrom(2022-09-06T22:35:21.094654/6048.999294, priority=EXCEPTIONAL, transfer_id=28, fragmented_payload=[7B+7B+7B+7B+7B+7B+7B+7B+1B], source_node_id=125))
430:
  _meta_: {ts_system: 1662518121.094654, ts_monotonic: 6048.999294, source_node_id: 125, transfer_id: 28, priority: exceptional, dtype: uavcan.node.GetInfo.1.0, rtt: 0.002061}
  protocol_version: {major: 1, minor: 0}
  hardware_version: {major: 0, minor: 0}
  software_version: {major: 1, minor: 0}
  software_vcs_revision_id: 0
  unique_id: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
  name: io.ghost.bms.mcu
  software_image_crc: []
  certificate_of_authenticity: ''

Yes.

The CAN backend you are using with Yakut is not working correctly. This is not related to your node.

Why can’t you simply use this driver? It implements the correct behavior out of the box, unlike the stock driver from the chip vendor.

1 Like

Hi,

I tried that bxcan driver and it is giving me that error in the yakut call. I wanted to understand what it means. However, the Yakut monitor is working fine. I am using a virtual machine (Ubuntu).

WAR yakut.cmd.call: The transport implementation is misbehaving: ...

Thanks.

The driver you use in your MCU cannot possibly have any relation to the warning (not error) you are receiving from Yakut.

Both drivers the HAL and the bxcan one give me the same warning. I wonder where should I look to fix it…

I think it is safe to ignore it in your case. It just says that a certain part of Yakut is not working properly; this is not related to your application. Can you share the Yakut configuration you’re using?

export UAVCAN__CAN__IFACE="socketcan:can0"
export UAVCAN__CAN__MTU=8
export UAVCAN__CAN__BITRATE="500000 500000"
export UAVCAN__NODE__ID=$(yakut accommodate)  # Pick an unoccupied node-ID automatically for this shell session.
echo "Auto-selected node-ID for this session: $UAVCAN__NODE__ID"

yakut, version 0.11.1

Okay, and how is can0 implemented? The error means that the SocketCAN loopback is not implemented correctly by this iface driver.

I do this command for the terminal: yakut call 95 uavcan.node.getinfo +M -T3 -Pe

and i am using a CAN to USB converter (Innomaker) uses socketCAN and the candump is showing the frames correclty , no errors …

It is not a loopback interface, it is real hardware interface STM32 board → CAN/USB converter → Ubuntu VM

To set the CAN up I do the following:

ip link set can0 up type can bitrate 500000
ip link set up can0
ifconfig can0 txqueuelen 1000

I suspect that the adapter is misbehaving, as it is not emitting loopback frames as requested by Yakut. Loopback frames should be sent by the network interface controller or its driver when requested by the application for various purposes, often related to timestamping and delivery confirmation. Yakut uses this for timestamping, which in turn is used for advanced diagnostics.

This has nothing to do with the issue at hand.

Anyway, it is safe to disregard this warning. I suggest you file a defect report against the adapter’s manufacturer and ask them to fix it.

1 Like