ardupilot/libraries/AP_HAL_ChibiOS/shared_dma.h
Andy Piper 9f30d01561 AP_HAL_ChibiOS: bdshot for f103 iofirmware
add support to tell if shared DMA channel is actually shared
avoid starting and stopping the timer peripheral with bdshot
ensure that rcout DMA allocation and deallocation happens entirely within the lock
increase rcout thread working area for bdshot
fix mode mask that is sent to the iomcu
ensure iomcu rcout thread gets timeouts for callbacks
control bdshot input and output line levels on f103
use input capture channel pairs to read rising and falling edges of telemetry on f103
reset channel pairs together on iomcu
generalize the bdshot input path to support suitable buffer sizes for iomcu
generalize DMAR reading of CCR registers to read two at a time on iomcu
enable bi-directional dshot channels on PWM1-4 on iomcu
add methods to directly access erpm values from rcout
update erpm mask and esc telemetry correctly for firmware supporting dshot
add support for propagating bdmask to iomcu
dshot commands to all channels need to be aware of iomcu
ensure esc type is propagated to iomcu
cope with iomcu channel numbering when using EDT
ensure pwm driver is reset properly for dshot commands on iomcu
correctly reset pwm for dshot commands
correctly mask off bdshot bits going to iomcu
don't reset GPIO modes on disabled lines
don't reset pwm_started when sharing DMA channels
set thread name on iomcu rcout and reduce stack size on iomcu
ensure that bdshot pulses with no response are handled correctly
correctly setup DMA for input capture on f103
deal with out of order captured bytes when decoding bdshot telemetry
ensure DMA sharing on f103 does not pull lines low
only disable the timer peripheral when switching DMA channels on iomcu
add support for waiting for _UP to finish before proceeding with dshot
re-order iomcu dshot channels to let TIM4_UP go first
ensure that a cascading event will always come when expected on rcout
allow timeouts when using cascading dshot
always rotate telemetry channel after trying to capture input
cater for both in order and out-of-order bdshot telemetry packets
cope with reversed packets when decoding bdshot telemetry
ensure UP DMA channel is fully free on iomcu before starting next dshot cycle
refactor rcout for iofirmware into separate file
2023-12-18 19:02:52 +11:00

119 lines
3.6 KiB
C++

/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* Code by Andrew Tridgell and Siddharth Bharat Purohit
*/
#pragma once
#include "AP_HAL_ChibiOS.h"
#define SHARED_DMA_MAX_STREAM_ID (8*2)
// DMA stream ID for stream_id2 when only one is needed
#define SHARED_DMA_NONE 255
#if AP_HAL_SHARED_DMA_ENABLED
class ChibiOS::Shared_DMA
{
public:
FUNCTOR_TYPEDEF(dma_allocate_fn_t, void, Shared_DMA *);
FUNCTOR_TYPEDEF(dma_deallocate_fn_t, void, Shared_DMA *);
// the use of two stream IDs is for support of peripherals that
// need both a RX and TX DMA channel
Shared_DMA(uint8_t stream_id1, uint8_t stream_id2,
dma_allocate_fn_t allocate,
dma_allocate_fn_t deallocate);
// initialise the stream locks
static void init(void);
// blocking lock call
void lock(void);
// non-blocking lock call
bool lock_nonblock(void);
// unlock call. The DMA channel will not be immediately
// deallocated. Instead it will be deallocated if another driver
// needs it
void unlock(bool success = true);
//should be called inside the destructor of Shared DMA participants
void unregister(void);
// return true if this DMA channel is being actively contended for
// by multiple drivers
bool has_contention(void) const { return contention; }
// is this DMA channel locked?
bool is_locked(void) const { return have_lock; }
// lock all shared DMA channels. Used on reboot
static void lock_all(void);
// display dma contention statistics as text buffer for @SYS/dma.txt
static void dma_info(ExpandingString &str);
// return true if a stream ID is shared between two peripherals
static bool is_shared(uint8_t stream_id);
bool is_shared();
private:
dma_allocate_fn_t allocate;
dma_allocate_fn_t deallocate;
uint8_t stream_id1;
uint8_t stream_id2;
bool have_lock;
// we set the contention flag if two drivers are fighting over a DMA channel.
// the UART driver uses this to change its max transmit size to reduce latency
bool contention;
// core of lock call, after semaphores gained
void lock_core(void);
// lock one stream
static bool lock_stream(uint8_t stream_id);
// unlock one stream
void unlock_stream(uint8_t stream_id, bool success);
// lock one stream, non-blocking
bool lock_stream_nonblocking(uint8_t stream_id);
static struct dma_lock {
// semaphore to ensure only one peripheral uses a DMA channel at a time
#if CH_CFG_USE_MUTEXES == TRUE
mutex_t mutex;
#endif // CH_CFG_USE_MUTEXES
// a de-allocation function that is called to release an existing user
dma_deallocate_fn_t deallocate;
// point to object that holds the allocation, if allocated
Shared_DMA *obj;
} locks[SHARED_DMA_MAX_STREAM_ID+1];
// contention statistics
static volatile struct dma_stats {
uint32_t contended_locks;
uint32_t uncontended_locks;
uint32_t transactions;
} *_contention_stats;
};
#endif // AP_HAL_SHARED_DMA_ENABLED