WPILibC++ 2024.3.2
DMA Functions

Classes

struct  HAL_DMASample
 Buffer for containing all DMA data for a specific sample. More...
 

Enumerations

enum  HAL_DMAReadStatus : int32_t { HAL_DMA_OK = 1 , HAL_DMA_TIMEOUT = 2 , HAL_DMA_ERROR = 3 }
 The DMA Read Status. More...
 

Functions

HAL_DMAHandle HAL_InitializeDMA (int32_t *status)
 Initializes an object for performing DMA transfers. More...
 
void HAL_FreeDMA (HAL_DMAHandle handle)
 Frees a DMA object. More...
 
void HAL_SetDMAPause (HAL_DMAHandle handle, HAL_Bool pause, int32_t *status)
 Pauses or unpauses a DMA transfer. More...
 
void HAL_SetDMATimedTrigger (HAL_DMAHandle handle, double periodSeconds, int32_t *status)
 Sets DMA transfers to occur at a specific timed interval. More...
 
void HAL_SetDMATimedTriggerCycles (HAL_DMAHandle handle, uint32_t cycles, int32_t *status)
 Sets DMA transfers to occur at a specific timed interval in FPGA cycles. More...
 
void HAL_AddDMAEncoder (HAL_DMAHandle handle, HAL_EncoderHandle encoderHandle, int32_t *status)
 Adds position data for an encoder to be collected by DMA. More...
 
void HAL_AddDMAEncoderPeriod (HAL_DMAHandle handle, HAL_EncoderHandle encoderHandle, int32_t *status)
 Adds timer data for an encoder to be collected by DMA. More...
 
void HAL_AddDMACounter (HAL_DMAHandle handle, HAL_CounterHandle counterHandle, int32_t *status)
 Adds position data for an counter to be collected by DMA. More...
 
void HAL_AddDMACounterPeriod (HAL_DMAHandle handle, HAL_CounterHandle counterHandle, int32_t *status)
 Adds timer data for an counter to be collected by DMA. More...
 
void HAL_AddDMADigitalSource (HAL_DMAHandle handle, HAL_Handle digitalSourceHandle, int32_t *status)
 Adds a digital source to be collected by DMA. More...
 
void HAL_AddDMAAnalogInput (HAL_DMAHandle handle, HAL_AnalogInputHandle aInHandle, int32_t *status)
 Adds an analog input to be collected by DMA. More...
 
void HAL_AddDMAAveragedAnalogInput (HAL_DMAHandle handle, HAL_AnalogInputHandle aInHandle, int32_t *status)
 Adds averaged data of an analog input to be collected by DMA. More...
 
void HAL_AddDMAAnalogAccumulator (HAL_DMAHandle handle, HAL_AnalogInputHandle aInHandle, int32_t *status)
 Adds accumulator data of an analog input to be collected by DMA. More...
 
void HAL_AddDMADutyCycle (HAL_DMAHandle handle, HAL_DutyCycleHandle dutyCycleHandle, int32_t *status)
 Adds a duty cycle input to be collected by DMA. More...
 
int32_t HAL_SetDMAExternalTrigger (HAL_DMAHandle handle, HAL_Handle digitalSourceHandle, HAL_AnalogTriggerType analogTriggerType, HAL_Bool rising, HAL_Bool falling, int32_t *status)
 Sets DMA transfers to occur on an external trigger. More...
 
void HAL_ClearDMASensors (HAL_DMAHandle handle, int32_t *status)
 Clear all sensors from the DMA collection list. More...
 
void HAL_ClearDMAExternalTriggers (HAL_DMAHandle handle, int32_t *status)
 Clear all external triggers from the DMA trigger list. More...
 
void HAL_StartDMA (HAL_DMAHandle handle, int32_t queueDepth, int32_t *status)
 Starts DMA Collection. More...
 
void HAL_StopDMA (HAL_DMAHandle handle, int32_t *status)
 Stops DMA Collection. More...
 
void * HAL_GetDMADirectPointer (HAL_DMAHandle handle)
 Gets the direct pointer to the DMA object. More...
 
enum HAL_DMAReadStatus HAL_ReadDMADirect (void *dmaPointer, HAL_DMASample *dmaSample, double timeoutSeconds, int32_t *remainingOut, int32_t *status)
 Reads a DMA sample using a direct DMA pointer. More...
 
enum HAL_DMAReadStatus HAL_ReadDMA (HAL_DMAHandle handle, HAL_DMASample *dmaSample, double timeoutSeconds, int32_t *remainingOut, int32_t *status)
 Reads a DMA sample from the queue. More...
 
uint64_t HAL_GetDMASampleTime (const HAL_DMASample *dmaSample, int32_t *status)
 Returns the timestamp of the sample. More...
 
int32_t HAL_GetDMASampleEncoderRaw (const HAL_DMASample *dmaSample, HAL_EncoderHandle encoderHandle, int32_t *status)
 Returns the raw distance data for an encoder from the sample. More...
 
int32_t HAL_GetDMASampleCounter (const HAL_DMASample *dmaSample, HAL_CounterHandle counterHandle, int32_t *status)
 Returns the distance data for an counter from the sample. More...
 
int32_t HAL_GetDMASampleEncoderPeriodRaw (const HAL_DMASample *dmaSample, HAL_EncoderHandle encoderHandle, int32_t *status)
 Returns the raw period data for an encoder from the sample. More...
 
int32_t HAL_GetDMASampleCounterPeriod (const HAL_DMASample *dmaSample, HAL_CounterHandle counterHandle, int32_t *status)
 Returns the period data for an counter from the sample. More...
 
HAL_Bool HAL_GetDMASampleDigitalSource (const HAL_DMASample *dmaSample, HAL_Handle dSourceHandle, int32_t *status)
 Returns the state of a digital source from the sample. More...
 
int32_t HAL_GetDMASampleAnalogInputRaw (const HAL_DMASample *dmaSample, HAL_AnalogInputHandle aInHandle, int32_t *status)
 Returns the raw analog data for an analog input from the sample. More...
 
int32_t HAL_GetDMASampleAveragedAnalogInputRaw (const HAL_DMASample *dmaSample, HAL_AnalogInputHandle aInHandle, int32_t *status)
 Returns the raw averaged analog data for an analog input from the sample. More...
 
void HAL_GetDMASampleAnalogAccumulator (const HAL_DMASample *dmaSample, HAL_AnalogInputHandle aInHandle, int64_t *count, int64_t *value, int32_t *status)
 Returns the analog accumulator data for an analog input from the sample. More...
 
int32_t HAL_GetDMASampleDutyCycleOutputRaw (const HAL_DMASample *dmaSample, HAL_DutyCycleHandle dutyCycleHandle, int32_t *status)
 Returns the raw duty cycle input ratio data from the sample. More...
 

Detailed Description

Enumeration Type Documentation

◆ HAL_DMAReadStatus

enum HAL_DMAReadStatus : int32_t

The DMA Read Status.

Enumerator
HAL_DMA_OK 
HAL_DMA_TIMEOUT 
HAL_DMA_ERROR 

Function Documentation

◆ HAL_AddDMAAnalogAccumulator()

void HAL_AddDMAAnalogAccumulator ( HAL_DMAHandle  handle,
HAL_AnalogInputHandle  aInHandle,
int32_t *  status 
)

Adds accumulator data of an analog input to be collected by DMA.

This can only be called if DMA is not started.

Parameters
[in]handlethe dma handle
[in]aInHandlethe analog input to add
[out]statusError status variable. 0 on success.

◆ HAL_AddDMAAnalogInput()

void HAL_AddDMAAnalogInput ( HAL_DMAHandle  handle,
HAL_AnalogInputHandle  aInHandle,
int32_t *  status 
)

Adds an analog input to be collected by DMA.

This can only be called if DMA is not started.

Parameters
[in]handlethe dma handle
[in]aInHandlethe analog input to add
[out]statusError status variable. 0 on success.

◆ HAL_AddDMAAveragedAnalogInput()

void HAL_AddDMAAveragedAnalogInput ( HAL_DMAHandle  handle,
HAL_AnalogInputHandle  aInHandle,
int32_t *  status 
)

Adds averaged data of an analog input to be collected by DMA.

This can only be called if DMA is not started.

Parameters
[in]handlethe dma handle
[in]aInHandlethe analog input to add
[out]statusError status variable. 0 on success.

◆ HAL_AddDMACounter()

void HAL_AddDMACounter ( HAL_DMAHandle  handle,
HAL_CounterHandle  counterHandle,
int32_t *  status 
)

Adds position data for an counter to be collected by DMA.

This can only be called if DMA is not started.

Parameters
[in]handlethe dma handle
[in]counterHandlethe counter to add
[out]statusError status variable. 0 on success.

◆ HAL_AddDMACounterPeriod()

void HAL_AddDMACounterPeriod ( HAL_DMAHandle  handle,
HAL_CounterHandle  counterHandle,
int32_t *  status 
)

Adds timer data for an counter to be collected by DMA.

This can only be called if DMA is not started.

Parameters
[in]handlethe dma handle
[in]counterHandlethe counter to add
[out]statusError status variable. 0 on success.

◆ HAL_AddDMADigitalSource()

void HAL_AddDMADigitalSource ( HAL_DMAHandle  handle,
HAL_Handle  digitalSourceHandle,
int32_t *  status 
)

Adds a digital source to be collected by DMA.

This can only be called if DMA is not started.

Parameters
[in]handlethe dma handle
[in]digitalSourceHandlethe digital source to add
[out]statusError status variable. 0 on success.

◆ HAL_AddDMADutyCycle()

void HAL_AddDMADutyCycle ( HAL_DMAHandle  handle,
HAL_DutyCycleHandle  dutyCycleHandle,
int32_t *  status 
)

Adds a duty cycle input to be collected by DMA.

This can only be called if DMA is not started.

Parameters
[in]handlethe dma handle
[in]dutyCycleHandlethe duty cycle input to add
[out]statusError status variable. 0 on success.

◆ HAL_AddDMAEncoder()

void HAL_AddDMAEncoder ( HAL_DMAHandle  handle,
HAL_EncoderHandle  encoderHandle,
int32_t *  status 
)

Adds position data for an encoder to be collected by DMA.

This can only be called if DMA is not started.

Parameters
[in]handlethe dma handle
[in]encoderHandlethe encoder to add
[out]statusError status variable. 0 on success.

◆ HAL_AddDMAEncoderPeriod()

void HAL_AddDMAEncoderPeriod ( HAL_DMAHandle  handle,
HAL_EncoderHandle  encoderHandle,
int32_t *  status 
)

Adds timer data for an encoder to be collected by DMA.

This can only be called if DMA is not started.

Parameters
[in]handlethe dma handle
[in]encoderHandlethe encoder to add
[out]statusError status variable. 0 on success.

◆ HAL_ClearDMAExternalTriggers()

void HAL_ClearDMAExternalTriggers ( HAL_DMAHandle  handle,
int32_t *  status 
)

Clear all external triggers from the DMA trigger list.

This can only be called if DMA is not started.

Parameters
[in]handlethe dma handle
[out]statusError status variable. 0 on success.

◆ HAL_ClearDMASensors()

void HAL_ClearDMASensors ( HAL_DMAHandle  handle,
int32_t *  status 
)

Clear all sensors from the DMA collection list.

This can only be called if DMA is not started.

Parameters
[in]handlethe dma handle
[out]statusError status variable. 0 on success.

◆ HAL_FreeDMA()

void HAL_FreeDMA ( HAL_DMAHandle  handle)

Frees a DMA object.

Parameters
handlethe dma handle

◆ HAL_GetDMADirectPointer()

void * HAL_GetDMADirectPointer ( HAL_DMAHandle  handle)

Gets the direct pointer to the DMA object.

This is only to be used if absolute maximum performance is required. This will only be valid until the handle is freed.

Parameters
handlethe dma handle

◆ HAL_GetDMASampleAnalogAccumulator()

void HAL_GetDMASampleAnalogAccumulator ( const HAL_DMASample dmaSample,
HAL_AnalogInputHandle  aInHandle,
int64_t *  count,
int64_t *  value,
int32_t *  status 
)

Returns the analog accumulator data for an analog input from the sample.

Parameters
[in]dmaSamplethe sample to read from
[in]aInHandlethe analog input handle
[in]countthe accumulator count
[in]valuethe accumulator value
[out]statusError status variable. 0 on success.

◆ HAL_GetDMASampleAnalogInputRaw()

int32_t HAL_GetDMASampleAnalogInputRaw ( const HAL_DMASample dmaSample,
HAL_AnalogInputHandle  aInHandle,
int32_t *  status 
)

Returns the raw analog data for an analog input from the sample.

This can be scaled with HAL_GetAnalogValueToVolts to match GetVoltage().

Parameters
[in]dmaSamplethe sample to read from
[in]aInHandlethe analog input handle
[out]statusError status variable. 0 on success.
Returns
raw analog data

◆ HAL_GetDMASampleAveragedAnalogInputRaw()

int32_t HAL_GetDMASampleAveragedAnalogInputRaw ( const HAL_DMASample dmaSample,
HAL_AnalogInputHandle  aInHandle,
int32_t *  status 
)

Returns the raw averaged analog data for an analog input from the sample.

This can be scaled with HAL_GetAnalogValueToVolts to match GetAveragedVoltage().

Parameters
[in]dmaSamplethe sample to read from
[in]aInHandlethe analog input handle
[out]statusError status variable. 0 on success.
Returns
raw averaged analog data

◆ HAL_GetDMASampleCounter()

int32_t HAL_GetDMASampleCounter ( const HAL_DMASample dmaSample,
HAL_CounterHandle  counterHandle,
int32_t *  status 
)

Returns the distance data for an counter from the sample.

Parameters
[in]dmaSamplethe sample to read from
[in]counterHandlethe counter handle
[out]statusError status variable. 0 on success.
Returns
counter ticks

◆ HAL_GetDMASampleCounterPeriod()

int32_t HAL_GetDMASampleCounterPeriod ( const HAL_DMASample dmaSample,
HAL_CounterHandle  counterHandle,
int32_t *  status 
)

Returns the period data for an counter from the sample.

Parameters
[in]dmaSamplethe sample to read from
[in]counterHandlethe counter handle
[out]statusError status variable. 0 on success.
Returns
counter period

◆ HAL_GetDMASampleDigitalSource()

HAL_Bool HAL_GetDMASampleDigitalSource ( const HAL_DMASample dmaSample,
HAL_Handle  dSourceHandle,
int32_t *  status 
)

Returns the state of a digital source from the sample.

Parameters
[in]dmaSamplethe sample to read from
[in]dSourceHandlethe digital source handle
[out]statusError status variable. 0 on success.
Returns
digital source state

◆ HAL_GetDMASampleDutyCycleOutputRaw()

int32_t HAL_GetDMASampleDutyCycleOutputRaw ( const HAL_DMASample dmaSample,
HAL_DutyCycleHandle  dutyCycleHandle,
int32_t *  status 
)

Returns the raw duty cycle input ratio data from the sample.

Use HAL_GetDutyCycleOutputScaleFactor to scale this to a percentage.

Parameters
[in]dmaSamplethe sample to read from
[in]dutyCycleHandlethe duty cycle handle
[out]statusError status variable. 0 on success.
Returns
raw duty cycle input data

◆ HAL_GetDMASampleEncoderPeriodRaw()

int32_t HAL_GetDMASampleEncoderPeriodRaw ( const HAL_DMASample dmaSample,
HAL_EncoderHandle  encoderHandle,
int32_t *  status 
)

Returns the raw period data for an encoder from the sample.

This can be scaled with DistancePerPulse and DecodingScaleFactor to match the result of GetRate()

Parameters
[in]dmaSamplethe sample to read from
[in]encoderHandlethe encoder handle
[out]statusError status variable. 0 on success.
Returns
raw encoder period

◆ HAL_GetDMASampleEncoderRaw()

int32_t HAL_GetDMASampleEncoderRaw ( const HAL_DMASample dmaSample,
HAL_EncoderHandle  encoderHandle,
int32_t *  status 
)

Returns the raw distance data for an encoder from the sample.

This can be scaled with DistancePerPulse and DecodingScaleFactor to match the result of GetDistance()

Parameters
[in]dmaSamplethe sample to read from
[in]encoderHandlethe encoder handle
[out]statusError status variable. 0 on success.
Returns
raw encoder ticks

◆ HAL_GetDMASampleTime()

uint64_t HAL_GetDMASampleTime ( const HAL_DMASample dmaSample,
int32_t *  status 
)

Returns the timestamp of the sample.

This is in the same time domain as HAL_GetFPGATime().

Parameters
[in]dmaSamplethe sample to read from
[out]statusError status variable. 0 on success.
Returns
timestamp in microseconds since FPGA Initialization

◆ HAL_InitializeDMA()

HAL_DMAHandle HAL_InitializeDMA ( int32_t *  status)

Initializes an object for performing DMA transfers.

Parameters
[out]statusError status variable. 0 on success.
Returns
the created dma handle

◆ HAL_ReadDMA()

enum HAL_DMAReadStatus HAL_ReadDMA ( HAL_DMAHandle  handle,
HAL_DMASample dmaSample,
double  timeoutSeconds,
int32_t *  remainingOut,
int32_t *  status 
)

Reads a DMA sample from the queue.

Parameters
[in]handlethe dma handle
[in]dmaSamplethe sample object to place data into
[in]timeoutSecondsthe time to wait for data to be queued before timing out
[in]remainingOutthe number of samples remaining in the queue
[out]statusError status variable. 0 on success.
Returns
the success result of the sample read

◆ HAL_ReadDMADirect()

enum HAL_DMAReadStatus HAL_ReadDMADirect ( void *  dmaPointer,
HAL_DMASample dmaSample,
double  timeoutSeconds,
int32_t *  remainingOut,
int32_t *  status 
)

Reads a DMA sample using a direct DMA pointer.

See HAL_ReadDMA for full documentation.

Parameters
[in]dmaPointerdirect DMA pointer
[in]dmaSamplethe sample object to place data into
[in]timeoutSecondsthe time to wait for data to be queued before timing out
[in]remainingOutthe number of samples remaining in the queue
[out]statusError status variable. 0 on success.

◆ HAL_SetDMAExternalTrigger()

int32_t HAL_SetDMAExternalTrigger ( HAL_DMAHandle  handle,
HAL_Handle  digitalSourceHandle,
HAL_AnalogTriggerType  analogTriggerType,
HAL_Bool  rising,
HAL_Bool  falling,
int32_t *  status 
)

Sets DMA transfers to occur on an external trigger.

This will remove any timed trigger set. Only timed or external is supported.

Up to 8 external triggers are currently supported.

This can only be called if DMA is not started.

Parameters
[in]handlethe dma handle
[in]digitalSourceHandlethe digital source handle (either a HAL_AnalogTriggerHandle or a HAL_DigitalHandle)
[in]analogTriggerTypethe analog trigger type if the source is an analog trigger
[in]risingtrue to trigger on rising edge
[in]fallingtrue to trigger on falling edge
[out]statusError status variable. 0 on success.
Returns
the index of the trigger

◆ HAL_SetDMAPause()

void HAL_SetDMAPause ( HAL_DMAHandle  handle,
HAL_Bool  pause,
int32_t *  status 
)

Pauses or unpauses a DMA transfer.

This can only be called while DMA is running.

Parameters
[in]handlethe dma handle
[in]pausetrue to pause transfers, false to resume.
[out]statusError status variable. 0 on success.

◆ HAL_SetDMATimedTrigger()

void HAL_SetDMATimedTrigger ( HAL_DMAHandle  handle,
double  periodSeconds,
int32_t *  status 
)

Sets DMA transfers to occur at a specific timed interval.

This will remove any external triggers. Only timed or external is supported.

Only 1 timed period is supported.

This can only be called if DMA is not started.

Parameters
[in]handlethe dma handle
[in]periodSecondsthe period to trigger in seconds
[out]statusError status variable. 0 on success.

◆ HAL_SetDMATimedTriggerCycles()

void HAL_SetDMATimedTriggerCycles ( HAL_DMAHandle  handle,
uint32_t  cycles,
int32_t *  status 
)

Sets DMA transfers to occur at a specific timed interval in FPGA cycles.

This will remove any external triggers. Only timed or external is supported.

Only 1 timed period is supported

The FPGA currently runs at 40 MHz, but this can change. HAL_GetSystemClockTicksPerMicrosecond can be used to get a computable value for this.

This can only be called if DMA is not started.

Parameters
[in]handlethe dma handle
[in]cyclesthe period to trigger in FPGA cycles
[out]statusError status variable. 0 on success.

◆ HAL_StartDMA()

void HAL_StartDMA ( HAL_DMAHandle  handle,
int32_t  queueDepth,
int32_t *  status 
)

Starts DMA Collection.

Parameters
[in]handlethe dma handle
[in]queueDepththe number of objects to be able to queue
[out]statusError status variable. 0 on success.

◆ HAL_StopDMA()

void HAL_StopDMA ( HAL_DMAHandle  handle,
int32_t *  status 
)

Stops DMA Collection.

Parameters
[in]handlethe dma handle
[out]statusError status variable. 0 on success.