Now I can transmit classic CAN or CANFD messages. Everything is fine here.
Then I have to generate a UAVCAN frame and transmit it via CANbus as a standard message - question how to do this?
Now I can transmit classic CAN or CANFD messages. Everything is fine here.
Then I have to generate a UAVCAN frame and transmit it via CANbus as a standard message - question how to do this?
Use canardTxPush()
/ canardTxPeek()
/ canardTxPop()
as explained in the libcanard documentation.
Thank you!
Hi all!
I can’t translate UAVCAN frame via CANbus
How do I tell the program that CAN_message_t &msg is CanardFrame const & frame
Or how do I pass CanardFrame const & frame through the Can1.write(msg) function;
See sketch below
/**************************************************************************************
* INCLUDE
**************************************************************************************/
#include <Arduino.h>
#include "../lib/UAVCAN/src/ArduinoUAVCAN.h"
#include "../lib/FlexCAN_T4/FlexCAN_T4.h"
/**************************************************************************************
* NAMESPACE
**************************************************************************************/
using namespace uavcan::node;
/**************************************************************************************
* CONSTANTS
**************************************************************************************/
static int const NODE_ID = 126; // от 1 до 127
static int const LED_BLINK_PIN = 2; // UAVCAN Detector
static int const SILENT_CAN_PIN = 21; //
static CanardPortID const BIT_PORT_ID = 1620U; //
/**************************************************************************************
* FUNCTION DECLARATION
**************************************************************************************/
//CAN
void can_normal ();
void can_silent ();
//UAVCAN
bool transmitCanFrame(CanardFrame const &);
/**************************************************************************************
* GLOBAL VARIABLES
**************************************************************************************/
FlexCAN_T4<CAN1, RX_SIZE_256, TX_SIZE_16> Can1;
CAN_message_t msg;
ArduinoUAVCAN uc(NODE_ID, transmitCanFrame);
Heartbeat_1_0<> hb;
/**************************************************************************************
* SETUP/LOOP
**************************************************************************************/
void setup()
{
Serial.begin(9600);
while(!Serial) { }
/* Setup CAN access */
can_normal();
Can1.begin();
Can1.setClock(CLK_16MHz);
Can1.setBaudRate(250000);
//Can1.setMaxMB(16);
//Can1.enableFIFO();
//Can1.enableFIFOInterrupt();
//Can1.onReceive(canSniff);
//Can1.mailboxStatus();
/* Configure initial heartbeat */
hb.data.uptime = 0;
hb = Heartbeat_1_0<>::Health::NOMINAL;
hb = Heartbeat_1_0<>::Mode::INITIALIZATION;
hb.data.vendor_specific_status_code = 0;
}
void loop()
{
/* Update the heartbeat object */
hb.data.uptime = millis() / 1000;
hb = Heartbeat_1_0<>::Mode::OPERATIONAL;
/* Publish the heartbeat once/second */
static unsigned long prev = 0;
unsigned long const now = millis();
if(now - prev > 1000) {
uc.publish(hb);
prev = now;
}
/* Transmit all enqeued CAN frames */
while(uc.transmitCanFrame()) { }
}
/**************************************************************************************
* FUNCTION DEFINITION
**************************************************************************************/
void can_normal()
{
pinMode (SILENT_CAN_PIN, OUTPUT);
digitalWrite(SILENT_CAN_PIN, LOW);
}
void can_silent()
{
pinMode (SILENT_CAN_PIN, OUTPUT);
digitalWrite(SILENT_CAN_PIN, HIGH);
}
bool transmitCanFrame(CanardFrame const & frame)
{
/* ???????????????
How do I tell the program that CAN_message_t &msg is CanardFrame const & frame
Or how do I pass CanardFrame const & frame through the Can1.write(msg) function;
*/
//return Can1.write(msg);
}
I connected two libraries
and
You have to construct a new instance of CAN_message_t
and populate its fields with the values taken from CanardFrame
. The latter can be discarded afterwards.
bool transmitCanFrame(CanardFrame const & frame)
{
CAN_message_t msg;
msg.id = frame.extended_can_id;
msg.buf = reinterpret_cast<uint8_t const *>(frame.payload);
msg.len = static_cast<uint8_t const>(frame.payload_size);
return Can1.write(msg);
}
Get error:
incompatible types in assignment of ‘const uint8_t* {aka const unsigned char*}’ to ‘uint8_t [8] {aka unsigned char [8]}’
Please help
Use std::copy
or std::memcpy
It’s working now!
The data is being transmitted.
Now all that’s left is to learn how to receive it.
But here’s the strange thing. I have a box UAVCAN detector, which listens to the can bus and if it recognizes the heartbeat, it starts blinking LED. In the case of my sketch the LED does not blink. But if I connect a gnss receiver or a pixhawk then the LED blinks. Can it be related to different versions of libcanard?
It’s the different versions of uavcan. Your detector, gnss and pixhawk (and almost every other uavcan device on the market) will be using v0, which is not compatible with v1.
Thanks everyone for the help!
Tomorrow I will continue my experiments. As soon as I get a more or less working prototype, I will post it on the github.
James is right. I wrote on choosing v0 vs. v1 here:
Hi all!
I tried to build a sketch for the second device to receive heartbeat (subscribe) according to the example.
But my serial monitor is silent. At the same time if i look at the messages received via CAN, the publisher transmits the payload correctly.
/**************************************************************************************
* Heartbeat SUBSCRIBE
**************************************************************************************/
/**************************************************************************************
* INCLUDE
**************************************************************************************/
#include <Arduino.h>
#include "../lib/UAVCAN/src/ArduinoUAVCAN.h"
#include "../lib/FlexCAN_T4/FlexCAN_T4.h"
/**************************************************************************************
* NAMESPACE
**************************************************************************************/
using namespace uavcan::node;
/**************************************************************************************
* CONSTANTS
**************************************************************************************/
static int const NODE_ID = 124; // от 1 до 127
static int const LED_BLINK_PIN = 2; // UAVCAN Detector
static int const SILENT_CAN_PIN = 21; //
static CanardPortID const BIT_PORT_ID = 1620U; //
/**************************************************************************************
* FUNCTION DECLARATION
**************************************************************************************/
void can_normal ();
void can_silent ();
void onReceive (const CAN_message_t &);
void onHeartbeat_1_0_Received (CanardTransfer const &, ArduinoUAVCAN &);
/**************************************************************************************
* GLOBAL VARIABLES
**************************************************************************************/
FlexCAN_T4<CAN1, RX_SIZE_256, TX_SIZE_16> Can1;
//CAN_message_t msg;
ArduinoUAVCAN uc(NODE_ID, nullptr);
//Heartbeat_1_0<> hb;
/**************************************************************************************
* SETUP/LOOP
**************************************************************************************/
void setup()
{
Serial.begin(9600);
/* Setup CAN access */
can_normal();
Can1.begin();
Can1.setClock(CLK_60MHz);
Can1.setBaudRate(1000000);
Can1.enableFIFO();
Can1.enableFIFOInterrupt();
Can1.onReceive(onReceive);
/* Subscribe to the reception of Heartbeat message. */
uc.subscribe<Heartbeat_1_0<>>(onHeartbeat_1_0_Received);
}
void loop()
{
}
/**************************************************************************************
* FUNCTION DEFINITION
**************************************************************************************/
void can_normal()
{
pinMode (SILENT_CAN_PIN, OUTPUT);
digitalWrite(SILENT_CAN_PIN, LOW);
}
void can_silent()
{
pinMode (SILENT_CAN_PIN, OUTPUT);
digitalWrite(SILENT_CAN_PIN, HIGH);
}
void onReceive(const CAN_message_t &msg) // received a packet
{
CanardFrame const frame /* create libcanard frame */
{
msg.timestamp, /* timestamp_usec */
msg.id, /* extended_can_id limited to 29 bit */
msg.len, /* payload_size */
(const void *) msg.buf /* payload */
};
uc.onCanFrameReceived(frame);
//DEBUG
//for ( uint8_t i = 0; i < msg.len; i++ ) {
// Serial.print(msg.buf[i], HEX); Serial.print(" ");
//} Serial.println();
}
void onHeartbeat_1_0_Received(CanardTransfer const & transfer, ArduinoUAVCAN & /* uc */)
{
Heartbeat_1_0<> const hb = Heartbeat_1_0<>::deserialize(transfer);
if (hb.data.mode.value)
{
char msg[64];
snprintf(msg, 64,
"ID %02X, Uptime = %lu, Health = %d, Mode = %d, VSSC = %d",
transfer.remote_node_id, hb.data.uptime, hb.data.health.value, hb.data.mode.value, hb.data.vendor_specific_status_code);
Serial.println(msg);
} else {Serial.println("no data");}
}
Can you tell me what may be the problem?
Thank you!
I recommend printing converted instances of CanardFrame just before calling uc.onCanFrameReceived(frame)
to understand what’s happening.
Transmitted frame
LEN: 8 TS: 0 CAN_ID: 107D557B Buffer: 4E 1 0 0 1 2 7 F6
Received frame
LEN: 8 TS: 0 CAN_ID: 57B Buffer: 4E 1 0 0 1 2 7 F6
The difference is only in CAN_ID
Publisher code:
bool transmitCanFrame(CanardFrame const & frame)
{
CAN_message_t msg;
msg.id = frame.extended_can_id;
msg.timestamp = frame.timestamp_usec;
std::copy(reinterpret_cast<uint8_t const *>(frame.payload), reinterpret_cast<uint8_t const *>(frame.payload) + static_cast<uint8_t const>(frame.payload_size), msg.buf);
msg.len = static_cast<uint8_t const>(frame.payload_size);
//uc.onCanFrameReceived(frame);
Can1.write(msg);
led_blink();
if (Serial) {
//Frame decode
Serial.print(" LEN: "); Serial.print(frame.payload_size);
Serial.print(" TS: "); Serial.print(frame.timestamp_usec);
Serial.print(" CAN_ID: "); Serial.print(frame.extended_can_id, HEX);
Serial.print(" Buffer: ");
for ( uint8_t i = 0; i < static_cast<uint8_t const>(frame.payload_size); i++ ) {
Serial.print(reinterpret_cast<uint8_t const *>(frame.payload)[i], HEX); Serial.print(" ");
} Serial.println();
}
return true;
}
Subscriber code:
void onReceive(const CAN_message_t &msg) // received a packet
{
CanardFrame const frame /* create libcanard frame */
{
0, /* timestamp_usec */
msg.id, /* extended_can_id limited to 29 bit */
msg.len, /* payload_size */
(const void *) msg.buf /* payload */
};
if (Serial) {
//Frame decode
Serial.print(" LEN: "); Serial.print(frame.payload_size);
Serial.print(" TS: "); Serial.print(frame.timestamp_usec);
Serial.print(" CAN_ID: "); Serial.print(frame.extended_can_id, HEX);
Serial.print(" Buffer: ");
for ( uint8_t i = 0; i < static_cast<uint8_t const>(frame.payload_size); i++ ) {
Serial.print(reinterpret_cast<uint8_t const *>(frame.payload)[i], HEX); Serial.print(" ");
} Serial.println();
}
uc.onCanFrameReceived(frame);
//Serial.println("OK");
}
You forgot to set msg.flags.extended = true
before transmission. All UAVCAN frames are always extended frames.
Thank you so much!
Everything is working!
Now I’ll clean up the code a bit and upload it to githab.
And we can announce that UAVCAN runs on Teensy 4.0 (IMXRT1062 chip).
I already feel like I might even migrate PX4 to libcanard v 1.0 instead of the original libuavcan
Project already on GitHub
Thanks everyone for the help!
It is already done actually, albeit not yet fully finished. I am certain that PX4 would benefit from some docs around UAVCAN v1 though.
Yes indeed, I just saw it. This is great news.