1
0
Эх сурвалжийг харах

[bsp][stm32][f469-disco]Add touch drivers

Signed-off-by: Willian Chan <chentingwei@rt-thread.com>
Willian Chan 6 жил өмнө
parent
commit
9cd099c33c

+ 31 - 0
bsp/stm32/stm32f469-st-disco/board/Kconfig

@@ -26,6 +26,19 @@ menu "Onboard Peripheral Drivers"
         select FAL_USING_SFUD_PORT
         default n
         
+    config BSP_USING_TOUCH
+        bool "Enable TOUCH"
+        select BSP_USING_I2C1
+        default n
+        if BSP_USING_TOUCH
+            config BSP_TOUCH_INT_PIN
+                int "Touch interrupt pin"
+                default 149
+            config BSP_I2C_NAME
+                string "I2C Bus Name"
+                default "i2c1"
+        endif
+        
     config BSP_MOUNT_QSPI_WITH_LFS
         bool "Mount QSPI flash to / with little fs"
         depends on BSP_USING_QSPI_FLASH
@@ -55,6 +68,24 @@ menu "On-chip Peripheral Drivers"
                 depends on BSP_USING_UART3 && RT_SERIAL_USING_DMA
                 default n
         endif
+        
+    menuconfig BSP_USING_I2C1
+        bool "Enable I2C1 BUS (software simulation)"
+        default n
+        select RT_USING_I2C
+        select RT_USING_I2C_BITOPS
+        select RT_USING_PIN
+        if BSP_USING_I2C1
+            comment "Notice: PB8 --> 24; PB9 --> 25" 
+            config BSP_I2C1_SCL_PIN
+                int "I2C1 scl pin number"
+                range 1 176
+                default 24
+            config BSP_I2C1_SDA_PIN
+                int "I2C1 sda pin number"
+                range 1 176
+                default 25
+        endif
 
     config BSP_USING_QSPI
         bool "Enable QSPI BUS"

+ 3 - 0
bsp/stm32/stm32f469-st-disco/board/SConscript

@@ -20,6 +20,9 @@ if GetDepend(['PKG_USING_FAL']):
     
 if GetDepend(['BSP_USING_LCD_OTM8009A']):
     src += Glob('ports/drv_lcd_otm8009a.c')
+    
+if GetDepend(['BSP_USING_TOUCH']):
+    src += Glob('ports/touch/*.c')
 
 path =  [cwd]
 path += [cwd + '/CubeMX_Config/Inc']

+ 9 - 0
bsp/stm32/stm32f469-st-disco/board/ports/touch/SConscript

@@ -0,0 +1,9 @@
+from building import *
+
+cwd     = GetCurrentDir()
+src     = Glob('*.c')
+CPPPATH = [cwd, str(Dir('#'))]
+
+group = DefineGroup('touch', src, depend = ['BSP_USING_TOUCH'], CPPPATH = CPPPATH)
+
+Return('group')

+ 209 - 0
bsp/stm32/stm32f469-st-disco/board/ports/touch/drv_touch.c

@@ -0,0 +1,209 @@
+/*
+ * File      : drv_touch.c
+ * This file is part of RT-Thread RTOS
+ * COPYRIGHT (C) 2017, RT-Thread Development Team
+ *
+ *  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 2 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, write to the Free Software Foundation, Inc.,
+ *  51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2018-02-08     Zhangyihong  the first version
+ */
+#include "drv_touch.h"
+#include <string.h>
+#ifdef BSP_USING_TOUCH
+#ifdef PKG_USING_GUIENGINE
+#include <rtgui/event.h>
+#include <rtgui/rtgui_server.h>
+#elif defined(PKG_USING_LITTLEVGL2RTT)
+#include <littlevgl2rtt.h>
+#endif
+#define BSP_TOUCH_SAMPLE_HZ    (50)
+
+#define DBG_ENABLE
+#define DBG_SECTION_NAME  "TOUCH"
+#define DBG_LEVEL         DBG_LOG
+#define DBG_COLOR
+#include <rtdbg.h>
+
+static rt_list_t driver_list;
+
+
+void rt_touch_drivers_register(touch_drv_t drv)
+{
+    rt_list_insert_before(&driver_list, &drv->list);
+}
+
+static void post_down_event(rt_uint16_t x, rt_uint16_t y, rt_tick_t ts)
+{
+#ifdef PKG_USING_GUIENGINE
+    struct rtgui_event_mouse emouse;
+
+    emouse.parent.sender = RT_NULL;
+    emouse.wid = RT_NULL;
+
+    emouse.parent.type = RTGUI_EVENT_MOUSE_BUTTON;
+    emouse.button = RTGUI_MOUSE_BUTTON_LEFT | RTGUI_MOUSE_BUTTON_DOWN;
+    emouse.x = x;
+    emouse.y = y;
+    emouse.ts = rt_tick_get();
+    emouse.id = ts;
+    rtgui_server_post_event(&emouse.parent, sizeof(emouse));
+#elif defined(PKG_USING_LITTLEVGL2RTT)
+    littlevgl2rtt_send_input_event(x, y, LITTLEVGL2RTT_INPUT_DOWN);
+#endif
+}
+
+static void post_motion_event(rt_uint16_t x, rt_uint16_t y, rt_tick_t ts)
+{
+#ifdef PKG_USING_GUIENGINE
+    struct rtgui_event_mouse emouse;
+
+    emouse.parent.sender = RT_NULL;
+    emouse.wid = RT_NULL;
+
+    emouse.button = RTGUI_MOUSE_BUTTON_LEFT | RTGUI_MOUSE_BUTTON_DOWN;
+    emouse.parent.type = RTGUI_EVENT_MOUSE_MOTION;
+    emouse.x = x;
+    emouse.y = y;
+    emouse.ts = rt_tick_get();
+    emouse.id = ts;
+    rtgui_server_post_event(&emouse.parent, sizeof(emouse));
+#elif defined(PKG_USING_LITTLEVGL2RTT)
+    littlevgl2rtt_send_input_event(x, y, LITTLEVGL2RTT_INPUT_MOVE);
+#endif
+}
+
+static void post_up_event(rt_uint16_t x, rt_uint16_t y, rt_tick_t ts)
+{
+#ifdef PKG_USING_GUIENGINE
+    struct rtgui_event_mouse emouse;
+
+    emouse.parent.sender = RT_NULL;
+    emouse.wid = RT_NULL;
+
+    emouse.parent.type = RTGUI_EVENT_MOUSE_BUTTON;
+    emouse.button = RTGUI_MOUSE_BUTTON_LEFT | RTGUI_MOUSE_BUTTON_UP;
+    emouse.x = x;
+    emouse.y = y;
+    emouse.ts = rt_tick_get();
+    emouse.id = ts;
+    rtgui_server_post_event(&emouse.parent, sizeof(emouse));
+#elif defined(PKG_USING_LITTLEVGL2RTT)
+    littlevgl2rtt_send_input_event(x, y, LITTLEVGL2RTT_INPUT_MOVE);
+#endif
+}
+
+static void touch_thread_entry(void *parameter)
+{
+    touch_drv_t touch = (touch_drv_t)parameter;
+    struct touch_message msg;
+    rt_tick_t emouse_id = 0;
+    touch->ops->isr_enable(RT_TRUE);
+    while (1)
+    {
+        if (rt_sem_take(touch->isr_sem, 10) != RT_EOK)
+        {
+            continue;
+        }
+        
+        while(touch->ops->read_point(&msg) == RT_EOK)
+        {
+            switch (msg.event)
+            {
+            case TOUCH_EVENT_UP:
+                post_up_event(msg.x, msg.y, emouse_id);
+                break;
+            case TOUCH_EVENT_DOWN:
+                emouse_id = rt_tick_get();
+                post_down_event(msg.x, msg.y, emouse_id);
+                break;
+            case TOUCH_EVENT_MOVE:
+                post_motion_event(msg.x, msg.y, emouse_id);
+                break;
+            default:
+                break;
+            }
+            rt_thread_delay(RT_TICK_PER_SECOND / BSP_TOUCH_SAMPLE_HZ);
+        }
+        touch->ops->isr_enable(RT_TRUE);
+    }
+}
+
+static int rt_touch_driver_init(void)
+{
+    rt_list_init(&driver_list);
+    return 0;
+}
+INIT_BOARD_EXPORT(rt_touch_driver_init);
+
+static struct rt_i2c_bus_device *i2c_bus = RT_NULL;
+static int rt_touch_thread_init(void)
+{
+    rt_list_t *l;
+    touch_drv_t current_driver;
+    rt_thread_t tid = RT_NULL;
+    i2c_bus = (struct rt_i2c_bus_device *)rt_device_find(BSP_I2C_NAME);
+    RT_ASSERT(i2c_bus);
+    current_driver = RT_NULL;
+    if (rt_device_open((rt_device_t)i2c_bus, RT_DEVICE_OFLAG_RDWR) != RT_EOK)
+        return -1;
+    for (l = driver_list.next; l != &driver_list; l = l->next)
+    {
+        if (rt_list_entry(l, struct touch_drivers, list)->probe(i2c_bus))
+        {
+            current_driver = rt_list_entry(l, struct touch_drivers, list);
+            break;
+        }
+    }
+    if (current_driver == RT_NULL)
+    {
+        LOG_E("no touch screen or do not have driver\r\n");
+        rt_device_close((rt_device_t)i2c_bus);
+        return -1;
+    }
+    current_driver->ops->init(i2c_bus);
+    LOG_I("touch screen found driver\r\n");
+    tid = rt_thread_create("touch", touch_thread_entry, current_driver, 2048, 27, 20);
+    if (tid == RT_NULL)
+    {
+        current_driver->ops->deinit();
+        rt_device_close((rt_device_t)i2c_bus);
+        return -1;
+    }
+    rt_thread_startup(tid);
+    return 0;
+}
+
+static void touch_init_thread_entry(void *parameter)
+{
+    rt_touch_thread_init();
+}
+
+static int touc_bg_init(void)
+{
+    rt_thread_t tid = RT_NULL;
+    tid = rt_thread_create("touchi", touch_init_thread_entry, RT_NULL, 2048, 28, 20);
+    if (tid == RT_NULL)
+    {
+        return -1;
+    }
+    rt_thread_startup(tid);
+    return 0;
+}
+INIT_APP_EXPORT(touc_bg_init);
+
+
+#endif

+ 68 - 0
bsp/stm32/stm32f469-st-disco/board/ports/touch/drv_touch.h

@@ -0,0 +1,68 @@
+/*
+ * File      : drv_touch.h
+ * This file is part of RT-Thread RTOS
+ * COPYRIGHT (C) 2017, RT-Thread Development Team
+ *
+ *  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 2 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, write to the Free Software Foundation, Inc.,
+ *  51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2018-02-08     Zhangyihong  the first version
+ */
+#ifndef __DRV_TOUCH_H__
+#define __DRV_TOUCH_H__
+
+#include "rtthread.h"
+#include "rtdevice.h"
+
+#define TOUCH_DBG_LEVEL DBG_LOG
+
+#define IIC_RETRY_NUM 2
+
+#define TOUCH_EVENT_UP      (0x01)
+#define TOUCH_EVENT_DOWN    (0x02)
+#define TOUCH_EVENT_MOVE    (0x03)
+#define TOUCH_EVENT_NONE    (0x80)
+
+struct touch_message
+{
+    rt_uint16_t x;
+    rt_uint16_t y;
+    rt_uint8_t event;
+};
+typedef struct touch_message *touch_msg_t;
+
+struct touch_ops
+{
+    void (* isr_enable)(rt_bool_t);
+    rt_err_t (* read_point)(touch_msg_t);
+    void (* init)(struct rt_i2c_bus_device *);
+    void (* deinit)(void);
+};
+typedef struct touch_ops *touch_ops_t;
+
+struct touch_drivers
+{
+    rt_list_t       list;
+    unsigned char   address;
+    rt_bool_t (*probe)(struct rt_i2c_bus_device *i2c_bus);
+    rt_sem_t        isr_sem;
+    touch_ops_t     ops;
+    void           *user_data;
+};
+typedef struct touch_drivers *touch_drv_t;
+
+extern void rt_touch_drivers_register(touch_drv_t drv);
+#endif

+ 227 - 0
bsp/stm32/stm32f469-st-disco/board/ports/touch/drv_touch_ft.c

@@ -0,0 +1,227 @@
+/*
+ * File      : drv_touch_ft.c
+ *             ft touch driver
+ * COPYRIGHT (C) 2006 - 2017, RT-Thread Development Team
+ *
+ *  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 2 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, write to the Free Software Foundation, Inc.,
+ *  51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
+ *
+ * Change Logs:
+ * Date           Author        Notes
+ * 2017-08-08     Yang          the first version
+ * 2019-04-23     WillianChan   porting to ft6206
+ */
+
+#include <rtthread.h>
+#include <rthw.h>
+#include <rtdevice.h>
+#include "drv_touch.h"
+#include <string.h>
+
+#ifdef BSP_USING_TOUCH
+
+#define DBG_ENABLE
+#define DBG_SECTION_NAME  "TOUCH.ft"
+#define DBG_LEVEL         TOUCH_DBG_LEVEL
+#define DBG_COLOR
+#include <rtdbg.h>
+
+static struct rt_i2c_bus_device *ft_i2c_bus;
+static struct touch_drivers ft_driver;
+
+static int ft_read(struct rt_i2c_bus_device *i2c_bus, rt_uint8_t addr, rt_uint8_t *buffer, rt_size_t length)
+{
+    int ret = -1;
+    int retries = 0;
+
+    struct rt_i2c_msg msgs[] =
+    {
+        {
+            .addr   = ft_driver.address,
+            .flags  = RT_I2C_WR,
+            .len    = 1,
+            .buf    = &addr,
+        },
+        {
+            .addr   = ft_driver.address,
+            .flags  = RT_I2C_RD,
+            .len    = length,
+            .buf    = buffer,
+        },
+    };
+
+    while (retries < IIC_RETRY_NUM)
+    {
+        ret = rt_i2c_transfer(i2c_bus, msgs, 2);
+        if (ret == 2)break;
+        retries++;
+    }
+
+    if (retries >= IIC_RETRY_NUM)
+    {
+        LOG_E("%s i2c read error: %d", __func__, ret);
+        return -1;
+    }
+
+    return ret;
+}
+
+static void ft_write(touch_drv_t driver, struct rt_i2c_bus_device *i2c_bus, rt_uint8_t addr, rt_uint8_t *buffer, rt_size_t length)
+{
+    rt_uint8_t *send_buffer = rt_malloc(length + 1);
+
+    RT_ASSERT(send_buffer);
+
+    send_buffer[0] = addr;
+    memcpy(send_buffer + 1, buffer, length);
+
+    struct rt_i2c_msg msgs[] =
+    {
+        {
+            .addr   = ft_driver.address,
+            .flags  = RT_I2C_WR,
+            .len    = length + 1,
+            .buf    = send_buffer,
+        }
+    };
+
+    length = rt_i2c_transfer(i2c_bus, msgs, 1);
+    rt_free(send_buffer);
+    send_buffer = RT_NULL;
+}
+
+static void ft_isr_enable(rt_bool_t enable)
+{
+    rt_pin_irq_enable(BSP_TOUCH_INT_PIN, enable);
+}
+
+static void ft_touch_isr(void *parameter)
+{
+    ft_isr_enable(RT_FALSE);
+    rt_sem_release(ft_driver.isr_sem);
+}
+
+static rt_err_t ft_read_point(touch_msg_t msg)
+{
+    int ret = -1;
+    uint8_t point_num = 0;
+    static uint8_t s_tp_down = 0;
+    uint8_t point[6];
+    ret = ft_read(ft_i2c_bus, 0x02, &point_num, 1);
+    if (ret < 0)
+    {
+        return RT_ERROR;
+    }
+    
+    if (point_num == 0)
+    {
+        if (s_tp_down)
+        {
+            s_tp_down = 0;
+            msg->event = TOUCH_EVENT_UP;
+            return RT_EOK;
+        }
+        msg->event = TOUCH_EVENT_NONE;
+        return RT_ERROR;
+    }
+    
+    ret = ft_read(ft_i2c_bus, 0x03, point, 6);
+    if (ret < 0)
+    {
+        return RT_ERROR;
+    }
+
+    msg->y = (point[0]&0x0F) << 8 | point[1];
+    msg->x = (point[2]&0x0F) << 8 | point[3];
+    
+    if (s_tp_down)
+    {
+        msg->event = TOUCH_EVENT_MOVE;
+        return RT_EOK;
+    }
+    msg->event = TOUCH_EVENT_DOWN;
+    s_tp_down = 1;
+    
+    return RT_EOK;
+}
+
+static void ft_init(struct rt_i2c_bus_device *i2c_bus)
+{
+    if (ft_i2c_bus == RT_NULL)
+    {
+        ft_i2c_bus = i2c_bus;
+    }
+    ft_driver.isr_sem = rt_sem_create("ft", 0, RT_IPC_FLAG_FIFO);
+    RT_ASSERT(ft_driver.isr_sem);
+
+    rt_pin_mode(BSP_TOUCH_INT_PIN, PIN_MODE_INPUT_PULLUP);
+    rt_pin_attach_irq(BSP_TOUCH_INT_PIN, PIN_IRQ_MODE_FALLING, ft_touch_isr, RT_NULL);
+
+    rt_thread_mdelay(200);
+}
+
+static void ft_deinit(void)
+{
+    if (ft_driver.isr_sem)
+    {
+        rt_sem_delete(ft_driver.isr_sem);
+        ft_driver.isr_sem = RT_NULL;
+    }
+}
+
+struct touch_ops ft_ops =
+{
+    ft_isr_enable,
+    ft_read_point,
+    ft_init,
+    ft_deinit,
+};
+
+static rt_bool_t ft_probe(struct rt_i2c_bus_device *i2c_bus)
+{
+    int err = 0;
+    uint8_t cid = 0xFF;
+
+    ft_i2c_bus = i2c_bus;
+    /* FT6206 Chip identification register address is 0xA8 */
+    err = ft_read(ft_i2c_bus, 0xA8, (uint8_t *)&cid, 1);
+    if (err < 0)
+    {
+        LOG_E("%s failed: %d", __func__, err);
+        return RT_FALSE;
+    }
+    LOG_I("touch CID:0x%02X", cid);
+    /* FT6206 ID Value is 0x11 */
+    if(cid == 0x11)
+    {
+        return RT_TRUE;
+    }
+    return RT_FALSE;
+}
+
+int ft_driver_register(void)
+{
+    /* TouchScreen FT6206 Slave I2C address is 0x54
+     * 0x54 << 1 = 0x2A
+     */
+    ft_driver.address = 0x2A;
+    ft_driver.probe = ft_probe;
+    ft_driver.ops = &ft_ops;
+    ft_driver.user_data = RT_NULL;
+    rt_touch_drivers_register(&ft_driver);
+    return 0;
+}
+INIT_DEVICE_EXPORT(ft_driver_register);
+
+#endif

+ 18 - 0
bsp/stm32/stm32f469-st-disco/project.ewp

@@ -2135,6 +2135,9 @@
     <file>
       <name>$PROJ_DIR$\..\libraries\HAL_Drivers\drv_usart.c</name>
     </file>
+    <file>
+      <name>$PROJ_DIR$\..\libraries\HAL_Drivers\drv_soft_i2c.c</name>
+    </file>
     <file>
       <name>$PROJ_DIR$\..\libraries\HAL_Drivers\drv_common.c</name>
     </file>
@@ -2159,6 +2162,15 @@
   </group>
   <group>
     <name>DeviceDrivers</name>
+    <file>
+      <name>$PROJ_DIR$\..\..\..\components\drivers\i2c\i2c_core.c</name>
+    </file>
+    <file>
+      <name>$PROJ_DIR$\..\..\..\components\drivers\i2c\i2c_dev.c</name>
+    </file>
+    <file>
+      <name>$PROJ_DIR$\..\..\..\components\drivers\i2c\i2c-bit-ops.c</name>
+    </file>
     <file>
       <name>$PROJ_DIR$\..\..\..\components\drivers\misc\pin.c</name>
     </file>
@@ -2291,5 +2303,11 @@
     <file>
       <name>$PROJ_DIR$\..\libraries\STM32F4xx_HAL\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_usart.c</name>
     </file>
+    <file>
+      <name>$PROJ_DIR$\..\libraries\STM32F4xx_HAL\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_i2c.c</name>
+    </file>
+    <file>
+      <name>$PROJ_DIR$\..\libraries\STM32F4xx_HAL\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_i2c_ex.c</name>
+    </file>
   </group>
 </project>

+ 102 - 42
bsp/stm32/stm32f469-st-disco/project.uvoptx

@@ -408,7 +408,7 @@
 
   <Group>
     <GroupName>Drivers</GroupName>
-    <tvExp>0</tvExp>
+    <tvExp>1</tvExp>
     <tvExpOptDlg>0</tvExpOptDlg>
     <cbSel>0</cbSel>
     <RteFlg>0</RteFlg>
@@ -567,6 +567,42 @@
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
       <bDave2>0</bDave2>
+      <PathWithFileName>..\..\..\components\drivers\i2c\i2c_core.c</PathWithFileName>
+      <FilenameWithoutPath>i2c_core.c</FilenameWithoutPath>
+      <RteFlg>0</RteFlg>
+      <bShared>0</bShared>
+    </File>
+    <File>
+      <GroupNumber>5</GroupNumber>
+      <FileNumber>30</FileNumber>
+      <FileType>1</FileType>
+      <tvExp>0</tvExp>
+      <tvExpOptDlg>0</tvExpOptDlg>
+      <bDave2>0</bDave2>
+      <PathWithFileName>..\..\..\components\drivers\i2c\i2c_dev.c</PathWithFileName>
+      <FilenameWithoutPath>i2c_dev.c</FilenameWithoutPath>
+      <RteFlg>0</RteFlg>
+      <bShared>0</bShared>
+    </File>
+    <File>
+      <GroupNumber>5</GroupNumber>
+      <FileNumber>31</FileNumber>
+      <FileType>1</FileType>
+      <tvExp>0</tvExp>
+      <tvExpOptDlg>0</tvExpOptDlg>
+      <bDave2>0</bDave2>
+      <PathWithFileName>..\..\..\components\drivers\i2c\i2c-bit-ops.c</PathWithFileName>
+      <FilenameWithoutPath>i2c-bit-ops.c</FilenameWithoutPath>
+      <RteFlg>0</RteFlg>
+      <bShared>0</bShared>
+    </File>
+    <File>
+      <GroupNumber>5</GroupNumber>
+      <FileNumber>32</FileNumber>
+      <FileType>1</FileType>
+      <tvExp>0</tvExp>
+      <tvExpOptDlg>0</tvExpOptDlg>
+      <bDave2>0</bDave2>
       <PathWithFileName>..\..\..\components\drivers\misc\pin.c</PathWithFileName>
       <FilenameWithoutPath>pin.c</FilenameWithoutPath>
       <RteFlg>0</RteFlg>
@@ -574,7 +610,7 @@
     </File>
     <File>
       <GroupNumber>5</GroupNumber>
-      <FileNumber>30</FileNumber>
+      <FileNumber>33</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -586,7 +622,7 @@
     </File>
     <File>
       <GroupNumber>5</GroupNumber>
-      <FileNumber>31</FileNumber>
+      <FileNumber>34</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -598,7 +634,7 @@
     </File>
     <File>
       <GroupNumber>5</GroupNumber>
-      <FileNumber>32</FileNumber>
+      <FileNumber>35</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -610,7 +646,7 @@
     </File>
     <File>
       <GroupNumber>5</GroupNumber>
-      <FileNumber>33</FileNumber>
+      <FileNumber>36</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -622,7 +658,7 @@
     </File>
     <File>
       <GroupNumber>5</GroupNumber>
-      <FileNumber>34</FileNumber>
+      <FileNumber>37</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -634,7 +670,7 @@
     </File>
     <File>
       <GroupNumber>5</GroupNumber>
-      <FileNumber>35</FileNumber>
+      <FileNumber>38</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -646,7 +682,7 @@
     </File>
     <File>
       <GroupNumber>5</GroupNumber>
-      <FileNumber>36</FileNumber>
+      <FileNumber>39</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -658,7 +694,7 @@
     </File>
     <File>
       <GroupNumber>5</GroupNumber>
-      <FileNumber>37</FileNumber>
+      <FileNumber>40</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -678,7 +714,7 @@
     <RteFlg>0</RteFlg>
     <File>
       <GroupNumber>6</GroupNumber>
-      <FileNumber>38</FileNumber>
+      <FileNumber>41</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -690,7 +726,7 @@
     </File>
     <File>
       <GroupNumber>6</GroupNumber>
-      <FileNumber>39</FileNumber>
+      <FileNumber>42</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -702,7 +738,7 @@
     </File>
     <File>
       <GroupNumber>6</GroupNumber>
-      <FileNumber>40</FileNumber>
+      <FileNumber>43</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -714,7 +750,7 @@
     </File>
     <File>
       <GroupNumber>6</GroupNumber>
-      <FileNumber>41</FileNumber>
+      <FileNumber>44</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -726,7 +762,7 @@
     </File>
     <File>
       <GroupNumber>6</GroupNumber>
-      <FileNumber>42</FileNumber>
+      <FileNumber>45</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -738,7 +774,7 @@
     </File>
     <File>
       <GroupNumber>6</GroupNumber>
-      <FileNumber>43</FileNumber>
+      <FileNumber>46</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -750,7 +786,7 @@
     </File>
     <File>
       <GroupNumber>6</GroupNumber>
-      <FileNumber>44</FileNumber>
+      <FileNumber>47</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -762,7 +798,7 @@
     </File>
     <File>
       <GroupNumber>6</GroupNumber>
-      <FileNumber>45</FileNumber>
+      <FileNumber>48</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -774,7 +810,7 @@
     </File>
     <File>
       <GroupNumber>6</GroupNumber>
-      <FileNumber>46</FileNumber>
+      <FileNumber>49</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -786,7 +822,7 @@
     </File>
     <File>
       <GroupNumber>6</GroupNumber>
-      <FileNumber>47</FileNumber>
+      <FileNumber>50</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -798,7 +834,7 @@
     </File>
     <File>
       <GroupNumber>6</GroupNumber>
-      <FileNumber>48</FileNumber>
+      <FileNumber>51</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -810,7 +846,7 @@
     </File>
     <File>
       <GroupNumber>6</GroupNumber>
-      <FileNumber>49</FileNumber>
+      <FileNumber>52</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -822,7 +858,7 @@
     </File>
     <File>
       <GroupNumber>6</GroupNumber>
-      <FileNumber>50</FileNumber>
+      <FileNumber>53</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -834,7 +870,7 @@
     </File>
     <File>
       <GroupNumber>6</GroupNumber>
-      <FileNumber>51</FileNumber>
+      <FileNumber>54</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -846,7 +882,7 @@
     </File>
     <File>
       <GroupNumber>6</GroupNumber>
-      <FileNumber>52</FileNumber>
+      <FileNumber>55</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -858,7 +894,7 @@
     </File>
     <File>
       <GroupNumber>6</GroupNumber>
-      <FileNumber>53</FileNumber>
+      <FileNumber>56</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -878,7 +914,7 @@
     <RteFlg>0</RteFlg>
     <File>
       <GroupNumber>7</GroupNumber>
-      <FileNumber>54</FileNumber>
+      <FileNumber>57</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -890,7 +926,7 @@
     </File>
     <File>
       <GroupNumber>7</GroupNumber>
-      <FileNumber>55</FileNumber>
+      <FileNumber>58</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -902,7 +938,7 @@
     </File>
     <File>
       <GroupNumber>7</GroupNumber>
-      <FileNumber>56</FileNumber>
+      <FileNumber>59</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -914,7 +950,7 @@
     </File>
     <File>
       <GroupNumber>7</GroupNumber>
-      <FileNumber>57</FileNumber>
+      <FileNumber>60</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -926,7 +962,7 @@
     </File>
     <File>
       <GroupNumber>7</GroupNumber>
-      <FileNumber>58</FileNumber>
+      <FileNumber>61</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -938,7 +974,7 @@
     </File>
     <File>
       <GroupNumber>7</GroupNumber>
-      <FileNumber>59</FileNumber>
+      <FileNumber>62</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -950,7 +986,7 @@
     </File>
     <File>
       <GroupNumber>7</GroupNumber>
-      <FileNumber>60</FileNumber>
+      <FileNumber>63</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -962,7 +998,7 @@
     </File>
     <File>
       <GroupNumber>7</GroupNumber>
-      <FileNumber>61</FileNumber>
+      <FileNumber>64</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -974,7 +1010,7 @@
     </File>
     <File>
       <GroupNumber>7</GroupNumber>
-      <FileNumber>62</FileNumber>
+      <FileNumber>65</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -986,7 +1022,7 @@
     </File>
     <File>
       <GroupNumber>7</GroupNumber>
-      <FileNumber>63</FileNumber>
+      <FileNumber>66</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -998,7 +1034,7 @@
     </File>
     <File>
       <GroupNumber>7</GroupNumber>
-      <FileNumber>64</FileNumber>
+      <FileNumber>67</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -1010,7 +1046,7 @@
     </File>
     <File>
       <GroupNumber>7</GroupNumber>
-      <FileNumber>65</FileNumber>
+      <FileNumber>68</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -1022,7 +1058,7 @@
     </File>
     <File>
       <GroupNumber>7</GroupNumber>
-      <FileNumber>66</FileNumber>
+      <FileNumber>69</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -1034,7 +1070,7 @@
     </File>
     <File>
       <GroupNumber>7</GroupNumber>
-      <FileNumber>67</FileNumber>
+      <FileNumber>70</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -1046,7 +1082,7 @@
     </File>
     <File>
       <GroupNumber>7</GroupNumber>
-      <FileNumber>68</FileNumber>
+      <FileNumber>71</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -1058,7 +1094,7 @@
     </File>
     <File>
       <GroupNumber>7</GroupNumber>
-      <FileNumber>69</FileNumber>
+      <FileNumber>72</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -1070,7 +1106,7 @@
     </File>
     <File>
       <GroupNumber>7</GroupNumber>
-      <FileNumber>70</FileNumber>
+      <FileNumber>73</FileNumber>
       <FileType>1</FileType>
       <tvExp>0</tvExp>
       <tvExpOptDlg>0</tvExpOptDlg>
@@ -1080,6 +1116,30 @@
       <RteFlg>0</RteFlg>
       <bShared>0</bShared>
     </File>
+    <File>
+      <GroupNumber>7</GroupNumber>
+      <FileNumber>74</FileNumber>
+      <FileType>1</FileType>
+      <tvExp>0</tvExp>
+      <tvExpOptDlg>0</tvExpOptDlg>
+      <bDave2>0</bDave2>
+      <PathWithFileName>..\libraries\STM32F4xx_HAL\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_i2c.c</PathWithFileName>
+      <FilenameWithoutPath>stm32f4xx_hal_i2c.c</FilenameWithoutPath>
+      <RteFlg>0</RteFlg>
+      <bShared>0</bShared>
+    </File>
+    <File>
+      <GroupNumber>7</GroupNumber>
+      <FileNumber>75</FileNumber>
+      <FileType>1</FileType>
+      <tvExp>0</tvExp>
+      <tvExpOptDlg>0</tvExpOptDlg>
+      <bDave2>0</bDave2>
+      <PathWithFileName>..\libraries\STM32F4xx_HAL\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_i2c_ex.c</PathWithFileName>
+      <FilenameWithoutPath>stm32f4xx_hal_i2c_ex.c</FilenameWithoutPath>
+      <RteFlg>0</RteFlg>
+      <bShared>0</bShared>
+    </File>
   </Group>
 
 </ProjectOpt>

+ 43 - 1
bsp/stm32/stm32f469-st-disco/project.uvproj

@@ -359,7 +359,7 @@
               <MiscControls />
               <Define>USE_HAL_DRIVER, STM32F469xx</Define>
               <Undefine />
-              <IncludePath>.;..\..\..\include;applications;board;board\CubeMX_Config\Inc;board\ports;..\libraries\HAL_Drivers;..\libraries\HAL_Drivers\config;..\..\..\libcpu\arm\common;..\..\..\libcpu\arm\cortex-m4;..\..\..\components\drivers\include;..\..\..\components\drivers\include;..\..\..\components\drivers\include;..\..\..\components\finsh;..\libraries\STM32F4xx_HAL\STM32F4xx_HAL_Driver\Inc;..\libraries\STM32F4xx_HAL\CMSIS\Device\ST\STM32F4xx\Include;..\libraries\STM32F4xx_HAL\CMSIS\Include</IncludePath>
+              <IncludePath>.;..\..\..\include;applications;board;board\CubeMX_Config\Inc;board\ports;..\libraries\HAL_Drivers;..\libraries\HAL_Drivers\config;..\..\..\libcpu\arm\common;..\..\..\libcpu\arm\cortex-m4;..\..\..\components\drivers\include;..\..\..\components\drivers\include;..\..\..\components\drivers\include;..\..\..\components\drivers\include;..\..\..\components\finsh;..\libraries\STM32F4xx_HAL\STM32F4xx_HAL_Driver\Inc;..\libraries\STM32F4xx_HAL\CMSIS\Device\ST\STM32F4xx\Include;..\libraries\STM32F4xx_HAL\CMSIS\Include</IncludePath>
             </VariousControls>
           </Cads>
           <Aads>
@@ -561,6 +561,13 @@
               <FilePath>..\libraries\HAL_Drivers\drv_usart.c</FilePath>
             </File>
           </Files>
+          <Files>
+            <File>
+              <FileName>drv_soft_i2c.c</FileName>
+              <FileType>1</FileType>
+              <FilePath>..\libraries\HAL_Drivers\drv_soft_i2c.c</FilePath>
+            </File>
+          </Files>
           <Files>
             <File>
               <FileName>drv_common.c</FileName>
@@ -609,6 +616,27 @@
         </Group>
         <Group>
           <GroupName>DeviceDrivers</GroupName>
+          <Files>
+            <File>
+              <FileName>i2c_core.c</FileName>
+              <FileType>1</FileType>
+              <FilePath>..\..\..\components\drivers\i2c\i2c_core.c</FilePath>
+            </File>
+          </Files>
+          <Files>
+            <File>
+              <FileName>i2c_dev.c</FileName>
+              <FileType>1</FileType>
+              <FilePath>..\..\..\components\drivers\i2c\i2c_dev.c</FilePath>
+            </File>
+          </Files>
+          <Files>
+            <File>
+              <FileName>i2c-bit-ops.c</FileName>
+              <FileType>1</FileType>
+              <FilePath>..\..\..\components\drivers\i2c\i2c-bit-ops.c</FilePath>
+            </File>
+          </Files>
           <Files>
             <File>
               <FileName>pin.c</FileName>
@@ -909,6 +937,20 @@
               <FilePath>..\libraries\STM32F4xx_HAL\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_usart.c</FilePath>
             </File>
           </Files>
+          <Files>
+            <File>
+              <FileName>stm32f4xx_hal_i2c.c</FileName>
+              <FileType>1</FileType>
+              <FilePath>..\libraries\STM32F4xx_HAL\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_i2c.c</FilePath>
+            </File>
+          </Files>
+          <Files>
+            <File>
+              <FileName>stm32f4xx_hal_i2c_ex.c</FileName>
+              <FileType>1</FileType>
+              <FilePath>..\libraries\STM32F4xx_HAL\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_i2c_ex.c</FilePath>
+            </File>
+          </Files>
         </Group>
       </Groups>
     </Target>

+ 26 - 1
bsp/stm32/stm32f469-st-disco/project.uvprojx

@@ -338,7 +338,7 @@
               <MiscControls></MiscControls>
               <Define>USE_HAL_DRIVER, STM32F469xx</Define>
               <Undefine></Undefine>
-              <IncludePath>.;..\..\..\include;applications;board;board\CubeMX_Config\Inc;board\ports;..\libraries\HAL_Drivers;..\libraries\HAL_Drivers\config;..\..\..\libcpu\arm\common;..\..\..\libcpu\arm\cortex-m4;..\..\..\components\drivers\include;..\..\..\components\drivers\include;..\..\..\components\drivers\include;..\..\..\components\finsh;..\libraries\STM32F4xx_HAL\STM32F4xx_HAL_Driver\Inc;..\libraries\STM32F4xx_HAL\CMSIS\Device\ST\STM32F4xx\Include;..\libraries\STM32F4xx_HAL\CMSIS\Include</IncludePath>
+              <IncludePath>.;..\..\..\include;applications;board;board\CubeMX_Config\Inc;board\ports;..\libraries\HAL_Drivers;..\libraries\HAL_Drivers\config;..\..\..\libcpu\arm\common;..\..\..\libcpu\arm\cortex-m4;..\..\..\components\drivers\include;..\..\..\components\drivers\include;..\..\..\components\drivers\include;..\..\..\components\drivers\include;..\..\..\components\finsh;..\libraries\STM32F4xx_HAL\STM32F4xx_HAL_Driver\Inc;..\libraries\STM32F4xx_HAL\CMSIS\Device\ST\STM32F4xx\Include;..\libraries\STM32F4xx_HAL\CMSIS\Include</IncludePath>
             </VariousControls>
           </Cads>
           <Aads>
@@ -542,6 +542,21 @@
         <Group>
           <GroupName>DeviceDrivers</GroupName>
           <Files>
+            <File>
+              <FileName>i2c_core.c</FileName>
+              <FileType>1</FileType>
+              <FilePath>..\..\..\components\drivers\i2c\i2c_core.c</FilePath>
+            </File>
+            <File>
+              <FileName>i2c_dev.c</FileName>
+              <FileType>1</FileType>
+              <FilePath>..\..\..\components\drivers\i2c\i2c_dev.c</FilePath>
+            </File>
+            <File>
+              <FileName>i2c-bit-ops.c</FileName>
+              <FileType>1</FileType>
+              <FilePath>..\..\..\components\drivers\i2c\i2c-bit-ops.c</FilePath>
+            </File>
             <File>
               <FileName>pin.c</FileName>
               <FileType>1</FileType>
@@ -762,6 +777,16 @@
               <FileType>1</FileType>
               <FilePath>..\libraries\STM32F4xx_HAL\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_usart.c</FilePath>
             </File>
+            <File>
+              <FileName>stm32f4xx_hal_i2c.c</FileName>
+              <FileType>1</FileType>
+              <FilePath>..\libraries\STM32F4xx_HAL\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_i2c.c</FilePath>
+            </File>
+            <File>
+              <FileName>stm32f4xx_hal_i2c_ex.c</FileName>
+              <FileType>1</FileType>
+              <FilePath>..\libraries\STM32F4xx_HAL\STM32F4xx_HAL_Driver\Src\stm32f4xx_hal_i2c_ex.c</FilePath>
+            </File>
           </Files>
         </Group>
       </Groups>