Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_DroneCAN/AP_Canard_iface.h
Views: 1798
#pragma once1#include <AP_HAL/AP_HAL.h>2#if HAL_ENABLE_DRONECAN_DRIVERS3#include <canard/interface.h>4#include <dronecan_msgs.h>56class AP_DroneCAN;7class CANSensor;89class CanardInterface : public Canard::Interface {10friend class AP_DroneCAN;11public:1213/// @brief delete copy constructor and assignment operator14CanardInterface(const CanardInterface&) = delete;15CanardInterface& operator=(const CanardInterface&) = delete;1617CanardInterface(uint8_t driver_index);1819void init(void* mem_arena, size_t mem_arena_size, uint8_t node_id);2021/// @brief broadcast message to all listeners on Interface22/// @param bc_transfer23/// @return true if message was added to the queue24bool broadcast(const Canard::Transfer &bcast_transfer) override;2526/// @brief request message from27/// @param destination_node_id28/// @param req_transfer29/// @return true if request was added to the queue30bool request(uint8_t destination_node_id, const Canard::Transfer &req_transfer) override;3132/// @brief respond to a request33/// @param destination_node_id34/// @param res_transfer35/// @return true if response was added to the queue36bool respond(uint8_t destination_node_id, const Canard::Transfer &res_transfer) override;3738void processTx(bool raw_commands_only);39void processRx();4041void process(uint32_t duration);4243static void onTransferReception(CanardInstance* ins, CanardRxTransfer* transfer);44static bool shouldAcceptTransfer(const CanardInstance* ins,45uint64_t* out_data_type_signature,46uint16_t data_type_id,47CanardTransferType transfer_type,48uint8_t source_node_id);4950bool add_interface(AP_HAL::CANIface *can_drv);5152// add an auxillary driver for 11 bit frames53bool add_11bit_driver(CANSensor *sensor);5455// handler for outgoing frames for auxillary drivers56bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us);5758#if AP_TEST_DRONECAN_DRIVERS59static CanardInterface& get_test_iface() { return test_iface; }60static void processTestRx();61#endif6263void update_rx_protocol_stats(int16_t res);6465uint8_t get_node_id() const override { return canard.node_id; }66private:67CanardInstance canard;68AP_HAL::CANIface* ifaces[HAL_NUM_CAN_IFACES];69#if AP_TEST_DRONECAN_DRIVERS70static CanardInterface* canard_ifaces[3];71static CanardInterface test_iface;72#endif73uint8_t num_ifaces;74HAL_BinarySemaphore sem_handle;75bool initialized;76HAL_Semaphore _sem_tx;77HAL_Semaphore _sem_rx;78CanardTxTransfer tx_transfer;79dronecan_protocol_Stats protocol_stats;8081// auxillary 11 bit CANSensor82CANSensor *aux_11bit_driver;83};84#endif // HAL_ENABLE_DRONECAN_DRIVERS858687