А также изучите пример из libcyphal-docs. Тут идет передача и чтение heartbeat. Все узлы Cyphal, имеющие node-ID, обязаны периодически публиковать это сообщение в закрепленном за ними топике.
Чтение напряжения из топика
Подключаем все нужные библиотеки и заголовочные файлы
#include <VBCoreG4_arduino_system.h> // системный хэдер
#include <Libcanard2.h> // базовые библиотеки (canard, uavcan, etc.)
#include <cyphal.h> // сам libcyphal
#include <uavcan/si/unit/voltage/Scalar_1_0.h> // тип сообщения, которе будем использовать
#include <uavcan/node/Heartbeat_1_0.h>
// Настройка fdcan из VBCoreG4
CanFD canfd;
FDCAN_HandleTypeDef* hfdcan1;
// Таймер, по прерыванию которого будем посылать сообщения
uint32_t uptime = 0;
HardwareTimer *timer = new HardwareTimer(TIM3);
// Класс с API для доступа к cyphal
CyphalInterface* interface;
// Объявим функцию, которую libcyphal будем вызывать для обработки ошибок
void error_handler() {Serial.println("error"); while (1) {};}
uint64_t micros_64() {return micros();}
SUBSCRIPTION_CLASS_MESSAGE - это макрос, который объявляет класс VoltageReader. Вы можете дать классу любое другое имя - VoltReader, Reader и т.д. Не забудьте в качестве 3 аргумента передать топик, в котором будет публиковаться сообщение с напряжением.
Описание всех макросов вы можете найти в файле cyphal/subscriptions/subscription.h
// Макрос, объявляющий класс VoltageReader, обрабатывающий ПОЛУЧЕНИЕ uavcan_si_unit_voltage_Scalar_1_0SUBSCRIPTION_CLASS_MESSAGE(VoltageReader, uavcan_si_unit_voltage_Scalar_1_0,1111)
Функция, которая обрабатывает полученное сообщение:
В setup() запустим can, cancyphal и настроим таймер
Serial.begin(115200);
// запускаем can
canfd.can_init();
hfdcan1 = canfd.get_hfdcan();
// "Запускаем" cyphal, id нашего узла будет 99
interface = new CyphalInterface(99);
// Инициализация - мы находимся на G4, алокатор памяти - системный
// NOTE: в следующей версии, setup может пропасть и достаточно будет просто сделать
// new CyphalInterface<G4CAN, SystemAllocator>(99, hfdcan1);
interface->setup<G4CAN, SystemAllocator>(hfdcan1);
// Создаем обработчик сообщений, который объявили выше
reader = new VoltageReader(interface);
// Настраиваем таймер на прерывания раз в секунду
timer->pause();
timer->setOverflow(1, HERTZ_FORMAT);
timer->attachInterrupt(hbeat_func);
timer->refresh();
timer->resume();
В сновном цикле вызываем функцию cyphal интерфейса - loop.
interface->loop();
Напомним, что все узлы cyphal должны публиковать сообщение heartbeat. Наш узел это делает 1 раз в секунду по таймеру. Добавим в код функцию отправки сообщения и функцию прерывания
#include<VBCoreG4_arduino_system.h>// системный хэдер#include<Libcanard2.h>// базовые библиотеки (canard, uavcan, etc.)#include<cyphal.h>// сам libcyphal#include<uavcan/si/unit/voltage/Scalar_1_0.h>// тип сообщения, которе будем использовать#include<uavcan/node/Heartbeat_1_0.h>// Настройка fdcan из VBCoreG4CanFD canfd;FDCAN_HandleTypeDef* hfdcan1;// Таймер, по прерыванию которого будем посылать сообщенияuint32_t uptime =0;HardwareTimer *timer =newHardwareTimer(TIM3);// Класс с API для доступа к cyphalCyphalInterface* interface;// Объявим функцию, которую libcyphal будем вызывать для обработки ошибокvoiderror_handler() {Serial.println("error"); while (1) {};}uint64_tmicros_64() {returnmicros();}// Макрос, объявляющий класс VoltageReader, обрабатывающий ПОЛУЧЕНИЕ uavcan_si_unit_voltage_Scalar_1_0SUBSCRIPTION_CLASS_MESSAGE(VoltageReader, uavcan_si_unit_voltage_Scalar_1_0,1111)// Если все же пользоваться макросами (что я рекомендую), то остается только реализовать функцию-обработчик получения сообщений:// Сигнатура у них всегда (const ТИП_СООБЩЕНИЯ&, CanardRxTransfer*). Обратите внимание, что первое это константная ссылка, а второе указательvoid VoltageReader::handler(constuavcan_si_unit_voltage_Scalar_1_0& voltage,CanardRxTransfer* transfer) {Serial.print(+transfer->metadata.remote_node_id);Serial.print(": ");Serial.println(voltage.volt);}VoltageReader* reader;voidsetup() {Serial.begin(115200); // запускаем cancanfd.can_init(); hfdcan1 =canfd.get_hfdcan(); // "Запускаем" cyphal, id нашего узла будет 99 interface =newCyphalInterface(99); // Инициализация - мы находимся на G4, алокатор памяти - системный // NOTE: в следующей версии, setup может пропасть и достаточно будет просто сделать // new CyphalInterface<G4CAN, SystemAllocator>(99, hfdcan1);interface->setup<G4CAN, SystemAllocator>(hfdcan1); // Создаем обработчик сообщений, который объявили выше reader =newVoltageReader(interface); // Настраиваем таймер на прерывания раз в секундуtimer->pause();timer->setOverflow(1, HERTZ_FORMAT);timer->attachInterrupt(hbeat_func);timer->refresh();timer->resume();}voidloop() { // Вся обработка и fdcan, и cyphal, есть в CyphalInterface::loopinterface->loop();}/* * Макрос, прячущий шаблонный код для объявления всякого для ОТПРАВКИ сообщений * Раскрывается в:uint8_t hbeat_buf[uavcan_node_Heartbeat_1_0_EXTENT_BYTES_];CanardTransferID hbeat_transfer_id = 0; * Объявлен в cyphal/cyphal.h */PREPARE_MESSAGE(uavcan_node_Heartbeat_1_0, hbeat)voidsend_heartbeat() { // Заполняем сообщение uavcan_node_Heartbeat_1_0 heartbeat_msg = {.uptime = uptime, .health = {uavcan_node_Health_1_0_NOMINAL}, .mode = {uavcan_node_Mode_1_0_OPERATIONAL}}; // Отправляем сообщениеinterface->SEND_MSG(uavcan_node_Heartbeat_1_0,&heartbeat_msg, hbeat_buf, uavcan_node_Heartbeat_1_0_FIXED_PORT_ID_,&hbeat_transfer_id);}// Функция таймераvoidhbeat_func() {digitalWrite(LED2,!digitalRead(LED2));send_heartbeat(); uptime +=1;}
Загружаем ее на плату, открываем SerialMonitor и командную строку. В командной строке отправим сообщение с желаемым напряжением в вольтах:
y pub 1111:uavcan.si.unit.voltage.scalar 3.5
В Serial Monitor вы должны увидеть следующее
Передача угла датчика мотора
Здесь все очень похоже на передачу heartbeat. ДОБАВИТЬ ОТПРАВКУ HEARTBEAT В КОД