Commit 519632a5 authored by Henrique Silva's avatar Henrique Silva

Remove old i2c driver remains

This i2c.* files were just holding some helper functions, like a I2CInit
wrapper and GA discovery.
Just move these function to their right places
parent a31e5a55
......@@ -29,7 +29,6 @@
/* Project includes */
#include "chip.h"
#include "pin_mapping.h"
#include "i2c.h"
#include "led.h"
#include "ipmi.h"
#include "sdr.h"
......
......@@ -5,7 +5,7 @@ set(PROJ_HDRS ${PROJ_HDRS} ${MODULE_PATH} )
set(PROJ_SRCS ${PROJ_SRCS} ${MODULE_PATH}/utils.c)
set(PROJ_SRCS ${PROJ_SRCS} ${MODULE_PATH}/board_version.c)
set(PROJ_SRCS ${PROJ_SRCS} ${MODULE_PATH}/led.c)
set(PROJ_SRCS ${PROJ_SRCS} ${MODULE_PATH}/i2c.c ${MODULE_PATH}/ipmb.c ${MODULE_PATH}/ipmi.c)
set(PROJ_SRCS ${PROJ_SRCS} ${MODULE_PATH}/ipmb.c ${MODULE_PATH}/ipmi.c)
if (";${TARGET_MODULES};" MATCHES ";FRU;")
set(PROJ_SRCS ${PROJ_SRCS} ${MODULE_PATH}/fru.c )
......
......@@ -27,7 +27,6 @@
#include "board_version.h"
#include "port.h"
#include "ipmb.h"
#include "i2c.h"
/* Chip_ID
* 0 <- LM75AIM
......@@ -141,7 +140,7 @@ void board_i2c_init( void )
uint8_t i;
for (i=0; i<I2C_MUX_COUNT; i++) {
i2c_mux[i].semaphore = xSemaphoreCreateBinary();
vI2CInit(i2c_mux[i].i2c_interface, SPEED_100KHZ, I2C_Mode_Local_Master);
vI2CConfig(i2c_mux[i].i2c_interface, SPEED_100KHZ);
xSemaphoreGive(i2c_mux[i].semaphore);
}
}
......
......@@ -25,7 +25,6 @@
#include "fpga_spi.h"
#include "pin_mapping.h"
#include "task_priorities.h"
#include "i2c.h"
#include "string.h"
#include "led.h"
#include "board_version.h"
......
/*
* openMMC -- Open Source modular IPM Controller firmware
*
* Copyright (C) 2015-2016 Henrique Silva <henrique.silva@lnls.br>
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
* @license GPL-3.0+ <http://spdx.org/licenses/GPL-3.0+>
*/
/*!
* @file i2c.c
* @author Henrique Silva <henrique.silva@lnls.br>, LNLS
* @date August 2015
*
* @brief Implementation of a generic I2C driver using FreeRTOS features
*/
/* FreeRTOS includes */
#include "FreeRTOS.h"
/* Project includes */
#include "i2c.h"
#include "pin_mapping.h"
#include "port.h"
void vI2CInit( I2C_ID_T i2c_id, uint32_t speed, I2C_Mode mode )
{
/* Enable and configure I2C clock */
vI2CConfig( i2c_id, speed );
if ( mode == I2C_Mode_IPMB ) {
/* Configure Slave Address */
ipmb_addr = get_ipmb_addr( );
vI2CSlaveSetup( i2c_id, ipmb_addr );
}
} /* End of vI2C_Init */
/*
*==============================================================
* MMC ADDRESSING
*==============================================================
*/
/*! @brief Table holding all possible address values in IPMB specification
* @see get_ipmb_addr()
*/
unsigned char IPMBL_TABLE[IPMBL_TABLE_SIZE] = {
0x70, 0x8A, 0x72, 0x8E, 0x92, 0x90, 0x74, 0x8C, 0x76,
0x98, 0x9C, 0x9A, 0xA0, 0xA4, 0x88, 0x9E, 0x86, 0x84,
0x78, 0x94, 0x7A, 0x96, 0x82, 0x80, 0x7C, 0x7E, 0xA2 };
/*! The state of each GA signal is represented by G (grounded), U (unconnected),
* or P (pulled up to Management Power).
*
* The MMC drives P1 low and reads the GA lines. The MMC then drives P1 high and
* reads the GA lines. Any line that changes state between the two reads indicate
* an unconnected (U) pin.
*
* The IPMB-L address of a Module can be calculated as (70h + Site Number x 2). <br>
* G = 0, P = 1, U = 2 <br>
* | Pin | Ternary | Decimal | Address |
* |:---:|:-------:|:-------:|:-------:|
* | GGG | 000 | 0 | 0x70 |
* | GGP | 001 | 1 | 0x8A |
* | GGU | 002 | 2 | 0x72 |
* | GPG | 010 | 3 | 0x8E |
* | GPP | 011 | 4 | 0x92 |
* | GPU | 012 | 5 | 0x90 |
* | GUG | 020 | 6 | 0x74 |
* | GUP | 021 | 7 | 0x8C |
* | GUU | 022 | 8 | 0x76 |
* | PGG | 100 | 9 | 0x98 |
* | PGP | 101 | 10 | 0x9C |
* | PGU | 102 | 11 | 0x9A |
* | PPG | 110 | 12 | 0xA0 |
* | PPP | 111 | 13 | 0xA4 |
* | PPU | 112 | 14 | 0x88 |
* | PUG | 120 | 15 | 0x9E |
* | PUP | 121 | 16 | 0x86 |
* | PUU | 122 | 17 | 0x84 |
* | UGG | 200 | 18 | 0x78 |
* | UGP | 201 | 19 | 0x94 |
* | UGU | 202 | 20 | 0x7A |
* | UPG | 210 | 21 | 0x96 |
* | UPP | 211 | 22 | 0x82 |
* | UPU | 212 | 23 | 0x80 |
* | UUG | 220 | 24 | 0x7C |
* | UUP | 221 | 25 | 0x7E |
* | UUU | 222 | 26 | 0xA2 |
*/
#define GPIO_GA_DELAY 10
uint8_t get_ipmb_addr( void )
{
uint8_t ga0, ga1, ga2;
uint8_t index;
/* Set the test pin and read all GA pins */
gpio_set_pin_dir(GA_TEST_PORT, GA_TEST_PIN, OUTPUT);
gpio_set_pin_state(GA_TEST_PORT, GA_TEST_PIN, HIGH);
/* when using NAMC-EXT-RTM at least 11 instruction cycles required
* to have correct GA value after GA_TEST_PIN changes */
{
uint8_t i;
for (i = 0; i < GPIO_GA_DELAY; i++){
__asm volatile ("nop");
}
}
ga0 = gpio_read_pin(GA0_PORT, GA0_PIN);
ga1 = gpio_read_pin(GA1_PORT, GA1_PIN);
ga2 = gpio_read_pin(GA2_PORT, GA2_PIN);
/* Clear the test pin and see if any GA pin has changed is value,
* meaning that it is unconnected */
gpio_set_pin_state(GA_TEST_PORT, GA_TEST_PIN, LOW);
/* when using NAMC-EXT-RTM at least 11 instruction cycles required
* to have correct GA value after GA_TEST_PIN changes */
{
uint8_t i;
for (i = 0; i < GPIO_GA_DELAY; i++)
__asm volatile ("nop");
}
if ( ga0 != gpio_read_pin(GA0_PORT, GA0_PIN) ){
ga0 = UNCONNECTED;
}
if ( ga1 != gpio_read_pin(GA1_PORT, GA1_PIN) ){
ga1 = UNCONNECTED;
}
if ( ga2 != gpio_read_pin(GA2_PORT, GA2_PIN) ){
ga2 = UNCONNECTED;
}
/* Transform the 3-based code in a decimal number */
index = (9 * ga2) + (3 * ga1) + (1 * ga0);
if ( index >= IPMBL_TABLE_SIZE ){
return 0;
}
return IPMBL_TABLE[index];
}
#undef GPIO_GA_DELAY
/*
* openMMC -- Open Source modular IPM Controller firmware
*
* Copyright (C) 2015-2016 Henrique Silva <henrique.silva@lnls.br>
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
* @license GPL-3.0+ <http://spdx.org/licenses/GPL-3.0+>
*/
/*!
* @file i2c.h
* @author Henrique Silva <henrique.silva@lnls.br>, LNLS
* @date August 2015
*
* @brief Definitions used in I2C Driver
*/
#ifndef I2C_H_
#define I2C_H_
#include "FreeRTOS.h"
#include "task.h"
/*! @brief Max message length (in bits) used in I2C */
#define i2cMAX_MSG_LENGTH 32
/*! @brief Size of #IPMBL_TABLE
*/
#define IPMBL_TABLE_SIZE 27
/*! @brief GA pins definition */
typedef enum {
GROUNDED = 0,
POWERED,
UNCONNECTED
}GA_Pin_state;
/*! @brief I2C Modes definition
* @warning Slave Transmit (Slave write) mode is not implemented
*/
typedef enum {
I2C_Mode_Local_Master = 0, /*!< <b>Master Write</b> and <b>Master Read</b> modes only */
I2C_Mode_IPMB /*!< <b>Master Write</b> and <b>Slave Read</b> modes only */
} I2C_Mode;
/*! @brief I2C driver error enumeration */
typedef enum {
i2c_err_SUCCESS = 0,
i2c_err_FAILURE, /*!< General Failure in I2C driver */
i2c_err_MAX_LENGTH, /*!< Message trying to be sent is higher than I2C buffer limit */
i2c_err_SLA_R_SENT_NACK, /*!< SLA+R address transmitted, but no response has been received.
* @see #I2C_STAT_SLA_R_SENT_NACK */
i2c_err_SLA_DATA_RECV_NACK, /*!< DATA byte has been received, NACK has been returned.
* This usually means that the master will only be reading one
* more byte from the slave.
* @see #I2C_STAT_DATA_RECV_NACK */
i2c_err_SLA_W_SENT_NACK, /*!< SLA+R address transmitted, but no response has been received.
* Slave is either busy or unreachable.
* @see #I2C_STAT_SLA_W_SENT_NACK */
i2c_err_DATA_SENT_NACK /*!< DATA byte has been transmitted, but NACK has returned.
* Slave is either busy or unreachable.
* @see #I2C_STAT_DATA_SENT_NACK */
} i2c_err;
/*! @brief I2C transaction parameter structure */
typedef struct xI2C_msg
{
uint8_t i2c_id; /*!< I2C interface number (0, 1 or 2) */
uint8_t addr; /*!< Slave address of I2C device */
uint8_t tx_data[i2cMAX_MSG_LENGTH]; /*!< Buffer cointaning bytes to transmit, limitted to #i2cMAX_MSG_LENGTH */
uint8_t tx_len; /*!< Number of bytes to transmit */
uint8_t rx_data[i2cMAX_MSG_LENGTH]; /*!< Buffer cointaning received bytes, limitted to #i2cMAX_MSG_LENGTH */
uint8_t rx_len; /*!< Number of bytes to receive */
i2c_err error; /*!< Error value from I2C driver
* @see #i2c_err
*/
} xI2C_msg;
extern uint8_t ipmb_addr;
/***********************/
/* Function Prototypes */
/***********************/
/*! @todo Update i2c function comments */
/*! @brief I2C Interface Initialization
*
* Initialize I2C corresponding pins with the following characteristics:
* - Open Drain
* - Function #3 (If I2C0, it's function #1)
* - No pull-up nor pull-down
*
* Configure and init the I2C interruption, with its priority set to one
* level below the maximum FreeRTOS priority, so the interruption service
* can access the API and manage the semaphore.
* @param i2c_id: Interface ID ( I2C0, I2C1, I2C2 )
* @param mode: Operating mode for the specified I2C interface
*/
void vI2CInit( uint8_t i2c_id, uint32_t speed, I2C_Mode mode );
/*! @todo Document this function */
//void vI2CConfig( I2C_ID_T id, uint32_t speed );
/*! @brief Enter Master Write mode and transmit a buffer
*
* Bytes are transmitted in crescent order, incrementing the buffer index.
*
* @note This function blocks until its completion, in other words, it'll only
* return when the whole buffer has been transmitted or an error occurs in I2C Driver.
*
* Example:
* @code
* uint8_t tx_buffer = { 0xAA, 0x55, 0x00, 0x01 };
* uint8_t slave_address = 0x72;
*
* if( xI2CWrite ( I2C1, slave_address, tx_buffer, sizeof(tx_buffer)/sizeof(tx_buffer[0])) == i2c_err_SUCCESS ) {
*
* // Send next message, for example
*
* } else {
*
* // Retry sending this message or handle error
*
* }
* @endcode
* @param i2c_id: Interface ID ( I2C0, I2C1, I2C2 ).
* @param addr: Destination of the message (7 bit address).
* @param tx_data: Pointer to buffer of bytes to be transmitted.
* @param tx_len: Length of tx_data buffer (must be lower than #i2cMAX_MSG_LENGTH, or an error will return)
* @return I2C Driver error
* @see #xI2CRead
* @see #xI2CSlaveTransfer
*/
//i2c_err xI2CMasterWrite( I2C_ID_T id, uint8_t addr, uint8_t * tx_buff, uint8_t tx_len );
/*! @brief Enter Master Read mode and receive a buffer from slave
*
* @note This function blocks until its completion, in other words, it'll only
* return when the whole buffer has been read or an error occurs in I2C Driver.
*
* @warning @p rx_data must be previously allocated to prevent invalid memory access by functions inside this routine.
*
* Example:
* @code
* uint8_t rx_data[i2cMAX_MSG_LENGTH];
* uint8_t slave_address = 0x72;
* uint8_t bytes_to_receive = 5;
*
* if( xI2CRead ( I2C1, slave_address, rx_data, bytes_to_receive)) == i2c_err_SUCCESS ) {
*
* //Read message and blink a LED
* if ( rx_data[1] == 0x0A ) {
* blink_led(green);
* } else {
* blink_led(red);
* }
*
* } else {
*
* // Retry sending this command or handle error
*
* }
* @endcode
* @param i2c_id: Interface ID ( I2C0, I2C1, I2C2 ).
* @param addr: Destination of the message (7 bit address).
* @param rx_data: Pointer to buffer in which the received bytes will be copied.
* @param rx_len: Number of bytes that will be read from slave
* @return I2C Driver error
* @see #xI2CWrite
* @see #xI2CSlaveTransfer
*/
//i2c_err xI2CMasterRead( I2C_ID_T id, uint8_t addr, uint8_t * rx_buff, uint8_t rx_len );
/*! @todo Document this function */
//i2c_err xI2CMasterWriteRead( I2C_ID_T id, uint8_t addr, uint8_t cmd, uint8_t * rx_buff, uint8_t rx_len );
/*! @brief Enter Slave Receiver mode and waits a data transmission
*
* This function forces the I2C interface switch to Slave Listen (Receiver) mode
* and waits another Master on the bus transmit any data.
* A timeout can be specified for this function, so your functions only block here
* as long as they want.
*
* @warning @p rx_data must be previously allocated to prevent invalid memory access by functions inside this routine.
*
* Example:
* @code
* uint8_t rx_data[i2cMAX_MSG_LENGTH];
* uint32_t timeout = 1000/portTICK_PERIOD_MS; // Specified in ticks ( you can convert to ms dividing the desired value by portTICK_PERIOD_MS macro, defined in portmacro.h file )
* uint8_t data_len;
*
* data_len = xI2CSlaveTransfer( I2C0, rx_data, timeout );
*
* //Read message and blink a LED
* if ( (data_len > 2) && (rx_data[1] == 0x0A) ) {
* blink_led(green);
* } else {
* blink_led(red);
* }
* @endcode
* @param i2c_id: Interface ID ( I2C0, I2C1, I2C2 ).
* @param rx_data: Pointer to buffer in which the received bytes will be copied.
* @param timeout: Amount of time to remain blocked until a message arrives (32-bit value)
* @return Length of message received
* @see #xI2CWrite
* @see #xI2CRead
*/
//uint8_t xI2CSlaveReceive( I2C_ID_T id, uint8_t * rx_buff, uint8_t buff_len, TickType_t timeout );
/*! @todo Document this function */
//void vI2CSlaveSetup ( I2C_ID_T id, uint8_t slave_addr );
/*! @brief Reads own I2C slave address using GA pins
*
* Based on coreipm/coreipm/mmc.c
* @author Gokhan Sozmen
* Reads the GA pins, performing an unconnection checking, to define the device I2C slave address, as specified by MicroTCA documentation.
*
* @return 7-bit Slave Address
*
* @todo Develop a function to discover the Geographic Address once (checking the GA pins)
* and store it into a global variable, since everytime a IPMI message is built
* (request or response) the MMC has to check its own address to fill the rs/rqSA field,
* and it takes some time to go through all this function.
*/
uint8_t get_ipmb_addr( void );
extern uint8_t ipmb_addr;
#endif /*I2C_H_*/
......@@ -30,7 +30,6 @@
/* Project includes */
#include "utils.h"
#include "i2c.h"
#include "ipmb.h"
#include "ipmi.h"
#include "pin_mapping.h"
......@@ -174,9 +173,13 @@ void IPMB_RXTask ( void *pvParameters )
void ipmb_init ( void )
{
vI2CInit( IPMB_I2C, I2C_SPEED, I2C_Mode_IPMB );
vI2CConfig( IPMB_I2C, I2C_SPEED );
ipmb_addr = get_ipmb_addr( );
vI2CSlaveSetup( IPMB_I2C, ipmb_addr );
ipmb_txqueue = xQueueCreate( IPMB_TXQUEUE_LEN, sizeof(ipmi_msg_cfg) );
vQueueAddToRegistry( ipmb_txqueue, "IPMB_TX_QUEUE");
xTaskCreate( IPMB_TXTask, (const char*)"IPMB_TX", 150, ( void * ) NULL, tskIPMB_TX_PRIORITY, ( TaskHandle_t * ) NULL );
xTaskCreate( IPMB_RXTask, (const char*)"IPMB_RX", 300, ( void * ) NULL, tskIPMB_RX_PRIORITY, ( TaskHandle_t * ) NULL );
}
......@@ -390,3 +393,116 @@ ipmb_error ipmb_decode ( ipmi_msg * msg, uint8_t * buffer, uint8_t len )
return ipmb_error_success;
}
/*
*==============================================================
* MMC ADDRESSING
*==============================================================
*/
/*! @brief Table holding all possible address values in IPMB specification
* @see get_ipmb_addr()
*/
unsigned char IPMBL_TABLE[IPMBL_TABLE_SIZE] = {
0x70, 0x8A, 0x72, 0x8E, 0x92, 0x90, 0x74, 0x8C, 0x76,
0x98, 0x9C, 0x9A, 0xA0, 0xA4, 0x88, 0x9E, 0x86, 0x84,
0x78, 0x94, 0x7A, 0x96, 0x82, 0x80, 0x7C, 0x7E, 0xA2 };
/*! The state of each GA signal is represented by G (grounded), U (unconnected),
* or P (pulled up to Management Power).
*
* The MMC drives P1 low and reads the GA lines. The MMC then drives P1 high and
* reads the GA lines. Any line that changes state between the two reads indicate
* an unconnected (U) pin.
*
* The IPMB-L address of a Module can be calculated as (70h + Site Number x 2). <br>
* G = 0, P = 1, U = 2 <br>
* | Pin | Ternary | Decimal | Address |
* |:---:|:-------:|:-------:|:-------:|
* | GGG | 000 | 0 | 0x70 |
* | GGP | 001 | 1 | 0x8A |
* | GGU | 002 | 2 | 0x72 |
* | GPG | 010 | 3 | 0x8E |
* | GPP | 011 | 4 | 0x92 |
* | GPU | 012 | 5 | 0x90 |
* | GUG | 020 | 6 | 0x74 |
* | GUP | 021 | 7 | 0x8C |
* | GUU | 022 | 8 | 0x76 |
* | PGG | 100 | 9 | 0x98 |
* | PGP | 101 | 10 | 0x9C |
* | PGU | 102 | 11 | 0x9A |
* | PPG | 110 | 12 | 0xA0 |
* | PPP | 111 | 13 | 0xA4 |
* | PPU | 112 | 14 | 0x88 |
* | PUG | 120 | 15 | 0x9E |
* | PUP | 121 | 16 | 0x86 |
* | PUU | 122 | 17 | 0x84 |
* | UGG | 200 | 18 | 0x78 |
* | UGP | 201 | 19 | 0x94 |
* | UGU | 202 | 20 | 0x7A |
* | UPG | 210 | 21 | 0x96 |
* | UPP | 211 | 22 | 0x82 |
* | UPU | 212 | 23 | 0x80 |
* | UUG | 220 | 24 | 0x7C |
* | UUP | 221 | 25 | 0x7E |
* | UUU | 222 | 26 | 0xA2 |
*/
#define GPIO_GA_DELAY 10
uint8_t get_ipmb_addr( void )
{
uint8_t ga0, ga1, ga2;
uint8_t index;
/* Set the test pin and read all GA pins */
gpio_set_pin_dir(GA_TEST_PORT, GA_TEST_PIN, OUTPUT);
gpio_set_pin_state(GA_TEST_PORT, GA_TEST_PIN, HIGH);
/* when using NAMC-EXT-RTM at least 11 instruction cycles required
* to have correct GA value after GA_TEST_PIN changes */
{
uint8_t i;
for (i = 0; i < GPIO_GA_DELAY; i++){
__asm volatile ("nop");
}
}
ga0 = gpio_read_pin(GA0_PORT, GA0_PIN);
ga1 = gpio_read_pin(GA1_PORT, GA1_PIN);
ga2 = gpio_read_pin(GA2_PORT, GA2_PIN);
/* Clear the test pin and see if any GA pin has changed is value,
* meaning that it is unconnected */
gpio_set_pin_state(GA_TEST_PORT, GA_TEST_PIN, LOW);
/* when using NAMC-EXT-RTM at least 11 instruction cycles required
* to have correct GA value after GA_TEST_PIN changes */
{
uint8_t i;
for (i = 0; i < GPIO_GA_DELAY; i++)
__asm volatile ("nop");
}
if ( ga0 != gpio_read_pin(GA0_PORT, GA0_PIN) ){
ga0 = UNCONNECTED;
}
if ( ga1 != gpio_read_pin(GA1_PORT, GA1_PIN) ){
ga1 = UNCONNECTED;
}
if ( ga2 != gpio_read_pin(GA2_PORT, GA2_PIN) ){
ga2 = UNCONNECTED;
}
/* Transform the 3-based code in a decimal number */
index = (9 * ga2) + (3 * ga1) + (1 * ga0);
if ( index >= IPMBL_TABLE_SIZE ){
return 0;
}
return IPMBL_TABLE[index];
}
#undef GPIO_GA_DELAY
......@@ -89,7 +89,6 @@
*/
#define IPMB_RESP_HEADER_LENGTH 7
#define IPMB_NETFN_MASK 0xFC
#define IPMB_DEST_LUN_MASK 0x3
#define IPMB_SEQ_MASK 0xFC
......@@ -101,6 +100,17 @@
/* @brief Macro to check is the message is a response (odd netfn) */
#define IS_RESPONSE(msg) (msg.netfn & 0x01)
/*! @brief Size of #IPMBL_TABLE
*/
#define IPMBL_TABLE_SIZE 27
/*! @brief GA pins definition */
typedef enum {
GROUNDED = 0,
POWERED,
UNCONNECTED
}GA_Pin_state;
/*! @brief IPMI message struct */
typedef struct ipmi_msg {
uint8_t dest_addr; /*!< Destination slave address */
......@@ -145,6 +155,8 @@ typedef enum ipmb_error {
ipmb_error_queue_creation /*!< Client queue couldn't be created. Invalid pointer to handler was given */
} ipmb_error;
extern uint8_t ipmb_addr;
/* Function Prototypes */
/*! @brief IPMB Transmitter Task
......@@ -206,4 +218,19 @@ ipmb_error ipmb_register_rxqueue ( QueueHandle_t * queue );
ipmb_error ipmb_assert_chksum ( uint8_t * buffer, uint8_t buffer_len );
/*! @brief Reads own I2C slave address using GA pins
*
* Based on coreipm/coreipm/mmc.c
* @author Gokhan Sozmen
* Reads the GA pins, performing an unconnection checking, to define the device I2C slave address, as specified by MicroTCA documentation.
*
* @return 7-bit Slave Address
*
* @todo Develop a function to discover the Geographic Address once (checking the GA pins)
* and store it into a global variable, since everytime a IPMI message is built
* (request or response) the MMC has to check its own address to fill the rs/rqSA field,
* and it takes some time to go through all this function.
*/
uint8_t get_ipmb_addr( void );
#endif
......@@ -26,7 +26,6 @@
#include "semphr.h"
/* Project Includes */
#include "i2c.h"
#include "sdr.h"
#include "sensors.h"
#include "ipmi.h"
......
#include "port.h"
#include "i2c.h"
#include "string.h"
#include "board_version.h"
......
#include "FreeRTOS.h"
/*! @brief Max message length (in bits) used in I2C */
#define i2cMAX_MSG_LENGTH 32
#define xI2CMasterWrite(id, addr, tx_buff, tx_len) Chip_I2C_MasterSend(id, addr, tx_buff, tx_len)
#define xI2CMasterRead(id, addr, rx_buff, rx_len) Chip_I2C_MasterRead(id, addr, rx_buff, rx_len)
#define xI2CMasterWriteRead(id, addr, cmd, rx_buff, rx_len) Chip_I2C_MasterCmdRead(id, addr, cmd, rx_buff, rx_len)
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment