diff --git a/.cproject b/.cproject
index fe359b4..30489c1 100644
--- a/.cproject
+++ b/.cproject
@@ -31,6 +31,9 @@
+
+
+
@@ -46,4 +49,5 @@
+
diff --git a/Drivers/Custom/MCP980x/MCP980x.cpp b/Drivers/Custom/MCP980x/MCP980x.cpp
index c5d4eca..31abba0 100644
--- a/Drivers/Custom/MCP980x/MCP980x.cpp
+++ b/Drivers/Custom/MCP980x/MCP980x.cpp
@@ -7,7 +7,7 @@
#include "stm32l1xx.h"
#include "i2c.h"
-#include "MCP980x\MCP980x.h"
+#include "MCP980x.h"
/*---------------------------------------------------------------------------------------------------------------------+
| global functions
diff --git a/Drivers/Custom/MCP980x/MCP980x_drv_by_PG.cpp b/Drivers/Custom/MCP980x/MCP980x_drv_by_PG.cpp
new file mode 100644
index 0000000..9edc556
--- /dev/null
+++ b/Drivers/Custom/MCP980x/MCP980x_drv_by_PG.cpp
@@ -0,0 +1,131 @@
+/*
+ * MCP980x_drv_by_PG.cpp
+ *
+ * Created on: 3 mar 2015
+ * Author: pgielmuda
+ */
+
+#include "error.h"
+#include "semphr.h"
+#include "MCP980x_drv_by_PG.h"
+#include "i2c_by_PG.h"
+
+
+static xSemaphoreHandle _drvMCPSemaphore[8];
+
+
+enum Error initMCP980x(uint8_t addr)
+{
+ enum Error error=i2cInitialize(); //initialize I2C
+
+
+ vSemaphoreCreateBinary(_drvMCPSemaphore[USR_ADDR(addr)]);
+
+ if (_drvMCPSemaphore[USR_ADDR(addr)] == NULL) // semaphore not created?
+ return ERROR_FreeRTOS_errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY;// return with error
+
+ //check if there is a connection to MCP with this address
+ char buff=CONF_REG;
+ //read from CONF register
+ error = i2cWriteToSlave(addr, &buff, 1, portMAX_DELAY );
+ RET_ERROR( error );
+ buff=0xff;
+ error = i2cReadFromSlave(addr, &buff, 1,portMAX_DELAY );
+ if(buff&0x80)//only 7th bit is certainly not zero
+ return ERROR_MCP;
+
+ return error;
+}
+
+
+enum Error readTemperature(float* pvTemp, uint8_t addr)
+{
+ //taking semaphore
+ portBASE_TYPE ret=xSemaphoreTake(_drvMCPSemaphore[USR_ADDR(addr)], portMAX_DELAY);
+ enum Error error = errorConvert_portBASE_TYPE(ret);
+ RET_ERROR( error );
+
+ //checking one-shot mode
+ char confBuff[2]={CONF_REG,0x00};
+ error = i2cWriteToSlave(addr,confBuff,1,portMAX_DELAY);
+ RET_ERROR( error );
+ error = i2cReadFromSlave(addr,(confBuff+1),1,portMAX_DELAY);
+ RET_ERROR( error );
+
+
+ if( confBuff[1] & 0x01){//one-shot mode it is
+ confBuff[1]|=0x80;
+ error = i2cWriteToSlave(addr,confBuff,2,portMAX_DELAY);//starting conversion
+ RET_ERROR( error );
+ while(confBuff[1] & 0x80){//waiting for a end of conversion
+ error = i2cReadFromSlave(addr,(confBuff+1),1,portMAX_DELAY);
+ RET_ERROR( error );
+ }
+ }
+
+ //now we can read a tempareature
+ char tempBuff[2]={TEMP_REG,0x00};
+ error = i2cWriteToSlave(addr,tempBuff,1,portMAX_DELAY);
+ RET_ERROR( error );
+ error = i2cReadFromSlave(addr,tempBuff,2,portMAX_DELAY);
+ RET_ERROR( error );
+
+ //releasing semaphore
+ xSemaphoreGive(_drvMCPSemaphore[USR_ADDR(addr)]);
+ //converting temperature to float
+ *pvTemp=(float)tempBuff[0]+(float)tempBuff[1]/256;
+ return ERROR_NONE;
+
+}
+
+
+enum Error readConfRegister(uint8_t* pvConfRegValue, uint8_t addr)
+{
+ //taking semaphore
+ portBASE_TYPE ret=xSemaphoreTake(_drvMCPSemaphore[USR_ADDR(addr)], portMAX_DELAY);
+ enum Error error = errorConvert_portBASE_TYPE(ret);
+ RET_ERROR( error );
+ //reading conf register
+ char buff=CONF_REG;
+ error = i2cWriteToSlave(addr,&buff,1,portMAX_DELAY);
+ RET_ERROR( error );
+ error = i2cReadFromSlave(addr,&buff,1,portMAX_DELAY);
+ RET_ERROR( error );
+ //releasing semaphore
+ xSemaphoreGive(_drvMCPSemaphore[USR_ADDR(addr)]);
+ //returning value
+ *pvConfRegValue=buff;
+ return ERROR_NONE;
+
+
+}
+
+enum Error setConfRegister(uint8_t confRegValue, uint8_t addr)
+{
+ //taking semaphore
+ portBASE_TYPE ret=xSemaphoreTake(_drvMCPSemaphore[USR_ADDR(addr)], portMAX_DELAY);
+ enum Error error = errorConvert_portBASE_TYPE(ret);
+ RET_ERROR( error );
+
+ //setting conf register
+ char buff[2]={CONF_REG,confRegValue};
+ error = i2cWriteToSlave(addr,buff,2,portMAX_DELAY);
+ RET_ERROR( error );
+
+ //reading conf register
+ buff[1]=0xff;
+ error = i2cReadFromSlave(addr,(buff+1),1,portMAX_DELAY);
+ RET_ERROR( error );
+
+ //checking if everything is ok
+ if(buff[1]!=confRegValue)
+ return ERROR_MCP;
+
+ //releasing semaphore
+ xSemaphoreGive(_drvMCPSemaphore[USR_ADDR(addr)]);
+
+ return ERROR_NONE;
+
+
+}
+
diff --git a/Drivers/Custom/MCP980x/MCP980x_drv_by_PG.h b/Drivers/Custom/MCP980x/MCP980x_drv_by_PG.h
new file mode 100644
index 0000000..d1f4f84
--- /dev/null
+++ b/Drivers/Custom/MCP980x/MCP980x_drv_by_PG.h
@@ -0,0 +1,58 @@
+/*
+ * MCP980x_drv.h
+ *
+ * Created on: 1 mar 2015
+ * Author: pgielmuda
+ */
+
+#ifndef PERIPHERALS_MCP980X_DRV_H_
+#define PERIPHERALS_MCP980X_DRV_H_
+
+#define TEMP_REG 0x00
+#define CONF_REG 0x01
+#define HYST_REG 0x02
+#define LIMIT_REG 0x03
+#define RET_ERROR( error ) if(error != ERROR_NONE) return error
+
+#define MCP_MSB_ADDR 0x48
+#define USR_ADDR( addr ) addr & 0x03
+
+
+/** \brief Initialize MCP980x in continuous conversion mode
+ * Initialize MCP980x in continuous conversion mode
+ * \param[in] addr -I2C address of MCP980x
+ * \return ERROR_NONE on success, otherwise an error code defined in the file error.h
+ */
+enum Error initMCP980x(uint8_t addr);
+
+/** \brief Read temperature from MCP980x
+ * Read last converted temperature or make a single measurement
+ * \param[out] pvTemp - pointer to a float where temperature will be written
+ * \param[in] addr -I2C address of MCP980x
+ * \return ERROR_NONE on success, otherwise an error code defined in the file error.h
+ */
+enum Error readTemperature(float* pvTemp, uint8_t addr);
+
+/** \brief Read conf register from MCP980x
+ * Read conf register from MCP980x
+ * \param[out] pvConfRegVAlue - pointer to a uint_8 where conf register value will be written
+ * \param[in] addr -I2C address of MCP980x
+ * \return ERROR_NONE on success, otherwise an error code defined in the file error.h
+ */
+enum Error readConfRegister(uint8_t* pvConfRegValue, uint8_t addr);
+
+/** Set conf register to MCP980x
+* \param[in] confRegVAlue - uint_8 value to write into conf register
+* (all bits of configuration register are descibed in datasheet)
+* \param[in] addr -I2C address of MCP980x
+* \return ERROR_NONE on success, otherwise an error code defined in the file error.h
+*/
+enum Error setConfRegister(uint8_t confRegValue, uint8_t addr);
+enum Error readHyst(uint16_t* pvHystValue, uint8_t addr);
+enum Error setHyst(uint16_t hystValue, uint8_t addr);
+
+
+
+
+
+#endif /* PERIPHERALS_MCP980X_DRV_H_ */
diff --git a/Makefile b/Makefile
index c93e4a3..dc6f03d 100644
--- a/Makefile
+++ b/Makefile
@@ -52,13 +52,13 @@ AS_DEFS =
# folders with source files, current folder is always included)
SRCS_DIRS = configuration hdr Inc FatFS peripherals Drivers/ST/STM32_USB_Device_Library/Class/CDC Drivers/ST/STM32_USB_Device_Library/Core \
Drivers Drivers/CMSIS Drivers/CMSIS/Device/ST/STM32L1xx Drivers/CMSIS/Include Drivers/STM32L1xx_HAL_Driver \
- FreeRTOS FreeRTOS/portable/GCC/ARM_CM3 FreeRTOS/portable/MemMang
+ FreeRTOS FreeRTOS/portable/GCC/ARM_CM3 FreeRTOS/portable/MemMang Drivers/Custom/MCP980x
# include directories (absolute or relative paths to additional folders with
# headers, current folder is always included)
INC_DIRS = configuration hdr Inc FatFS peripherals Drivers/ST/STM32_USB_Device_Library/Class/CDC Drivers/ST/STM32_USB_Device_Library/Core \
Drivers Drivers/CMSIS Drivers/CMSIS/Device/ST/STM32L1xx Drivers/CMSIS/Include Drivers/STM32L1xx_HAL_Driver \
- FreeRTOS/include FreeRTOS FreeRTOS/portable/GCC/ARM_CM3 FreeRTOS/portable/MemMang
+ FreeRTOS/include FreeRTOS FreeRTOS/portable/GCC/ARM_CM3 FreeRTOS/portable/MemMang Drivers/Custom/MCP980x
# library directories (absolute or relative paths to additional folders with
# libraries)
diff --git a/configuration/FreeRTOSConfig.h b/configuration/FreeRTOSConfig.h
index 290056b..70950d5 100644
--- a/configuration/FreeRTOSConfig.h
+++ b/configuration/FreeRTOSConfig.h
@@ -167,6 +167,10 @@ See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */
#define USART_RX_TASK_PRIORITY (tskIDLE_PRIORITY + 2)
#define USART_RX_STACK_SIZE 256
+// I2C task
+#define I2C_TASK_PRIORITY (tskIDLE_PRIORITY + 2)
+#define I2C_TASK_STACK_SIZE 128
+
#define CONTEXT_SWITCH() vTaskDelay(0);
/*---------------------------------------------------------------------------------------------------------------------+
| Runtime stats configuration
diff --git a/configuration/config.h b/configuration/config.h
index 8c09199..76b06bd 100644
--- a/configuration/config.h
+++ b/configuration/config.h
@@ -166,6 +166,8 @@
#define I2C_FREQUENCY 100000
+#define I2C_RXTX_QUEUE_LENGTH 16
+
/*---------------------------------------------------------------------------------------------------------------------+
| commands
+---------------------------------------------------------------------------------------------------------------------*/
diff --git a/configuration/error.h b/configuration/error.h
index a3b5102..2dcaf18 100644
--- a/configuration/error.h
+++ b/configuration/error.h
@@ -29,6 +29,7 @@
enum Error
{
// --- negative values ---
+ ERROR_MCP = -127,
ERROR_FreeRTOS_errSCHEDULER_FAIL, // Scheduler leak
// FreeRTOS errors from projdefs.h
diff --git a/configuration/main.cpp b/configuration/main.cpp
index 12ded61..189b654 100644
--- a/configuration/main.cpp
+++ b/configuration/main.cpp
@@ -45,6 +45,8 @@
#include "st_rcc.h"
#include "pwr.h"
#include "stm32l1xx_gpio.h"
+#include "i2c_by_PG.h"
+#include "MCP980x_drv_by_PG.h"
/* Private variables ---------------------------------------------------------*/
@@ -70,6 +72,10 @@ static enum Error _runtimestatsHandler(const char **arguments_array, uint32_t ar
static enum Error _tasklistHandler(const char **arguments_array, uint32_t arguments_count, char *output_buffer,
size_t output_buffer_length);
+void myTask();
+void initializeMyTask();
+void ButtonIRQInit();
+
/*---------------------------------------------------------------------------------------------------------------------+
| local variables
+---------------------------------------------------------------------------------------------------------------------*/
@@ -110,10 +116,15 @@ int main(void)
{
/* Configure the system clock and pll*/
_sysInit();
+ //ButtonIRQInit();
+
gpioInitialize();
+ gpioConfigurePin(GPIOA, BUTTON_PIN, BUTTON_CONFIGURATION);
enum Error error = usartInitialize();
+ //??
+ //i2cInitialize();
FRESULT fresult = f_mount(0, &_fileSystem); // try mounting the filesystem on SD card
ASSERT("f_mount()", fresult == FR_OK);
@@ -124,8 +135,11 @@ int main(void)
error = _initializePowerSaveTask();
ASSERT("_initializeHeartbeatTask()", error == ERROR_NONE);
+ initializeMyTask();
gpioInitialize();
+
+
/* Special delay for debugging because after scheduler start
* it may be hard to catch core in run mode to connect to debugger
*/
@@ -261,6 +275,47 @@ static enum Error _dirHandler(const char **arguments_array, uint32_t arguments_c
return error;
}
+
+
+/**
+ * Moja własna funkcja, sterowanie drugim ledem
+ */
+void myTask()
+{
+
+ float temp;
+ initMCP980x(MCP_MSB_ADDR);
+ setConfRegister(0x61,MCP_MSB_ADDR);
+ for(;;)
+ {
+ int bv=1;
+ gpioInitialize();
+ gpioConfigurePin(LED_GPIO, LED_pin, GPIO_OUT_PP_2MHz);
+ gpioConfigurePin(GPIOA, BUTTON_PIN, BUTTON_CONFIGURATION);
+
+ bv=(int)(HAL_GPIO_ReadPin(GPIOA,GPIO_PIN_0 ));
+ //odczytanie pozycji przycisku
+ if(bv){
+ setConfRegister(0x01, MCP_MSB_ADDR);
+ LED_bb |=0x01;
+ readTemperature(&temp, 0x48);
+ } else
+ LED_bb &=~0x01;
+ //włączenie diody jeśli przycisk jest włączony
+ vTaskDelay(100/portTICK_RATE_MS);
+ }
+}
+
+void initializeMyTask()
+{
+ xTaskHandle xHandleMyTask;
+
+ xTaskCreate(myTask, (signed char*)"myTask", HEARTBEAT_STACK_SIZE, NULL, HEARTBEAT_TASK_PRIORITY, &xHandleMyTask );
+
+
+}
+
+
/**
* \brief Heartbeat task that simulate real system behavior
*
@@ -274,6 +329,7 @@ static void _heartbeatTask(void *parameters)
portTickType xLastHeartBeat;
xLastHeartBeat = xTaskGetTickCount();
+ float temp;
for(;;){
int a = 0,b = 0;
@@ -283,6 +339,7 @@ static void _heartbeatTask(void *parameters)
LED1_bb ^= 1;
for(int i=0; i<700000; i++) a = 2*b+1; //do some fake calculations
LED1_bb ^= 1;
+ readTemperature(&temp, 0x48);
vTaskDelay(100/portTICK_RATE_MS); //Then go sleep
}
diff --git a/peripherals/i2c.cpp b/peripherals/i2c.cpp
deleted file mode 100644
index 0f7eb32..0000000
--- a/peripherals/i2c.cpp
+++ /dev/null
@@ -1,152 +0,0 @@
-/**
- * \file i2c.cpp
- * \brief I2C driver
- *
- * Functions for I2C control
- *
- * chip: STM32L1xx; prefix: i2c
- *
- * \author: Mazeryt Freager
- * \date 2014-07-20
- */
-
-#include
-
-#include "stm32l152xc.h"
-
-#include "hdr/hdr_rcc.h"
-#include "hdr/hdr_i2c.h"
-
-#include "config.h"
-
-#include "i2c.h"
-#include "gpio.h"
-#include "rcc.h"
-
-/*---------------------------------------------------------------------------------------------------------------------+
-| global functions
-+---------------------------------------------------------------------------------------------------------------------*/
-
-/**
- * \brief Initializes I2C module
- *
- * Configures I/Os of I2C, enable clock for I2C module and configures it.
- */
-
-void i2cInitialize(void)
-{
- gpioConfigurePin(I2Cx_SCL_GPIO, I2Cx_SCL_PIN, I2Cx_SCL_CONFIGURATION);
- gpioConfigurePin(I2Cx_SDA_GPIO, I2Cx_SDA_PIN, I2Cx_SDA_CONFIGURATION);
-
- RCC_APBxENR_I2CxEN_bb = 1; // enable clock for I2C module
-
- uint32_t frequency = rccGetCoreFrequency();
-
- I2Cx_CR1_SWRST_bb(I2Cx) = 1; // force software reset of I2C peripheral
- I2Cx_CR1_SWRST_bb(I2Cx) = 0;
-
- I2Cx->TRISE = frequency / 1000000 + 1; // limit slope (standard mode)
- I2Cx->CCR = frequency / I2C_FREQUENCY / 2; // setup clock
- I2Cx->CR2 = (frequency / 1000000) << I2C_CR2_FREQ_bit; // config I2C module's frequency
- I2Cx_CR1_PE_bb(I2Cx) = 1; // enable peripheral
-}
-
-/**
- * \brief Reads a block of data from I2C.
- *
- * Reads a block of data from I2C.
- *
- * \param [in] address is the address of the slave chip
- * \param [in] data points to buffer for data that will be read
- * \param [in] length is the length of the data block to be received
- *
- * \return pointer to received data block (data)
- */
-uint8_t* i2cRead(uint8_t address, uint8_t *data, size_t length)
-{
- uint8_t *data_copy = data;
-
- I2Cx_CR1_START_bb(I2Cx) = 1; // request a start
- while (I2Cx_SR1_SB_bb(I2Cx) == 0); // wait for start to finish
- I2Cx->SR1; // read of SR1 clears the flag
- address = address << 1;
- I2Cx->DR = address | 1; // transfer address (LSB set - read)
- while (I2Cx_SR1_ADDR_bb(I2Cx) == 0); // wait for address transfer
- I2Cx->SR1; // clear the flag
- I2Cx->SR2;
-
- while (length--)
- {
- I2Cx_CR1_ACK_bb(I2Cx) = (length == 0 ? 0 : 1); // acknowledge all but last byte
-
- while (I2Cx_SR1_RxNE_bb(I2Cx) == 0); // wait for DR not-empty
- *data++ = I2Cx->DR;
- }
-
- I2Cx_CR1_STOP_bb(I2Cx) = 1; // request a stop
-
- return data_copy;
-}
-
-/**
- * \brief Transfers a block of data through I2C.
- *
- * Transfers a block of data through I2C.
- *
- * \param [in] address is the address of the slave chip
- * \param [in] data points to data block that will be sent
- * \param [in] length is the length of the data block
- */
-
-void i2cWrite(uint8_t address, const uint8_t *data, size_t length)
-{
- I2Cx_CR1_START_bb(I2Cx) = 1; // request a start
- while (I2Cx_SR1_SB_bb(I2Cx) == 0); // wait for start to finish
- I2Cx->SR1; // read of SR1 clears the flag
- address = address << 1;
- I2Cx->DR = (address & ~1); // transfer address (LSB cleared - write)
- while (I2Cx_SR1_ADDR_bb(I2Cx) == 0); // wait for address transfer
- I2Cx->SR1; // clear the flag
- I2Cx->SR2;
-
- while (length--)
- {
- while (I2Cx_SR1_TxE_bb(I2Cx) == 0); // wait for DR empty
- I2Cx->DR = *data++;
- }
-
- while (I2Cx_SR1_TxE_bb(I2Cx) == 0 || I2Cx_SR1_BTF_bb(I2Cx) == 1); // wait for bus not-busy
- I2Cx_CR1_STOP_bb(I2Cx) = 1; // request a stop
-}
-
-/**
- * \brief Transfers one byte of data through I2C without sending stop signal.
- *
- * Transfers one byte of data through I2C without sending stop signal.
- *
- * \param [in] address is the address of the slave chip
- * \param [in] byte to send
- */
-void i2cWriteOneByteWhithoutStop(uint8_t address, uint8_t data)
-{
- I2Cx_CR1_START_bb(I2Cx) = 1; // request a start
- while (I2Cx_SR1_SB_bb(I2Cx) == 0); // wait for start to finish
- I2Cx->SR1; // read of SR1 clears the flag
- address = address << 1;
- I2Cx->DR = (address & ~1); // transfer address (LSB cleared - write)
- while (I2Cx_SR1_ADDR_bb(I2Cx) == 0); // wait for address transfer
- I2Cx->SR1; // clear the flag
- I2Cx->SR2;
-
- while (I2Cx_SR1_TxE_bb(I2Cx) == 0); // wait for DR empty
- I2Cx->DR = data;
-
- while (I2Cx_SR1_TxE_bb(I2Cx) == 0 || I2Cx_SR1_BTF_bb(I2Cx) == 1); // wait for bus not-busy
-}
-
-
-
-
-
-
-
diff --git a/peripherals/i2c.h b/peripherals/i2c.h
deleted file mode 100644
index c5b7227..0000000
--- a/peripherals/i2c.h
+++ /dev/null
@@ -1,23 +0,0 @@
-/**
- * \file i2c.h
- * \brief Header for i2c.cpp
- * \author: Mazeryt Freager
- * \date 2014-07-20
- */
-
-#ifndef I2C_H_
-#define I2C_H_
-
-#include
-#include
-
-/*---------------------------------------------------------------------------------------------------------------------+
-| global functions' prototypes
-+---------------------------------------------------------------------------------------------------------------------*/
-
-void i2cInitialize(void);
-uint8_t* i2cRead(uint8_t address, uint8_t *data, size_t length);
-void i2cWrite(uint8_t address, const uint8_t *data, size_t length);
-void i2cWriteOneByteWhithoutStop(uint8_t address, uint8_t data);
-
-#endif /* I2C_H_ */
diff --git a/peripherals/i2c_by_PG.cpp b/peripherals/i2c_by_PG.cpp
new file mode 100644
index 0000000..d7dc4f0
--- /dev/null
+++ b/peripherals/i2c_by_PG.cpp
@@ -0,0 +1,280 @@
+/*
+ * i2c_by_PG.c
+ *
+ * Created on: 1 mar 2015
+ * Author: pgielmuda
+ */
+#include "stm32l152xc.h"
+
+#include "hdr/hdr_rcc.h"
+#include "hdr/hdr_i2c.h"
+
+#include "config.h"
+#include "i2c_by_PG.h"
+#include "gpio.h"
+#include "rcc.h"
+#include "error.h"
+
+#include "FreeRTOS.h"
+#include "task.h"
+#include "queue.h"
+#include "semphr.h"
+
+
+#include
+#include
+#include
+#include
+
+static xSemaphoreHandle _i2cHrdSemaphore;
+static xQueueHandle _rxTxQueue;
+extern char __ram_start[];
+
+
+static void _i2cTask();
+
+typedef enum
+{
+ TX_FLAG = 0,
+ RX_FLAG
+}RXTX_FLAG;
+
+/// message for I2C RX/TX queue
+struct _i2cMessage {
+ RXTX_FLAG rxFlag; ///< RX or TX flag
+ uint16_t addr; ///< slave address
+ size_t length; ///< length of string, not including trailing '\0'
+ char *string; ///< pointer to null-terminated string, either in flash or in dynamic buffer
+ xTaskHandle sendMessTaskHandle; ///< pointer to TaskHandle of the task which send message
+};
+
+
+/*---------------------------------------------------------------------------------------------------------------------+
+| global functions
++---------------------------------------------------------------------------------------------------------------------*/
+
+/**
+ * \brief Initializes I2C module
+ *
+ * Configures I/Os of I2C, enable clock for I2C module and configures it.
+ * Also starts a task, initialize RX/TX queue and Semaphore
+ */
+
+enum Error i2cInitialize(void)
+{
+ // configure I2C
+ gpioConfigurePin(I2Cx_SCL_GPIO, I2Cx_SCL_PIN, I2Cx_SCL_CONFIGURATION);
+ gpioConfigurePin(I2Cx_SDA_GPIO, I2Cx_SDA_PIN, I2Cx_SDA_CONFIGURATION);
+
+ RCC_APBxENR_I2CxEN_bb = 1; // enable clock for I2C module
+
+ uint32_t frequency = rccGetCoreFrequency();
+
+ I2Cx_CR1_SWRST_bb(I2Cx) = 1; // force software reset of I2C peripheral
+ I2Cx_CR1_SWRST_bb(I2Cx) = 0;
+
+ I2Cx->TRISE = frequency / 1000000 + 1; // limit slope (standard mode)
+ I2Cx->CCR = frequency / I2C_FREQUENCY / 2; // setup clock
+ I2Cx->CR2 = (frequency / 1000000) << I2C_CR2_FREQ_bit; // config I2C module's frequency
+ I2Cx_CR1_PE_bb(I2Cx) = 1; // enable peripheral
+
+ // create semaphore, queue, task
+ vSemaphoreCreateBinary(_i2cHrdSemaphore);
+
+ if (_i2cHrdSemaphore == NULL) // semaphore not created?
+ return ERROR_FreeRTOS_errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY;// return with error
+
+ _rxTxQueue = xQueueCreate(I2C_RXTX_QUEUE_LENGTH, sizeof(struct _i2cMessage));
+
+ if (_rxTxQueue == NULL) // queue not created?
+ return ERROR_FreeRTOS_errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY;// return with error
+
+ portBASE_TYPE ret = xTaskCreate(_i2cTask, (signed char* )"I2C TASK",
+ I2C_TASK_STACK_SIZE, NULL, I2C_TASK_PRIORITY, NULL);
+
+ enum Error error = errorConvert_portBASE_TYPE(ret);
+
+
+ return error;
+}
+
+
+/**
+ * \brief Adds one message to I2C RXTX queue.
+ *
+ * Adds one message to I2C RXTX queue. Calling task should have read-only access to shared_data section.
+ *
+ * \param [in] address of I2C slave
+ * \param [in] string is the pointer to zero terminated string
+ * \param [in] lenght is a lenght of string without '\0' termination
+ * \param [in] ticks_to_wait is the amount of time the call should block while waiting for the operation to finish, use
+ * portMAX_DELAY to suspend
+ *
+ * \return ERROR_NONE on success, otherwise an error code defined in the file error.h
+ */
+
+enum Error i2cWriteToSlave(uint16_t addr, const char *string, uint8_t lenght, portTickType ticks_to_wait)
+{
+ struct _i2cMessage message;
+
+ message.length = lenght;
+ message.addr=addr;
+ message.rxFlag=TX_FLAG;
+ message.sendMessTaskHandle=xTaskGetCurrentTaskHandle();
+
+ if (message.length == 0)
+ return ERROR_NONE;
+
+ if (string >= __ram_start) // is the string in RAM?
+ {
+ message.string = (char*) pvPortMalloc(message.length);
+ if (message.string == NULL)
+ return ERROR_FreeRTOS_errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY;
+
+ memcpy(message.string, string, message.length);
+ } else
+ message.string = (char*) string;// no, string in ROM - just use the address
+
+ portBASE_TYPE ret = xQueueSend(_rxTxQueue, &message, ticks_to_wait);
+
+ enum Error error = errorConvert_portBASE_TYPE(ret);
+
+
+ return error;
+}
+
+/**
+ * \brief Adds one request for reading from I2C slave.
+ *
+ * Adds one one request for reading from I2C slave.
+ *
+ * \param [in] address of I2C slave
+ * \param [in] string is the pointer to readed data string, calling function should know how many bytes want to read from slave and should give a pointer to a memory for readed data.
+ * \param [in] lenght is a lenght of string without '\0' termination
+ * \param [in] ticks_to_wait is the amount of time the call should block while waiting for the operation to finish, use
+ * portMAX_DELAY to suspend
+ *
+ * \return ERROR_NONE on success, otherwise an error code defined in the file error.h
+ */
+
+enum Error i2cReadFromSlave(uint16_t addr, char *string, uint8_t lenght, portTickType ticks_to_wait)
+{
+ struct _i2cMessage message;
+ //lets initialize new message
+ message.length = lenght;
+ message.addr=addr;
+ message.rxFlag=RX_FLAG;
+ message.sendMessTaskHandle=xTaskGetCurrentTaskHandle();
+ message.string=string;
+
+ if (message.length == 0)
+ return ERROR_NONE;
+
+ portBASE_TYPE ret = xQueueSend(_rxTxQueue, &message, ticks_to_wait);//add new message to a RXTX queue
+ enum Error error = errorConvert_portBASE_TYPE(ret);
+
+ vTaskSuspend(NULL);//a task which is reading something from I2C slave need to wait for an answer
+ return error;
+}
+
+
+
+/*---------------------------------------------------------------------------------------------------------------------+
+| local functions
++---------------------------------------------------------------------------------------------------------------------*/
+
+/**
+ * \brief Reads a block of data from I2C.
+ *
+ * Reads a block of data from I2C.
+ *
+ * \param [in] message- a pointer to a _i2cMessage structure, which has all information needed for a I2C transfer
+ *
+ */
+static void _i2cRead(_i2cMessage* message)
+{
+ I2Cx_CR1_START_bb(I2Cx) = 1; // request a start
+ while (I2Cx_SR1_SB_bb(I2Cx) == 0); // wait for start to finish
+ I2Cx->SR1; // read of SR1 clears the flag
+ message->addr = message->addr << 1;
+ I2Cx->DR = message->addr | 1; // transfer address (LSB set - read)
+ while (I2Cx_SR1_ADDR_bb(I2Cx) == 0); // wait for address transfer
+ I2Cx->SR1; // clear the flag
+ I2Cx->SR2;
+
+
+ while (message->length--)
+ {
+ I2Cx_CR1_ACK_bb(I2Cx) = (message->length == 0 ? 0 : 1); // acknowledge all but last byte
+
+ while (I2Cx_SR1_RxNE_bb(I2Cx) == 0); // wait for DR not-empty
+ *message->string++ = I2Cx->DR;
+ }
+
+ I2Cx_CR1_STOP_bb(I2Cx) = 1; // request a stop
+ vTaskResume(message->sendMessTaskHandle); //some task now have the answer for its request
+}
+
+/**
+ * \brief Writes a block of data from I2C.
+ *
+ * Writes a block of data from I2C.
+ *
+ * \param [in] message- a pointer to a _i2cMessage structure, which has all information needed for a I2C transfer
+ *
+ */
+ static void _i2cWrite(_i2cMessage* message)
+{
+ char* lastString=message->string;
+ I2Cx_CR1_START_bb(I2Cx) = 1; // request a start
+ while (I2Cx_SR1_SB_bb(I2Cx) == 0); // wait for start to finish
+ I2Cx->SR1; // read of SR1 clears the flag
+ message->addr = message->addr << 1;
+ I2Cx->DR = (message->addr & ~1); // transfer address (LSB cleared - write)
+ while (I2Cx_SR1_ADDR_bb(I2Cx) == 0); // wait for address transfer
+ I2Cx->SR1; // clear the flag
+ I2Cx->SR2;
+
+ while (message->length--){
+ while (I2Cx_SR1_TxE_bb(I2Cx) == 0); // wait for DR empty
+ I2Cx->DR = *message->string++;
+ }
+
+ while (I2Cx_SR1_TxE_bb(I2Cx) == 0 || I2Cx_SR1_BTF_bb(I2Cx) == 1); // wait for bus not-busy
+ I2Cx_CR1_STOP_bb(I2Cx) = 1; // request a stop
+
+ //some memory shouldn't leak out
+ if (lastString >= __ram_start) // is the string in RAM?
+ vPortFree(lastString);
+
+}
+
+/**
+ * \brief Transfers a block of data through I2C.
+ *
+ * Transfers a block of data through I2C from RXTX queue.
+ */
+
+static void _i2cTask(void)
+{
+
+ while(1){
+
+ struct _i2cMessage message;
+
+ xQueueReceive(_rxTxQueue, &message, portMAX_DELAY); // get data to send
+
+ xSemaphoreTake(_i2cHrdSemaphore, portMAX_DELAY); // wait for DMA to be free, useful think for a future
+
+ if(message.rxFlag){
+ _i2cRead(&message);
+ }else{
+ _i2cWrite(&message);
+ }
+
+
+ xSemaphoreGive(_i2cHrdSemaphore);
+ vTaskDelay(10/portTICK_RATE_MS); //Then go sleep
+ }
+}
+
diff --git a/peripherals/i2c_by_PG.h b/peripherals/i2c_by_PG.h
new file mode 100644
index 0000000..3682dfc
--- /dev/null
+++ b/peripherals/i2c_by_PG.h
@@ -0,0 +1,56 @@
+/*
+ * i2c_by_PG.h
+ *
+ * Created on: 1 mar 2015
+ * Author: pgielmuda
+ */
+
+#ifndef PERIPHERALS_I2C_BY_PG_H_
+#define PERIPHERALS_I2C_BY_PG_H_
+#include "FreeRTOS.h"
+
+#include "error.h"
+
+/*---------------------------------------------------------------------------------------------------------------------+
+| global functions' prototypes
++---------------------------------------------------------------------------------------------------------------------*/
+/**
+ * \brief Initializes I2C module
+ *
+ * Configures I/Os of I2C, enable clock for I2C module and configures it.
+ * Also starts a task, initialize RX/TX queue and Semaphore
+ */
+enum Error i2cInitialize(void);
+/**
+ * \brief Adds one message to send by I2C .
+ *
+ * Adds one message to send by I2C. Calling task should have read-only access to shared_data section.
+ *
+ * \param [in] address of I2C slave
+ * \param [in] string is the pointer to zero terminated string
+ * \param [in] lenght is a lenght of string without '\0' termination
+ * \param [in] ticks_to_wait is the amount of time the call should block while waiting for the operation to finish, use
+ * portMAX_DELAY to suspend
+ *
+ * \return ERROR_NONE on success, otherwise an error code defined in the file error.h
+ */
+
+enum Error i2cWriteToSlave(uint16_t addr, const char *string, uint8_t lenght, portTickType ticks_to_wait);
+/**
+ * \brief Adds one request for reading from I2C slave.
+ *
+ * Adds one one request for reading from I2C slave.
+ *
+ * \param [in] address of I2C slave
+ * \param [in] string is the pointer to readed data string, calling function should know how many bytes want to read from slave and should give a pointer to a memory for readed data.
+ * \param [in] lenght is a lenght of string without '\0' termination
+ * \param [in] ticks_to_wait is the amount of time the call should block while waiting for the operation to finish, use
+ * portMAX_DELAY to suspend
+ *
+ * \return ERROR_NONE on success, otherwise an error code defined in the file error.h
+ */
+
+enum Error i2cReadFromSlave(uint16_t addr, char *string, uint8_t lenght, portTickType ticks_to_wait);
+
+
+#endif /* PERIPHERALS_I2C_BY_PG_H_ */