WPILibC++ 2025.3.1
Loading...
Searching...
No Matches
Analog Output Functions

Functions

HAL_AnalogOutputHandle HAL_InitializeAnalogOutputPort (HAL_PortHandle portHandle, const char *allocationLocation, int32_t *status)
 Initializes the analog output port using the given port object.
 
void HAL_FreeAnalogOutputPort (HAL_AnalogOutputHandle analogOutputHandle)
 Frees an analog output port.
 
void HAL_SetAnalogOutput (HAL_AnalogOutputHandle analogOutputHandle, double voltage, int32_t *status)
 Sets an analog output value.
 
double HAL_GetAnalogOutput (HAL_AnalogOutputHandle analogOutputHandle, int32_t *status)
 Gets the current analog output value.
 
HAL_Bool HAL_CheckAnalogOutputChannel (int32_t channel)
 Checks that the analog output channel number is valid.
 

Detailed Description

Function Documentation

◆ HAL_CheckAnalogOutputChannel()

HAL_Bool HAL_CheckAnalogOutputChannel ( int32_t channel)

Checks that the analog output channel number is valid.

Verifies that the analog channel number is one of the legal channel numbers. Channel numbers are 0-based.

Returns
Analog channel is valid

◆ HAL_FreeAnalogOutputPort()

void HAL_FreeAnalogOutputPort ( HAL_AnalogOutputHandle analogOutputHandle)

Frees an analog output port.

Parameters
analogOutputHandlethe analog output handle

◆ HAL_GetAnalogOutput()

double HAL_GetAnalogOutput ( HAL_AnalogOutputHandle analogOutputHandle,
int32_t * status )

Gets the current analog output value.

Parameters
[in]analogOutputHandlethe analog output handle
[out]statusError status variable. 0 on success.
Returns
the current output voltage (0-5v)

◆ HAL_InitializeAnalogOutputPort()

HAL_AnalogOutputHandle HAL_InitializeAnalogOutputPort ( HAL_PortHandle portHandle,
const char * allocationLocation,
int32_t * status )

Initializes the analog output port using the given port object.

Parameters
[in]portHandlehandle to the port
[in]allocationLocationthe location where the allocation is occurring (can be null)
[out]statusError status variable. 0 on success.
Returns
the created analog output handle

◆ HAL_SetAnalogOutput()

void HAL_SetAnalogOutput ( HAL_AnalogOutputHandle analogOutputHandle,
double voltage,
int32_t * status )

Sets an analog output value.

Parameters
[in]analogOutputHandlethe analog output handle
[in]voltagethe voltage (0-5v) to output
[out]statusError status variable. 0 on success.