123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566 |
- #pragma once
- #include <inttypes.h>
- #include <AP_HAL/HAL.h>
- #include "Semaphores.h"
- #include "AP_HAL_ChibiOS.h"
- #if HAL_USE_I2C == TRUE || HAL_USE_SPI == TRUE
- #include "Scheduler.h"
- #include "shared_dma.h"
- #include "hwdef/common/bouncebuffer.h"
- namespace ChibiOS {
- class DeviceBus {
- public:
- DeviceBus(uint8_t _thread_priority = APM_I2C_PRIORITY);
- struct DeviceBus *next;
- Semaphore semaphore;
- Shared_DMA *dma_handle;
- AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb, AP_HAL::Device *hal_device);
- bool adjust_timer(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec);
- static void bus_thread(void *arg);
- void bouncebuffer_setup(const uint8_t *&buf_tx, uint16_t tx_len,
- uint8_t *&buf_rx, uint16_t rx_len);
- void bouncebuffer_finish(const uint8_t *buf_tx, uint8_t *buf_rx, uint16_t rx_len);
-
- private:
- struct callback_info {
- struct callback_info *next;
- AP_HAL::Device::PeriodicCb cb;
- uint32_t period_usec;
- uint64_t next_usec;
- } *callbacks;
- uint8_t thread_priority;
- thread_t* thread_ctx;
- bool thread_started;
- AP_HAL::Device *hal_device;
-
- struct bouncebuffer_t *bounce_buffer_tx;
- struct bouncebuffer_t *bounce_buffer_rx;
- };
- }
- #endif
|