Когда устройство становится достаточно сложным, появляется потребность в коммуникации между контроллерами, или между контроллером и компьютером (например, Raspberry Pi). Для этого в микроконтроллерах STM32G4 встроен модуль FDCAN. Этот протокол является популярным и достаточно гибким способом построения коммуникационных сетей, однако он не предоставляет никаких абстракций над пакетами байтов, которыми оперирует.
Для целей общения между устройствами, нами был выбран прокол , создающий слой абстракции над FDCAN без потерь в скорости и дающий возможность передавать структурированные сообщения произвольной длины, а не просто байты.
У этого протокола есть и множество других достоинств, описание всего протокола выходит за рамки этой докуменации, подробнее о нем можно прочитать .
libcxxcanard
Нами была разработана и проверена на множестве устройств универсальная C++ библиотека для работы с cyphal (на основе libcanard) - . Далее будет дан обзор возможностей и типичных примеров использования данной библиотеки.
Подробная документация -
Примеры -
Короткое сравнение с libcanard
libcxxcanard основана на libcanard и призвана упростить ее использование. Далее несколько наглядных сравнений "на пальцах" (на картинки лучше нажать, чтоб рассмотреть подробнее):
Дальше будут параллельно разбираться примеры для linux (raspberry pi) и stm32g4. Считается, что сделаны следующие инклюды:
Код инициализации короткий и кроссплатформенный, надо только выбрать нужный провайдер:
#include <cyphal/providers/LinuxCAN.h>
std::shared_ptr<CyphalInterface> cyphal_interface;
void main() {
cyphal_interface = std::shared_ptr<CyphalInterface>(CyphalInterface::create_heap<LinuxCAN, O1Allocator>(
NODE_ID,
"can0", // SocketCAN
200, // длина очереди
DEFAULT_CONFIG // дефолтные настройки для линукса, объявлены в библиотеке
));
}
#include <cyphal/providers/G4CAN.h>
static std::shared_ptr<CyphalInterface> cyphal_interface;
// Необходимо определить для репорта ошибок - просто вызовем дефолтный хэндлер
// Но можно делать и что-то более разумное - например:
// https://github.com/voltbro/gyrobro_foc/blob/feature/mech-angle/App/communication.cpp#L47
void error_handler() {
Error_Handler();
}
// micros_64 - надо объявить отдельно, с помощью таймера
// или для ленивых HAL_GetTick()*1000
UtilityConfig utilities(micros_64, cyphal_error_handler);
void main() {
cyphal_interface = std::shared_ptr<CyphalInterface>(CyphalInterface::create_heap<G4CAN, O1Allocator>(
NODE_ID,
&hfdcan1, // считаем что настроен, например через CubeMX
200, // длина очереди
utilities // объявлен выше
));
}
Подписки и отправка сообщений
По сравнению с libcanard, работа с отправкой/приемом сообщений гораздо проще. Есть единственное неудобство: из-за того что libcxxcanard работает поверх сишного libcanard, для любого используемого типа сообщений нужно (единожды) использовать макрос TYPE_ALIAS - TYPE_ALIAS(УдобноеНовоеНазваниеТипа, сгенерированный_cyhal_тип_сообщения).
Минимальный пример, echo-сервиса:
#include <voltbro/echo/echo_servoce_1_0.h>
TYPE_ALIAS(EchoRequest, voltbro_echo_echo_service_Request_1_0)
TYPE_ALIAS(EchoResponse, voltbro_echo_echo_service_Response_1_0)
// Подписки наследуются от шаблонного класса AbstractSubscription
// 1000 - port_id для сервиса
class EchoSub: public AbstractSubscription<EchoRequest> {
public:
EchoSub(InterfacePtr interface):
AbstractSubscription<EchoRequest>(interface, 1000)
{};
void handler(const EchoRequest::Type& request, CanardRxTransfer* transfer) override {
EchoResponse::Type response = {.pong = request.ping};
interface->send_response<EchoResponse>(&response, transfer);
}
};
std::shared_ptr<EchoSub> echo_sub;
void main() {
// ... сначала тут описанная выше инициализация cyphal
echo_sub = std::make_shared<EchoSub>(cyphal_interface);
}
#include <voltbro/echo/echo_servoce_1_0.h>
TYPE_ALIAS(EchoRequest, voltbro_echo_echo_service_Request_1_0)
TYPE_ALIAS(EchoResponse, voltbro_echo_echo_service_Response_1_0)
// Подписки наследуются от шаблонного класса AbstractSubscription
// 1000 - port_id для сервиса
class EchoSub: public AbstractSubscription<EchoRequest> {
public:
EchoSub(InterfacePtr interface):
AbstractSubscription<EchoRequest>(interface, 1000)
{};
void handler(const EchoRequest::Type& request, CanardRxTransfer* transfer) override {
EchoResponse::Type response = {.pong = request.ping};
interface->send_response<EchoResponse>(&response, transfer);
}
};
std::shared_ptr<EchoSub> echo_sub;
void main() {
// ... сначала тут описанная выше инициализация cyphal
echo_sub = std::make_shared<EchoSub>(cyphal_interface);
}
// Пример настройки хардварных фильтров для подписки, актуально только для STM32
void setup_filters() {
HAL_FDCAN_ConfigGlobalFilter(
&hfdcan1,
FDCAN_REJECT,
FDCAN_REJECT,
FDCAN_REJECT_REMOTE,
FDCAN_REJECT_REMOTE
);
static FDCAN_FilterTypeDef sFilterConfig;
// Хардварный фильтр для пордписки. apply_filter - из libcxxcanard
apply_filter(&hfdcan1, &sFilterConfig,echo_sub->make_filter(NODE_ID))
}
Развернутый пример подписчика на обычные сообщения, связанного с ROS (для linux):