[][src]Module wpilib_sys::bindings

Modules

HALUsageReporting_tInstances
HALUsageReporting_tResourceType
HAL_AccelerometerRange
HAL_AllianceStationID
HAL_AnalogTriggerType
HAL_Counter_Mode
HAL_EncoderEncodingType
HAL_EncoderIndexingType
HAL_I2CPort
HAL_MatchType
HAL_RuntimeType
HAL_SPIPort
HAL_SerialPort

Structs

HAL_CANStreamMessage

Storage for CAN Stream Messages.

HAL_ControlWord
HAL_JoystickAxes
HAL_JoystickButtons
HAL_JoystickDescriptor
HAL_JoystickPOVs
HAL_MatchInfo
__BindgenBitfieldUnit

Constants

HAL_kInvalidHandle
HAL_kMaxJoystickAxes
HAL_kMaxJoystickPOVs
HAL_kMaxJoysticks

Functions

HAL_AllocateDigitalPWM

Allocates a DO PWM Generator.

HAL_AttachInterruptHandler

Attaches an asynchronous interrupt handler to the interrupt.

HAL_AttachInterruptHandlerThreaded

Attaches an asynchronous interrupt handler to the interrupt.

HAL_BaseInitialize

The base HAL initialize function. Useful if you need to ensure the DS and base HAL functions (the ones above this declaration in HAL.h) are properly initialized. For normal programs and executables, please use HAL_Initialize.

HAL_CalibrateAnalogGyro

Calibrates the analog gyro.

HAL_CancelNotifierAlarm

Cancels the next notifier alarm.

HAL_CheckAnalogInputChannel

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

HAL_CheckAnalogModule

Checks that the analog module number is valid.

HAL_CheckAnalogOutputChannel

Checks that the analog output channel number is value.

HAL_CheckCompressorModule

Gets if a compressor module is valid.

HAL_CheckDIOChannel

Checks if a DIO channel is valid.

HAL_CheckPDPChannel

Checks if a PDP channel is valid.

HAL_CheckPDPModule

Checks if a PDP module is valid.

HAL_CheckPWMChannel

Checks if a pwm channel is valid.

HAL_CheckRelayChannel

Checks if a relay channel is valid.

HAL_CheckSolenoidChannel

Checks if a solenoid channel is in the valid range.

HAL_CheckSolenoidModule

Checks if a solenoid module is in the valid range.

HAL_CleanAnalogTrigger

Frees an analog trigger.

HAL_CleanInterrupts

Frees an interrupt.

HAL_CleanNotifier

Cleans a notifier.

HAL_CleanPDP

Cleans a PDP module.

HAL_ClearAllPCMStickyFaults

Clears all faults on a module.

HAL_ClearCounterDownSource

Disables the down counting source to the counter.

HAL_ClearCounterUpSource

Disables the up counting source to the counter.

HAL_ClearPDPStickyFaults

Clears any PDP sticky faults.

HAL_ClearSerial

Clears the receive buffer of the serial port.

HAL_CloseI2C

Closes an I2C port

HAL_CloseSPI

Closes the SPI port.

HAL_CloseSerial

Closes a serial port.

HAL_DisableInterrupts

Disables interrupts without without deallocating structures.

HAL_DisableSerialTermination

Disables a termination character for reads.

HAL_EnableInterrupts

Enables interrupts to occur on this input.

HAL_EnableSerialTermination

Sets the termination character that terminates a read.

HAL_FireOneShot

Fires a single pulse on a solenoid channel.

HAL_FlushSerial

Flushes the serial write buffer out to the port.

HAL_ForceSPIAutoRead

Immediately forces an SPI read to happen.

HAL_FreeAnalogGyro

Frees an analog gyro.

HAL_FreeAnalogInputPort

Frees an analog input port.

HAL_FreeAnalogOutputPort

Frees an analog output port.

HAL_FreeCounter

Frees a counter.

HAL_FreeDIOPort
HAL_FreeDigitalPWM

Frees the resource associated with a DO PWM generator.

HAL_FreeEncoder

Frees an encoder.

HAL_FreeJoystickName

Frees a joystick name received with HAL_GetJoystickName

HAL_FreePWMPort

Frees a PWM port.

HAL_FreeRelayPort

Frees a relay port.

HAL_FreeSPIAuto

Frees an SPI automatic accumulator.

HAL_FreeSolenoidPort

Frees a solenoid port.

HAL_GetAccelerometerX

Gets the x-axis acceleration.

HAL_GetAccelerometerY

Gets the y-axis acceleration.

HAL_GetAccelerometerZ

Gets the z-axis acceleration.

HAL_GetAccumulatorCount

Read the number of accumulated values.

HAL_GetAccumulatorOutput

Read the accumulated value and the number of accumulated values atomically.

HAL_GetAccumulatorValue

Read the accumulated value.

HAL_GetAllSolenoids

Gets the status of all solenoids on a specific module.

HAL_GetAllianceStation

Gets the current alliance station ID.

HAL_GetAnalogAverageBits

Gets the number of averaging bits.

HAL_GetAnalogAverageValue

Gets a sample from the output of the oversample and average engine for the channel.

HAL_GetAnalogAverageVoltage

Gets a scaled sample from the output of the oversample and average engine for the channel.

HAL_GetAnalogGyroAngle

Gets the gyro angle in degrees.

HAL_GetAnalogGyroCenter

Gets the calibrated gyro center.

HAL_GetAnalogGyroOffset

Gets the calibrated gyro offset.

HAL_GetAnalogGyroRate

Gets the gyro rate in degrees/second.

HAL_GetAnalogLSBWeight

Gets the factory scaling least significant bit weight constant. The least significant bit weight constant for the channel that was calibrated in manufacturing and stored in an eeprom in the module.

HAL_GetAnalogOffset

Gets the factory scaling offset constant. The offset constant for the channel that was calibrated in manufacturing and stored in an eeprom in the module.

HAL_GetAnalogOutput

Gets the current analog output value.

HAL_GetAnalogOversampleBits

Gets the number of oversample bits.

HAL_GetAnalogSampleRate

Gets the current sample rate.

HAL_GetAnalogTriggerInWindow

Returns the InWindow output of the analog trigger.

HAL_GetAnalogTriggerOutput

Gets the state of the analog trigger output.

HAL_GetAnalogTriggerTriggerState

Returns the TriggerState output of the analog trigger.

HAL_GetAnalogValue

Gets a sample straight from the channel on this module.

HAL_GetAnalogVoltage

Gets a scaled sample straight from the channel on this module.

HAL_GetAnalogVoltsToValue

Converts a voltage to a raw value for a specified channel.

HAL_GetBrownedOut

Gets if the system is in a browned out state.

HAL_GetCompressor

Gets the compressor state (on or off).

HAL_GetCompressorClosedLoopControl

Gets if the compressor is in closed loop mode.

HAL_GetCompressorCurrent

Gets the compressor current.

HAL_GetCompressorCurrentTooHighFault

Gets if the compressor is faulted because of too high of current.

HAL_GetCompressorCurrentTooHighStickyFault

Gets if a sticky fauly is triggered because of too high of current.

HAL_GetCompressorNotConnectedFault

Gets if the compressor is not connected.

HAL_GetCompressorNotConnectedStickyFault

Gets if a sticky fault is triggered of the compressor not connected.

HAL_GetCompressorPressureSwitch

Gets the compressor pressure switch state.

HAL_GetCompressorShortedFault

Gets if the compressor is faulted because of a short.

HAL_GetCompressorShortedStickyFault

Gets if a sticky fauly is triggered because of a short.

HAL_GetControlWord

Gets the current control word of the driver station.

HAL_GetCounter

Reads the current counter value.

HAL_GetCounterDirection

Gets the last direction the counter value changed.

HAL_GetCounterPeriod
HAL_GetCounterSamplesToAverage

Gets the Samples to Average which specifies the number of samples of the timer to average when calculating the period. Perform averaging to account for mechanical imperfections or as oversampling to increase resolution.

HAL_GetCounterStopped

Determines if the clock is stopped.

HAL_GetDIO

Reads a digital value from a DIO channel.

HAL_GetDIODirection

Reads the direction of a DIO channel.

HAL_GetEncoder

Gets the current counts of the encoder after encoding type scaling.

HAL_GetEncoderDecodingScaleFactor

Gets the decoding scale factor of the encoder.

HAL_GetEncoderDirection

Gets the last direction the encoder value changed.

HAL_GetEncoderDistance

Gets the current distance traveled by the encoder.

HAL_GetEncoderDistancePerPulse

Gets the user set distance per pulse of the encoder.

HAL_GetEncoderEncodingScale

Gets the encoder scale value.

HAL_GetEncoderEncodingType

Gets the encoding type of the encoder.

HAL_GetEncoderFPGAIndex

Gets the FPGA index of the encoder.

HAL_GetEncoderPeriod
HAL_GetEncoderRate

Gets the current rate of the encoder.

HAL_GetEncoderRaw

Gets the raw counts of the encoder.

HAL_GetEncoderSamplesToAverage

Gets the current samples to average value.

HAL_GetEncoderStopped

Determines if the clock is stopped.

HAL_GetErrorMessage

Gets the error message for a specific status code.

HAL_GetFPGAButton

Gets the state of the "USER" button on the roboRIO.

HAL_GetFPGARevision

Returns the FPGA Revision number.

HAL_GetFPGATime

Reads the microsecond-resolution timer on the FPGA.

HAL_GetFPGAVersion

Returns the FPGA Version number.

HAL_GetFilterPeriod

Gets the filter period for the specified filter index.

HAL_GetFilterSelect

Reads the filter index from the FPGA.

HAL_GetJoystickAxes

Gets the axes of a specific joystick.

HAL_GetJoystickAxisType

Gets the type of a specific joystick axis.

HAL_GetJoystickButtons

Gets the buttons of a specific joystick.

HAL_GetJoystickDescriptor

Retrieves the Joystick Descriptor for particular slot.

HAL_GetJoystickIsXbox

Gets is a specific joystick is considered to be an XBox controller.

HAL_GetJoystickName

Gets the name of a joystick.

HAL_GetJoystickPOVs

Gets the POVs of a specific joystick.

HAL_GetJoystickType

Gets the type of joystick connected.

HAL_GetMatchInfo

Gets info about a specific match.

HAL_GetMatchTime

Returns the approximate match time.

HAL_GetNumAccumulators

Gets the number of analog accumulators in the current system.

HAL_GetNumAnalogInputs

Gets the number of analog inputs in the current system.

HAL_GetNumAnalogOutputs

Gets the number of analog outputs in the current system.

HAL_GetNumAnalogTriggers

Gets the number of analog triggers in the current system.

HAL_GetNumCounters

Gets the number of analog counters in the current system.

HAL_GetNumDigitalChannels

Gets the number of digital channels in the current system.

HAL_GetNumDigitalHeaders

Gets the number of digital headers in the current system.

HAL_GetNumDigitalPWMOutputs

Gets the number of digital IO PWM outputs in the current system.

HAL_GetNumEncoders

Gets the number of quadrature encoders in the current system.

HAL_GetNumInterrupts

Gets the number of interrupts in the current system.

HAL_GetNumPCMModules

Gets the number of PCM modules in the current system.

HAL_GetNumPDPChannels

Gets the number of PDP channels in the current system.

HAL_GetNumPDPModules

Gets the number of PDP modules in the current system.

HAL_GetNumPWMChannels

Gets the number of PWM channels in the current system.

HAL_GetNumPWMHeaders

Gets the number of PWM headers in the current system.

HAL_GetNumRelayChannels

Gets the number of relay channels in the current system.

HAL_GetNumRelayHeaders

Gets the number of relay headers in the current system.

HAL_GetNumSolenoidChannels

Gets the number of solenoid channels in the current system.

HAL_GetPCMSolenoidBlackList

Gets the channels blacklisted from being enabled on a module.

HAL_GetPCMSolenoidVoltageFault

Gets if a specific module has an over or under voltage fault.

HAL_GetPCMSolenoidVoltageStickyFault

Gets if a specific module has an over or under voltage sticky fault.

HAL_GetPDPChannelCurrent

Gets the current of a specific PDP channel.

HAL_GetPDPTemperature

Gets the temperature of the PDP.

HAL_GetPDPTotalCurrent

Gets the total current of the PDP.

HAL_GetPDPTotalEnergy

Gets the total energy of the PDP.

HAL_GetPDPTotalPower

Gets the total power of the PDP.

HAL_GetPDPVoltage

Gets the PDP input voltage.

HAL_GetPWMConfigRaw

Gets the raw pwm configuration settings for the PWM channel.

HAL_GetPWMCycleStartTime

Gets the pwm starting cycle time.

HAL_GetPWMEliminateDeadband

Gets the current eliminate deadband value.

HAL_GetPWMLoopTiming

Gets the loop timing of the PWM system.

HAL_GetPWMPosition

Gets a position value from a PWM channel.

HAL_GetPWMRaw

Gets a value from a PWM channel.

HAL_GetPWMSpeed

Gets a scaled value from a PWM channel.

HAL_GetPort

Gets a port handle for a specific channel.

HAL_GetPortWithModule

Gets a port handle for a specific channel and module.

HAL_GetRelay

Gets the current state of the relay channel.

HAL_GetRuntimeType
HAL_GetSPIAutoDroppedCount

Gets the count of how many SPI accumulations have been missed.

HAL_GetSPIHandle

Gets the stored handle for a SPI port.

HAL_GetSerialBytesReceived

Gets the number of bytes currently in the read buffer.

HAL_GetSolenoid

Gets the current solenoid output value.

HAL_GetSystemActive

Gets if the system outputs are currently active

HAL_GetSystemClockTicksPerMicrosecond

Gets the number of FPGA system clock ticks per microsecond.

HAL_GetUserActive5V

Gets the active state of the 5V rail.

HAL_GetUserActive6V

Gets the active state of the 6V rail.

HAL_GetUserActive3V3

Gets the active state of the 3V3 rail.

HAL_GetUserCurrent5V

Gets the 5V rail current.

HAL_GetUserCurrent6V

Gets the 6V rail current.

HAL_GetUserCurrent3V3

Gets the 3V3 rail current.

HAL_GetUserCurrentFaults5V

Gets the fault count for the 5V rail.

HAL_GetUserCurrentFaults6V

Gets the fault count for the 6V rail.

HAL_GetUserCurrentFaults3V3

Gets the fault count for the 3V3 rail.

HAL_GetUserVoltage5V

Gets the 5V rail voltage.

HAL_GetUserVoltage6V

Gets the 6V rail voltage.

HAL_GetUserVoltage3V3

Gets the 3V3 rail voltage.

HAL_GetVinCurrent

Gets the roboRIO input current.

HAL_GetVinVoltage

Gets the roboRIO input voltage.

HAL_InitAccumulator

Initialize the accumulator.

HAL_InitSPIAuto

Initializes the SPI automatic accumulator.

HAL_Initialize

Call this to start up HAL. This is required for robot programs.

HAL_InitializeAnalogGyro

Initializes an analog gyro.

HAL_InitializeAnalogInputPort

Initializes the analog input port using the given port object.

HAL_InitializeAnalogOutputPort

Initializes the analog output port using the given port object.

HAL_InitializeAnalogTrigger

Initializes an analog trigger.

HAL_InitializeCompressor

Initializes a compressor on the given PCM module.

HAL_InitializeCounter

Initializes a counter.

HAL_InitializeDIOPort

Creates a new instance of a digital port.

HAL_InitializeDriverStation

Initializes the driver station communication. This will properly handle multiple calls. However note that this CANNOT be called from a library that interfaces with LabVIEW.

HAL_InitializeEncoder

Initializes an encoder.

HAL_InitializeI2C

Initializes the I2C port.

HAL_InitializeInterrupts

Initializes an interrupt.

HAL_InitializeNotifier

Initializes a notifier.

HAL_InitializePDP

Initializes a Power Distribution Panel.

HAL_InitializePWMPort

Initializes a PWM port.

HAL_InitializeRelayPort

Initializes a relay.

HAL_InitializeSPI

Initializes the SPI port. Opens the port if necessary and saves the handle.

HAL_InitializeSerialPort

Initializes a serial port.

HAL_InitializeSerialPortDirect

Initializes a serial port with a direct name.

HAL_InitializeSolenoidPort

Initializes a solenoid port.

HAL_IsAccumulatorChannel

Is the channel attached to an accumulator.

HAL_IsAnyPulsing

Checks if any DIO line is currently generating a pulse.

HAL_IsNewControlData

Has a new control packet from the driver station arrived since the last time this function was called?

HAL_IsPulsing

Checks a DIO line to see if it is currently generating a pulse.

HAL_LatchPWMZero

Forces a PWM signal to go to 0 temporarily.

HAL_ObserveUserProgramAutonomous

Sets the autonomous enabled flag in the DS.

HAL_ObserveUserProgramDisabled

Sets the disabled flag in the DS.

HAL_ObserveUserProgramStarting

Sets the program starting flag in the DS.

HAL_ObserveUserProgramTeleop

Sets the teleoperated enabled flag in the DS.

HAL_ObserveUserProgramTest

Sets the test mode flag in the DS.

HAL_Pulse

Generates a single digital pulse.

HAL_ReadI2C

Executes a read transaction with the device.

HAL_ReadInterruptFallingTimestamp

Returns the timestamp for the falling interrupt that occurred most recently.

HAL_ReadInterruptRisingTimestamp

Returns the timestamp for the rising interrupt that occurred most recently.

HAL_ReadSPI

Executes a read from the device.

HAL_ReadSPIAutoReceivedData

Reads data received by the SPI accumulator. Each received data sequence consists of a timestamp followed by the received data bytes, one byte per word (in the least significant byte). The length of each received data sequence is the same as the combined dataSize + zeroSize set in HAL_SetSPIAutoTransmitData.

HAL_ReadSerial

Reads data from the serial port.

HAL_ReleaseDSMutex

Releases the DS Mutex to allow proper shutdown of any threads that are waiting on it.

HAL_Report

Reports a hardware usage to the HAL.

HAL_RequestInterrupts

Requests interrupts on a specific digital source.

HAL_ResetAccumulator

Resets the accumulator to the initial value.

HAL_ResetAnalogGyro

Resets the analog gyro value to 0.

HAL_ResetCounter

Resets the Counter to zero.

HAL_ResetEncoder

Reads the current encoder value.

HAL_ResetPDPTotalEnergy

Resets the PDP accumulated energy.

HAL_SendError

Sends an error to the driver station.

HAL_SetAccelerometerActive

Sets the accelerometer to active or standby mode.

HAL_SetAccelerometerRange

Sets the range of values that can be measured (either 2, 4, or 8 g-forces).

HAL_SetAccumulatorCenter

Set the center value of the accumulator.

HAL_SetAccumulatorDeadband

Set the accumulator's deadband.

HAL_SetAllSolenoids

Sets all channels on a specific module.

HAL_SetAnalogAverageBits

Sets the number of averaging bits.

HAL_SetAnalogGyroDeadband

Sets the deadband of the analog gyro.

HAL_SetAnalogGyroParameters

Sets the analog gyro parameters to the specified values.

HAL_SetAnalogGyroVoltsPerDegreePerSecond

Sets the analog gyro volts per degrees per second scaling.

HAL_SetAnalogOutput

Sets an analog output value.

HAL_SetAnalogOversampleBits

Sets the number of oversample bits.

HAL_SetAnalogSampleRate

Sets the sample rate.

HAL_SetAnalogTriggerAveraged

Configures the analog trigger to use the averaged vs. raw values.

HAL_SetAnalogTriggerFiltered

Configures the analog trigger to use a filtered value.

HAL_SetAnalogTriggerLimitsRaw

Sets the raw ADC upper and lower limits of the analog trigger.

HAL_SetAnalogTriggerLimitsVoltage

Sets the upper and lower limits of the analog trigger.

HAL_SetCompressorClosedLoopControl

Sets the compressor to closed loop mode.

HAL_SetCounterAverageSize

Sets the average sample size of a counter.

HAL_SetCounterDownSource

Sets the source object that causes the counter to count down.

HAL_SetCounterDownSourceEdge

Sets the down source to either detect rising edges or falling edges. Note that both are allowed to be set true at the same time without issues.

HAL_SetCounterExternalDirectionMode

Sets directional counting mode on this counter.

HAL_SetCounterMaxPeriod

Sets the maximum period where the device is still considered "moving".

HAL_SetCounterPulseLengthMode

Configures the counter to count in up or down based on the length of the input pulse.

HAL_SetCounterReverseDirection

Sets the Counter to return reversed sensing on the direction.

HAL_SetCounterSamplesToAverage

Sets the Samples to Average which specifies the number of samples of the timer to average when calculating the period. Perform averaging to account for mechanical imperfections or as oversampling to increase resolution.

HAL_SetCounterSemiPeriodMode

Sets Semi-period mode on this counter.

HAL_SetCounterUpDownMode

Sets standard up / down counting mode on this counter.

HAL_SetCounterUpSource

Sets the source object that causes the counter to count up.

HAL_SetCounterUpSourceEdge

Sets the up source to either detect rising edges or falling edges.

HAL_SetCounterUpdateWhenEmpty

Selects whether you want to continue updating the event timer output when there are no samples captured.

HAL_SetDIO

Writes a digital value to a DIO channel.

HAL_SetDIODirection

Sets the direction of a DIO channel.

HAL_SetDigitalPWMDutyCycle

Configures the duty-cycle of the PWM generator.

HAL_SetDigitalPWMOutputChannel

Configures which DO channel the PWM signal is output on.

HAL_SetDigitalPWMRate

Changes the frequency of the DO PWM generator.

HAL_SetEncoderDistancePerPulse

Sets the distance traveled per encoder pulse. This is used as a scaling factor for the rate and distance calls.

HAL_SetEncoderIndexSource

Sets the source for an index pulse on the encoder.

HAL_SetEncoderMaxPeriod

Sets the maximum period where the device is still considered "moving".

HAL_SetEncoderMinRate

Sets the minimum rate to be considered moving by the encoder.

HAL_SetEncoderReverseDirection

Sets if to reverse the direction of the encoder.

HAL_SetEncoderSamplesToAverage

Sets the number of encoder samples to average when calculating encoder rate.

HAL_SetFilterPeriod

Sets the filter period for the specified filter index.

HAL_SetFilterSelect

Writes the filter index from the FPGA.

HAL_SetInterruptUpSourceEdge

Sets the edges to trigger the interrupt on.

HAL_SetJoystickOutputs

Set joystick outputs.

HAL_SetOneShotDuration

Sets the one shot duration on a solenoid channel.

HAL_SetPWMConfig

Sets the configuration settings for the PWM channel.

HAL_SetPWMConfigRaw

Sets the raw configuration settings for the PWM channel.

HAL_SetPWMDisabled

Sets a PWM channel to be disabled.

HAL_SetPWMEliminateDeadband

Sets if the FPGA should output the center value if the input value is within the deadband.

HAL_SetPWMPeriodScale

Sets how how often the PWM signal is squelched, thus scaling the period.

HAL_SetPWMPosition

Sets a PWM channel to the desired position value.

HAL_SetPWMRaw

Sets a PWM channel to the desired value.

HAL_SetPWMSpeed

Sets a PWM channel to the desired scaled value.

HAL_SetRelay

Sets the state of a relay output.

HAL_SetSPIAutoTransmitData

Sets the data to be transmitted to the device to initiate a read.

HAL_SetSPIChipSelectActiveHigh

Sets the CS Active high for a SPI port.

HAL_SetSPIChipSelectActiveLow

Sets the CS Active low for a SPI port.

HAL_SetSPIHandle

Sets the stored handle for a SPI port.

HAL_SetSPIOpts

Sets the SPI options.

HAL_SetSPISpeed

Sets the clock speed for the SPI bus.

HAL_SetSerialBaudRate

Sets the baud rate of a serial port.

HAL_SetSerialDataBits

Sets the number of data bits on a serial port.

HAL_SetSerialFlowControl

Sets the flow control mode of a serial port.

HAL_SetSerialParity

Sets the number of parity bits on a serial port.

HAL_SetSerialReadBufferSize

Sets the size of the read buffer.

HAL_SetSerialStopBits

Sets the number of stop bits on a serial port.

HAL_SetSerialTimeout

Sets the minimum serial read timeout of a port.

HAL_SetSerialWriteBufferSize

Sets the size of the write buffer.

HAL_SetSerialWriteMode

Sets the write mode on a serial port.

HAL_SetSolenoid

Sets a solenoid output value.

HAL_SetupAnalogGyro

Sets up an analog gyro with the proper offsets and settings for the KOP analog gyro.

HAL_StartSPIAutoRate

Sets the period for automatic SPI accumulation.

HAL_StartSPIAutoTrigger

Starts the auto SPI accumulator on a specific trigger.

HAL_StopNotifier

Stops a notifier from running.

HAL_StopSPIAuto

Stops an automatic SPI accumlation.

HAL_TransactionI2C

Generic I2C read/write transaction.

HAL_TransactionSPI

Performs an SPI send/receive transaction.

HAL_UpdateNotifierAlarm

Updates the trigger time for a notifier.

HAL_WaitForDSData

Waits for the newest DS packet to arrive. Note that this is a blocking call.

HAL_WaitForDSDataTimeout

Waits for the newest DS packet to arrive. If timeout is <= 0, this will wait forever. Otherwise, it will wait until either a new packet, or the timeout time has passed.

HAL_WaitForInterrupt

In synchronous mode, waits for the defined interrupt to occur.

HAL_WaitForNotifierAlarm

Waits for the next alarm for the specific notifier.

HAL_WriteI2C

Executes a write transaction with the device.

HAL_WriteSPI

Executes a write transaction with the device.

HAL_WriteSerial

Writes data to the serial port.

Type Definitions

HAL_AnalogInputHandle
HAL_AnalogOutputHandle
HAL_AnalogTriggerHandle
HAL_Bool
HAL_CANHandle
HAL_CompressorHandle
HAL_CounterHandle
HAL_DigitalHandle
HAL_DigitalPWMHandle
HAL_EncoderHandle
HAL_FPGAEncoderHandle
HAL_GyroHandle
HAL_Handle
HAL_InterruptHandle
HAL_InterruptHandlerFunction
HAL_NotifierHandle
HAL_PDPHandle
HAL_PortHandle
HAL_RelayHandle
HAL_SolenoidHandle