Документация libcxxcanard
Если лень читать
Рекомедуемая конфигурация: CyphalInterface::create_heap, O1Allocator, DEFAULT_CONFIG, провайдер зависимо от платформы.
Главный класс
CyphalInterface - главный и единственный открытый для пользователя класс, не считая AbstractSubscription.
-
class CyphalInterface
Основной класс со всей функциональностью. Это единственный класс непостредственно из этой библиотеки, экземплляр которого надо создать.
Public Functions
-
inline CyphalInterface(CanardNodeID node_id, const UtilityConfig &config, AbstractCANProvider *provider)
Конструктор, позволяющий самому инициализировать AbstractCANProvider. Не рекомендуется к использованию, всегда предпочитайте
create_bss/create_heap.
-
inline bool is_up()
Проверка, инициализирован ли интерфейс (должна быть всегда
true, если вы использовалиcreate_...).
-
inline size_t queue_size()
Количество FDCAN-сообщений в очереди на отправку.
-
inline bool has_unsent_frames()
Есть ли еще не отправленные фреймы?
-
inline void process_tx_once()
Прокрутить логику обработки исходящих сообщений один раз.
-
void loop()
Обрабатывать входящие/исходящие сообщения. НЕ бесконечный цикл, характерное использование:
while (...) { interface->loop(); }
-
template<typename TypeAlias>
inline void send_msg(typename TypeAlias::Type *obj, CanardPortID port, CanardTransferID *transfer_id, uint64_t timeout_delta = DEFAULT_TIMEOUT_MICROS, CanardPriority priority = CanardPriorityNominal) const Поставить одно сообщение в очередь на отправку.
- Parameters:
obj – Указатель на сообщение (cyphal-структура)
port – PortID назначения
transfer_id – TransferID - отдельные для каждого port и не забывайте инкрементировать!
timeout_delta – Таймаут отправки в нс - по умочанию 1с
priority – Приоритет сообщения
-
template<typename TypeAlias>
inline void send_response(typename TypeAlias::Type *obj, CanardRxTransfer *transfer, uint64_t timeout_delta = DEFAULT_TIMEOUT_MICROS) const Отправить ответ на запрос.
- Parameters:
obj – Указатель на сообщение (cyphal-структура)
transfer – Структура CanardRxTransfer полученная вместе с запросом
timeout_delta – Таймаут отправки в нс - по умочанию 1с
-
template<typename TypeAlias>
inline void send_request(typename TypeAlias::Type *obj, CanardPortID port, CanardTransferID *transfer_id, CanardNodeID to_node_id, uint64_t timeout_delta = DEFAULT_TIMEOUT_MICROS, CanardPriority priority = CanardPriorityNominal) const Отправить запрос
- Parameters:
obj – Указатель на сообщение (cyphal-структура)
port – PortID назначения
transfer_id – TransferID - отдельные для каждого port и не забывайте инкрементировать!
to_node_id – NodeID узла назначения
timeout_delta – Таймаут отправки в нс - по умочанию 1с
priority – Приоритет сообщения
Public Static Functions
-
template<typename Provider, class Allocator, class ...Args>
static inline CyphalInterface *create_bss(std::byte *buffer, CanardNodeID node_id, typename Provider::Handler handler, size_t queue_len, Args&&... args, const UtilityConfig &config) Инициализировать CyphalInterface в глобальной памяти (.bss), не использует кучу.
- Parameters:
buffer – Буффер размера
sizeof(CyphalInterface) + sizeof(выбранный_провайдер) + sizeof(выбранный_аллокатор)node_id – ID текущей ноды
handler – Низкоуровневый интерфейс CAN. Для linux просто строка “can0”/”can1”. Для stm32 - обычно
&hfdcan1.queue_len – Размер очереди сообщений
args – Variadic параметры, которые будут переданы в provider.
config – Ссылка на UtilityConfig.
Инициализировать CyphalInterface на куче. Гораздо удобнее чем .bss, выделяет память только на старте программы и столько же сколько и
create_bss, поэтому если можете пользоваться кучей - пользуйтесь этим методом.- Parameters:
node_id – ID текущей ноды
handler – Низкоуровневый интерфейс CAN. Для linux просто строка “can0”/”can1”. Для stm32 - обычно
&hfdcan1.queue_len – Размер очереди сообщений
args – Variadic параметры, которые будут переданы в provider.
config – Ссылка на UtilityConfig.
-
inline CyphalInterface(CanardNodeID node_id, const UtilityConfig &config, AbstractCANProvider *provider)
Провайдеры (/providers)
Конструкторами провайдеров лучше не пользоваться напрямую, их вызывает фабричный метод в CyphalInterface. То, какой конструктор вызовется, зависит от переданных аргументов.
-
class AbstractCANProvider
Абстрактная обертка вокруг основного функционала CAN.
-
class LinuxCAN : public AbstractCANProvider
Реализация для linux, работает на основне SocketCAN. Аргументы для конструкторов смотри в
CyphalInterface::create_bss / CyphalInterface::create_heap(фабричные методы).
-
class G4CAN : public AbstractCANProvider
Реализация для stm32g4, работает на основне SocketCAN. Аргументы для конструкторов смотри в
CyphalInterface::create_bss / CyphalInterface::create_heap(фабричные методы).
Аллокаторы (/allocators)
Конструкторами аллокаторов лучше не пользоваться напрямую, их вызывает фабричный метод в CyphalInterface. То, какой конструктор вызовется, зависит от переданных аргументов.
-
class AbstractAllocator
Абстрактный менеджер памяти. Сам по себе ничего не делает, вместо него надо передавать экземпляр наследника -
o1илиsys.Subclassed by O1Allocator, SystemAllocator
-
class SystemAllocator : public AbstractAllocator
Наивный менеджер памяти, просто обертка вокруг malloc и free.
-
class O1Allocator : public AbstractAllocator
Обертка вокруг O1Heap. Рекомендуемый аллокатор для cyphal. Можем аллоцировать память для себя сам при создании, может принять указатель на заранее выделенный участок.
Public Functions
-
O1Allocator(size_t size, void *memory, const UtilityConfig &utilities)
Создать на основе заранее выделенной памяти.
- Parameters:
size – Размер буффера
memory – Указатель на выделенный сегмент
-
explicit O1Allocator(size_t size, const UtilityConfig &utilities)
Создать аллокатор, который выдеит себя память сам.
- Parameters:
size – Размер буффера
-
O1Allocator(size_t size, void *memory, const UtilityConfig &utilities)
Подписки (/subscriptions)
-
template<typename T>
class AbstractSubscription : public IListener<CanardRxTransfer*> TODO
Утилиты
-
struct UtilityConfig
Коллекция разных функций, требуемых для работы cyphal: микросекунды и обработчик ошибок. Не очень типично для linux, но привычно на stm32 - поэтому используется везде ради кроссплатформенности.
Public Functions
-
inline explicit UtilityConfig(micros_64_type &µs, error_handler_type &&handler) noexcept
- Parameters:
micros – Функция (функтор), возвращающая
uint64_tмикросекундыhandler – Функция - “*что делать при ошибке*”. На stm32 обычно просто
Error_Handler, на linux - что угодно, можно простоexit().
-
inline explicit UtilityConfig(micros_64_type &µs, error_handler_type &&handler) noexcept