Macros | Functions
spi_master.c File Reference

SPI master common service for SAM. More...

#include "spi_master.h"
Include dependency graph for spi_master.c:

Go to the source code of this file.

Macros

#define DEFAULT_CHIP_ID   0
 The default chip select id. More...
 
#define MAX_NUM_WITH_DECODER   0x10
 Max number when the chip selects are connected to a 4- to 16-bit decoder. More...
 
#define MAX_NUM_WITHOUT_DECODER   0x04
 Max number when the chip selects are directly connected to peripheral device. More...
 
#define NONE_CHIP_SELECT_ID   0x0f
 Max number when the chip selects are directly connected to peripheral device. More...
 

Functions

void spi_deselect_device (Spi *p_spi, struct spi_device *device)
 Deselect the given device on the SPI bus. More...
 
void spi_master_init (Spi *p_spi)
 Initialize the SPI in master mode. More...
 
void spi_master_setup_device (Spi *p_spi, struct spi_device *device, spi_flags_t flags, uint32_t baud_rate, board_spi_select_id_t sel_id)
 Set up an SPI device. More...
 
status_code_t spi_read_packet (Spi *p_spi, uint8_t *data, size_t len)
 Receive a sequence of bytes from an SPI device. More...
 
void spi_select_device (Spi *p_spi, struct spi_device *device)
 Select the given device on the SPI bus. More...
 
status_code_t spi_transceive_packet (Spi *p_spi, uint8_t *tx_data, uint8_t *rx_data, size_t len)
 Send and receive a sequence of bytes from an SPI device. More...
 
status_code_t spi_write_packet (Spi *p_spi, const uint8_t *data, size_t len)
 Send a sequence of bytes to an SPI device. More...
 

Detailed Description

SPI master common service for SAM.

Copyright (c) 2011-2018 Microchip Technology Inc. and its subsidiaries.

Definition in file spi_master.c.

Macro Definition Documentation

◆ DEFAULT_CHIP_ID

#define DEFAULT_CHIP_ID   0

The default chip select id.

Definition at line 61 of file spi_master.c.

◆ MAX_NUM_WITH_DECODER

#define MAX_NUM_WITH_DECODER   0x10

Max number when the chip selects are connected to a 4- to 16-bit decoder.

Definition at line 46 of file spi_master.c.

◆ MAX_NUM_WITHOUT_DECODER

#define MAX_NUM_WITHOUT_DECODER   0x04

Max number when the chip selects are directly connected to peripheral device.

Definition at line 51 of file spi_master.c.

◆ NONE_CHIP_SELECT_ID

#define NONE_CHIP_SELECT_ID   0x0f

Max number when the chip selects are directly connected to peripheral device.

Definition at line 56 of file spi_master.c.

Function Documentation

◆ spi_deselect_device()

void spi_deselect_device ( Spi p_spi,
struct spi_device device 
)

Deselect the given device on the SPI bus.

Call board chip deselect.

Parameters
p_spiBase address of the SPI instance.
deviceSPI device.
Precondition
SPI device must be selected with spi_select_device() first.

Definition at line 155 of file spi_master.c.

◆ spi_master_init()

void spi_master_init ( Spi p_spi)

Initialize the SPI in master mode.

Parameters
p_spiBase address of the SPI instance.

Definition at line 68 of file spi_master.c.

◆ spi_master_setup_device()

void spi_master_setup_device ( Spi p_spi,
struct spi_device device,
spi_flags_t  flags,
uint32_t  baud_rate,
board_spi_select_id_t  sel_id 
)

Set up an SPI device.

The returned device descriptor structure must be passed to the driver whenever that device should be used as current slave device.

Parameters
p_spiBase address of the SPI instance.
devicePointer to SPI device struct that should be initialized.
flagsSPI configuration flags. Common flags for all implementations are the SPI modes SPI_MODE_0 ... SPI_MODE_3.
baud_rateBaud rate for communication with slave device in Hz.
sel_idBoard specific select id.

Definition at line 100 of file spi_master.c.

◆ spi_read_packet()

status_code_t spi_read_packet ( Spi p_spi,
uint8_t *  data,
size_t  len 
)

Receive a sequence of bytes from an SPI device.

All bytes sent out on SPI bus are sent as value 0.

Parameters
p_spiBase address of the SPI instance.
dataData buffer to read.
lenLength of data to be read.
Precondition
SPI device must be selected with spi_select_device() first.

Definition at line 215 of file spi_master.c.

◆ spi_select_device()

void spi_select_device ( Spi p_spi,
struct spi_device device 
)

Select the given device on the SPI bus.

Set device specific setting and call board chip select.

Parameters
p_spiBase address of the SPI instance.
deviceSPI device.

Definition at line 132 of file spi_master.c.

◆ spi_transceive_packet()

status_code_t spi_transceive_packet ( Spi p_spi,
uint8_t *  tx_data,
uint8_t *  rx_data,
size_t  len 
)

Send and receive a sequence of bytes from an SPI device.

Parameters
p_spiBase address of the SPI instance.
tx_dataData buffer to send.
rx_dataData buffer to read.
lenLength of data to be read.
Precondition
SPI device must be selected with spi_select_device() first.

Definition at line 256 of file spi_master.c.

◆ spi_write_packet()

status_code_t spi_write_packet ( Spi p_spi,
const uint8_t *  data,
size_t  len 
)

Send a sequence of bytes to an SPI device.

Received bytes on the SPI bus are discarded.

Parameters
p_spiBase address of the SPI instance.
dataData buffer to write.
lenLength of data to be written.
Precondition
SPI device must be selected with spi_select_device() first.

Definition at line 181 of file spi_master.c.



inertial_sense_ros
Author(s):
autogenerated on Sat Sep 19 2020 03:19:07