Cyphal Arduino

Скачайте библиотеку libcypcal. В libcyphal-docs есть документация с примерами к этой библиотеке.

Давайте рассмотрим два примера - чтение напряжения и передача угла датчика мотора.

Перед написанием примера настоятельно рекомендуем прочитать документацию к регламентированным типам данных. Это существенно облегчит вам понимание особенностей типов и их адресации.

А также изучите пример из 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_0
SUBSCRIPTION_CLASS_MESSAGE(VoltageReader, uavcan_si_unit_voltage_Scalar_1_0, 1111)

Функция, которая обрабатывает полученное сообщение:

void VoltageReader::handler(const uavcan_si_unit_voltage_Scalar_1_0& voltage, CanardRxTransfer* transfer) {
    Serial.print(+transfer->metadata.remote_node_id);
    Serial.print(": ");
    Serial.println(voltage.volt);
}

Создадим указатель на класс VoltageReader

VoltageReader* reader;

В 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 раз в секунду по таймеру. Добавим в код функцию отправки сообщения и функцию прерывания

PREPARE_MESSAGE(uavcan_node_Heartbeat_1_0, hbeat)
void send_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);
}

// Функция таймера
void hbeat_func() {
    digitalWrite(LED2, !digitalRead(LED2));
    send_heartbeat();
    uptime += 1;
}

Все, программа готова. Полный listing кода:

#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();}

// Макрос, объявляющий класс VoltageReader, обрабатывающий ПОЛУЧЕНИЕ uavcan_si_unit_voltage_Scalar_1_0
SUBSCRIPTION_CLASS_MESSAGE(VoltageReader, uavcan_si_unit_voltage_Scalar_1_0, 1111)
// Если все же пользоваться макросами (что я рекомендую), то остается только реализовать функцию-обработчик получения сообщений:
// Сигнатура у них всегда (const ТИП_СООБЩЕНИЯ&, CanardRxTransfer*). Обратите внимание, что первое это константная ссылка, а второе указатель
void VoltageReader::handler(const uavcan_si_unit_voltage_Scalar_1_0& voltage, CanardRxTransfer* transfer) {
    Serial.print(+transfer->metadata.remote_node_id);
    Serial.print(": ");
    Serial.println(voltage.volt);
}
VoltageReader* reader;

void setup() {
  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();
}

void loop() {
    // Вся обработка и fdcan, и cyphal, есть в CyphalInterface::loop
    interface->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)
void send_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);
}

// Функция таймера
void hbeat_func() {
    digitalWrite(LED2, !digitalRead(LED2));
    send_heartbeat();
    uptime += 1;
}

Загружаем ее на плату, открываем SerialMonitor и командную строку. В командной строке отправим сообщение с желаемым напряжением в вольтах:

y pub 1111:uavcan.si.unit.voltage.scalar 3.5

В Serial Monitor вы должны увидеть следующее

Передача угла датчика мотора

Здесь все очень похоже на передачу heartbeat. ДОБАВИТЬ ОТПРАВКУ HEARTBEAT В КОД

#include <SimpleFOC.h>

#include <VBCoreG4_arduino_system.h>
#include <Libcanard2.h>
#include <cyphal.h>
#include <uavcan/si/sample/angle/Scalar_1_0.h>


CanFD canfd;
FDCAN_HandleTypeDef* hfdcan1;

CyphalInterface* interface;

void error_handler() {Serial.println("error"); while (1) {};}
uint64_t micros_64() {return micros();}

//пины SPI3 - mosi, miso, sclk
SPIClass SPI_3(PC12, PC11, PC10);
//пин chip select (может называться cs, nss, ss) - PA15 
//разрешение магнитного датчика - 14
//регистр чтения углов - по умолчанию 0x3FFF
MagneticSensorSPI sensor = MagneticSensorSPI(PA15, 14, 0x3FFF);

void setup() {
    Serial.begin(115200);
    canfd.can_init();
    hfdcan1 = canfd.get_hfdcan();

    interface = new CyphalInterface(99);
    interface->setup<G4CAN, SystemAllocator>(hfdcan1);

    sensor.init(&SPI_3);
    Serial.println("sensor ready");
    delay(1000);
}

PREPARE_MESSAGE(uavcan_si_sample_angle_Scalar_1_0, angle)  // создаст angle_buf, angle_transfer_id
#define ANGLE_PORT_ID 1111
void send_angle(float radian) {
    uavcan_si_sample_angle_Scalar_1_0 angle_msg = {
        .timestamp = {.microsecond=micros_64()},
        .radian = radian
    };
    interface->SEND_MSG(uavcan_si_sample_angle_Scalar_1_0, &angle_msg, angle_buf, ANGLE_PORT_ID, &angle_transfer_id);
}

uint64_t last_send = 0;
#define MICROS_SEC 1000000
void loop() {
    interface->loop();
    sensor.update();
    auto now = micros_64();
    int count = 0;
    if ( (now - last_send) > MICROS_SEC ) {
        last_send = now;
        //float some_angle = 3.14;
        send_angle(sensor.getAngle());
       
    }
}

Last updated