hal - adding doxygen documentation

The most doxygen docs are taken from ARMmbed/mbed-hal module.
pull/1778/head
0xc0170 2016-05-25 13:34:28 +01:00
parent 0203b96b5f
commit 709f479093
13 changed files with 475 additions and 121 deletions

View File

@ -24,12 +24,39 @@
extern "C" {
#endif
/** Analogin hal structure. analogin_s is declared in the target's hal
*/
typedef struct analogin_s analogin_t;
void analogin_init (analogin_t *obj, PinName pin);
float analogin_read (analogin_t *obj);
/**
* \defgroup hal_analogin Analogin hal functions
* @{
*/
/** Initialize the analogin peripheral
*
* Configures the pin used by analogin.
* @param obj The analogin object to initialize
* @param pin The analogin pin name
*/
void analogin_init(analogin_t *obj, PinName pin);
/** Read the input voltage, represented as a float in the range [0.0, 1.0]
*
* @param obj The analogin object
* @return A floating value representing the current input voltage
*/
float analogin_read(analogin_t *obj);
/** Read the value from analogin pin, represented as an unsigned 16bit value
*
* @param obj The analogin object
* @return An unsigned 16bit value representing the current input voltage
*/
uint16_t analogin_read_u16(analogin_t *obj);
/**@}*/
#ifdef __cplusplus
}
#endif

View File

@ -24,14 +24,60 @@
extern "C" {
#endif
/** Analogout hal structure. dac_s is declared in the target's hal
*/
typedef struct dac_s dac_t;
void analogout_init (dac_t *obj, PinName pin);
void analogout_free (dac_t *obj);
void analogout_write (dac_t *obj, float value);
void analogout_write_u16(dac_t *obj, uint16_t value);
float analogout_read (dac_t *obj);
uint16_t analogout_read_u16 (dac_t *obj);
/**
* \defgroup hal_analogout Analogout hal functions
* @{
*/
/** Initialize the analogout peripheral
*
* Configures the pin used by analogout.
* @param obj The analogout object to initialize
* @param pin The analogout pin name
*/
void analogout_init(dac_t *obj, PinName pin);
/** Release the analogout object
*
* Note: This is not currently used in the mbed-drivers
* @param obj The analogout object
*/
void analogout_free(dac_t *obj);
/** Set the output voltage, specified as a percentage (float)
*
* @param obj The analogin object
* @param value The floating-point output voltage to be set
*/
void analogout_write(dac_t *obj, float value);
/** Set the output voltage, specified as unsigned 16-bit
*
* @param obj The analogin object
* @param value The unsigned 16-bit output voltage to be set
*/
void analogout_write_u16(dac_t *obj, uint16_t value);
/** Read the current voltage value on the pin
*
* @param obj The analogin object
* @return A floating-point value representing the current voltage on the pin,
* measured as a percentage
*/
float analogout_read(dac_t *obj);
/** Read the current voltage value on the pin, as a normalized unsigned 16bit value
*
* @param obj The analogin object
* @return An unsigned 16-bit value representing the current voltage on the pin
*/
uint16_t analogout_read_u16(dac_t *obj);
/**@}*/
#ifdef __cplusplus
}

View File

@ -16,40 +16,111 @@
#ifndef MBED_GPIO_API_H
#define MBED_GPIO_API_H
#include <stdint.h>
#include "device.h"
#ifdef __cplusplus
extern "C" {
#endif
/* Set the given pin as GPIO
/**
* \defgroup hal_gpio GPIO HAL functions
* @{
*/
/** Set the given pin as GPIO
*
* @param pin The pin to be set as GPIO
* @return The GPIO port mask for this pin
**/
uint32_t gpio_set(PinName pin);
/* Checks if gpio object is connected (pin was not initialized with NC)
* @param pin The pin to be set as GPIO
* @return 0 if port is initialized with NC
**/
int gpio_is_connected(const gpio_t *obj);
/* GPIO object */
/** Initialize the GPIO pin
*
* @param obj The GPIO object to initialize
* @param pin The GPIO pin to initialize
*/
void gpio_init(gpio_t *obj, PinName pin);
void gpio_mode (gpio_t *obj, PinMode mode);
void gpio_dir (gpio_t *obj, PinDirection direction);
/** Set the input pin mode
*
* @param obj The GPIO object
* @param mode The pin mode to be set
*/
void gpio_mode(gpio_t *obj, PinMode mode);
/** Set the pin direction
*
* @param obj The GPIO object
* @param direction The pin direction to be set
*/
void gpio_dir(gpio_t *obj, PinDirection direction);
/** Set the output value
*
* @param obj The GPIO object
* @param value The value to be set
*/
void gpio_write(gpio_t *obj, int value);
int gpio_read (gpio_t *obj);
// the following set of functions are generic and are implemented in the common gpio.c file
/** Read the input value
*
* @param obj The GPIO object
* @return An integer value 1 or 0
*/
int gpio_read(gpio_t *obj);
// the following functions are generic and implemented in the common gpio.c file
// TODO: fix, will be moved to the common gpio header file
/** Init the input pin and set mode to PullDefault
*
* @param obj The GPIO object
* @param pin The pin name
*/
void gpio_init_in(gpio_t* gpio, PinName pin);
/** Init the input pin and set the mode
*
* @param obj The GPIO object
* @param pin The pin name
* @param mode The pin mode to be set
*/
void gpio_init_in_ex(gpio_t* gpio, PinName pin, PinMode mode);
/** Init the output pin as an output, with predefined output value 0
*
* @param obj The GPIO object
* @param pin The pin name
* @return An integer value 1 or 0
*/
void gpio_init_out(gpio_t* gpio, PinName pin);
/** Init the pin as an output and set the output value
*
* @param obj The GPIO object
* @param pin The pin name
* @param value The value to be set
*/
void gpio_init_out_ex(gpio_t* gpio, PinName pin, int value);
/** Init the pin to be in/out
*
* @param obj The GPIO object
* @param pin The pin name
* @param direction The pin direction to be set
* @param mode The pin mode to be set
* @param value The value to be set for an output pin
*/
void gpio_init_inout(gpio_t* gpio, PinName pin, PinDirection direction, PinMode mode, int value);
/**@}*/
#ifdef __cplusplus
}
#endif

View File

@ -24,22 +24,65 @@
extern "C" {
#endif
/** GPIO IRQ events
*/
typedef enum {
IRQ_NONE,
IRQ_RISE,
IRQ_FALL
} gpio_irq_event;
/** GPIO IRQ HAL structure. gpio_irq_s is declared in the target's HAL
*/
typedef struct gpio_irq_s gpio_irq_t;
typedef void (*gpio_irq_handler)(uint32_t id, gpio_irq_event event);
int gpio_irq_init(gpio_irq_t *obj, PinName pin, gpio_irq_handler handler, uint32_t id);
/**
* \defgroup hal_gpioirq GPIO IRQ HAL functions
* @{
*/
/** Initialize the GPIO IRQ pin
*
* @param obj The GPIO object to initialize
* @param pin The GPIO pin name
* @param handler The handler to be attached to GPIO IRQ
* @param id The object ID (id != 0, 0 is reserved)
* @return -1 if pin is NC, 0 otherwise
*/
int gpio_irq_init(gpio_irq_t *obj, PinName pin, gpio_irq_handler handler, uint32_t id);
/** Release the GPIO IRQ PIN
*
* @param obj The gpio object
*/
void gpio_irq_free(gpio_irq_t *obj);
void gpio_irq_set (gpio_irq_t *obj, gpio_irq_event event, uint32_t enable);
/** Enable/disable pin IRQ event
*
* @param obj The GPIO object
* @param event The GPIO IRQ event
* @param enable The enable flag
*/
void gpio_irq_set(gpio_irq_t *obj, gpio_irq_event event, uint32_t enable);
/** Enable GPIO IRQ
*
* This is target dependent, as it might enable the entire port or just a pin
* @param obj The GPIO object
*/
void gpio_irq_enable(gpio_irq_t *obj);
/** Disable GPIO IRQ
*
* This is target dependent, as it might disable the entire port or just a pin
* @param obj The GPIO object
*/
void gpio_irq_disable(gpio_irq_t *obj);
/**@}*/
#ifdef __cplusplus
}
#endif

View File

@ -18,12 +18,15 @@
#include "device.h"
#include "buffer.h"
#if DEVICE_I2C_ASYNCH
#include "dma_api.h"
#endif
#if DEVICE_I2C
/**
* @defgroup I2CEvents I2C Events Macros
* @defgroup hal_I2CEvents I2C Events Macros
*
* @{
*/
@ -36,16 +39,16 @@
/**@}*/
#if DEVICE_I2C_ASYNCH
/** Asynch i2c hal structure
/** Asynch I2C HAL structure
*/
typedef struct {
struct i2c_s i2c; /**< Target specific i2c structure */
struct i2c_s i2c; /**< Target specific I2C structure */
struct buffer_s tx_buff; /**< Tx buffer */
struct buffer_s rx_buff; /**< Rx buffer */
} i2c_t;
#else
/** Non-asynch i2c hal structure
/** Non-asynch I2C HAL structure
*/
typedef struct i2c_s i2c_t;
@ -61,72 +64,81 @@ extern "C" {
#endif
/**
* \defgroup GeneralI2C I2C Configuration Functions
* \defgroup hal_GeneralI2C I2C Configuration Functions
* @{
*/
/** Initialize the I2C peripheral. It sets the default parameters for I2C
* peripheral, and configure its specifieds pins.
* @param obj The i2c object
* peripheral, and configures its specifieds pins.
*
* @param obj The I2C object
* @param sda The sda pin
* @param scl The scl pin
*/
void i2c_init(i2c_t *obj, PinName sda, PinName scl);
/** Configure the I2C frequency.
* @param obj The i2c object
/** Configure the I2C frequency
*
* @param obj The I2C object
* @param hz Frequency in Hz
*/
void i2c_frequency(i2c_t *obj, int hz);
/** Send START command.
* @param obj The i2c object
/** Send START command
*
* @param obj The I2C object
*/
int i2c_start(i2c_t *obj);
/** Send STOP command.
* @param obj The i2c object
/** Send STOP command
*
* @param obj The I2C object
*/
int i2c_stop(i2c_t *obj);
/** Blocking reading data.
* @param obj The i2c object
/** Blocking reading data
*
* @param obj The I2C object
* @param address 7-bit address (last bit is 1)
* @param data The buffer for receiving
* @param length Number of bytes to read
* @param stop Stop to be generated after the transfer is done
* @return Number of read bytes
*/
int i2c_read(i2c_t *obj, int address, char *data, int length, int stop);
int i2c_read(i2c_t *obj, int address, char *data, int length, int stop);
/** Blocking sending data.
* @param obj The i2c object
/** Blocking sending data
*
* @param obj The I2C object
* @param address 7-bit address (last bit is 0)
* @param data The buffer for sending
* @param length Number of bytes to wrte
* @param length Number of bytes to write
* @param stop Stop to be generated after the transfer is done
* @return Number of written bytes
*/
int i2c_write(i2c_t *obj, int address, const char *data, int length, int stop);
int i2c_write(i2c_t *obj, int address, const char *data, int length, int stop);
/** Reset I2C peripheral. TODO: The action here. Most of the implementation sends stop().
* @param obj The i2c object
/** Reset I2C peripheral. TODO: The action here. Most of the implementation sends stop()
*
* @param obj The I2C object
*/
void i2c_reset(i2c_t *obj);
/** Read one byte.
* @param obj The i2c object
/** Read one byte
*
* @param obj The I2C object
* @param last Acknoledge
* @return The read byte
*/
int i2c_byte_read(i2c_t *obj, int last);
int i2c_byte_read(i2c_t *obj, int last);
/** Write one byte.
* @param obj The i2c object
/** Write one byte
*
* @param obj The I2C object
* @param data Byte to be written
* @return 0 if NAK was received, 1 if ACK was received, 2 for timeout.
*/
int i2c_byte_write(i2c_t *obj, int data);
int i2c_byte_write(i2c_t *obj, int data);
/**@}*/
@ -177,17 +189,18 @@ void i2c_slave_address(i2c_t *obj, int idx, uint32_t address, uint32_t mask);
#if DEVICE_I2C_ASYNCH
/**
* \defgroup AsynchI2C Asynchronous I2C Hardware Abstraction Layer
* \defgroup hal_AsynchI2C Asynchronous I2C Hardware Abstraction Layer
* @{
*/
/** Start i2c asynchronous transfer.
/** Start I2C asynchronous transfer
*
* @param obj The I2C object
* @param tx The buffer to send
* @param tx_length The number of words to transmit
* @param rx The buffer to receive
* @param rx_length The number of words to receive
* @param address The address to be set - 7bit or 9 bit
* @param tx The transmit buffer
* @param tx_length The number of bytes to transmit
* @param rx The receive buffer
* @param rx_length The number of bytes to receive
* @param address The address to be set - 7bit or 9bit
* @param stop If true, stop will be generated after the transfer is done
* @param handler The I2C IRQ handler to be set
* @param hint DMA hint usage
@ -195,18 +208,22 @@ void i2c_slave_address(i2c_t *obj, int idx, uint32_t address, uint32_t mask);
void i2c_transfer_asynch(i2c_t *obj, const void *tx, size_t tx_length, void *rx, size_t rx_length, uint32_t address, uint32_t stop, uint32_t handler, uint32_t event, DMAUsage hint);
/** The asynchronous IRQ handler
*
* @param obj The I2C object which holds the transfer information
* @return event flags if a transfer termination condition was met or 0 otherwise.
* @return Event flags if a transfer termination condition was met, otherwise return 0.
*/
uint32_t i2c_irq_handler_asynch(i2c_t *obj);
/** Attempts to determine if I2C peripheral is already in use.
/** Attempts to determine if the I2C peripheral is already in use
*
* @param obj The I2C object
* @return non-zero if the I2C module is active or zero if it is not
* @return Non-zero if the I2C module is active or zero if it is not
*/
uint8_t i2c_active(i2c_t *obj);
/** Abort ongoing asynchronous transaction.
/** Abort asynchronous transfer
*
* This function does not perform any check - that should happen in upper layers.
* @param obj The I2C object
*/
void i2c_abort_asynch(i2c_t *obj);

View File

@ -27,7 +27,7 @@ extern "C" {
#endif
/**
* \defgroup LpTicker Low Power Ticker Functions
* \defgroup hal_LpTicker Low Power Ticker Functions
* @{
*/

View File

@ -24,15 +24,61 @@
extern "C" {
#endif
/** Port HAL structure. port_s is declared in the target's HAL
*/
typedef struct port_s port_t;
/**
* \defgroup hal_port Port HAL functions
* @{
*/
/** Get the pin name from the port's pin number
*
* @param port The port name
* @param pin_n The pin number within the specified port
* @return The pin name for the port's pin number
*/
PinName port_pin(PortName port, int pin_n);
void port_init (port_t *obj, PortName port, int mask, PinDirection dir);
void port_mode (port_t *obj, PinMode mode);
void port_dir (port_t *obj, PinDirection dir);
/** Initilize the port
*
* @param obj The port object to initialize
* @param port The port name
* @param mask The bitmask to identify which bits in the port should be included (0 - ignore)
* @param dir The port direction
*/
void port_init(port_t *obj, PortName port, int mask, PinDirection dir);
/** Set the input port mode
*
* @param obj The port object
* @param mode THe port mode to be set
*/
void port_mode(port_t *obj, PinMode mode);
/** Set port direction (in/out)
*
* @param obj The port object
* @param dir The port direction to be set
*/
void port_dir(port_t *obj, PinDirection dir);
/** Write value to the port
*
* @param obj The port object
* @param value The value to be set
*/
void port_write(port_t *obj, int value);
int port_read (port_t *obj);
/** Read the current value on the port
*
* @param obj The port object
* @return An integer with each bit corresponding to an associated port pin setting
*/
int port_read(port_t *obj);
/**@}*/
#ifdef __cplusplus
}

View File

@ -24,21 +24,87 @@
extern "C" {
#endif
/** Pwmout hal structure. pwmout_s is declared in the target's hal
*/
typedef struct pwmout_s pwmout_t;
void pwmout_init (pwmout_t* obj, PinName pin);
void pwmout_free (pwmout_t* obj);
/**
* \defgroup hal_pwmout Pwmout hal functions
* @{
*/
void pwmout_write (pwmout_t* obj, float percent);
float pwmout_read (pwmout_t* obj);
/** Initialize the pwm out peripheral and configure the pin
*
* @param obj The pwmout object to initialize
* @param pin The pwmout pin to initialize
*/
void pwmout_init(pwmout_t *obj, PinName pin);
void pwmout_period (pwmout_t* obj, float seconds);
void pwmout_period_ms (pwmout_t* obj, int ms);
void pwmout_period_us (pwmout_t* obj, int us);
/** Deinitialize the pwmout object
*
* @param obj The pwmout object
*/
void pwmout_free(pwmout_t *obj);
void pwmout_pulsewidth (pwmout_t* obj, float seconds);
void pwmout_pulsewidth_ms(pwmout_t* obj, int ms);
void pwmout_pulsewidth_us(pwmout_t* obj, int us);
/** Set the output duty-cycle in range <0.0f, 1.0f>
*
* Value 0.0f represents 0 percentage, 1.0f represents 100 percent.
* @param obj The pwmout object
* @param percent The floating-point percentage number
*/
void pwmout_write(pwmout_t *obj, float percent);
/** Read the current float-point output duty-cycle
*
* @param obj The pwmout object
* @return A floating-point output duty-cycle
*/
float pwmout_read(pwmout_t *obj);
/** Set the PWM period specified in seconds, keeping the duty cycle the same
*
* Periods smaller than microseconds (the lowest resolution) are set to zero.
* @param obj The pwmout object
* @param seconds The floating-point seconds period
*/
void pwmout_period(pwmout_t *obj, float seconds);
/** Set the PWM period specified in miliseconds, keeping the duty cycle the same
*
* @param obj The pwmout object
* @param ms The milisecond period
*/
void pwmout_period_ms(pwmout_t *obj, int ms);
/** Set the PWM period specified in microseconds, keeping the duty cycle the same
*
* @param obj The pwmout object
* @param us The microsecond period
*/
void pwmout_period_us(pwmout_t *obj, int us);
/** Set the PWM pulsewidth specified in seconds, keeping the period the same.
*
* @param obj The pwmout object
* @param seconds The floating-point pulsewidth in seconds
*/
void pwmout_pulsewidth(pwmout_t *obj, float seconds);
/** Set the PWM pulsewidth specified in miliseconds, keeping the period the same.
*
* @param obj The pwmout object
* @param ms The floating-point pulsewidth in miliseconds
*/
void pwmout_pulsewidth_ms(pwmout_t *obj, int ms);
/** Set the PWM pulsewidth specified in microseconds, keeping the period the same.
*
* @param obj The pwmout object
* @param us The floating-point pulsewidth in microseconds
*/
void pwmout_pulsewidth_us(pwmout_t *obj, int us);
/**@}*/
#ifdef __cplusplus
}

View File

@ -26,13 +26,43 @@
extern "C" {
#endif
/**
* \defgroup hal_rtc RTC hal functions
* @{
*/
/** Initialize the RTC peripheral
*
*/
void rtc_init(void);
/** Deinitialize RTC
*
* TODO: The function is not used by rtc api in mbed-drivers.
*/
void rtc_free(void);
/** Get the RTC enable status
*
* @retval 0 disabled
* @retval 1 enabled
*/
int rtc_isenabled(void);
/** Get the current time from the RTC peripheral
*
* @return The current time
*/
time_t rtc_read(void);
/** Set the current time to the RTC peripheral
*
* @param t The current time to be set
*/
void rtc_write(time_t t);
/**@}*/
#ifdef __cplusplus
}
#endif

View File

@ -80,18 +80,18 @@ typedef enum {
typedef void (*uart_irq_handler)(uint32_t id, SerialIrq event);
#if DEVICE_SERIAL_ASYNCH
/** Asynch serial hal structure
/** Asynch serial HAL structure
*/
typedef struct {
struct serial_s serial; /**< Target specific serial structure */
struct buffer_s tx_buff; /**< Tx buffer */
struct buffer_s rx_buff; /**< Rx buffer */
struct buffer_s tx_buff; /**< TX buffer */
struct buffer_s rx_buff; /**< RX buffer */
uint8_t char_match; /**< Character to be matched */
uint8_t char_found; /**< State of the matched character */
} serial_t;
#else
/** Non-asynch serial hal structure
/** Non-asynch serial HAL structure
*/
typedef struct serial_s serial_t;
@ -102,16 +102,16 @@ extern "C" {
#endif
/**
* \defgroup GeneralSerial Serial Configuration Functions
* \defgroup hal_GeneralSerial Serial Configuration Functions
* @{
*/
/** Initialize the serial peripheral. It sets the default parameters for serial
* peripheral, and configure its specifieds pins.
* peripheral, and configures its specifieds pins.
*
* @param obj The serial object
* @param tx The TX pin
* @param rx The RX pin
* @param tx The TX pin name
* @param rx The RX pin name
*/
void serial_init(serial_t *obj, PinName tx, PinName rx);
@ -138,10 +138,10 @@ void serial_baud(serial_t *obj, int baudrate);
*/
void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_bits);
/** The serial interrupt handler registration.
/** The serial interrupt handler registration
*
* @param obj The serial object
* @param handler The interrupt handler which will be invoked when interrupt fires.
* @param handler The interrupt handler which will be invoked when the interrupt fires
* @param id The SerialBase object
*/
void serial_irq_handler(serial_t *obj, uart_irq_handler handler, uint32_t id);
@ -160,7 +160,7 @@ void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable);
*/
int serial_getc(serial_t *obj);
/** Put a character. This is a blocking call, waiting for a peripheral to be available
/** Send a character. This is a blocking call, waiting for a peripheral to be available
* for writing
*
* @param obj The serial object
@ -171,7 +171,7 @@ void serial_putc(serial_t *obj, int c);
/** Check if the serial peripheral is readable
*
* @param obj The serial object
* @return Non-zero value if a character can be read, 0 if nothing to read.
* @return Non-zero value if a character can be read, 0 if nothing to read
*/
int serial_readable(serial_t *obj);
@ -202,7 +202,7 @@ void serial_break_clear(serial_t *obj);
/** Configure the TX pin for UART function.
*
* @param tx The pin used for TX
* @param tx The pin name used for TX
*/
void serial_pinout_tx(PinName tx);
@ -211,8 +211,8 @@ void serial_pinout_tx(PinName tx);
*
* @param obj The serial object
* @param type The type of the flow control. Look at the available FlowControl types.
* @param rxflow The tx pin
* @param txflow The rx pin
* @param rxflow The TX pin name
* @param txflow The RX pin name
*/
void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, PinName txflow);
@ -221,7 +221,7 @@ void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, Pi
/**@}*/
/**
* \defgroup AsynchSerial Asynchronous Serial Hardware Abstraction Layer
* \defgroup hal_AsynchSerial Asynchronous Serial Hardware Abstraction Layer
* @{
*/
@ -229,13 +229,13 @@ void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, Pi
* tx_buff
*
* @param obj The serial object
* @param tx The buffer for sending
* @param tx_length The number of words to transmit
* @param tx_width The bit width of buffer word
* @param tx The transmit buffer
* @param tx_length The number of bytes to transmit
* @param tx_width Deprecated argument
* @param handler The serial handler
* @param event The logical OR of events to be registered
* @param hint A suggestion for how to use DMA with this transfer
* @return Returns number of data transfered, or 0 otherwise
* @return Returns number of data transfered, otherwise returns 0
*/
int serial_tx_asynch(serial_t *obj, const void *tx, size_t tx_length, uint8_t tx_width, uint32_t handler, uint32_t event, DMAUsage hint);
@ -243,9 +243,9 @@ int serial_tx_asynch(serial_t *obj, const void *tx, size_t tx_length, uint8_t tx
* The used buffer is specified in the serial object - rx_buff
*
* @param obj The serial object
* @param rx The buffer for sending
* @param rx_length The number of words to transmit
* @param rx_width The bit width of buffer word
* @param rx The receive buffer
* @param rx_length The number of bytes to receive
* @param rx_width Deprecated argument
* @param handler The serial handler
* @param event The logical OR of events to be registered
* @param handler The serial handler
@ -271,19 +271,19 @@ uint8_t serial_rx_active(serial_t *obj);
/** The asynchronous TX and RX handler.
*
* @param obj The serial object
* @return Returns event flags if a RX transfer termination condition was met or 0 otherwise
* @return Returns event flags if an RX transfer termination condition was met; otherwise returns 0
*/
int serial_irq_handler_asynch(serial_t *obj);
/** Abort the ongoing TX transaction. It disables the enabled interupt for TX and
* flush TX hardware buffer if TX FIFO is used
* flushes the TX hardware buffer if TX FIFO is used
*
* @param obj The serial object
*/
void serial_tx_abort_asynch(serial_t *obj);
/** Abort the ongoing RX transaction It disables the enabled interrupt for RX and
* flush RX hardware buffer if RX FIFO is used
/** Abort the ongoing RX transaction. It disables the enabled interrupt for RX and
* flushes the RX hardware buffer if RX FIFO is used
*
* @param obj The serial object
*/

View File

@ -27,21 +27,21 @@
#define SPI_EVENT_RX_OVERFLOW (1 << 3)
#define SPI_EVENT_ALL (SPI_EVENT_ERROR | SPI_EVENT_COMPLETE | SPI_EVENT_RX_OVERFLOW)
#define SPI_EVENT_INTERNAL_TRANSFER_COMPLETE (1 << 30) // internal flag to report an event occurred
#define SPI_EVENT_INTERNAL_TRANSFER_COMPLETE (1 << 30) // Internal flag to report that an event occurred
#define SPI_FILL_WORD (0xFFFF)
#if DEVICE_SPI_ASYNCH
/** Asynch spi hal structure
/** Asynch SPI HAL structure
*/
typedef struct {
struct spi_s spi; /**< Target specific spi structure */
struct spi_s spi; /**< Target specific SPI structure */
struct buffer_s tx_buff; /**< Tx buffer */
struct buffer_s rx_buff; /**< Rx buffer */
} spi_t;
#else
/** Non-asynch spi hal structure
/** Non-asynch SPI HAL structure
*/
typedef struct spi_s spi_t;
@ -52,7 +52,7 @@ extern "C" {
#endif
/**
* \defgroup GeneralSPI SPI Configuration Functions
* \defgroup hal_GeneralSPI SPI Configuration Functions
* @{
*/
@ -159,11 +159,11 @@ uint8_t spi_get_module(spi_t *obj);
/** Begin the SPI transfer. Buffer pointers and lengths are specified in tx_buff and rx_buff
*
* @param[in] obj The SPI object which holds the transfer information
* @param[in] tx The buffer to send
* @param[in] tx_length The number of words to transmit
* @param[in] rx The buffer to receive
* @param[in] rx_length The number of words to receive
* @param[in] obj The SPI object that holds the transfer information
* @param[in] tx The transmit buffer
* @param[in] tx_length The number of bytes to transmit
* @param[in] rx The receive buffer
* @param[in] rx_length The number of bytes to receive
* @param[in] bit_width The bit width of buffer words
* @param[in] event The logical OR of events to be registered
* @param[in] handler SPI interrupt handler
@ -175,12 +175,12 @@ void spi_master_transfer(spi_t *obj, const void *tx, size_t tx_length, void *rx,
*
* Reads the received values out of the RX FIFO, writes values into the TX FIFO and checks for transfer termination
* conditions, such as buffer overflows or transfer complete.
* @param[in] obj The SPI object which holds the transfer information
* @return event flags if a transfer termination condition was met or 0 otherwise.
* @param[in] obj The SPI object that holds the transfer information
* @return Event flags if a transfer termination condition was met; otherwise 0.
*/
uint32_t spi_irq_handler_asynch(spi_t *obj);
/** Attempts to determine if the SPI peripheral is already in use.
/** Attempts to determine if the SPI peripheral is already in use
*
* If a temporary DMA channel has been allocated, peripheral is in use.
* If a permanent DMA channel has been allocated, check if the DMA channel is in use. If not, proceed as though no DMA
@ -189,7 +189,7 @@ uint32_t spi_irq_handler_asynch(spi_t *obj);
* if the corresponding buffer position is less than the buffer length. If buffers do not indicate activity, check if
* there are any bytes in the FIFOs.
* @param[in] obj The SPI object to check for activity
* @return non-zero if the SPI port is active or zero if it is not.
* @return Non-zero if the SPI port is active or zero if it is not.
*/
uint8_t spi_active(spi_t *obj);

View File

@ -16,6 +16,7 @@
#ifndef MBED_TICKER_API_H
#define MBED_TICKER_API_H
#include <stdint.h>
#include "device.h"
typedef uint32_t timestamp_t;
@ -40,32 +41,37 @@ typedef struct {
void (*set_interrupt)(timestamp_t timestamp); /**< Set interrupt function */
} ticker_interface_t;
/** Tickers events queue structure
/** Ticker's event queue structure
*/
typedef struct {
ticker_event_handler event_handler; /**< Event handler */
ticker_event_t *head; /**< A pointer to head */
} ticker_event_queue_t;
/** Tickers data structure
/** Ticker's data structure
*/
typedef struct {
const ticker_interface_t *interface; /**< Ticker's interface */
ticker_event_queue_t *queue; /**< Ticker's events queue */
ticker_event_queue_t *queue; /**< Ticker's event queue */
} ticker_data_t;
#ifdef __cplusplus
extern "C" {
#endif
/** Initialize a ticker and sets the event handler
/**
* \defgroup hal_ticker Ticker HAL functions
* @{
*/
/** Initialize a ticker and set the event handler
*
* @param data The ticker's data
* @param handler A handler to be set
*/
void ticker_set_handler(const ticker_data_t *const data, ticker_event_handler handler);
/** Irq handler which goes through the events to trigger events in the past.
/** IRQ handler that goes through the events to trigger overdue events.
*
* @param data The ticker's data
*/
@ -74,14 +80,14 @@ void ticker_irq_handler(const ticker_data_t *const data);
/** Remove an event from the queue
*
* @param data The ticker's data
* @param obj The event's queue to be removed
* @param obj The event object to be removed from the queue
*/
void ticker_remove_event(const ticker_data_t *const data, ticker_event_t *obj);
/** Insert an event from the queue
/** Insert an event to the queue
*
* @param data The ticker's data
* @param obj The event's queue to be removed
* @param obj The event object to be inserted to the queue
* @param timestamp The event's timestamp
* @param id The event object
*/
@ -101,6 +107,8 @@ timestamp_t ticker_read(const ticker_data_t *const data);
*/
int ticker_get_next_timestamp(const ticker_data_t *const data, timestamp_t *timestamp);
/**@}*/
#ifdef __cplusplus
}
#endif

View File

@ -24,7 +24,7 @@ extern "C" {
#endif
/**
* \defgroup UsTicker Microseconds Ticker Functions
* \defgroup hal_UsTicker Microseconds Ticker Functions
* @{
*/