meta-st-stm32mp/recipes-kernel/linux/linux-stm32mp/5.10/5.10.10/0016-ARM-5.10.10-stm32mp1-r...

1503 lines
46 KiB
Diff

From c74780d4cb41745849aaf03a9704a96ee9ae92ba Mon Sep 17 00:00:00 2001
From: Romuald JEANNE <romuald.jeanne@st.com>
Date: Tue, 16 Mar 2021 09:16:04 +0100
Subject: [PATCH 16/22] ARM 5.10.10-stm32mp1-r1 PINCTRL-REGULATOR-SPI
Signed-off-by: Romuald JEANNE <romuald.jeanne@st.com>
---
drivers/pinctrl/stm32/pinctrl-stm32.c | 42 ++-
drivers/pinctrl/stm32/pinctrl-stm32.h | 17 +-
drivers/pinctrl/stm32/pinctrl-stm32mp157.c | 1 +
drivers/pwm/pwm-stm32.c | 4 +
drivers/regulator/stm32-pwr.c | 85 ++++-
drivers/regulator/stpmic1_regulator.c | 182 ++++++++++-
drivers/spi/spi-stm32-qspi.c | 18 +-
drivers/spi/spi-stm32.c | 345 +++++++++++---------
include/dt-bindings/pinctrl/stm32-pinfunc.h | 1 +
9 files changed, 508 insertions(+), 187 deletions(-)
diff --git a/drivers/pinctrl/stm32/pinctrl-stm32.c b/drivers/pinctrl/stm32/pinctrl-stm32.c
index 7d9bdedcd71b..a20c06b06e19 100644
--- a/drivers/pinctrl/stm32/pinctrl-stm32.c
+++ b/drivers/pinctrl/stm32/pinctrl-stm32.c
@@ -73,6 +73,7 @@ static const char * const stm32_gpio_functions[] = {
"af8", "af9", "af10",
"af11", "af12", "af13",
"af14", "af15", "analog",
+ "reserved",
};
struct stm32_pinctrl_group {
@@ -115,6 +116,7 @@ struct stm32_pinctrl {
u32 pkg;
u16 irqmux_map;
spinlock_t irqmux_lock;
+ u32 pin_base_shift;
};
static inline int stm32_gpio_pin(int gpio)
@@ -513,7 +515,7 @@ stm32_pctrl_find_group_by_pin(struct stm32_pinctrl *pctl, u32 pin)
static bool stm32_pctrl_is_function_valid(struct stm32_pinctrl *pctl,
u32 pin_num, u32 fnum)
{
- int i;
+ int i, k;
for (i = 0; i < pctl->npins; i++) {
const struct stm32_desc_pin *pin = pctl->pins + i;
@@ -522,7 +524,10 @@ static bool stm32_pctrl_is_function_valid(struct stm32_pinctrl *pctl,
if (pin->pin.number != pin_num)
continue;
- while (func && func->name) {
+ if (fnum == STM32_PIN_RSVD)
+ return true;
+
+ for (k = 0; k < STM32_CONFIG_NUM; k++) {
if (func->num == fnum)
return true;
func++;
@@ -833,6 +838,11 @@ static int stm32_pmx_set_mux(struct pinctrl_dev *pctldev,
return -EINVAL;
}
+ if (function == STM32_PIN_RSVD) {
+ dev_dbg(pctl->dev, "Reserved pins, skipping HW update.\n");
+ return 0;
+ }
+
bank = gpiochip_get_data(range->gc);
pin = stm32_gpio_pin(g->pin);
@@ -1147,10 +1157,27 @@ static int stm32_pconf_set(struct pinctrl_dev *pctldev, unsigned int pin,
return 0;
}
+static struct stm32_desc_pin *
+stm32_pconf_get_pin_desc_by_pin_number(struct stm32_pinctrl *pctl,
+ unsigned int pin_number)
+{
+ struct stm32_desc_pin *pins = pctl->pins;
+ int i;
+
+ for (i = 0; i < pctl->npins; i++) {
+ if (pins->pin.number == pin_number)
+ return pins;
+ pins++;
+ }
+ return NULL;
+}
+
static void stm32_pconf_dbg_show(struct pinctrl_dev *pctldev,
struct seq_file *s,
unsigned int pin)
{
+ struct stm32_pinctrl *pctl = pinctrl_dev_get_drvdata(pctldev);
+ const struct stm32_desc_pin *pin_desc;
struct pinctrl_gpio_range *range;
struct stm32_gpio_bank *bank;
int offset;
@@ -1200,7 +1227,12 @@ static void stm32_pconf_dbg_show(struct pinctrl_dev *pctldev,
case 2:
drive = stm32_pconf_get_driving(bank, offset);
speed = stm32_pconf_get_speed(bank, offset);
- seq_printf(s, "%d - %s - %s - %s %s", alt,
+ pin_desc = stm32_pconf_get_pin_desc_by_pin_number(pctl, pin);
+ if (!pin_desc)
+ return;
+
+ seq_printf(s, "%d (%s) - %s - %s - %s %s", alt,
+ pin_desc->functions[alt + 1].name,
drive ? "open drain" : "push pull",
biasing[bias],
speeds[speed], "speed");
@@ -1404,7 +1436,8 @@ static int stm32_pctrl_create_pins_tab(struct stm32_pinctrl *pctl,
if (pctl->pkg && !(pctl->pkg & p->pkg))
continue;
pins->pin = p->pin;
- pins->functions = p->functions;
+ memcpy((struct stm32_desc_pin *)pins->functions, p->functions,
+ STM32_CONFIG_NUM * sizeof(struct stm32_desc_function));
pins++;
nb_pins_available++;
}
@@ -1513,6 +1546,7 @@ int stm32_pctl_probe(struct platform_device *pdev)
pctl->pctl_desc.pctlops = &stm32_pctrl_ops;
pctl->pctl_desc.pmxops = &stm32_pmx_ops;
pctl->dev = &pdev->dev;
+ pctl->pin_base_shift = pctl->match_data->pin_base_shift;
pctl->pctl_dev = devm_pinctrl_register(&pdev->dev, &pctl->pctl_desc,
pctl);
diff --git a/drivers/pinctrl/stm32/pinctrl-stm32.h b/drivers/pinctrl/stm32/pinctrl-stm32.h
index b0882d120765..a7137fbff5d0 100644
--- a/drivers/pinctrl/stm32/pinctrl-stm32.h
+++ b/drivers/pinctrl/stm32/pinctrl-stm32.h
@@ -17,6 +17,8 @@
#define STM32_PIN_GPIO 0
#define STM32_PIN_AF(x) ((x) + 1)
#define STM32_PIN_ANALOG (STM32_PIN_AF(15) + 1)
+#define STM32_PIN_RSVD (STM32_PIN_ANALOG + 1)
+#define STM32_CONFIG_NUM (STM32_PIN_RSVD + 1)
/* package information */
#define STM32MP_PKG_AA BIT(0)
@@ -24,6 +26,8 @@
#define STM32MP_PKG_AC BIT(2)
#define STM32MP_PKG_AD BIT(3)
+#define STM32MP157_Z_BASE_SHIFT 400
+
struct stm32_desc_function {
const char *name;
const unsigned char num;
@@ -31,26 +35,26 @@ struct stm32_desc_function {
struct stm32_desc_pin {
struct pinctrl_pin_desc pin;
- const struct stm32_desc_function *functions;
+ const struct stm32_desc_function functions[STM32_CONFIG_NUM];
const unsigned int pkg;
};
#define STM32_PIN(_pin, ...) \
{ \
.pin = _pin, \
- .functions = (struct stm32_desc_function[]){ \
- __VA_ARGS__, { } }, \
+ .functions = { \
+ __VA_ARGS__}, \
}
#define STM32_PIN_PKG(_pin, _pkg, ...) \
{ \
.pin = _pin, \
.pkg = _pkg, \
- .functions = (struct stm32_desc_function[]){ \
- __VA_ARGS__, { } }, \
+ .functions = { \
+ __VA_ARGS__}, \
}
#define STM32_FUNCTION(_num, _name) \
- { \
+ [_num] = { \
.num = _num, \
.name = _name, \
}
@@ -58,6 +62,7 @@ struct stm32_desc_pin {
struct stm32_pinctrl_match_data {
const struct stm32_desc_pin *pins;
const unsigned int npins;
+ const unsigned int pin_base_shift;
};
struct stm32_gpio_bank;
diff --git a/drivers/pinctrl/stm32/pinctrl-stm32mp157.c b/drivers/pinctrl/stm32/pinctrl-stm32mp157.c
index 2ccb99d64df8..86fe6d5ac54d 100644
--- a/drivers/pinctrl/stm32/pinctrl-stm32mp157.c
+++ b/drivers/pinctrl/stm32/pinctrl-stm32mp157.c
@@ -2328,6 +2328,7 @@ static struct stm32_pinctrl_match_data stm32mp157_match_data = {
static struct stm32_pinctrl_match_data stm32mp157_z_match_data = {
.pins = stm32mp157_z_pins,
.npins = ARRAY_SIZE(stm32mp157_z_pins),
+ .pin_base_shift = STM32MP157_Z_BASE_SHIFT,
};
static const struct of_device_id stm32mp157_pctrl_match[] = {
diff --git a/drivers/pwm/pwm-stm32.c b/drivers/pwm/pwm-stm32.c
index d3be944f2ae9..13f47e25572e 100644
--- a/drivers/pwm/pwm-stm32.c
+++ b/drivers/pwm/pwm-stm32.c
@@ -207,6 +207,10 @@ static int stm32_pwm_capture(struct pwm_chip *chip, struct pwm_device *pwm,
regmap_write(priv->regmap, TIM_ARR, priv->max_arr);
regmap_write(priv->regmap, TIM_PSC, psc);
+ /* Reset input selector to its default input and disable slave mode */
+ regmap_write(priv->regmap, TIM_TISEL, 0x0);
+ regmap_write(priv->regmap, TIM_SMCR, 0x0);
+
/* Map TI1 or TI2 PWM input to IC1 & IC2 (or TI3/4 to IC3 & IC4) */
regmap_update_bits(priv->regmap,
pwm->hwpwm < 2 ? TIM_CCMR1 : TIM_CCMR2,
diff --git a/drivers/regulator/stm32-pwr.c b/drivers/regulator/stm32-pwr.c
index 2a42acb7c24e..2b328b970b46 100644
--- a/drivers/regulator/stm32-pwr.c
+++ b/drivers/regulator/stm32-pwr.c
@@ -3,12 +3,15 @@
// Authors: Gabriel Fernandez <gabriel.fernandez@st.com>
// Pascal Paillet <p.paillet@st.com>.
+#include <linux/arm-smccc.h>
#include <linux/io.h>
#include <linux/iopoll.h>
+#include <linux/mfd/syscon.h>
#include <linux/module.h>
#include <linux/of_address.h>
#include <linux/of_device.h>
#include <linux/platform_device.h>
+#include <linux/regmap.h>
#include <linux/regulator/driver.h>
#include <linux/regulator/of_regulator.h>
@@ -24,6 +27,11 @@
#define REG_1_1_EN BIT(30)
#define REG_1_1_RDY BIT(31)
+#define STM32_SMC_PWR 0x82001001
+#define STM32_WRITE 0x1
+#define STM32_SMC_REG_SET 0x2
+#define STM32_SMC_REG_CLEAR 0x3
+
/* list of supported regulators */
enum {
PWR_REG11,
@@ -39,10 +47,18 @@ static u32 ready_mask_table[STM32PWR_REG_NUM_REGS] = {
};
struct stm32_pwr_reg {
+ int tzen;
void __iomem *base;
u32 ready_mask;
};
+#define SMC(class, op, address, val)\
+ ({\
+ struct arm_smccc_res res;\
+ arm_smccc_smc(class, op, address, val,\
+ 0, 0, 0, 0, &res);\
+ })
+
static int stm32_pwr_reg_is_ready(struct regulator_dev *rdev)
{
struct stm32_pwr_reg *priv = rdev_get_drvdata(rdev);
@@ -69,9 +85,15 @@ static int stm32_pwr_reg_enable(struct regulator_dev *rdev)
int ret;
u32 val;
- val = readl_relaxed(priv->base + REG_PWR_CR3);
- val |= rdev->desc->enable_mask;
- writel_relaxed(val, priv->base + REG_PWR_CR3);
+ if (priv->tzen) {
+ SMC(STM32_SMC_PWR, STM32_SMC_REG_SET, REG_PWR_CR3,
+ rdev->desc->enable_mask);
+ } else {
+ val = readl_relaxed(priv->base + REG_PWR_CR3);
+ val |= rdev->desc->enable_mask;
+ writel_relaxed(val, priv->base + REG_PWR_CR3);
+ }
+
/* use an arbitrary timeout of 20ms */
ret = readx_poll_timeout(stm32_pwr_reg_is_ready, rdev, val, val,
@@ -88,9 +110,14 @@ static int stm32_pwr_reg_disable(struct regulator_dev *rdev)
int ret;
u32 val;
- val = readl_relaxed(priv->base + REG_PWR_CR3);
- val &= ~rdev->desc->enable_mask;
- writel_relaxed(val, priv->base + REG_PWR_CR3);
+ if (priv->tzen) {
+ SMC(STM32_SMC_PWR, STM32_SMC_REG_CLEAR, REG_PWR_CR3,
+ rdev->desc->enable_mask);
+ } else {
+ val = readl_relaxed(priv->base + REG_PWR_CR3);
+ val &= ~rdev->desc->enable_mask;
+ writel_relaxed(val, priv->base + REG_PWR_CR3);
+ }
/* use an arbitrary timeout of 20ms */
ret = readx_poll_timeout(stm32_pwr_reg_is_ready, rdev, val, !val,
@@ -121,12 +148,50 @@ static const struct regulator_ops stm32_pwr_reg_ops = {
.supply_name = _supply, \
} \
-static const struct regulator_desc stm32_pwr_desc[] = {
+static struct regulator_desc stm32_pwr_desc[] = {
PWR_REG(PWR_REG11, "reg11", 1100000, REG_1_1_EN, "vdd"),
PWR_REG(PWR_REG18, "reg18", 1800000, REG_1_8_EN, "vdd"),
PWR_REG(PWR_USB33, "usb33", 3300000, USB_3_3_EN, "vdd_3v3_usbfs"),
};
+static int is_stm32_soc_secured(struct platform_device *pdev, int *val)
+{
+ struct device_node *np = pdev->dev.of_node;
+ struct regmap *syscon;
+ u32 reg, mask;
+ int tzc_val = 0;
+ int err;
+
+ syscon = syscon_regmap_lookup_by_phandle(np, "st,tzcr");
+ if (IS_ERR(syscon)) {
+ if (PTR_ERR(syscon) != -EPROBE_DEFER)
+ dev_err(&pdev->dev, "tzcr syscon required\n");
+ return PTR_ERR(syscon);
+ }
+
+ err = of_property_read_u32_index(np, "st,tzcr", 1, &reg);
+ if (err) {
+ dev_err(&pdev->dev, "tzcr offset required !\n");
+ return err;
+ }
+
+ err = of_property_read_u32_index(np, "st,tzcr", 2, &mask);
+ if (err) {
+ dev_err(&pdev->dev, "tzcr mask required !\n");
+ return err;
+ }
+
+ err = regmap_read(syscon, reg, &tzc_val);
+ if (err) {
+ dev_err(&pdev->dev, "failed to read tzcr status !\n");
+ return err;
+ }
+
+ *val = tzc_val & mask;
+
+ return 0;
+}
+
static int stm32_pwr_regulator_probe(struct platform_device *pdev)
{
struct device_node *np = pdev->dev.of_node;
@@ -135,6 +200,11 @@ static int stm32_pwr_regulator_probe(struct platform_device *pdev)
struct regulator_dev *rdev;
struct regulator_config config = { };
int i, ret = 0;
+ int tzen = 0;
+
+ ret = is_stm32_soc_secured(pdev, &tzen);
+ if (ret)
+ return ret;
base = of_iomap(np, 0);
if (!base) {
@@ -149,6 +219,7 @@ static int stm32_pwr_regulator_probe(struct platform_device *pdev)
GFP_KERNEL);
if (!priv)
return -ENOMEM;
+ priv->tzen = tzen;
priv->base = base;
priv->ready_mask = ready_mask_table[i];
config.driver_data = priv;
diff --git a/drivers/regulator/stpmic1_regulator.c b/drivers/regulator/stpmic1_regulator.c
index cf10fdb72e32..c5337a12a61a 100644
--- a/drivers/regulator/stpmic1_regulator.c
+++ b/drivers/regulator/stpmic1_regulator.c
@@ -2,7 +2,9 @@
// Copyright (C) STMicroelectronics 2018
// Author: Pascal Paillet <p.paillet@st.com> for STMicroelectronics.
+#include <linux/delay.h>
#include <linux/interrupt.h>
+#include <linux/ktime.h>
#include <linux/mfd/stpmic1.h>
#include <linux/module.h>
#include <linux/of_irq.h>
@@ -30,10 +32,26 @@ struct stpmic1_regulator_cfg {
u8 icc_mask;
};
+/**
+ * struct boost_data - this structure is used as driver data for the usb boost
+ * @boost_rdev: device for boost regulator
+ * @vbus_otg_rdev: device for vbus_otg regulator
+ * @sw_out_rdev: device for sw_out regulator
+ * @occ_timeout: overcurrent detection timeout
+ */
+struct boost_data {
+ struct regulator_dev *boost_rdev;
+ struct regulator_dev *vbus_otg_rdev;
+ struct regulator_dev *sw_out_rdev;
+ ktime_t occ_timeout;
+};
+
static int stpmic1_set_mode(struct regulator_dev *rdev, unsigned int mode);
static unsigned int stpmic1_get_mode(struct regulator_dev *rdev);
static int stpmic1_set_icc(struct regulator_dev *rdev);
static unsigned int stpmic1_map_mode(unsigned int mode);
+static int regulator_enable_boost(struct regulator_dev *rdev);
+static int regulator_disable_boost(struct regulator_dev *rdev);
enum {
STPMIC1_BUCK1 = 0,
@@ -181,8 +199,8 @@ static const struct regulator_ops stpmic1_vref_ddr_ops = {
static const struct regulator_ops stpmic1_boost_regul_ops = {
.is_enabled = regulator_is_enabled_regmap,
- .enable = regulator_enable_regmap,
- .disable = regulator_disable_regmap,
+ .enable = regulator_enable_boost,
+ .disable = regulator_disable_boost,
.set_over_current_protection = stpmic1_set_icc,
};
@@ -513,6 +531,79 @@ static irqreturn_t stpmic1_curlim_irq_handler(int irq, void *data)
return IRQ_HANDLED;
}
+static int regulator_enable_boost(struct regulator_dev *rdev)
+{
+ struct boost_data *usb_data = rdev_get_drvdata(rdev);
+
+ usb_data->occ_timeout = ktime_add_us(ktime_get(), 100000);
+
+ return regulator_enable_regmap(rdev);
+}
+
+static int regulator_disable_boost(struct regulator_dev *rdev)
+{
+ struct boost_data *usb_data = rdev_get_drvdata(rdev);
+
+ usb_data->occ_timeout = 0;
+
+ return regulator_disable_regmap(rdev);
+}
+
+static void stpmic1_reset_boost(struct boost_data *usb_data)
+{
+ int otg_on = 0;
+ int sw_out_on = 0;
+
+ dev_dbg(rdev_get_dev(usb_data->boost_rdev), "reset usb boost\n");
+
+ /* the boost was actually disabled by the over-current protection */
+ regulator_disable_regmap(usb_data->boost_rdev);
+
+ if (usb_data->vbus_otg_rdev)
+ otg_on = regulator_is_enabled_regmap(usb_data->vbus_otg_rdev);
+ if (otg_on)
+ regulator_disable_regmap(usb_data->vbus_otg_rdev);
+
+ if (usb_data->sw_out_rdev)
+ sw_out_on = regulator_is_enabled_regmap(usb_data->sw_out_rdev);
+ if (sw_out_on)
+ regulator_disable_regmap(usb_data->sw_out_rdev);
+
+ regulator_enable_regmap(usb_data->boost_rdev);
+
+ /* sleep at least 5ms */
+ usleep_range(5000, 10000);
+
+ if (otg_on)
+ regulator_enable_regmap(usb_data->vbus_otg_rdev);
+
+ if (sw_out_on)
+ regulator_enable_regmap(usb_data->sw_out_rdev);
+
+}
+
+static irqreturn_t stpmic1_boost_irq_handler(int irq, void *data)
+{
+ struct boost_data *usb_data = (struct boost_data *)data;
+
+ dev_dbg(rdev_get_dev(usb_data->boost_rdev), "usb boost irq handler\n");
+
+ /* overcurrent detected on boost after timeout */
+ if (usb_data->occ_timeout != 0 &&
+ ktime_compare(ktime_get(), usb_data->occ_timeout) > 0) {
+ /* reset usb boost and usb power switches */
+ stpmic1_reset_boost(usb_data);
+ return IRQ_HANDLED;
+ }
+
+ /* Send an overcurrent notification */
+ regulator_notifier_call_chain(usb_data->boost_rdev,
+ REGULATOR_EVENT_OVER_CURRENT,
+ NULL);
+
+ return IRQ_HANDLED;
+}
+
#define MATCH(_name, _id) \
[STPMIC1_##_id] = { \
.name = #_name, \
@@ -536,9 +627,10 @@ static struct of_regulator_match stpmic1_matches[] = {
MATCH(pwr_sw2, SW_OUT),
};
-static int stpmic1_regulator_register(struct platform_device *pdev, int id,
- struct of_regulator_match *match,
- const struct stpmic1_regulator_cfg *cfg)
+static struct regulator_dev *
+stpmic1_regulator_register(struct platform_device *pdev, int id,
+ struct of_regulator_match *match,
+ const struct stpmic1_regulator_cfg *cfg)
{
struct stpmic1 *pmic_dev = dev_get_drvdata(pdev->dev.parent);
struct regulator_dev *rdev;
@@ -556,7 +648,7 @@ static int stpmic1_regulator_register(struct platform_device *pdev, int id,
if (IS_ERR(rdev)) {
dev_err(&pdev->dev, "failed to register %s regulator\n",
cfg->desc.name);
- return PTR_ERR(rdev);
+ return rdev;
}
/* set mask reset */
@@ -568,7 +660,7 @@ static int stpmic1_regulator_register(struct platform_device *pdev, int id,
cfg->mask_reset_mask);
if (ret) {
dev_err(&pdev->dev, "set mask reset failed\n");
- return ret;
+ return ERR_PTR(ret);
}
}
@@ -582,15 +674,60 @@ static int stpmic1_regulator_register(struct platform_device *pdev, int id,
pdev->name, rdev);
if (ret) {
dev_err(&pdev->dev, "Request IRQ failed\n");
- return ret;
+ return ERR_PTR(ret);
}
}
- return 0;
+
+ return rdev;
+}
+
+static struct regulator_dev *
+stpmic1_boost_register(struct platform_device *pdev, int id,
+ struct of_regulator_match *match,
+ const struct stpmic1_regulator_cfg *cfg,
+ struct boost_data *usb_data)
+{
+ struct stpmic1 *pmic_dev = dev_get_drvdata(pdev->dev.parent);
+ struct regulator_dev *rdev;
+ struct regulator_config config = {};
+ int ret = 0;
+ int irq;
+
+ config.dev = &pdev->dev;
+ config.init_data = match->init_data;
+ config.of_node = match->of_node;
+ config.regmap = pmic_dev->regmap;
+ config.driver_data = (void *)usb_data;
+
+ rdev = devm_regulator_register(&pdev->dev, &cfg->desc, &config);
+ if (IS_ERR(rdev)) {
+ dev_err(&pdev->dev, "failed to register %s regulator\n",
+ cfg->desc.name);
+ return rdev;
+ }
+
+ /* setup an irq handler for over-current detection */
+ irq = of_irq_get(config.of_node, 0);
+ if (irq > 0) {
+ ret = devm_request_threaded_irq(&pdev->dev,
+ irq, NULL,
+ stpmic1_boost_irq_handler,
+ IRQF_ONESHOT, pdev->name,
+ usb_data);
+ if (ret) {
+ dev_err(&pdev->dev, "Request IRQ failed\n");
+ return ERR_PTR(ret);
+ }
+ }
+
+ return rdev;
}
static int stpmic1_regulator_probe(struct platform_device *pdev)
{
int i, ret;
+ struct boost_data *usb_data;
+ struct regulator_dev *rdev;
ret = of_regulator_match(&pdev->dev, pdev->dev.of_node, stpmic1_matches,
ARRAY_SIZE(stpmic1_matches));
@@ -600,11 +737,30 @@ static int stpmic1_regulator_probe(struct platform_device *pdev)
return ret;
}
+ usb_data = devm_kzalloc(&pdev->dev, sizeof(*usb_data), GFP_KERNEL);
+ if (!usb_data)
+ return -ENOMEM;
+
for (i = 0; i < ARRAY_SIZE(stpmic1_regulator_cfgs); i++) {
- ret = stpmic1_regulator_register(pdev, i, &stpmic1_matches[i],
- &stpmic1_regulator_cfgs[i]);
- if (ret < 0)
- return ret;
+ if (i == STPMIC1_BOOST) {
+ rdev =
+ stpmic1_boost_register(pdev, i, &stpmic1_matches[i],
+ &stpmic1_regulator_cfgs[i],
+ usb_data);
+
+ usb_data->boost_rdev = rdev;
+ } else {
+ rdev =
+ stpmic1_regulator_register(pdev, i, &stpmic1_matches[i],
+ &stpmic1_regulator_cfgs[i]);
+
+ if (i == STPMIC1_VBUS_OTG)
+ usb_data->vbus_otg_rdev = rdev;
+ else if (i == STPMIC1_SW_OUT)
+ usb_data->sw_out_rdev = rdev;
+ }
+ if (IS_ERR(rdev))
+ return PTR_ERR(rdev);
}
dev_dbg(&pdev->dev, "stpmic1_regulator driver probed\n");
diff --git a/drivers/spi/spi-stm32-qspi.c b/drivers/spi/spi-stm32-qspi.c
index 947e6b9dc9f4..2786470a5201 100644
--- a/drivers/spi/spi-stm32-qspi.c
+++ b/drivers/spi/spi-stm32-qspi.c
@@ -727,21 +727,31 @@ static int __maybe_unused stm32_qspi_suspend(struct device *dev)
{
pinctrl_pm_select_sleep_state(dev);
- return 0;
+ return pm_runtime_force_suspend(dev);
}
static int __maybe_unused stm32_qspi_resume(struct device *dev)
{
struct stm32_qspi *qspi = dev_get_drvdata(dev);
+ int ret;
+
+ ret = pm_runtime_force_resume(dev);
+ if (ret < 0)
+ return ret;
pinctrl_pm_select_default_state(dev);
- clk_prepare_enable(qspi->clk);
+
+ ret = pm_runtime_get_sync(dev);
+ if (ret < 0) {
+ pm_runtime_put_noidle(dev);
+ return ret;
+ }
writel_relaxed(qspi->cr_reg, qspi->io_base + QSPI_CR);
writel_relaxed(qspi->dcr_reg, qspi->io_base + QSPI_DCR);
- pm_runtime_mark_last_busy(qspi->dev);
- pm_runtime_put_autosuspend(qspi->dev);
+ pm_runtime_mark_last_busy(dev);
+ pm_runtime_put_autosuspend(dev);
return 0;
}
diff --git a/drivers/spi/spi-stm32.c b/drivers/spi/spi-stm32.c
index 6017209c6d2f..23bf7d6eb23c 100644
--- a/drivers/spi/spi-stm32.c
+++ b/drivers/spi/spi-stm32.c
@@ -5,6 +5,7 @@
// Copyright (C) 2017, STMicroelectronics - All Rights Reserved
// Author(s): Amelie Delaunay <amelie.delaunay@st.com> for STMicroelectronics.
+#include <linux/bitfield.h>
#include <linux/debugfs.h>
#include <linux/clk.h>
#include <linux/delay.h>
@@ -31,8 +32,8 @@
#define STM32F4_SPI_CR1_CPHA BIT(0)
#define STM32F4_SPI_CR1_CPOL BIT(1)
#define STM32F4_SPI_CR1_MSTR BIT(2)
-#define STM32F4_SPI_CR1_BR_SHIFT 3
#define STM32F4_SPI_CR1_BR GENMASK(5, 3)
+#define STM32F4_SPI_CR1_BR_SHIFT 3
#define STM32F4_SPI_CR1_SPE BIT(6)
#define STM32F4_SPI_CR1_LSBFRST BIT(7)
#define STM32F4_SPI_CR1_SSI BIT(8)
@@ -94,27 +95,22 @@
#define STM32H7_SPI_CR1_SSI BIT(12)
/* STM32H7_SPI_CR2 bit fields */
-#define STM32H7_SPI_CR2_TSIZE_SHIFT 0
#define STM32H7_SPI_CR2_TSIZE GENMASK(15, 0)
+#define STM32H7_SPI_TSIZE_MAX GENMASK(15, 0)
/* STM32H7_SPI_CFG1 bit fields */
-#define STM32H7_SPI_CFG1_DSIZE_SHIFT 0
#define STM32H7_SPI_CFG1_DSIZE GENMASK(4, 0)
-#define STM32H7_SPI_CFG1_FTHLV_SHIFT 5
#define STM32H7_SPI_CFG1_FTHLV GENMASK(8, 5)
#define STM32H7_SPI_CFG1_RXDMAEN BIT(14)
#define STM32H7_SPI_CFG1_TXDMAEN BIT(15)
-#define STM32H7_SPI_CFG1_MBR_SHIFT 28
#define STM32H7_SPI_CFG1_MBR GENMASK(30, 28)
+#define STM32H7_SPI_CFG1_MBR_SHIFT 28
#define STM32H7_SPI_CFG1_MBR_MIN 0
#define STM32H7_SPI_CFG1_MBR_MAX (GENMASK(30, 28) >> 28)
/* STM32H7_SPI_CFG2 bit fields */
-#define STM32H7_SPI_CFG2_MIDI_SHIFT 4
#define STM32H7_SPI_CFG2_MIDI GENMASK(7, 4)
-#define STM32H7_SPI_CFG2_COMM_SHIFT 17
#define STM32H7_SPI_CFG2_COMM GENMASK(18, 17)
-#define STM32H7_SPI_CFG2_SP_SHIFT 19
#define STM32H7_SPI_CFG2_SP GENMASK(21, 19)
#define STM32H7_SPI_CFG2_MASTER BIT(22)
#define STM32H7_SPI_CFG2_LSBFRST BIT(23)
@@ -130,17 +126,15 @@
#define STM32H7_SPI_IER_EOTIE BIT(3)
#define STM32H7_SPI_IER_TXTFIE BIT(4)
#define STM32H7_SPI_IER_OVRIE BIT(6)
-#define STM32H7_SPI_IER_MODFIE BIT(9)
#define STM32H7_SPI_IER_ALL GENMASK(10, 0)
/* STM32H7_SPI_SR bit fields */
#define STM32H7_SPI_SR_RXP BIT(0)
#define STM32H7_SPI_SR_TXP BIT(1)
#define STM32H7_SPI_SR_EOT BIT(3)
+#define STM32H7_SPI_SR_TXTF BIT(4)
#define STM32H7_SPI_SR_OVR BIT(6)
-#define STM32H7_SPI_SR_MODF BIT(9)
#define STM32H7_SPI_SR_SUSP BIT(11)
-#define STM32H7_SPI_SR_RXPLVL_SHIFT 13
#define STM32H7_SPI_SR_RXPLVL GENMASK(14, 13)
#define STM32H7_SPI_SR_RXWNE BIT(15)
@@ -167,8 +161,6 @@
#define SPI_3WIRE_TX 3
#define SPI_3WIRE_RX 4
-#define SPI_1HZ_NS 1000000000
-
/*
* use PIO for small transfers, avoiding DMA setup/teardown overhead for drivers
* without fifo buffers.
@@ -249,7 +241,7 @@ struct stm32_spi_cfg {
int (*set_mode)(struct stm32_spi *spi, unsigned int comm_type);
void (*set_data_idleness)(struct stm32_spi *spi, u32 length);
int (*set_number_of_data)(struct stm32_spi *spi, u32 length);
- void (*transfer_one_dma_start)(struct stm32_spi *spi);
+ int (*transfer_one_dma_start)(struct stm32_spi *spi);
void (*dma_rx_cb)(void *data);
void (*dma_tx_cb)(void *data);
int (*transfer_one_irq)(struct stm32_spi *spi);
@@ -268,7 +260,6 @@ struct stm32_spi_cfg {
* @base: virtual memory area
* @clk: hw kernel clock feeding the SPI clock generator
* @clk_rate: rate of the hw kernel clock feeding the SPI clock generator
- * @rst: SPI controller reset line
* @lock: prevent I/O concurrent access
* @irq: SPI controller interrupt line
* @fifo_size: size of the embedded fifo in bytes
@@ -285,7 +276,10 @@ struct stm32_spi_cfg {
* @rx_len: number of data to be read in bytes
* @dma_tx: dma channel for TX transfer
* @dma_rx: dma channel for RX transfer
+ * @dma_completion: completion to wait for end of DMA transfer
* @phys_addr: SPI registers physical base address
+ * @xfer_completion: completion to wait for end of transfer
+ * @xfer_status: current transfer status
*/
struct stm32_spi {
struct device *dev;
@@ -294,7 +288,6 @@ struct stm32_spi {
void __iomem *base;
struct clk *clk;
u32 clk_rate;
- struct reset_control *rst;
spinlock_t lock; /* prevent I/O concurrent access */
int irq;
unsigned int fifo_size;
@@ -313,7 +306,10 @@ struct stm32_spi {
int rx_len;
struct dma_chan *dma_tx;
struct dma_chan *dma_rx;
+ struct completion dma_completion;
dma_addr_t phys_addr;
+ struct completion xfer_completion;
+ int xfer_status;
};
static const struct stm32_spi_regspec stm32f4_spi_regspec = {
@@ -417,9 +413,7 @@ static int stm32h7_spi_get_bpw_mask(struct stm32_spi *spi)
stm32_spi_set_bits(spi, STM32H7_SPI_CFG1, STM32H7_SPI_CFG1_DSIZE);
cfg1 = readl_relaxed(spi->base + STM32H7_SPI_CFG1);
- max_bpw = (cfg1 & STM32H7_SPI_CFG1_DSIZE) >>
- STM32H7_SPI_CFG1_DSIZE_SHIFT;
- max_bpw += 1;
+ max_bpw = FIELD_GET(STM32H7_SPI_CFG1_DSIZE, cfg1) + 1;
spin_unlock_irqrestore(&spi->lock, flags);
@@ -599,30 +593,30 @@ static void stm32f4_spi_read_rx(struct stm32_spi *spi)
/**
* stm32h7_spi_read_rxfifo - Read bytes in Receive Data Register
* @spi: pointer to the spi controller data structure
- * @flush: boolean indicating that FIFO should be flushed
*
* Write in rx_buf depends on remaining bytes to avoid to write beyond
* rx_buf end.
*/
-static void stm32h7_spi_read_rxfifo(struct stm32_spi *spi, bool flush)
+static void stm32h7_spi_read_rxfifo(struct stm32_spi *spi)
{
u32 sr = readl_relaxed(spi->base + STM32H7_SPI_SR);
- u32 rxplvl = (sr & STM32H7_SPI_SR_RXPLVL) >>
- STM32H7_SPI_SR_RXPLVL_SHIFT;
+ u32 rxplvl = FIELD_GET(STM32H7_SPI_SR_RXPLVL, sr);
while ((spi->rx_len > 0) &&
((sr & STM32H7_SPI_SR_RXP) ||
- (flush && ((sr & STM32H7_SPI_SR_RXWNE) || (rxplvl > 0))))) {
+ ((sr & STM32H7_SPI_SR_EOT) &&
+ ((sr & STM32H7_SPI_SR_RXWNE) || (rxplvl > 0))))) {
u32 offs = spi->cur_xferlen - spi->rx_len;
if ((spi->rx_len >= sizeof(u32)) ||
- (flush && (sr & STM32H7_SPI_SR_RXWNE))) {
+ (sr & STM32H7_SPI_SR_RXWNE)) {
u32 *rx_buf32 = (u32 *)(spi->rx_buf + offs);
*rx_buf32 = readl_relaxed(spi->base + STM32H7_SPI_RXDR);
spi->rx_len -= sizeof(u32);
} else if ((spi->rx_len >= sizeof(u16)) ||
- (flush && (rxplvl >= 2 || spi->cur_bpw > 8))) {
+ (!(sr & STM32H7_SPI_SR_RXWNE) &&
+ (rxplvl >= 2 || spi->cur_bpw > 8))) {
u16 *rx_buf16 = (u16 *)(spi->rx_buf + offs);
*rx_buf16 = readw_relaxed(spi->base + STM32H7_SPI_RXDR);
@@ -635,12 +629,11 @@ static void stm32h7_spi_read_rxfifo(struct stm32_spi *spi, bool flush)
}
sr = readl_relaxed(spi->base + STM32H7_SPI_SR);
- rxplvl = (sr & STM32H7_SPI_SR_RXPLVL) >>
- STM32H7_SPI_SR_RXPLVL_SHIFT;
+ rxplvl = FIELD_GET(STM32H7_SPI_SR_RXPLVL, sr);
}
- dev_dbg(spi->dev, "%s%s: %d bytes left\n", __func__,
- flush ? "(flush)" : "", spi->rx_len);
+ dev_dbg(spi->dev, "%s: %d bytes left (sr=%08x)\n",
+ __func__, spi->rx_len, sr);
}
/**
@@ -708,12 +701,7 @@ static void stm32f4_spi_disable(struct stm32_spi *spi)
* @spi: pointer to the spi controller data structure
*
* RX-Fifo is flushed when SPI controller is disabled. To prevent any data
- * loss, use stm32h7_spi_read_rxfifo(flush) to read the remaining bytes in
- * RX-Fifo.
- * Normally, if TSIZE has been configured, we should relax the hardware at the
- * reception of the EOT interrupt. But in case of error, EOT will not be
- * raised. So the subsystem unprepare_message call allows us to properly
- * complete the transfer from an hardware point of view.
+ * loss, use stm32_spi_read_rxfifo to read the remaining bytes in RX-Fifo.
*/
static void stm32h7_spi_disable(struct stm32_spi *spi)
{
@@ -748,7 +736,7 @@ static void stm32h7_spi_disable(struct stm32_spi *spi)
}
if (!spi->cur_usedma && spi->rx_buf && (spi->rx_len > 0))
- stm32h7_spi_read_rxfifo(spi, true);
+ stm32h7_spi_read_rxfifo(spi);
if (spi->cur_usedma && spi->dma_tx)
dmaengine_terminate_all(spi->dma_tx);
@@ -892,8 +880,7 @@ static irqreturn_t stm32f4_spi_irq_thread(int irq, void *dev_id)
struct spi_master *master = dev_id;
struct stm32_spi *spi = spi_master_get_devdata(master);
- spi_finalize_current_transfer(master);
- stm32f4_spi_disable(spi);
+ complete(&spi->xfer_completion);
return IRQ_HANDLED;
}
@@ -907,7 +894,7 @@ static irqreturn_t stm32h7_spi_irq_thread(int irq, void *dev_id)
{
struct spi_master *master = dev_id;
struct stm32_spi *spi = spi_master_get_devdata(master);
- u32 sr, ier, mask;
+ u32 sr, ier, mask, ifcr;
unsigned long flags;
bool end = false;
@@ -915,81 +902,78 @@ static irqreturn_t stm32h7_spi_irq_thread(int irq, void *dev_id)
sr = readl_relaxed(spi->base + STM32H7_SPI_SR);
ier = readl_relaxed(spi->base + STM32H7_SPI_IER);
+ ifcr = 0;
mask = ier;
- /* EOTIE is triggered on EOT, SUSP and TXC events. */
+ /*
+ * EOTIE enables irq from EOT, SUSP and TXC events. We need to set
+ * SUSP to acknowledge it later. TXC is automatically cleared
+ */
mask |= STM32H7_SPI_SR_SUSP;
/*
- * When TXTF is set, DXPIE and TXPIE are cleared. So in case of
- * Full-Duplex, need to poll RXP event to know if there are remaining
- * data, before disabling SPI.
+ * DXPIE is set in Full-Duplex, one IT will be raised if TXP and RXP
+ * are set. So in case of Full-Duplex, need to poll TXP and RXP event.
*/
- if (spi->rx_buf && !spi->cur_usedma)
- mask |= STM32H7_SPI_SR_RXP;
+ if ((spi->cur_comm == SPI_FULL_DUPLEX) && (!spi->cur_usedma))
+ mask |= STM32H7_SPI_SR_TXP | STM32H7_SPI_SR_RXP;
- if (!(sr & mask)) {
- dev_dbg(spi->dev, "spurious IT (sr=0x%08x, ier=0x%08x)\n",
- sr, ier);
+ mask &= sr;
+
+ if (!mask) {
+ dev_warn(spi->dev, "spurious IT (sr=0x%08x, ier=0x%08x)\n",
+ sr, ier);
spin_unlock_irqrestore(&spi->lock, flags);
return IRQ_NONE;
}
- if (sr & STM32H7_SPI_SR_SUSP) {
+ if (mask & STM32H7_SPI_SR_SUSP) {
static DEFINE_RATELIMIT_STATE(rs,
DEFAULT_RATELIMIT_INTERVAL * 10,
1);
if (__ratelimit(&rs))
dev_dbg_ratelimited(spi->dev, "Communication suspended\n");
if (!spi->cur_usedma && (spi->rx_buf && (spi->rx_len > 0)))
- stm32h7_spi_read_rxfifo(spi, false);
- /*
- * If communication is suspended while using DMA, it means
- * that something went wrong, so stop the current transfer
- */
- if (spi->cur_usedma)
- end = true;
+ stm32h7_spi_read_rxfifo(spi);
+ ifcr |= STM32H7_SPI_SR_SUSP;
}
- if (sr & STM32H7_SPI_SR_MODF) {
- dev_warn(spi->dev, "Mode fault: transfer aborted\n");
+ if (mask & STM32H7_SPI_SR_OVR) {
+ dev_err(spi->dev, "Overrun: RX data lost\n");
+ spi->xfer_status = -EIO;
end = true;
+ ifcr |= STM32H7_SPI_SR_OVR;
}
- if (sr & STM32H7_SPI_SR_OVR) {
- dev_warn(spi->dev, "Overrun: received value discarded\n");
- if (!spi->cur_usedma && (spi->rx_buf && (spi->rx_len > 0)))
- stm32h7_spi_read_rxfifo(spi, false);
- /*
- * If overrun is detected while using DMA, it means that
- * something went wrong, so stop the current transfer
- */
- if (spi->cur_usedma)
- end = true;
- }
+ if (mask & STM32H7_SPI_SR_TXTF)
+ ifcr |= STM32H7_SPI_SR_TXTF;
- if (sr & STM32H7_SPI_SR_EOT) {
+ if (mask & STM32H7_SPI_SR_EOT) {
if (!spi->cur_usedma && (spi->rx_buf && (spi->rx_len > 0)))
- stm32h7_spi_read_rxfifo(spi, true);
+ stm32h7_spi_read_rxfifo(spi);
end = true;
+ ifcr |= STM32H7_SPI_SR_EOT;
}
- if (sr & STM32H7_SPI_SR_TXP)
+ if (mask & STM32H7_SPI_SR_TXP)
if (!spi->cur_usedma && (spi->tx_buf && (spi->tx_len > 0)))
stm32h7_spi_write_txfifo(spi);
- if (sr & STM32H7_SPI_SR_RXP)
+ if (mask & STM32H7_SPI_SR_RXP)
if (!spi->cur_usedma && (spi->rx_buf && (spi->rx_len > 0)))
- stm32h7_spi_read_rxfifo(spi, false);
-
- writel_relaxed(sr & mask, spi->base + STM32H7_SPI_IFCR);
-
- spin_unlock_irqrestore(&spi->lock, flags);
+ stm32h7_spi_read_rxfifo(spi);
if (end) {
- stm32h7_spi_disable(spi);
- spi_finalize_current_transfer(master);
+ /* Disable interrupts and clear status flags */
+ writel_relaxed(0, spi->base + STM32H7_SPI_IER);
+ writel_relaxed(STM32H7_SPI_IFCR_ALL,
+ spi->base + STM32H7_SPI_IFCR);
+
+ complete(&spi->xfer_completion);
+ } else {
+ writel_relaxed(ifcr, spi->base + STM32H7_SPI_IFCR);
}
+ spin_unlock_irqrestore(&spi->lock, flags);
return IRQ_HANDLED;
}
@@ -1033,6 +1017,20 @@ static int stm32_spi_prepare_msg(struct spi_master *master,
spi_dev->mode & SPI_LSB_FIRST,
spi_dev->mode & SPI_CS_HIGH);
+ /* On STM32H7, messages should not exceed a maximum size setted
+ * afterward via the set_number_of_data function. In order to
+ * ensure that, split large messages into several messages
+ */
+ if (spi->cfg->set_number_of_data) {
+ int ret;
+
+ ret = spi_split_transfers_maxsize(master, msg,
+ STM32H7_SPI_TSIZE_MAX,
+ GFP_KERNEL | GFP_DMA);
+ if (ret)
+ return ret;
+ }
+
spin_lock_irqsave(&spi->lock, flags);
/* CPOL, CPHA and LSB FIRST bits have common register */
@@ -1057,10 +1055,8 @@ static void stm32f4_spi_dma_tx_cb(void *data)
{
struct stm32_spi *spi = data;
- if (spi->cur_comm == SPI_SIMPLEX_TX || spi->cur_comm == SPI_3WIRE_TX) {
- spi_finalize_current_transfer(spi->master);
- stm32f4_spi_disable(spi);
- }
+ if (spi->cur_comm == SPI_SIMPLEX_TX || spi->cur_comm == SPI_3WIRE_TX)
+ complete(&spi->xfer_completion);
}
/**
@@ -1073,33 +1069,25 @@ static void stm32f4_spi_dma_rx_cb(void *data)
{
struct stm32_spi *spi = data;
- spi_finalize_current_transfer(spi->master);
- stm32f4_spi_disable(spi);
+ complete(&spi->xfer_completion);
}
/**
* stm32h7_spi_dma_cb - dma callback
* @data: pointer to the spi controller data structure
*
- * DMA callback is called when the transfer is complete or when an error
- * occurs. If the transfer is complete, EOT flag is raised.
+ * DMA callback is called when the transfer is complete.
*/
static void stm32h7_spi_dma_cb(void *data)
{
struct stm32_spi *spi = data;
unsigned long flags;
- u32 sr;
spin_lock_irqsave(&spi->lock, flags);
- sr = readl_relaxed(spi->base + STM32H7_SPI_SR);
+ complete(&spi->dma_completion);
spin_unlock_irqrestore(&spi->lock, flags);
-
- if (!(sr & STM32H7_SPI_SR_EOT))
- dev_warn(spi->dev, "DMA error (sr=0x%08x)\n", sr);
-
- /* Now wait for EOT, or SUSP or OVR in case of error */
}
/**
@@ -1156,9 +1144,6 @@ static void stm32_spi_dma_config(struct stm32_spi *spi,
* stm32f4_spi_transfer_one_irq - transfer a single spi_transfer using
* interrupts
* @spi: pointer to the spi controller data structure
- *
- * It must returns 0 if the transfer is finished or 1 if the transfer is still
- * in progress.
*/
static int stm32f4_spi_transfer_one_irq(struct stm32_spi *spi)
{
@@ -1192,16 +1177,13 @@ static int stm32f4_spi_transfer_one_irq(struct stm32_spi *spi)
spin_unlock_irqrestore(&spi->lock, flags);
- return 1;
+ return 0;
}
/**
* stm32h7_spi_transfer_one_irq - transfer a single spi_transfer using
* interrupts
* @spi: pointer to the spi controller data structure
- *
- * It must returns 0 if the transfer is finished or 1 if the transfer is still
- * in progress.
*/
static int stm32h7_spi_transfer_one_irq(struct stm32_spi *spi)
{
@@ -1218,7 +1200,7 @@ static int stm32h7_spi_transfer_one_irq(struct stm32_spi *spi)
/* Enable the interrupts relative to the end of transfer */
ier |= STM32H7_SPI_IER_EOTIE | STM32H7_SPI_IER_TXTFIE |
- STM32H7_SPI_IER_OVRIE | STM32H7_SPI_IER_MODFIE;
+ STM32H7_SPI_IER_OVRIE;
spin_lock_irqsave(&spi->lock, flags);
@@ -1234,7 +1216,7 @@ static int stm32h7_spi_transfer_one_irq(struct stm32_spi *spi)
spin_unlock_irqrestore(&spi->lock, flags);
- return 1;
+ return 0;
}
/**
@@ -1242,8 +1224,12 @@ static int stm32h7_spi_transfer_one_irq(struct stm32_spi *spi)
* transfer using DMA
* @spi: pointer to the spi controller data structure
*/
-static void stm32f4_spi_transfer_one_dma_start(struct stm32_spi *spi)
+static int stm32f4_spi_transfer_one_dma_start(struct stm32_spi *spi)
{
+ unsigned long flags;
+
+ spin_lock_irqsave(&spi->lock, flags);
+
/* In DMA mode end of transfer is handled by DMA TX or RX callback. */
if (spi->cur_comm == SPI_SIMPLEX_RX || spi->cur_comm == SPI_3WIRE_RX ||
spi->cur_comm == SPI_FULL_DUPLEX) {
@@ -1256,6 +1242,10 @@ static void stm32f4_spi_transfer_one_dma_start(struct stm32_spi *spi)
}
stm32_spi_enable(spi);
+
+ spin_unlock_irqrestore(&spi->lock, flags);
+
+ return 0;
}
/**
@@ -1263,36 +1253,48 @@ static void stm32f4_spi_transfer_one_dma_start(struct stm32_spi *spi)
* transfer using DMA
* @spi: pointer to the spi controller data structure
*/
-static void stm32h7_spi_transfer_one_dma_start(struct stm32_spi *spi)
+static int stm32h7_spi_transfer_one_dma_start(struct stm32_spi *spi)
{
+ unsigned long flags;
+
+ spin_lock_irqsave(&spi->lock, flags);
+
/* Enable the interrupts relative to the end of transfer */
stm32_spi_set_bits(spi, STM32H7_SPI_IER, STM32H7_SPI_IER_EOTIE |
STM32H7_SPI_IER_TXTFIE |
- STM32H7_SPI_IER_OVRIE |
- STM32H7_SPI_IER_MODFIE);
+ STM32H7_SPI_IER_OVRIE);
stm32_spi_enable(spi);
stm32_spi_set_bits(spi, STM32H7_SPI_CR1, STM32H7_SPI_CR1_CSTART);
+
+ spin_unlock_irqrestore(&spi->lock, flags);
+
+ return 0;
}
/**
* stm32_spi_transfer_one_dma - transfer a single spi_transfer using DMA
* @spi: pointer to the spi controller data structure
* @xfer: pointer to the spi_transfer structure
- *
- * It must returns 0 if the transfer is finished or 1 if the transfer is still
- * in progress.
*/
static int stm32_spi_transfer_one_dma(struct stm32_spi *spi,
struct spi_transfer *xfer)
{
+ dma_async_tx_callback rx_done = NULL, tx_done = NULL;
struct dma_slave_config tx_dma_conf, rx_dma_conf;
struct dma_async_tx_descriptor *tx_dma_desc, *rx_dma_desc;
unsigned long flags;
spin_lock_irqsave(&spi->lock, flags);
+ if (spi->rx_buf)
+ rx_done = spi->cfg->dma_rx_cb;
+ else if (spi->tx_buf)
+ tx_done = spi->cfg->dma_tx_cb;
+
+ reinit_completion(&spi->dma_completion);
+
rx_dma_desc = NULL;
if (spi->rx_buf && spi->dma_rx) {
stm32_spi_dma_config(spi, &rx_dma_conf, DMA_DEV_TO_MEM);
@@ -1329,7 +1331,7 @@ static int stm32_spi_transfer_one_dma(struct stm32_spi *spi,
goto dma_desc_error;
if (rx_dma_desc) {
- rx_dma_desc->callback = spi->cfg->dma_rx_cb;
+ rx_dma_desc->callback = rx_done;
rx_dma_desc->callback_param = spi;
if (dma_submit_error(dmaengine_submit(rx_dma_desc))) {
@@ -1343,7 +1345,7 @@ static int stm32_spi_transfer_one_dma(struct stm32_spi *spi,
if (tx_dma_desc) {
if (spi->cur_comm == SPI_SIMPLEX_TX ||
spi->cur_comm == SPI_3WIRE_TX) {
- tx_dma_desc->callback = spi->cfg->dma_tx_cb;
+ tx_dma_desc->callback = tx_done;
tx_dma_desc->callback_param = spi;
}
@@ -1358,12 +1360,9 @@ static int stm32_spi_transfer_one_dma(struct stm32_spi *spi,
stm32_spi_set_bits(spi, spi->cfg->regs->dma_tx_en.reg,
spi->cfg->regs->dma_tx_en.mask);
}
-
- spi->cfg->transfer_one_dma_start(spi);
-
spin_unlock_irqrestore(&spi->lock, flags);
- return 1;
+ return spi->cfg->transfer_one_dma_start(spi);
dma_submit_error:
if (spi->dma_rx)
@@ -1405,15 +1404,13 @@ static void stm32h7_spi_set_bpw(struct stm32_spi *spi)
bpw = spi->cur_bpw - 1;
cfg1_clrb |= STM32H7_SPI_CFG1_DSIZE;
- cfg1_setb |= (bpw << STM32H7_SPI_CFG1_DSIZE_SHIFT) &
- STM32H7_SPI_CFG1_DSIZE;
+ cfg1_setb |= FIELD_PREP(STM32H7_SPI_CFG1_DSIZE, bpw);
spi->cur_fthlv = stm32h7_spi_prepare_fthlv(spi, spi->cur_xferlen);
fthlv = spi->cur_fthlv - 1;
cfg1_clrb |= STM32H7_SPI_CFG1_FTHLV;
- cfg1_setb |= (fthlv << STM32H7_SPI_CFG1_FTHLV_SHIFT) &
- STM32H7_SPI_CFG1_FTHLV;
+ cfg1_setb |= FIELD_PREP(STM32H7_SPI_CFG1_FTHLV, fthlv);
writel_relaxed(
(readl_relaxed(spi->base + STM32H7_SPI_CFG1) &
@@ -1431,8 +1428,7 @@ static void stm32_spi_set_mbr(struct stm32_spi *spi, u32 mbrdiv)
u32 clrb = 0, setb = 0;
clrb |= spi->cfg->regs->br.mask;
- setb |= ((u32)mbrdiv << spi->cfg->regs->br.shift) &
- spi->cfg->regs->br.mask;
+ setb |= (mbrdiv << spi->cfg->regs->br.shift) & spi->cfg->regs->br.mask;
writel_relaxed((readl_relaxed(spi->base + spi->cfg->regs->br.reg) &
~clrb) | setb,
@@ -1523,8 +1519,7 @@ static int stm32h7_spi_set_mode(struct stm32_spi *spi, unsigned int comm_type)
}
cfg2_clrb |= STM32H7_SPI_CFG2_COMM;
- cfg2_setb |= (mode << STM32H7_SPI_CFG2_COMM_SHIFT) &
- STM32H7_SPI_CFG2_COMM;
+ cfg2_setb |= FIELD_PREP(STM32H7_SPI_CFG2_COMM, mode);
writel_relaxed(
(readl_relaxed(spi->base + STM32H7_SPI_CFG2) &
@@ -1546,15 +1541,16 @@ static void stm32h7_spi_data_idleness(struct stm32_spi *spi, u32 len)
cfg2_clrb |= STM32H7_SPI_CFG2_MIDI;
if ((len > 1) && (spi->cur_midi > 0)) {
- u32 sck_period_ns = DIV_ROUND_UP(SPI_1HZ_NS, spi->cur_speed);
- u32 midi = min((u32)DIV_ROUND_UP(spi->cur_midi, sck_period_ns),
- (u32)STM32H7_SPI_CFG2_MIDI >>
- STM32H7_SPI_CFG2_MIDI_SHIFT);
+ u32 sck_period_ns = DIV_ROUND_UP(NSEC_PER_SEC, spi->cur_speed);
+ u32 midi = min_t(u32,
+ DIV_ROUND_UP(spi->cur_midi, sck_period_ns),
+ FIELD_GET(STM32H7_SPI_CFG2_MIDI,
+ STM32H7_SPI_CFG2_MIDI));
+
dev_dbg(spi->dev, "period=%dns, midi=%d(=%dns)\n",
sck_period_ns, midi, midi * sck_period_ns);
- cfg2_setb |= (midi << STM32H7_SPI_CFG2_MIDI_SHIFT) &
- STM32H7_SPI_CFG2_MIDI;
+ cfg2_setb |= FIELD_PREP(STM32H7_SPI_CFG2_MIDI, midi);
}
writel_relaxed((readl_relaxed(spi->base + STM32H7_SPI_CFG2) &
@@ -1569,14 +1565,8 @@ static void stm32h7_spi_data_idleness(struct stm32_spi *spi, u32 len)
*/
static int stm32h7_spi_number_of_data(struct stm32_spi *spi, u32 nb_words)
{
- u32 cr2_clrb = 0, cr2_setb = 0;
-
- if (nb_words <= (STM32H7_SPI_CR2_TSIZE >>
- STM32H7_SPI_CR2_TSIZE_SHIFT)) {
- cr2_clrb |= STM32H7_SPI_CR2_TSIZE;
- cr2_setb = nb_words << STM32H7_SPI_CR2_TSIZE_SHIFT;
- writel_relaxed((readl_relaxed(spi->base + STM32H7_SPI_CR2) &
- ~cr2_clrb) | cr2_setb,
+ if (nb_words <= STM32H7_SPI_TSIZE_MAX) {
+ writel_relaxed(FIELD_PREP(STM32H7_SPI_CR2_TSIZE, nb_words),
spi->base + STM32H7_SPI_CR2);
} else {
return -EMSGSIZE;
@@ -1675,8 +1665,16 @@ static int stm32_spi_transfer_one(struct spi_master *master,
struct spi_transfer *transfer)
{
struct stm32_spi *spi = spi_master_get_devdata(master);
+ u32 xfer_time, midi_delay_ns;
+ unsigned long timeout;
int ret;
+ /* Don't do anything on 0 bytes transfers */
+ if (transfer->len == 0) {
+ spi->xfer_status = 0;
+ goto finalize;
+ }
+
spi->tx_buf = transfer->tx_buf;
spi->rx_buf = transfer->rx_buf;
spi->tx_len = spi->tx_buf ? transfer->len : 0;
@@ -1691,10 +1689,40 @@ static int stm32_spi_transfer_one(struct spi_master *master,
return ret;
}
+ reinit_completion(&spi->xfer_completion);
+ spi->xfer_status = 0;
+
if (spi->cur_usedma)
- return stm32_spi_transfer_one_dma(spi, transfer);
+ ret = stm32_spi_transfer_one_dma(spi, transfer);
else
- return spi->cfg->transfer_one_irq(spi);
+ ret = spi->cfg->transfer_one_irq(spi);
+
+ if (ret)
+ return ret;
+
+ /* Wait for transfer to complete */
+ xfer_time = spi->cur_xferlen * 8 * MSEC_PER_SEC / spi->cur_speed;
+ midi_delay_ns = spi->cur_xferlen * 8 / spi->cur_bpw * spi->cur_midi;
+ xfer_time += DIV_ROUND_UP(midi_delay_ns, NSEC_PER_MSEC);
+ xfer_time = max(2 * xfer_time, 100U);
+ timeout = msecs_to_jiffies(xfer_time);
+
+ timeout = wait_for_completion_timeout(&spi->xfer_completion, timeout);
+ if (timeout && spi->cur_usedma)
+ timeout = wait_for_completion_timeout(&spi->dma_completion,
+ timeout);
+
+ if (!timeout) {
+ dev_err(spi->dev, "SPI transfer timeout (%u ms)\n", xfer_time);
+ spi->xfer_status = -ETIMEDOUT;
+ }
+
+ spi->cfg->disable(spi);
+
+finalize:
+ spi_finalize_current_transfer(master);
+
+ return spi->xfer_status;
}
/**
@@ -1831,6 +1859,7 @@ static int stm32_spi_probe(struct platform_device *pdev)
struct spi_master *master;
struct stm32_spi *spi;
struct resource *res;
+ struct reset_control *rst;
int ret;
master = spi_alloc_master(&pdev->dev, sizeof(struct stm32_spi));
@@ -1844,6 +1873,8 @@ static int stm32_spi_probe(struct platform_device *pdev)
spi->dev = &pdev->dev;
spi->master = master;
spin_lock_init(&spi->lock);
+ init_completion(&spi->xfer_completion);
+ init_completion(&spi->dma_completion);
spi->cfg = (const struct stm32_spi_cfg *)
of_match_device(pdev->dev.driver->of_match_table,
@@ -1892,11 +1923,19 @@ static int stm32_spi_probe(struct platform_device *pdev)
goto err_clk_disable;
}
- spi->rst = devm_reset_control_get_exclusive(&pdev->dev, NULL);
- if (!IS_ERR(spi->rst)) {
- reset_control_assert(spi->rst);
+ rst = devm_reset_control_get_optional_exclusive(&pdev->dev, NULL);
+ if (rst) {
+ if (IS_ERR(rst)) {
+ ret = PTR_ERR(rst);
+ if (ret != -EPROBE_DEFER)
+ dev_err(&pdev->dev, "reset get failed: %d\n",
+ ret);
+ goto err_clk_disable;
+ }
+
+ reset_control_assert(rst);
udelay(2);
- reset_control_deassert(spi->rst);
+ reset_control_deassert(rst);
}
if (spi->cfg->has_fifo)
@@ -1953,19 +1992,13 @@ static int stm32_spi_probe(struct platform_device *pdev)
pm_runtime_set_active(&pdev->dev);
pm_runtime_enable(&pdev->dev);
- ret = devm_spi_register_master(&pdev->dev, master);
+ ret = spi_register_master(master);
if (ret) {
dev_err(&pdev->dev, "spi master registration failed: %d\n",
ret);
goto err_pm_disable;
}
- if (!master->cs_gpiods) {
- dev_err(&pdev->dev, "no CS gpios available\n");
- ret = -EINVAL;
- goto err_pm_disable;
- }
-
dev_info(&pdev->dev, "driver initialized\n");
return 0;
@@ -1990,6 +2023,9 @@ static int stm32_spi_remove(struct platform_device *pdev)
struct spi_master *master = platform_get_drvdata(pdev);
struct stm32_spi *spi = spi_master_get_devdata(master);
+ pm_runtime_get_sync(&pdev->dev);
+
+ spi_unregister_master(master);
spi->cfg->disable(spi);
if (master->dma_tx)
@@ -1999,7 +2035,10 @@ static int stm32_spi_remove(struct platform_device *pdev)
clk_disable_unprepare(spi->clk);
+ pm_runtime_put_noidle(&pdev->dev);
pm_runtime_disable(&pdev->dev);
+ pm_runtime_set_suspended(&pdev->dev);
+ pm_runtime_dont_use_autosuspend(&pdev->dev);
pinctrl_pm_select_sleep_state(&pdev->dev);
diff --git a/include/dt-bindings/pinctrl/stm32-pinfunc.h b/include/dt-bindings/pinctrl/stm32-pinfunc.h
index e6fb8ada3f4d..370a25a9366c 100644
--- a/include/dt-bindings/pinctrl/stm32-pinfunc.h
+++ b/include/dt-bindings/pinctrl/stm32-pinfunc.h
@@ -26,6 +26,7 @@
#define AF14 0xf
#define AF15 0x10
#define ANALOG 0x11
+#define RSVD 0x12
/* define Pins number*/
#define PIN_NO(port, line) (((port) - 'A') * 0x10 + (line))
--
2.17.1