APM:Libraries
Device.h
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify
3  * it under the terms of the GNU General Public License as published
4  * by the Free Software Foundation, either version 3 of the License,
5  * or (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
10  * General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License
13  * along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #pragma once
16 
17 #include <inttypes.h>
18 #include <AP_HAL/HAL.h>
19 #include "Semaphores.h"
20 #include "Scheduler.h"
21 #include "shared_dma.h"
22 
23 namespace ChibiOS {
24 
25 class DeviceBus {
26 public:
27  DeviceBus(uint8_t _thread_priority = APM_I2C_PRIORITY) :
28  thread_priority(_thread_priority) {}
29 
30  struct DeviceBus *next;
33 
34  AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb, AP_HAL::Device *hal_device);
35  bool adjust_timer(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec);
36  static void bus_thread(void *arg);
37 
38  void bouncebuffer_setup(const uint8_t *&buf_tx, uint16_t tx_len,
39  uint8_t *&buf_rx, uint16_t rx_len);
40 
41  void bouncebuffer_setup_tx(const uint8_t *&buf_tx, uint16_t tx_len);
42 
43  void bouncebuffer_setup_rx(uint8_t *&buf_rx, uint16_t rx_len);
44 
45  void bouncebuffer_rx_copy(uint8_t *buf_rx, uint16_t rx_len);
46 
47 private:
48  struct callback_info {
50  AP_HAL::Device::PeriodicCb cb;
51  uint32_t period_usec;
52  uint64_t next_usec;
53  } *callbacks;
54  uint8_t thread_priority;
55  thread_t* thread_ctx;
58 
59  // support for bounce buffers for DMA-safe transfers
60  uint8_t *bounce_buffer_tx;
61  uint8_t *bounce_buffer_rx;
64 };
65 
66 }
struct ChibiOS::DeviceBus::callback_info * callbacks
uint16_t bounce_buffer_tx_size
Definition: Device.h:62
uint8_t thread_priority
Definition: Device.h:54
thread_t * thread_ctx
Definition: Device.h:55
void bouncebuffer_setup(const uint8_t *&buf_tx, uint16_t tx_len, uint8_t *&buf_rx, uint16_t rx_len)
Definition: Device.cpp:150
DeviceBus(uint8_t _thread_priority=APM_I2C_PRIORITY)
Definition: Device.h:27
Shared_DMA * dma_handle
Definition: Device.h:32
#define APM_I2C_PRIORITY
Definition: Scheduler.h:56
Semaphore semaphore
Definition: Device.h:31
void * PeriodicHandle
Definition: Device.h:42
uint8_t * bounce_buffer_rx
Definition: Device.h:61
static void bus_thread(void *arg)
Definition: Device.cpp:33
uint8_t * bounce_buffer_tx
Definition: Device.h:60
void bouncebuffer_setup_tx(const uint8_t *&buf_tx, uint16_t tx_len)
Definition: Device.cpp:157
struct DeviceBus * next
Definition: Device.h:30
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb, AP_HAL::Device *hal_device)
Definition: Device.cpp:84
uint16_t bounce_buffer_rx_size
Definition: Device.h:63
bool adjust_timer(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec)
Definition: Device.cpp:133
bool thread_started
Definition: Device.h:56
AP_HAL::Device::PeriodicCb cb
Definition: Device.h:50
void bouncebuffer_setup_rx(uint8_t *&buf_rx, uint16_t rx_len)
Definition: Device.cpp:176
struct callback_info * next
Definition: Device.h:49
AP_HAL::Device * hal_device
Definition: Device.h:57
void bouncebuffer_rx_copy(uint8_t *buf_rx, uint16_t rx_len)
Definition: Device.cpp:197