2021-02-11 14:20:47

by Kostya Porotchkin

[permalink] [raw]
Subject: [PATCH v3 0/2] Enable usage of Marvell FW SIP services

From: Konstantin Porotchkin <[email protected]>

These patches enable usage of Arm Trusted Firmware SIP services on
Marvell Armada plaforms for accessing system registers that are not
normally accessible from kernel or user space (EL1/EL0), like DFX
registers group.

v2:
* use separate legacy/smc regmap functions registered at ap-cpu
clock driver probe according to FW response

v3:
* fix build errors and rebase on top of clk-next branch

Grzegorz Jaszczyk (2):
thermal: armada: ap806: use firmware SiP services for thermal
operations
clk: mvebu: use firmware SiP service for accessing dfx register set

drivers/clk/mvebu/ap-cpu-clk.c | 174 ++++++++++++++++++--
drivers/thermal/armada_thermal.c | 125 +++++++++++++-
include/soc/marvell/armada8k/fw.h | 22 +++
3 files changed, 302 insertions(+), 19 deletions(-)
create mode 100644 include/soc/marvell/armada8k/fw.h

--
2.17.1


2021-02-11 14:23:09

by Kostya Porotchkin

[permalink] [raw]
Subject: [PATCH v3 1/2] thermal: armada: ap806: use firmware SiP services for thermal operations

From: Grzegorz Jaszczyk <[email protected]>

This patch introduces support for ap806 thermal driver in case when SoC
DFX region is marked as secure by the firmware. In such case accessing
thermal registers, which are part of dfx register set, will not be
possible from non-secure world. Due to above the ARM Trusted Firmware
exposes thermal driver as a SiP service. This allows Linux thermal
driver to initialise and perform various operations on thermal sensor
with use of SMC calls.

If during ap806 thermal initialisation the SMC is unhandled (old fw
case), fallback to regmap handling.

Signed-off-by: Grzegorz Jaszczyk <[email protected]>
Signed-off-by: Konstantin Porotchkin <[email protected]>
---
drivers/thermal/armada_thermal.c | 125 +++++++++++++++++++-
include/soc/marvell/armada8k/fw.h | 19 +++
2 files changed, 141 insertions(+), 3 deletions(-)
create mode 100644 include/soc/marvell/armada8k/fw.h

diff --git a/drivers/thermal/armada_thermal.c b/drivers/thermal/armada_thermal.c
index c2ebfb5be4b3..ec077e834c85 100644
--- a/drivers/thermal/armada_thermal.c
+++ b/drivers/thermal/armada_thermal.c
@@ -4,6 +4,7 @@
*
* Copyright (C) 2013 Marvell
*/
+#include <linux/arm-smccc.h>
#include <linux/device.h>
#include <linux/err.h>
#include <linux/io.h>
@@ -18,6 +19,8 @@
#include <linux/mfd/syscon.h>
#include <linux/regmap.h>
#include <linux/interrupt.h>
+#include <linux/time.h>
+#include "soc/marvell/armada8k/fw.h"

#include "thermal_core.h"

@@ -62,6 +65,8 @@
#define STATUS_POLL_TIMEOUT_US 100000
#define OVERHEAT_INT_POLL_DELAY_MS 1000

+#define THERMAL_SUPPORTED_IN_FIRMWARE(priv) (priv->data->is_smc_supported)
+
struct armada_thermal_data;

/* Marvell EBU Thermal Sensor Dev Structure */
@@ -111,6 +116,12 @@ struct armada_thermal_data {

/* One sensor is in the thermal IC, the others are in the CPUs if any */
unsigned int cpu_nr;
+
+ /*
+ * Thermal sensor operations exposed as firmware SIP services and
+ * accessed via SMC
+ */
+ bool is_smc_supported;
};

struct armada_drvdata {
@@ -135,6 +146,18 @@ struct armada_thermal_sensor {
int id;
};

+static int thermal_smc(u32 addr, u32 *reg, u32 val1, u32 val2)
+{
+ struct arm_smccc_res res;
+
+ arm_smccc_smc(MV_SIP_DFX, addr, val1, val2, 0, 0, 0, 0, &res);
+
+ if (res.a0 == 0 && reg != NULL)
+ *reg = res.a1;
+
+ return res.a0;
+}
+
static void armadaxp_init(struct platform_device *pdev,
struct armada_thermal_priv *priv)
{
@@ -206,6 +229,27 @@ static void armada375_init(struct platform_device *pdev,
static int armada_wait_sensor_validity(struct armada_thermal_priv *priv)
{
u32 reg;
+ int ret;
+ ktime_t timeout;
+
+ if (THERMAL_SUPPORTED_IN_FIRMWARE(priv)) {
+ timeout = ktime_add_us(ktime_get(), STATUS_POLL_TIMEOUT_US);
+ do {
+ ret = thermal_smc(MV_SIP_DFX_THERMAL_IS_VALID,
+ &reg, 0, 0);
+ if (ret || reg)
+ break;
+
+ usleep_range((STATUS_POLL_PERIOD_US >> 2) + 1,
+ STATUS_POLL_PERIOD_US);
+
+ } while (ktime_before(ktime_get(), timeout));
+
+ if (ret == SMCCC_RET_SUCCESS)
+ return reg ? 0 : -ETIMEDOUT;
+
+ return ret;
+ }

return regmap_read_poll_timeout(priv->syscon,
priv->data->syscon_status_off, reg,
@@ -238,6 +282,22 @@ static void armada_ap806_init(struct platform_device *pdev,
{
struct armada_thermal_data *data = priv->data;
u32 reg;
+ int ret;
+
+ /*
+ * The ap806 thermal sensor registers are part of DFX which is secured
+ * by latest firmware, therefore accessing relevant registers from
+ * not-secure world will not be possible. In that case Arm Trusted
+ * Firmware exposes thermal operations as firmware run-time service. If
+ * SMC initialization succeeds, perform other thermal operations using
+ * SMC, otherwise (old fw case) fallback to regmap handling.
+ */
+ ret = thermal_smc(MV_SIP_DFX_THERMAL_INIT, 0x0, 0, 0);
+ if (ret == SMCCC_RET_SUCCESS) {
+ dev_info(&pdev->dev, "firmware support\n");
+ THERMAL_SUPPORTED_IN_FIRMWARE(priv) = true;
+ return;
+ }

regmap_read(priv->syscon, data->syscon_control0_off, &reg);
reg &= ~CONTROL0_TSEN_RESET;
@@ -274,11 +334,17 @@ static void armada_cp110_init(struct platform_device *pdev,

static bool armada_is_valid(struct armada_thermal_priv *priv)
{
+ int ret;
u32 reg;

if (!priv->data->is_valid_bit)
return true;

+ if (THERMAL_SUPPORTED_IN_FIRMWARE(priv)) {
+ ret = thermal_smc(MV_SIP_DFX_THERMAL_IS_VALID, &reg, 0, 0);
+ return ret ? false : reg;
+ }
+
regmap_read(priv->syscon, priv->data->syscon_status_off, &reg);

return reg & priv->data->is_valid_bit;
@@ -324,6 +390,7 @@ static int armada_select_channel(struct armada_thermal_priv *priv, int channel)
{
struct armada_thermal_data *data = priv->data;
u32 ctrl0;
+ int ret;

if (channel < 0 || channel > priv->data->cpu_nr)
return -EINVAL;
@@ -331,6 +398,16 @@ static int armada_select_channel(struct armada_thermal_priv *priv, int channel)
if (priv->current_channel == channel)
return 0;

+ if (THERMAL_SUPPORTED_IN_FIRMWARE(priv)) {
+ ret = thermal_smc(MV_SIP_DFX_THERMAL_SEL_CHANNEL,
+ NULL, channel, 0);
+ if (ret)
+ return ret;
+
+ priv->current_channel = channel;
+ goto is_valid;
+ }
+
/* Stop the measurements */
regmap_read(priv->syscon, data->syscon_control0_off, &ctrl0);
ctrl0 &= ~CONTROL0_TSEN_START;
@@ -357,6 +434,7 @@ static int armada_select_channel(struct armada_thermal_priv *priv, int channel)
ctrl0 |= CONTROL0_TSEN_START;
regmap_write(priv->syscon, data->syscon_control0_off, ctrl0);

+is_valid:
/*
* The IP has a latency of ~15ms, so after updating the selected source,
* we must absolutely wait for the sensor validity bit to ensure we read
@@ -376,6 +454,9 @@ static int armada_read_sensor(struct armada_thermal_priv *priv, int *temp)
u32 reg, div;
s64 sample, b, m;

+ if (THERMAL_SUPPORTED_IN_FIRMWARE(priv))
+ return thermal_smc(MV_SIP_DFX_THERMAL_READ, temp, 0, 0);
+
regmap_read(priv->syscon, priv->data->syscon_status_off, &reg);
reg = (reg >> priv->data->temp_shift) & priv->data->temp_mask;
if (priv->data->signed_sample)
@@ -559,7 +640,13 @@ static irqreturn_t armada_overheat_isr_thread(int irq, void *blob)
goto enable_irq;
} while (temperature >= low_threshold);

- regmap_read(priv->syscon, priv->data->dfx_irq_cause_off, &dummy);
+ if (THERMAL_SUPPORTED_IN_FIRMWARE(priv)) {
+ if (thermal_smc(MV_SIP_DFX_THERMAL_IRQ, 0, 0, 0))
+ return IRQ_NONE;
+ } else {
+ regmap_read(priv->syscon, priv->data->dfx_irq_cause_off,
+ &dummy);
+ }

/* Notify the thermal core that the temperature is acceptable again */
thermal_zone_device_update(priv->overheat_sensor,
@@ -772,6 +859,27 @@ static void armada_set_sane_name(struct platform_device *pdev,
} while (insane_char);
}

+/*
+ * Let the firmware configure the thermal overheat threshold, hysteresis and
+ * enable overheat interrupt
+ */
+static int armada_fw_overheat_settings(struct armada_thermal_priv *priv,
+ int thresh_mc, int hyst_mc)
+{
+ int ret;
+
+ ret = thermal_smc(MV_SIP_DFX_THERMAL_THRESH, NULL, thresh_mc, hyst_mc);
+ if (ret)
+ return ret;
+
+ if (thresh_mc >= 0)
+ priv->current_threshold = thresh_mc;
+ if (hyst_mc >= 0)
+ priv->current_hysteresis = hyst_mc;
+
+ return 0;
+}
+
/*
* The IP can manage to trigger interrupts on overheat situation from all the
* sensors. However, the interrupt source changes along with the last selected
@@ -803,11 +911,22 @@ static int armada_configure_overheat_int(struct armada_thermal_priv *priv,
if (ret)
return ret;

+ priv->overheat_sensor = tz;
+ priv->interrupt_source = sensor_id;
+
+ if (THERMAL_SUPPORTED_IN_FIRMWARE(priv)) {
+ /*
+ * When thermal supported in firmware the configuring overheat
+ * threshold and enabling overheat interrupt is done in one
+ * step.
+ */
+ return armada_fw_overheat_settings(priv, trips[i].temperature,
+ trips[i].hysteresis);
+ }
+
armada_set_overheat_thresholds(priv,
trips[i].temperature,
trips[i].hysteresis);
- priv->overheat_sensor = tz;
- priv->interrupt_source = sensor_id;

armada_enable_overheat_interrupt(priv);

diff --git a/include/soc/marvell/armada8k/fw.h b/include/soc/marvell/armada8k/fw.h
new file mode 100644
index 000000000000..2a80f26cbf6f
--- /dev/null
+++ b/include/soc/marvell/armada8k/fw.h
@@ -0,0 +1,19 @@
+/* SPDX-License-Identifier: GPL-2.0 */
+/*
+ * Copyright (C) 2019 Marvell International Ltd.
+ */
+
+#ifndef _SOC_MARVELL_ARMADA8K_FW_H
+#define _SOC_MARVELL_ARMADA8K_FW_H
+
+/* FW related definitions */
+#define MV_SIP_DFX 0x82000014
+
+#define MV_SIP_DFX_THERMAL_INIT 1
+#define MV_SIP_DFX_THERMAL_READ 2
+#define MV_SIP_DFX_THERMAL_IS_VALID 3
+#define MV_SIP_DFX_THERMAL_IRQ 4
+#define MV_SIP_DFX_THERMAL_THRESH 5
+#define MV_SIP_DFX_THERMAL_SEL_CHANNEL 6
+
+#endif /* _SOC_MARVELL_ARMADA8K_FW_H */
--
2.17.1

2021-02-11 14:23:40

by Kostya Porotchkin

[permalink] [raw]
Subject: [PATCH v3 2/2] clk: mvebu: use firmware SiP service for accessing dfx register set

From: Grzegorz Jaszczyk <[email protected]>

This patch introduces support for cpu clk driver in case when SoC
DFX region is marked as secure by the firmware. In such case accessing
cpu clk registers, which are part of dfx register set, will not be
possible from non-secure world.

The ARM Trusted Firmware exposes SiP service which allows to read/write
some dfx registers (white-listed in firmware). This allows Linux cpu clk
driver to set_rate and recalc_rate with use of SMC calls.

If during cpu clk operation the SMC is unhandled (old fw case), fallback
to regmap handling.

Signed-off-by: Grzegorz Jaszczyk <[email protected]>
Signed-off-by: Konstantin Porotchkin <[email protected]>
---
drivers/clk/mvebu/ap-cpu-clk.c | 174 ++++++++++++++++++--
include/soc/marvell/armada8k/fw.h | 3 +
2 files changed, 161 insertions(+), 16 deletions(-)

diff --git a/drivers/clk/mvebu/ap-cpu-clk.c b/drivers/clk/mvebu/ap-cpu-clk.c
index b4259b60dcfd..9ddfa3f8a32d 100644
--- a/drivers/clk/mvebu/ap-cpu-clk.c
+++ b/drivers/clk/mvebu/ap-cpu-clk.c
@@ -10,6 +10,7 @@

#define pr_fmt(fmt) "ap-cpu-clk: " fmt

+#include <linux/arm-smccc.h>
#include <linux/clk-provider.h>
#include <linux/clk.h>
#include <linux/mfd/syscon.h>
@@ -19,6 +20,7 @@
#include <linux/platform_device.h>
#include <linux/regmap.h>
#include "armada_ap_cp_helper.h"
+#include "soc/marvell/armada8k/fw.h"

#define AP806_CPU_CLUSTER0 0
#define AP806_CPU_CLUSTER1 1
@@ -139,8 +141,122 @@ struct ap_cpu_clk {
struct clk_hw hw;
struct regmap *pll_cr_base;
const struct cpu_dfs_regs *pll_regs;
+ phys_addr_t phys;
+ int (*clk_regmap_read)(struct ap_cpu_clk *clk, unsigned int reg,
+ unsigned int *val);
+ int (*clk_regmap_write)(struct ap_cpu_clk *clk, unsigned int reg,
+ unsigned int val);
+ int (*clk_regmap_update_bits)(struct ap_cpu_clk *clk, unsigned int reg,
+ unsigned int mask, unsigned int val);
+ int (*clk_regmap_read_poll_timeout)(struct ap_cpu_clk *clk, unsigned int reg,
+ unsigned int stable_bit);
+
};

+static int dfx_sread_smc(unsigned long addr, unsigned int *reg)
+{
+ struct arm_smccc_res res;
+
+ arm_smccc_smc(MV_SIP_DFX, MV_SIP_DFX_SREAD, addr, 0, 0, 0, 0, 0, &res);
+
+ if (res.a0 == 0 && reg != NULL)
+ *reg = res.a1;
+
+ return res.a0;
+}
+
+static int dfx_swrite_smc(unsigned long addr, unsigned long val)
+{
+ struct arm_smccc_res res;
+
+ arm_smccc_smc(MV_SIP_DFX, MV_SIP_DFX_SWRITE, addr, val,
+ 0, 0, 0, 0, &res);
+
+ return res.a0;
+}
+
+static int smc_regmap_read(struct ap_cpu_clk *clk, unsigned int reg,
+ unsigned int *val)
+{
+ return dfx_sread_smc(clk->phys + reg, val);
+}
+
+static int legacy_regmap_read(struct ap_cpu_clk *clk, unsigned int reg,
+ unsigned int *val)
+{
+ return regmap_read(clk->pll_cr_base, reg, val);
+}
+
+static int smc_regmap_write(struct ap_cpu_clk *clk, unsigned int reg,
+ unsigned int val)
+{
+ return dfx_swrite_smc(clk->phys + reg, val);
+}
+
+static int legacy_regmap_write(struct ap_cpu_clk *clk, unsigned int reg,
+ unsigned int val)
+{
+ return regmap_write(clk->pll_cr_base, reg, val);
+}
+
+static int smc_regmap_update_bits(struct ap_cpu_clk *clk, unsigned int reg,
+ unsigned int mask, unsigned int val)
+{
+ int ret;
+ unsigned int tmp;
+
+ ret = dfx_sread_smc(clk->phys + reg, &tmp);
+ if (ret != SMCCC_RET_SUCCESS)
+ return ret;
+
+ tmp &= ~mask;
+ tmp |= val & mask;
+
+ return dfx_swrite_smc(clk->phys + reg, tmp);
+}
+
+static int legacy_regmap_update_bits(struct ap_cpu_clk *clk, unsigned int reg,
+ unsigned int mask, unsigned int val)
+{
+ return regmap_update_bits(clk->pll_cr_base, reg, mask, val);
+}
+
+static int smc_regmap_read_poll_timeout(struct ap_cpu_clk *clk,
+ unsigned int reg,
+ unsigned int stable_bit)
+{
+ int ret;
+ u32 val;
+ ktime_t timeout;
+
+ timeout = ktime_add_us(ktime_get(), STATUS_POLL_TIMEOUT_US);
+ do {
+ ret = dfx_sread_smc(clk->phys + reg, &val);
+ if (ret || (val & stable_bit))
+ break;
+
+ usleep_range((STATUS_POLL_PERIOD_US >> 2) + 1,
+ STATUS_POLL_PERIOD_US);
+
+ } while (ktime_before(ktime_get(), timeout));
+
+ if (ret == SMCCC_RET_SUCCESS)
+ return (val & stable_bit) ? 0 : -ETIMEDOUT;
+
+ return ret;
+}
+
+static int legacy_regmap_read_poll_timeout(struct ap_cpu_clk *clk,
+ unsigned int reg,
+ unsigned int stable_bit)
+{
+ u32 val;
+
+ return regmap_read_poll_timeout(clk->pll_cr_base,
+ reg, val,
+ (val & stable_bit), STATUS_POLL_PERIOD_US,
+ STATUS_POLL_TIMEOUT_US);
+}
static unsigned long ap_cpu_clk_recalc_rate(struct clk_hw *hw,
unsigned long parent_rate)
{
@@ -150,7 +266,7 @@ static unsigned long ap_cpu_clk_recalc_rate(struct clk_hw *hw,

cpu_clkdiv_reg = clk->pll_regs->divider_reg +
(clk->cluster * clk->pll_regs->cluster_offset);
- regmap_read(clk->pll_cr_base, cpu_clkdiv_reg, &cpu_clkdiv_ratio);
+ clk->clk_regmap_read(clk, cpu_clkdiv_reg, &cpu_clkdiv_ratio);
cpu_clkdiv_ratio &= clk->pll_regs->divider_mask;
cpu_clkdiv_ratio >>= clk->pll_regs->divider_offset;

@@ -171,7 +287,7 @@ static int ap_cpu_clk_set_rate(struct clk_hw *hw, unsigned long rate,
cpu_ratio_reg = clk->pll_regs->ratio_reg +
(clk->cluster * clk->pll_regs->cluster_offset);

- regmap_read(clk->pll_cr_base, cpu_clkdiv_reg, &reg);
+ clk->clk_regmap_read(clk, cpu_clkdiv_reg, &reg);
reg &= ~(clk->pll_regs->divider_mask);
reg |= (divider << clk->pll_regs->divider_offset);

@@ -184,29 +300,27 @@ static int ap_cpu_clk_set_rate(struct clk_hw *hw, unsigned long rate,
reg |= ((divider * clk->pll_regs->divider_ratio) <<
AP807_PLL_CR_1_CPU_CLK_DIV_RATIO_OFFSET);
}
- regmap_write(clk->pll_cr_base, cpu_clkdiv_reg, reg);
+ clk->clk_regmap_write(clk, cpu_clkdiv_reg, reg);

+ clk->clk_regmap_update_bits(clk, cpu_force_reg,
+ clk->pll_regs->force_mask,
+ clk->pll_regs->force_mask);

- regmap_update_bits(clk->pll_cr_base, cpu_force_reg,
- clk->pll_regs->force_mask,
- clk->pll_regs->force_mask);
-
- regmap_update_bits(clk->pll_cr_base, cpu_ratio_reg,
- BIT(clk->pll_regs->ratio_offset),
- BIT(clk->pll_regs->ratio_offset));
+ clk->clk_regmap_update_bits(clk, cpu_ratio_reg,
+ BIT(clk->pll_regs->ratio_offset),
+ BIT(clk->pll_regs->ratio_offset));

stable_bit = BIT(clk->pll_regs->ratio_state_offset +
clk->cluster *
clk->pll_regs->ratio_state_cluster_offset);
- ret = regmap_read_poll_timeout(clk->pll_cr_base,
- clk->pll_regs->ratio_state_reg, reg,
- reg & stable_bit, STATUS_POLL_PERIOD_US,
- STATUS_POLL_TIMEOUT_US);
+ ret = clk->clk_regmap_read_poll_timeout(clk,
+ clk->pll_regs->ratio_state_reg,
+ stable_bit);
if (ret)
return ret;

- regmap_update_bits(clk->pll_cr_base, cpu_ratio_reg,
- BIT(clk->pll_regs->ratio_offset), 0);
+ clk->clk_regmap_update_bits(clk, cpu_ratio_reg,
+ BIT(clk->pll_regs->ratio_offset), 0);

return 0;
}
@@ -235,6 +349,11 @@ static int ap_cpu_clock_probe(struct platform_device *pdev)
struct clk_hw_onecell_data *ap_cpu_data;
struct ap_cpu_clk *ap_cpu_clk;
struct regmap *regmap;
+ struct resource res;
+
+ ret = of_address_to_resource(np->parent, 0, &res);
+ if (ret)
+ return ret;

regmap = syscon_node_to_regmap(np->parent);
if (IS_ERR(regmap)) {
@@ -286,6 +405,7 @@ static int ap_cpu_clock_probe(struct platform_device *pdev)
const char *parent_name;
struct clk *parent;
int cpu, err;
+ unsigned int tmp;

err = of_property_read_u32(dn, "reg", &cpu);
if (WARN_ON(err))
@@ -313,6 +433,28 @@ static int ap_cpu_clock_probe(struct platform_device *pdev)
ap_cpu_clk[cluster_index].dev = dev;
ap_cpu_clk[cluster_index].pll_regs = of_device_get_match_data(&pdev->dev);

+ /* Get the physical address to hand to the firmware. */
+ ap_cpu_clk[cluster_index].phys = res.start;
+
+ /* Try to read a register using SMC and setup DFX access APIs accordingly */
+ ret = smc_regmap_read(&ap_cpu_clk[cluster_index],
+ ap_cpu_clk[cluster_index].pll_regs->divider_reg,
+ &tmp);
+ if (ret == SMCCC_RET_SUCCESS) {
+ ap_cpu_clk[cluster_index].clk_regmap_read = smc_regmap_read;
+ ap_cpu_clk[cluster_index].clk_regmap_write = smc_regmap_write;
+ ap_cpu_clk[cluster_index].clk_regmap_update_bits = smc_regmap_update_bits;
+ ap_cpu_clk[cluster_index].clk_regmap_read_poll_timeout =
+ smc_regmap_read_poll_timeout;
+ } else {
+ ap_cpu_clk[cluster_index].clk_regmap_read = legacy_regmap_read;
+ ap_cpu_clk[cluster_index].clk_regmap_write = legacy_regmap_write;
+ ap_cpu_clk[cluster_index].clk_regmap_update_bits =
+ legacy_regmap_update_bits;
+ ap_cpu_clk[cluster_index].clk_regmap_read_poll_timeout =
+ legacy_regmap_read_poll_timeout;
+ }
+
init.name = ap_cpu_clk[cluster_index].clk_name;
init.ops = &ap_cpu_clk_ops;
init.num_parents = 1;
diff --git a/include/soc/marvell/armada8k/fw.h b/include/soc/marvell/armada8k/fw.h
index 2a80f26cbf6f..e646212a3796 100644
--- a/include/soc/marvell/armada8k/fw.h
+++ b/include/soc/marvell/armada8k/fw.h
@@ -16,4 +16,7 @@
#define MV_SIP_DFX_THERMAL_THRESH 5
#define MV_SIP_DFX_THERMAL_SEL_CHANNEL 6

+#define MV_SIP_DFX_SREAD 20
+#define MV_SIP_DFX_SWRITE 21
+
#endif /* _SOC_MARVELL_ARMADA8K_FW_H */
--
2.17.1

2021-02-11 17:46:48

by kernel test robot

[permalink] [raw]
Subject: Re: [PATCH v3 1/2] thermal: armada: ap806: use firmware SiP services for thermal operations

Hi,

Thank you for the patch! Perhaps something to improve:

[auto build test WARNING on clk/clk-next]
[also build test WARNING on linus/master v5.11-rc7 next-20210211]
[If your patch is applied to the wrong git tree, kindly drop us a note.
And when submitting patch, we suggest to use '--base' as documented in
https://git-scm.com/docs/git-format-patch]

url: https://github.com/0day-ci/linux/commits/kostap-marvell-com/Enable-usage-of-Marvell-FW-SIP-services/20210211-220917
base: https://git.kernel.org/pub/scm/linux/kernel/git/clk/linux.git clk-next
config: i386-randconfig-s002-20210211 (attached as .config)
compiler: gcc-9 (Debian 9.3.0-15) 9.3.0
reproduce:
# apt-get install sparse
# sparse version: v0.6.3-215-g0fb77bb6-dirty
# https://github.com/0day-ci/linux/commit/f3d1a200c085eb2518257982a822f06711a7ce95
git remote add linux-review https://github.com/0day-ci/linux
git fetch --no-tags linux-review kostap-marvell-com/Enable-usage-of-Marvell-FW-SIP-services/20210211-220917
git checkout f3d1a200c085eb2518257982a822f06711a7ce95
# save the attached .config to linux build tree
make W=1 C=1 CF='-fdiagnostic-prefix -D__CHECK_ENDIAN__' ARCH=i386

If you fix the issue, kindly add following tag as appropriate
Reported-by: kernel test robot <[email protected]>


"sparse warnings: (new ones prefixed by >>)"
>> drivers/thermal/armada_thermal.c:295:52: sparse: sparse: Using plain integer as NULL pointer
drivers/thermal/armada_thermal.c:644:57: sparse: sparse: Using plain integer as NULL pointer

vim +295 drivers/thermal/armada_thermal.c

279
280 static void armada_ap806_init(struct platform_device *pdev,
281 struct armada_thermal_priv *priv)
282 {
283 struct armada_thermal_data *data = priv->data;
284 u32 reg;
285 int ret;
286
287 /*
288 * The ap806 thermal sensor registers are part of DFX which is secured
289 * by latest firmware, therefore accessing relevant registers from
290 * not-secure world will not be possible. In that case Arm Trusted
291 * Firmware exposes thermal operations as firmware run-time service. If
292 * SMC initialization succeeds, perform other thermal operations using
293 * SMC, otherwise (old fw case) fallback to regmap handling.
294 */
> 295 ret = thermal_smc(MV_SIP_DFX_THERMAL_INIT, 0x0, 0, 0);
296 if (ret == SMCCC_RET_SUCCESS) {
297 dev_info(&pdev->dev, "firmware support\n");
298 THERMAL_SUPPORTED_IN_FIRMWARE(priv) = true;
299 return;
300 }
301
302 regmap_read(priv->syscon, data->syscon_control0_off, &reg);
303 reg &= ~CONTROL0_TSEN_RESET;
304 reg |= CONTROL0_TSEN_START | CONTROL0_TSEN_ENABLE;
305
306 /* Sample every ~2ms */
307 reg |= CONTROL0_TSEN_OSR_MAX << CONTROL0_TSEN_OSR_SHIFT;
308
309 /* Enable average (2 samples by default) */
310 reg &= ~CONTROL0_TSEN_AVG_BYPASS;
311
312 regmap_write(priv->syscon, data->syscon_control0_off, reg);
313 }
314

---
0-DAY CI Kernel Test Service, Intel Corporation
https://lists.01.org/hyperkitty/list/[email protected]


Attachments:
(No filename) (3.15 kB)
.config.gz (51.56 kB)
Download all attachments

2021-02-11 18:39:55

by kernel test robot

[permalink] [raw]
Subject: Re: [PATCH v3 1/2] thermal: armada: ap806: use firmware SiP services for thermal operations

Hi,

Thank you for the patch! Yet something to improve:

[auto build test ERROR on clk/clk-next]
[also build test ERROR on linus/master thermal/next soc-thermal/next v5.11-rc7]
[If your patch is applied to the wrong git tree, kindly drop us a note.
And when submitting patch, we suggest to use '--base' as documented in
https://git-scm.com/docs/git-format-patch]

url: https://github.com/0day-ci/linux/commits/kostap-marvell-com/Enable-usage-of-Marvell-FW-SIP-services/20210211-220917
base: https://git.kernel.org/pub/scm/linux/kernel/git/clk/linux.git clk-next
config: parisc-allyesconfig (attached as .config)
compiler: hppa-linux-gcc (GCC) 9.3.0
reproduce (this is a W=1 build):
wget https://raw.githubusercontent.com/intel/lkp-tests/master/sbin/make.cross -O ~/bin/make.cross
chmod +x ~/bin/make.cross
# https://github.com/0day-ci/linux/commit/f3d1a200c085eb2518257982a822f06711a7ce95
git remote add linux-review https://github.com/0day-ci/linux
git fetch --no-tags linux-review kostap-marvell-com/Enable-usage-of-Marvell-FW-SIP-services/20210211-220917
git checkout f3d1a200c085eb2518257982a822f06711a7ce95
# save the attached .config to linux build tree
COMPILER_INSTALL_PATH=$HOME/0day COMPILER=gcc-9.3.0 make.cross ARCH=parisc

If you fix the issue, kindly add following tag as appropriate
Reported-by: kernel test robot <[email protected]>

All errors (new ones prefixed by >>):

hppa-linux-ld: drivers/thermal/armada_thermal.o: in function `thermal_smc':
>> (.text+0x2b0): undefined reference to `__arm_smccc_smc'

---
0-DAY CI Kernel Test Service, Intel Corporation
https://lists.01.org/hyperkitty/list/[email protected]


Attachments:
(No filename) (1.70 kB)
.config.gz (66.13 kB)
Download all attachments

2021-02-11 22:23:10

by kernel test robot

[permalink] [raw]
Subject: Re: [PATCH v3 1/2] thermal: armada: ap806: use firmware SiP services for thermal operations

Hi,

Thank you for the patch! Yet something to improve:

[auto build test ERROR on clk/clk-next]
[also build test ERROR on linus/master v5.11-rc7 next-20210211]
[If your patch is applied to the wrong git tree, kindly drop us a note.
And when submitting patch, we suggest to use '--base' as documented in
https://git-scm.com/docs/git-format-patch]

url: https://github.com/0day-ci/linux/commits/kostap-marvell-com/Enable-usage-of-Marvell-FW-SIP-services/20210211-220917
base: https://git.kernel.org/pub/scm/linux/kernel/git/clk/linux.git clk-next
config: microblaze-allyesconfig (attached as .config)
compiler: microblaze-linux-gcc (GCC) 9.3.0
reproduce (this is a W=1 build):
wget https://raw.githubusercontent.com/intel/lkp-tests/master/sbin/make.cross -O ~/bin/make.cross
chmod +x ~/bin/make.cross
# https://github.com/0day-ci/linux/commit/f3d1a200c085eb2518257982a822f06711a7ce95
git remote add linux-review https://github.com/0day-ci/linux
git fetch --no-tags linux-review kostap-marvell-com/Enable-usage-of-Marvell-FW-SIP-services/20210211-220917
git checkout f3d1a200c085eb2518257982a822f06711a7ce95
# save the attached .config to linux build tree
COMPILER_INSTALL_PATH=$HOME/0day COMPILER=gcc-9.3.0 make.cross ARCH=microblaze

If you fix the issue, kindly add following tag as appropriate
Reported-by: kernel test robot <[email protected]>

All errors (new ones prefixed by >>):

microblaze-linux-ld: drivers/thermal/armada_thermal.o: in function `thermal_smc':
>> drivers/thermal/.tmp_gl_armada_thermal.o:(.text+0x29c): undefined reference to `__arm_smccc_smc'

---
0-DAY CI Kernel Test Service, Intel Corporation
https://lists.01.org/hyperkitty/list/[email protected]


Attachments:
(No filename) (1.75 kB)
.config.gz (65.33 kB)
Download all attachments