1
0
Fork 0

Update extcon for 4.11

Detailed description for this pull request:
 1. Add the new extcon driver.
 - Intel INT3496 ACPI USB id detection driver detects whether
   EXTCON_USB_HOST is attached or detached. (extcon-intel-int3496.c)
 
 2. Add the new type of external connector.
 - EXTCON_CHG_USB_PD (USB Power Delivery) provides the increased
   power more than 7.5W to device with larger power demand.
 
 3. Add the description for EXTCON_CHG_USB_(SDP|ACA|SLOW|FAST)
 - EXTCON_CHG_USB_SDP should always appear together with EXTCON_USB
 - EXTCON_CHG_USB_ACA would normally appear with EXTCON_USB_HOST.
 - EXTCON_CHG_USB_SLOW can provide at least 500mA of current at 5V
 - EXTCON_CHG_USB_FAST can provide at least 1A of current at 5V.
 
 4. Modify the connector name of EXTCON_USB_HOST
 - "USB_HOST" -> "USB-HOST"
 
 5. Update the extcon core
 - Move the private extcon structure into driver/extcon directory.
   The 'struct extcon_dev' should be only handled by extcon core
   to prevent the direct access and to maintain the integrity of it.
 - Remove the ambigous operation of extcon_register_notifier()
   in case of the 'extcon_dev' instance is NULL. The user of
   extcon_register_notifier() have to specify the correct instance
   of the provider extcon driver.
 
 6. Update the extcon drivers and fix the minor issues
 - Update the extcon-axp288 driver to remove the unncessary code.
 - Add pinctrl operation during suspend mode to extcon-usb-gpio driver.
 - Clean up the extcon-arizona/adc-jack driver.
 - Use the dev_dbg() for debug messsage on extcon-palmas driver.
 - Return the error code on failure of extcon_sync()
 -----BEGIN PGP SIGNATURE-----
 Version: GnuPG v1
 
 iQIcBAABAgAGBQJYiEQUAAoJEJzN3yze689T/yoQALU9fN6cW0CsBpa9cOp5IitY
 jQhssvEYbYwXBge1Wcq/CpYbBVuwq4FGUAlUN3W5HEAoCt7zFAbBK4GGrN0zby5p
 qAyEXTgExEBOvP0JayCfsFQGWZNuhj2mEm3xPA5jLdoVazT/SOrexja8nmQCyJxq
 7bHgpfaqN0Kvo7rB8V0vnQsqSGvB1CZRBU419IkcvJF+3rjUGh1asJnjxUdysI/u
 V9C+lNEf75UiM7fh9LTggoboFVUtHCpY06W+MpoxArlcKNk2cPgbMYPsyF9z+DUJ
 814UyCrxzSAEXj/yLkuSgMSBBvnP1hz8arxFTi0GHoid/R6FNSQGGBtYtwLq0vkO
 A21HfLleuXDkx8vYxPK9g6bzX/Yv4dpQWymY8HU/gtyhYpmGKRmHBvxhAI903w2W
 caTF+AsSlIs1IR7L6wpnku6YNhhHyJK4eyx5qiX78dn3mzEFk9k9v+M/U2ZEgDKL
 rKKz+bueFEGlvYO8vqwUsTrgHSMHnM/jVvHjzEXHfnu1ND2P/vab3ss1iOGBUDhl
 aW8+YK9nM/kgLQ/qr5OR33hSRa9gZyQViKsD0HYy91FSKED6Eh8/XpGZoWRJSqWs
 MIV7MkgH9yAiU5R0qDhXREe5PQ7dU9NdWI+2tAZWy5UNhVrMOab48Ih6xhA8c2XQ
 7HhWLdYnalAA/y+MaVK2
 =o+zC
 -----END PGP SIGNATURE-----

Merge tag 'extcon-next-for-4.11' of git://git.kernel.org/pub/scm/linux/kernel/git/chanwoo/extcon into char-misc-next

Chanwoo writes:

Update extcon for 4.11

Detailed description for this pull request:
1. Add the new extcon driver.
- Intel INT3496 ACPI USB id detection driver detects whether
  EXTCON_USB_HOST is attached or detached. (extcon-intel-int3496.c)

2. Add the new type of external connector.
- EXTCON_CHG_USB_PD (USB Power Delivery) provides the increased
  power more than 7.5W to device with larger power demand.

3. Add the description for EXTCON_CHG_USB_(SDP|ACA|SLOW|FAST)
- EXTCON_CHG_USB_SDP should always appear together with EXTCON_USB
- EXTCON_CHG_USB_ACA would normally appear with EXTCON_USB_HOST.
- EXTCON_CHG_USB_SLOW can provide at least 500mA of current at 5V
- EXTCON_CHG_USB_FAST can provide at least 1A of current at 5V.

4. Modify the connector name of EXTCON_USB_HOST
- "USB_HOST" -> "USB-HOST"

5. Update the extcon core
- Move the private extcon structure into driver/extcon directory.
  The 'struct extcon_dev' should be only handled by extcon core
  to prevent the direct access and to maintain the integrity of it.
- Remove the ambigous operation of extcon_register_notifier()
  in case of the 'extcon_dev' instance is NULL. The user of
  extcon_register_notifier() have to specify the correct instance
  of the provider extcon driver.

6. Update the extcon drivers and fix the minor issues
- Update the extcon-axp288 driver to remove the unncessary code.
- Add pinctrl operation during suspend mode to extcon-usb-gpio driver.
- Clean up the extcon-arizona/adc-jack driver.
- Use the dev_dbg() for debug messsage on extcon-palmas driver.
- Return the error code on failure of extcon_sync()
hifive-unleashed-5.1
Greg Kroah-Hartman 2017-01-25 11:05:04 +01:00
commit 36bebcff6f
19 changed files with 411 additions and 189 deletions

View File

@ -0,0 +1,22 @@
Intel INT3496 ACPI device extcon driver documentation
-----------------------------------------------------
The Intel INT3496 ACPI device extcon driver is a driver for ACPI
devices with an acpi-id of INT3496, such as found for example on
Intel Baytrail and Cherrytrail tablets.
This ACPI device describes how the OS can read the id-pin of the devices'
USB-otg port, as well as how it optionally can enable Vbus output on the
otg port and how it can optionally control the muxing of the data pins
between an USB host and an USB peripheral controller.
The ACPI devices exposes this functionality by returning an array with up
to 3 gpio descriptors from its ACPI _CRS (Current Resource Settings) call:
Index 0: The input gpio for the id-pin, this is always present and valid
Index 1: The output gpio for enabling Vbus output from the device to the otg
port, write 1 to enable the Vbus output (this gpio descriptor may
be absent or invalid)
Index 2: The output gpio for muxing of the data pins between the USB host and
the USB peripheral controller, write 1 to mux to the peripheral
controller

View File

@ -42,6 +42,16 @@ config EXTCON_GPIO
Say Y here to enable GPIO based extcon support. Note that GPIO
extcon supports single state per extcon instance.
config EXTCON_INTEL_INT3496
tristate "Intel INT3496 ACPI device extcon driver"
depends on GPIOLIB && ACPI
help
Say Y here to enable extcon support for USB OTG ports controlled by
an Intel INT3496 ACPI device.
This ACPI device is typically found on Intel Baytrail or Cherrytrail
based tablets, or other Baytrail / Cherrytrail devices.
config EXTCON_MAX14577
tristate "Maxim MAX14577/77836 EXTCON Support"
depends on MFD_MAX14577

View File

@ -8,6 +8,7 @@ obj-$(CONFIG_EXTCON_ADC_JACK) += extcon-adc-jack.o
obj-$(CONFIG_EXTCON_ARIZONA) += extcon-arizona.o
obj-$(CONFIG_EXTCON_AXP288) += extcon-axp288.o
obj-$(CONFIG_EXTCON_GPIO) += extcon-gpio.o
obj-$(CONFIG_EXTCON_INTEL_INT3496) += extcon-intel-int3496.o
obj-$(CONFIG_EXTCON_MAX14577) += extcon-max14577.o
obj-$(CONFIG_EXTCON_MAX3355) += extcon-max3355.o
obj-$(CONFIG_EXTCON_MAX77693) += extcon-max77693.o

View File

@ -14,7 +14,7 @@
* GNU General Public License for more details.
*/
#include <linux/extcon.h>
#include "extcon.h"
static int devm_extcon_dev_match(struct device *dev, void *res, void *data)
{

View File

@ -67,7 +67,7 @@ static void adc_jack_handler(struct work_struct *work)
ret = iio_read_channel_raw(data->chan, &adc_val);
if (ret < 0) {
dev_err(&data->edev->dev, "read channel() error: %d\n", ret);
dev_err(data->dev, "read channel() error: %d\n", ret);
return;
}

View File

@ -236,12 +236,8 @@ static void arizona_extcon_set_mode(struct arizona_extcon_info *info, int mode)
mode %= info->micd_num_modes;
if (arizona->pdata.micd_pol_gpio > 0)
gpio_set_value_cansleep(arizona->pdata.micd_pol_gpio,
info->micd_modes[mode].gpio);
else
gpiod_set_value_cansleep(info->micd_pol_gpio,
info->micd_modes[mode].gpio);
gpiod_set_value_cansleep(info->micd_pol_gpio,
info->micd_modes[mode].gpio);
regmap_update_bits(arizona->regmap, ARIZONA_MIC_DETECT_1,
ARIZONA_MICD_BIAS_SRC_MASK,
@ -1412,21 +1408,21 @@ static int arizona_extcon_probe(struct platform_device *pdev)
regmap_update_bits(arizona->regmap, ARIZONA_GP_SWITCH_1,
ARIZONA_SW1_MODE_MASK, arizona->pdata.gpsw);
if (arizona->pdata.micd_pol_gpio > 0) {
if (pdata->micd_pol_gpio > 0) {
if (info->micd_modes[0].gpio)
mode = GPIOF_OUT_INIT_HIGH;
else
mode = GPIOF_OUT_INIT_LOW;
ret = devm_gpio_request_one(&pdev->dev,
arizona->pdata.micd_pol_gpio,
mode,
"MICD polarity");
ret = devm_gpio_request_one(&pdev->dev, pdata->micd_pol_gpio,
mode, "MICD polarity");
if (ret != 0) {
dev_err(arizona->dev, "Failed to request GPIO%d: %d\n",
arizona->pdata.micd_pol_gpio, ret);
pdata->micd_pol_gpio, ret);
goto err_register;
}
info->micd_pol_gpio = gpio_to_desc(pdata->micd_pol_gpio);
} else {
if (info->micd_modes[0].gpio)
mode = GPIOD_OUT_HIGH;

View File

@ -21,7 +21,6 @@
#include <linux/interrupt.h>
#include <linux/platform_device.h>
#include <linux/property.h>
#include <linux/usb/phy.h>
#include <linux/notifier.h>
#include <linux/extcon.h>
#include <linux/regmap.h>
@ -71,12 +70,6 @@
#define DET_STAT_CDP 2
#define DET_STAT_DCP 3
/* IRQ enable-1 register */
#define PWRSRC_IRQ_CFG_MASK (BIT(4)|BIT(3)|BIT(2))
/* IRQ enable-6 register */
#define BC12_IRQ_CFG_MASK BIT(1)
enum axp288_extcon_reg {
AXP288_PS_STAT_REG = 0x00,
AXP288_PS_BOOT_REASON_REG = 0x02,
@ -84,8 +77,6 @@ enum axp288_extcon_reg {
AXP288_BC_VBUS_CNTL_REG = 0x2d,
AXP288_BC_USB_STAT_REG = 0x2e,
AXP288_BC_DET_STAT_REG = 0x2f,
AXP288_PWRSRC_IRQ_CFG_REG = 0x40,
AXP288_BC12_IRQ_CFG_REG = 0x45,
};
enum axp288_mux_select {
@ -105,6 +96,7 @@ static const unsigned int axp288_extcon_cables[] = {
EXTCON_CHG_USB_SDP,
EXTCON_CHG_USB_CDP,
EXTCON_CHG_USB_DCP,
EXTCON_USB,
EXTCON_NONE,
};
@ -112,11 +104,11 @@ struct axp288_extcon_info {
struct device *dev;
struct regmap *regmap;
struct regmap_irq_chip_data *regmap_irqc;
struct axp288_extcon_pdata *pdata;
struct gpio_desc *gpio_mux_cntl;
int irq[EXTCON_IRQ_END];
struct extcon_dev *edev;
struct notifier_block extcon_nb;
struct usb_phy *otg;
unsigned int previous_cable;
};
/* Power up/down reason string array */
@ -156,10 +148,9 @@ static void axp288_extcon_log_rsi(struct axp288_extcon_info *info)
static int axp288_handle_chrg_det_event(struct axp288_extcon_info *info)
{
static bool notify_otg, notify_charger;
static unsigned int cable;
int ret, stat, cfg, pwr_stat;
u8 chrg_type;
unsigned int cable = info->previous_cable;
bool vbus_attach = false;
ret = regmap_read(info->regmap, AXP288_PS_STAT_REG, &pwr_stat);
@ -168,9 +159,9 @@ static int axp288_handle_chrg_det_event(struct axp288_extcon_info *info)
return ret;
}
vbus_attach = (pwr_stat & PS_STAT_VBUS_PRESENT);
vbus_attach = (pwr_stat & PS_STAT_VBUS_VALID);
if (!vbus_attach)
goto notify_otg;
goto no_vbus;
/* Check charger detection completion status */
ret = regmap_read(info->regmap, AXP288_BC_GLOBAL_REG, &cfg);
@ -190,19 +181,14 @@ static int axp288_handle_chrg_det_event(struct axp288_extcon_info *info)
switch (chrg_type) {
case DET_STAT_SDP:
dev_dbg(info->dev, "sdp cable is connected\n");
notify_otg = true;
notify_charger = true;
cable = EXTCON_CHG_USB_SDP;
break;
case DET_STAT_CDP:
dev_dbg(info->dev, "cdp cable is connected\n");
notify_otg = true;
notify_charger = true;
cable = EXTCON_CHG_USB_CDP;
break;
case DET_STAT_DCP:
dev_dbg(info->dev, "dcp cable is connected\n");
notify_charger = true;
cable = EXTCON_CHG_USB_DCP;
break;
default:
@ -210,27 +196,28 @@ static int axp288_handle_chrg_det_event(struct axp288_extcon_info *info)
"disconnect or unknown or ID event\n");
}
notify_otg:
if (notify_otg) {
/*
* If VBUS is absent Connect D+/D- lines to PMIC for BC
* detection. Else connect them to SOC for USB communication.
*/
if (info->pdata->gpio_mux_cntl)
gpiod_set_value(info->pdata->gpio_mux_cntl,
vbus_attach ? EXTCON_GPIO_MUX_SEL_SOC
: EXTCON_GPIO_MUX_SEL_PMIC);
no_vbus:
/*
* If VBUS is absent Connect D+/D- lines to PMIC for BC
* detection. Else connect them to SOC for USB communication.
*/
if (info->gpio_mux_cntl)
gpiod_set_value(info->gpio_mux_cntl,
vbus_attach ? EXTCON_GPIO_MUX_SEL_SOC
: EXTCON_GPIO_MUX_SEL_PMIC);
atomic_notifier_call_chain(&info->otg->notifier,
vbus_attach ? USB_EVENT_VBUS : USB_EVENT_NONE, NULL);
}
extcon_set_state_sync(info->edev, info->previous_cable, false);
if (info->previous_cable == EXTCON_CHG_USB_SDP)
extcon_set_state_sync(info->edev, EXTCON_USB, false);
if (notify_charger)
if (vbus_attach) {
extcon_set_state_sync(info->edev, cable, vbus_attach);
if (cable == EXTCON_CHG_USB_SDP)
extcon_set_state_sync(info->edev, EXTCON_USB,
vbus_attach);
/* Clear the flags on disconnect event */
if (!vbus_attach)
notify_otg = notify_charger = false;
info->previous_cable = cable;
}
return 0;
@ -253,15 +240,10 @@ static irqreturn_t axp288_extcon_isr(int irq, void *data)
return IRQ_HANDLED;
}
static void axp288_extcon_enable_irq(struct axp288_extcon_info *info)
static void axp288_extcon_enable(struct axp288_extcon_info *info)
{
/* Unmask VBUS interrupt */
regmap_write(info->regmap, AXP288_PWRSRC_IRQ_CFG_REG,
PWRSRC_IRQ_CFG_MASK);
regmap_update_bits(info->regmap, AXP288_BC_GLOBAL_REG,
BC_GLOBAL_RUN, 0);
/* Unmask the BC1.2 complete interrupts */
regmap_write(info->regmap, AXP288_BC12_IRQ_CFG_REG, BC12_IRQ_CFG_MASK);
/* Enable the charger detection logic */
regmap_update_bits(info->regmap, AXP288_BC_GLOBAL_REG,
BC_GLOBAL_RUN, BC_GLOBAL_RUN);
@ -271,6 +253,7 @@ static int axp288_extcon_probe(struct platform_device *pdev)
{
struct axp288_extcon_info *info;
struct axp20x_dev *axp20x = dev_get_drvdata(pdev->dev.parent);
struct axp288_extcon_pdata *pdata = pdev->dev.platform_data;
int ret, i, pirq, gpio;
info = devm_kzalloc(&pdev->dev, sizeof(*info), GFP_KERNEL);
@ -280,15 +263,10 @@ static int axp288_extcon_probe(struct platform_device *pdev)
info->dev = &pdev->dev;
info->regmap = axp20x->regmap;
info->regmap_irqc = axp20x->regmap_irqc;
info->pdata = pdev->dev.platform_data;
info->previous_cable = EXTCON_NONE;
if (pdata)
info->gpio_mux_cntl = pdata->gpio_mux_cntl;
if (!info->pdata) {
/* Try ACPI provided pdata via device properties */
if (!device_property_present(&pdev->dev,
"axp288_extcon_data\n"))
dev_err(&pdev->dev, "failed to get platform data\n");
return -ENODEV;
}
platform_set_drvdata(pdev, info);
axp288_extcon_log_rsi(info);
@ -308,23 +286,16 @@ static int axp288_extcon_probe(struct platform_device *pdev)
return ret;
}
/* Get otg transceiver phy */
info->otg = devm_usb_get_phy(&pdev->dev, USB_PHY_TYPE_USB2);
if (IS_ERR(info->otg)) {
dev_err(&pdev->dev, "failed to get otg transceiver\n");
return PTR_ERR(info->otg);
}
/* Set up gpio control for USB Mux */
if (info->pdata->gpio_mux_cntl) {
gpio = desc_to_gpio(info->pdata->gpio_mux_cntl);
if (info->gpio_mux_cntl) {
gpio = desc_to_gpio(info->gpio_mux_cntl);
ret = devm_gpio_request(&pdev->dev, gpio, "USB_MUX");
if (ret < 0) {
dev_err(&pdev->dev,
"failed to request the gpio=%d\n", gpio);
return ret;
}
gpiod_direction_output(info->pdata->gpio_mux_cntl,
gpiod_direction_output(info->gpio_mux_cntl,
EXTCON_GPIO_MUX_SEL_PMIC);
}
@ -349,14 +320,21 @@ static int axp288_extcon_probe(struct platform_device *pdev)
}
}
/* Enable interrupts */
axp288_extcon_enable_irq(info);
/* Start charger cable type detection */
axp288_extcon_enable(info);
return 0;
}
static const struct platform_device_id axp288_extcon_table[] = {
{ .name = "axp288_extcon" },
{},
};
MODULE_DEVICE_TABLE(platform, axp288_extcon_table);
static struct platform_driver axp288_extcon_driver = {
.probe = axp288_extcon_probe,
.id_table = axp288_extcon_table,
.driver = {
.name = "axp288_extcon",
},

View File

@ -0,0 +1,179 @@
/*
* Intel INT3496 ACPI device extcon driver
*
* Copyright (c) 2016 Hans de Goede <hdegoede@redhat.com>
*
* Based on android x86 kernel code which is:
*
* Copyright (c) 2014, Intel Corporation.
* Author: David Cohen <david.a.cohen@linux.intel.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License version 2 as
* published by the Free Software Foundation.
*
* 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.
*/
#include <linux/acpi.h>
#include <linux/extcon.h>
#include <linux/gpio.h>
#include <linux/interrupt.h>
#include <linux/module.h>
#include <linux/platform_device.h>
#define INT3496_GPIO_USB_ID 0
#define INT3496_GPIO_VBUS_EN 1
#define INT3496_GPIO_USB_MUX 2
#define DEBOUNCE_TIME msecs_to_jiffies(50)
struct int3496_data {
struct device *dev;
struct extcon_dev *edev;
struct delayed_work work;
struct gpio_desc *gpio_usb_id;
struct gpio_desc *gpio_vbus_en;
struct gpio_desc *gpio_usb_mux;
int usb_id_irq;
};
static const unsigned int int3496_cable[] = {
EXTCON_USB_HOST,
EXTCON_NONE,
};
static void int3496_do_usb_id(struct work_struct *work)
{
struct int3496_data *data =
container_of(work, struct int3496_data, work.work);
int id = gpiod_get_value_cansleep(data->gpio_usb_id);
/* id == 1: PERIPHERAL, id == 0: HOST */
dev_dbg(data->dev, "Connected %s cable\n", id ? "PERIPHERAL" : "HOST");
/*
* Peripheral: set USB mux to peripheral and disable VBUS
* Host: set USB mux to host and enable VBUS
*/
if (!IS_ERR(data->gpio_usb_mux))
gpiod_direction_output(data->gpio_usb_mux, id);
if (!IS_ERR(data->gpio_vbus_en))
gpiod_direction_output(data->gpio_vbus_en, !id);
extcon_set_state_sync(data->edev, EXTCON_USB_HOST, !id);
}
static irqreturn_t int3496_thread_isr(int irq, void *priv)
{
struct int3496_data *data = priv;
/* Let the pin settle before processing it */
mod_delayed_work(system_wq, &data->work, DEBOUNCE_TIME);
return IRQ_HANDLED;
}
static int int3496_probe(struct platform_device *pdev)
{
struct device *dev = &pdev->dev;
struct int3496_data *data;
int ret;
data = devm_kzalloc(dev, sizeof(*data), GFP_KERNEL);
if (!data)
return -ENOMEM;
data->dev = dev;
INIT_DELAYED_WORK(&data->work, int3496_do_usb_id);
data->gpio_usb_id = devm_gpiod_get_index(dev, "id",
INT3496_GPIO_USB_ID,
GPIOD_IN);
if (IS_ERR(data->gpio_usb_id)) {
ret = PTR_ERR(data->gpio_usb_id);
dev_err(dev, "can't request USB ID GPIO: %d\n", ret);
return ret;
}
data->usb_id_irq = gpiod_to_irq(data->gpio_usb_id);
if (data->usb_id_irq <= 0) {
dev_err(dev, "can't get USB ID IRQ: %d\n", data->usb_id_irq);
return -EINVAL;
}
data->gpio_vbus_en = devm_gpiod_get_index(dev, "vbus en",
INT3496_GPIO_VBUS_EN,
GPIOD_ASIS);
if (IS_ERR(data->gpio_vbus_en))
dev_info(dev, "can't request VBUS EN GPIO\n");
data->gpio_usb_mux = devm_gpiod_get_index(dev, "usb mux",
INT3496_GPIO_USB_MUX,
GPIOD_ASIS);
if (IS_ERR(data->gpio_usb_mux))
dev_info(dev, "can't request USB MUX GPIO\n");
/* register extcon device */
data->edev = devm_extcon_dev_allocate(dev, int3496_cable);
if (IS_ERR(data->edev))
return -ENOMEM;
ret = devm_extcon_dev_register(dev, data->edev);
if (ret < 0) {
dev_err(dev, "can't register extcon device: %d\n", ret);
return ret;
}
ret = devm_request_threaded_irq(dev, data->usb_id_irq,
NULL, int3496_thread_isr,
IRQF_SHARED | IRQF_ONESHOT |
IRQF_TRIGGER_RISING |
IRQF_TRIGGER_FALLING,
dev_name(dev), data);
if (ret < 0) {
dev_err(dev, "can't request IRQ for USB ID GPIO: %d\n", ret);
return ret;
}
/* queue initial processing of id-pin */
queue_delayed_work(system_wq, &data->work, 0);
platform_set_drvdata(pdev, data);
return 0;
}
static int int3496_remove(struct platform_device *pdev)
{
struct int3496_data *data = platform_get_drvdata(pdev);
devm_free_irq(&pdev->dev, data->usb_id_irq, data);
cancel_delayed_work_sync(&data->work);
return 0;
}
static struct acpi_device_id int3496_acpi_match[] = {
{ "INT3496" },
{ }
};
MODULE_DEVICE_TABLE(acpi, int3496_acpi_match);
static struct platform_driver int3496_driver = {
.driver = {
.name = "intel-int3496",
.acpi_match_table = int3496_acpi_match,
},
.probe = int3496_probe,
.remove = int3496_remove,
};
module_platform_driver(int3496_driver);
MODULE_AUTHOR("Hans de Goede <hdegoede@redhat.com>");
MODULE_DESCRIPTION("Intel INT3496 ACPI device extcon driver");
MODULE_LICENSE("GPL");

View File

@ -531,8 +531,10 @@ static int max14577_parse_irq(struct max14577_muic_info *info, int irq_type)
case MAX14577_IRQ_INT1_ADC:
case MAX14577_IRQ_INT1_ADCLOW:
case MAX14577_IRQ_INT1_ADCERR:
/* Handle all of accessory except for
type of charger accessory */
/*
* Handle all of accessory except for
* type of charger accessory.
*/
info->irq_adc = true;
return 1;
case MAX14577_IRQ_INT2_CHGTYP:

View File

@ -188,8 +188,10 @@ enum max77693_muic_acc_type {
MAX77693_MUIC_ADC_AUDIO_MODE_REMOTE,
MAX77693_MUIC_ADC_OPEN,
/* The below accessories have same ADC value so ADCLow and
ADC1K bit is used to separate specific accessory */
/*
* The below accessories have same ADC value so ADCLow and
* ADC1K bit is used to separate specific accessory.
*/
/* ADC|VBVolot|ADCLow|ADC1K| */
MAX77693_MUIC_GND_USB_HOST = 0x100, /* 0x0| 0| 0| 0| */
MAX77693_MUIC_GND_USB_HOST_VB = 0x104, /* 0x0| 1| 0| 0| */
@ -970,8 +972,10 @@ static void max77693_muic_irq_work(struct work_struct *work)
case MAX77693_MUIC_IRQ_INT1_ADC_LOW:
case MAX77693_MUIC_IRQ_INT1_ADC_ERR:
case MAX77693_MUIC_IRQ_INT1_ADC1K:
/* Handle all of accessory except for
type of charger accessory */
/*
* Handle all of accessory except for
* type of charger accessory.
*/
ret = max77693_muic_adc_handler(info);
break;
case MAX77693_MUIC_IRQ_INT2_CHGTYP:

View File

@ -97,8 +97,10 @@ enum max77843_muic_accessory_type {
MAX77843_MUIC_ADC_AUDIO_DEVICE_TYPE1,
MAX77843_MUIC_ADC_OPEN,
/* The blow accessories should check
not only ADC value but also ADC1K and VBVolt value. */
/*
* The below accessories should check
* not only ADC value but also ADC1K and VBVolt value.
*/
/* Offset|ADC1K|VBVolt| */
MAX77843_MUIC_GND_USB_HOST = 0x100, /* 0x1| 0| 0| */
MAX77843_MUIC_GND_USB_HOST_VB = 0x101, /* 0x1| 0| 1| */
@ -265,16 +267,20 @@ static int max77843_muic_get_cable_type(struct max77843_muic_info *info,
/* Check GROUND accessory with charger cable */
if (adc == MAX77843_MUIC_ADC_GROUND) {
if (chg_type == MAX77843_MUIC_CHG_NONE) {
/* The following state when charger cable is
/*
* The following state when charger cable is
* disconnected but the GROUND accessory still
* connected */
* connected.
*/
*attached = false;
cable_type = info->prev_chg_type;
info->prev_chg_type = MAX77843_MUIC_CHG_NONE;
} else {
/* The following state when charger cable is
* connected on the GROUND accessory */
/*
* The following state when charger cable is
* connected on the GROUND accessory.
*/
*attached = true;
cable_type = MAX77843_MUIC_CHG_GND;
info->prev_chg_type = MAX77843_MUIC_CHG_GND;
@ -299,11 +305,13 @@ static int max77843_muic_get_cable_type(struct max77843_muic_info *info,
} else {
*attached = true;
/* Offset|ADC1K|VBVolt|
/*
* Offset|ADC1K|VBVolt|
* 0x1| 0| 0| USB-HOST
* 0x1| 0| 1| USB-HOST with VB
* 0x1| 1| 0| MHL
* 0x1| 1| 1| MHL with VB */
* 0x1| 1| 1| MHL with VB
*/
/* Get ADC1K register bit */
gnd_type = (info->status[MAX77843_MUIC_STATUS1] &
MAX77843_MUIC_STATUS1_ADC1K_MASK);

View File

@ -62,7 +62,7 @@ static irqreturn_t palmas_vbus_irq_handler(int irq, void *_palmas_usb)
if (palmas_usb->linkstat != PALMAS_USB_STATE_VBUS) {
palmas_usb->linkstat = PALMAS_USB_STATE_VBUS;
extcon_set_state_sync(edev, EXTCON_USB, true);
dev_info(palmas_usb->dev, "USB cable is attached\n");
dev_dbg(palmas_usb->dev, "USB cable is attached\n");
} else {
dev_dbg(palmas_usb->dev,
"Spurious connect event detected\n");
@ -71,7 +71,7 @@ static irqreturn_t palmas_vbus_irq_handler(int irq, void *_palmas_usb)
if (palmas_usb->linkstat == PALMAS_USB_STATE_VBUS) {
palmas_usb->linkstat = PALMAS_USB_STATE_DISCONNECT;
extcon_set_state_sync(edev, EXTCON_USB, false);
dev_info(palmas_usb->dev, "USB cable is detached\n");
dev_dbg(palmas_usb->dev, "USB cable is detached\n");
} else {
dev_dbg(palmas_usb->dev,
"Spurious disconnect event detected\n");
@ -99,7 +99,7 @@ static irqreturn_t palmas_id_irq_handler(int irq, void *_palmas_usb)
PALMAS_USB_ID_INT_EN_HI_CLR_ID_GND);
palmas_usb->linkstat = PALMAS_USB_STATE_ID;
extcon_set_state_sync(edev, EXTCON_USB_HOST, true);
dev_info(palmas_usb->dev, "USB-HOST cable is attached\n");
dev_dbg(palmas_usb->dev, "USB-HOST cable is attached\n");
} else if ((set & PALMAS_USB_ID_INT_SRC_ID_FLOAT) &&
(id_src & PALMAS_USB_ID_INT_SRC_ID_FLOAT)) {
palmas_write(palmas_usb->palmas, PALMAS_USB_OTG_BASE,
@ -107,17 +107,17 @@ static irqreturn_t palmas_id_irq_handler(int irq, void *_palmas_usb)
PALMAS_USB_ID_INT_EN_HI_CLR_ID_FLOAT);
palmas_usb->linkstat = PALMAS_USB_STATE_DISCONNECT;
extcon_set_state_sync(edev, EXTCON_USB_HOST, false);
dev_info(palmas_usb->dev, "USB-HOST cable is detached\n");
dev_dbg(palmas_usb->dev, "USB-HOST cable is detached\n");
} else if ((palmas_usb->linkstat == PALMAS_USB_STATE_ID) &&
(!(set & PALMAS_USB_ID_INT_SRC_ID_GND))) {
palmas_usb->linkstat = PALMAS_USB_STATE_DISCONNECT;
extcon_set_state_sync(edev, EXTCON_USB_HOST, false);
dev_info(palmas_usb->dev, "USB-HOST cable is detached\n");
dev_dbg(palmas_usb->dev, "USB-HOST cable is detached\n");
} else if ((palmas_usb->linkstat == PALMAS_USB_STATE_DISCONNECT) &&
(id_src & PALMAS_USB_ID_INT_SRC_ID_GND)) {
palmas_usb->linkstat = PALMAS_USB_STATE_ID;
extcon_set_state_sync(edev, EXTCON_USB_HOST, true);
dev_info(palmas_usb->dev, " USB-HOST cable is attached\n");
dev_dbg(palmas_usb->dev, " USB-HOST cable is attached\n");
}
return IRQ_HANDLED;
@ -138,10 +138,10 @@ static void palmas_gpio_id_detect(struct work_struct *work)
if (id) {
extcon_set_state_sync(edev, EXTCON_USB_HOST, false);
dev_info(palmas_usb->dev, "USB-HOST cable is detached\n");
dev_dbg(palmas_usb->dev, "USB-HOST cable is detached\n");
} else {
extcon_set_state_sync(edev, EXTCON_USB_HOST, true);
dev_info(palmas_usb->dev, "USB-HOST cable is attached\n");
dev_dbg(palmas_usb->dev, "USB-HOST cable is attached\n");
}
}
@ -190,6 +190,11 @@ static int palmas_usb_probe(struct platform_device *pdev)
struct palmas_usb *palmas_usb;
int status;
if (!palmas) {
dev_err(&pdev->dev, "failed to get valid parent\n");
return -EINVAL;
}
palmas_usb = devm_kzalloc(&pdev->dev, sizeof(*palmas_usb), GFP_KERNEL);
if (!palmas_usb)
return -ENOMEM;

View File

@ -142,8 +142,10 @@ enum rt8973a_muic_acc_type {
RT8973A_MUIC_ADC_UNKNOWN_ACC_5,
RT8973A_MUIC_ADC_OPEN = 0x1f,
/* The below accessories has same ADC value (0x1f).
So, Device type1 is used to separate specific accessory. */
/*
* The below accessories has same ADC value (0x1f).
* So, Device type1 is used to separate specific accessory.
*/
/* |---------|--ADC| */
/* | [7:5]|[4:0]| */
RT8973A_MUIC_ADC_USB = 0x3f, /* | 001|11111| */

View File

@ -135,8 +135,10 @@ enum sm5502_muic_acc_type {
SM5502_MUIC_ADC_AUDIO_TYPE1,
SM5502_MUIC_ADC_OPEN = 0x1f,
/* The below accessories have same ADC value (0x1f or 0x1e).
So, Device type1 is used to separate specific accessory. */
/*
* The below accessories have same ADC value (0x1f or 0x1e).
* So, Device type1 is used to separate specific accessory.
*/
/* |---------|--ADC| */
/* | [7:5]|[4:0]| */
SM5502_MUIC_ADC_AUDIO_TYPE1_FULL_REMOTE = 0x3e, /* | 001|11110| */

View File

@ -27,6 +27,7 @@
#include <linux/slab.h>
#include <linux/workqueue.h>
#include <linux/acpi.h>
#include <linux/pinctrl/consumer.h>
#define USB_GPIO_DEBOUNCE_MS 20 /* ms */
@ -245,6 +246,9 @@ static int usb_extcon_suspend(struct device *dev)
if (info->vbus_gpiod)
disable_irq(info->vbus_irq);
if (!device_may_wakeup(dev))
pinctrl_pm_select_sleep_state(dev);
return ret;
}
@ -253,6 +257,9 @@ static int usb_extcon_resume(struct device *dev)
struct usb_extcon_info *info = dev_get_drvdata(dev);
int ret = 0;
if (!device_may_wakeup(dev))
pinctrl_pm_select_default_state(dev);
if (device_may_wakeup(dev)) {
if (info->id_gpiod) {
ret = disable_irq_wake(info->id_irq);

View File

@ -30,11 +30,12 @@
#include <linux/device.h>
#include <linux/fs.h>
#include <linux/err.h>
#include <linux/extcon.h>
#include <linux/of.h>
#include <linux/slab.h>
#include <linux/sysfs.h>
#include "extcon.h"
#define SUPPORTED_CABLE_MAX 32
#define CABLE_NAME_MAX 30
@ -59,7 +60,7 @@ struct __extcon_info {
[EXTCON_USB_HOST] = {
.type = EXTCON_TYPE_USB,
.id = EXTCON_USB_HOST,
.name = "USB_HOST",
.name = "USB-HOST",
},
/* Charging external connector */
@ -98,6 +99,11 @@ struct __extcon_info {
.id = EXTCON_CHG_WPT,
.name = "WPT",
},
[EXTCON_CHG_USB_PD] = {
.type = EXTCON_TYPE_CHG | EXTCON_TYPE_USB,
.id = EXTCON_CHG_USB_PD,
.name = "PD",
},
/* Jack external connector */
[EXTCON_JACK_MICROPHONE] = {
@ -906,35 +912,16 @@ int extcon_register_notifier(struct extcon_dev *edev, unsigned int id,
unsigned long flags;
int ret, idx = -EINVAL;
if (!nb)
if (!edev || !nb)
return -EINVAL;
if (edev) {
idx = find_cable_index_by_id(edev, id);
if (idx < 0)
return idx;
idx = find_cable_index_by_id(edev, id);
if (idx < 0)
return idx;
spin_lock_irqsave(&edev->lock, flags);
ret = raw_notifier_chain_register(&edev->nh[idx], nb);
spin_unlock_irqrestore(&edev->lock, flags);
} else {
struct extcon_dev *extd;
mutex_lock(&extcon_dev_list_lock);
list_for_each_entry(extd, &extcon_dev_list, entry) {
idx = find_cable_index_by_id(extd, id);
if (idx >= 0)
break;
}
mutex_unlock(&extcon_dev_list_lock);
if (idx >= 0) {
edev = extd;
return extcon_register_notifier(extd, id, nb);
} else {
ret = -ENODEV;
}
}
spin_lock_irqsave(&edev->lock, flags);
ret = raw_notifier_chain_register(&edev->nh[idx], nb);
spin_unlock_irqrestore(&edev->lock, flags);
return ret;
}

View File

@ -0,0 +1,62 @@
#ifndef __LINUX_EXTCON_INTERNAL_H__
#define __LINUX_EXTCON_INTERNAL_H__
#include <linux/extcon.h>
/**
* struct extcon_dev - An extcon device represents one external connector.
* @name: The name of this extcon device. Parent device name is
* used if NULL.
* @supported_cable: Array of supported cable names ending with EXTCON_NONE.
* If supported_cable is NULL, cable name related APIs
* are disabled.
* @mutually_exclusive: Array of mutually exclusive set of cables that cannot
* be attached simultaneously. The array should be
* ending with NULL or be NULL (no mutually exclusive
* cables). For example, if it is { 0x7, 0x30, 0}, then,
* {0, 1}, {0, 1, 2}, {0, 2}, {1, 2}, or {4, 5} cannot
* be attached simulataneously. {0x7, 0} is equivalent to
* {0x3, 0x6, 0x5, 0}. If it is {0xFFFFFFFF, 0}, there
* can be no simultaneous connections.
* @dev: Device of this extcon.
* @state: Attach/detach state of this extcon. Do not provide at
* register-time.
* @nh: Notifier for the state change events from this extcon
* @entry: To support list of extcon devices so that users can
* search for extcon devices based on the extcon name.
* @lock:
* @max_supported: Internal value to store the number of cables.
* @extcon_dev_type: Device_type struct to provide attribute_groups
* customized for each extcon device.
* @cables: Sysfs subdirectories. Each represents one cable.
*
* In most cases, users only need to provide "User initializing data" of
* this struct when registering an extcon. In some exceptional cases,
* optional callbacks may be needed. However, the values in "internal data"
* are overwritten by register function.
*/
struct extcon_dev {
/* Optional user initializing data */
const char *name;
const unsigned int *supported_cable;
const u32 *mutually_exclusive;
/* Internal data. Please do not set. */
struct device dev;
struct raw_notifier_head *nh;
struct list_head entry;
int max_supported;
spinlock_t lock; /* could be called by irq handler */
u32 state;
/* /sys/class/extcon/.../cable.n/... */
struct device_type extcon_dev_type;
struct extcon_cable *cables;
/* /sys/class/extcon/.../mutually_exclusive/... */
struct attribute_group attr_g_muex;
struct attribute **attrs_muex;
struct device_attribute *d_attrs_muex;
};
#endif /* __LINUX_EXTCON_INTERNAL_H__ */

View File

@ -46,7 +46,18 @@
#define EXTCON_USB 1
#define EXTCON_USB_HOST 2
/* Charging external connector */
/*
* Charging external connector
*
* When one SDP charger connector was reported, we should also report
* the USB connector, which means EXTCON_CHG_USB_SDP should always
* appear together with EXTCON_USB. The same as ACA charger connector,
* EXTCON_CHG_USB_ACA would normally appear with EXTCON_USB_HOST.
*
* The EXTCON_CHG_USB_SLOW connector can provide at least 500mA of
* current at 5V. The EXTCON_CHG_USB_FAST connector can provide at
* least 1A of current at 5V.
*/
#define EXTCON_CHG_USB_SDP 5 /* Standard Downstream Port */
#define EXTCON_CHG_USB_DCP 6 /* Dedicated Charging Port */
#define EXTCON_CHG_USB_CDP 7 /* Charging Downstream Port */
@ -54,6 +65,7 @@
#define EXTCON_CHG_USB_FAST 9
#define EXTCON_CHG_USB_SLOW 10
#define EXTCON_CHG_WPT 11 /* Wireless Power Transfer */
#define EXTCON_CHG_USB_PD 12 /* USB Power Delivery */
/* Jack external connector */
#define EXTCON_JACK_MICROPHONE 20
@ -160,62 +172,7 @@ union extcon_property_value {
};
struct extcon_cable;
/**
* struct extcon_dev - An extcon device represents one external connector.
* @name: The name of this extcon device. Parent device name is
* used if NULL.
* @supported_cable: Array of supported cable names ending with EXTCON_NONE.
* If supported_cable is NULL, cable name related APIs
* are disabled.
* @mutually_exclusive: Array of mutually exclusive set of cables that cannot
* be attached simultaneously. The array should be
* ending with NULL or be NULL (no mutually exclusive
* cables). For example, if it is { 0x7, 0x30, 0}, then,
* {0, 1}, {0, 1, 2}, {0, 2}, {1, 2}, or {4, 5} cannot
* be attached simulataneously. {0x7, 0} is equivalent to
* {0x3, 0x6, 0x5, 0}. If it is {0xFFFFFFFF, 0}, there
* can be no simultaneous connections.
* @dev: Device of this extcon.
* @state: Attach/detach state of this extcon. Do not provide at
* register-time.
* @nh: Notifier for the state change events from this extcon
* @entry: To support list of extcon devices so that users can
* search for extcon devices based on the extcon name.
* @lock:
* @max_supported: Internal value to store the number of cables.
* @extcon_dev_type: Device_type struct to provide attribute_groups
* customized for each extcon device.
* @cables: Sysfs subdirectories. Each represents one cable.
*
* In most cases, users only need to provide "User initializing data" of
* this struct when registering an extcon. In some exceptional cases,
* optional callbacks may be needed. However, the values in "internal data"
* are overwritten by register function.
*/
struct extcon_dev {
/* Optional user initializing data */
const char *name;
const unsigned int *supported_cable;
const u32 *mutually_exclusive;
/* Internal data. Please do not set. */
struct device dev;
struct raw_notifier_head *nh;
struct list_head entry;
int max_supported;
spinlock_t lock; /* could be called by irq handler */
u32 state;
/* /sys/class/extcon/.../cable.n/... */
struct device_type extcon_dev_type;
struct extcon_cable *cables;
/* /sys/class/extcon/.../mutually_exclusive/... */
struct attribute_group attr_g_muex;
struct attribute **attrs_muex;
struct device_attribute *d_attrs_muex;
};
struct extcon_dev;
#if IS_ENABLED(CONFIG_EXTCON)

View File

@ -59,7 +59,7 @@ struct adc_jack_pdata {
const char *name;
const char *consumer_channel;
const enum extcon *cable_names;
const unsigned int *cable_names;
/* The last entry's state should be 0 */
struct adc_jack_cond *adc_conditions;