sensors: add the sensors class support

Add a new sensors sysfs class and put all the sensors
device driver information in sensor class folder.

Change-Id: I141e79aee337d8a63998b5b5a4890b6eb6d1c4e4
Signed-off-by: Ananda Kishore <kananda@codeaurora.org>
diff --git a/drivers/Kconfig b/drivers/Kconfig
index a73d713..ed07f20 100644
--- a/drivers/Kconfig
+++ b/drivers/Kconfig
@@ -150,4 +150,6 @@
 
 source "drivers/coresight/Kconfig"
 
+source "drivers/sensors/Kconfig"
+
 endmenu
diff --git a/drivers/Makefile b/drivers/Makefile
index f461e83..debe9d7 100644
--- a/drivers/Makefile
+++ b/drivers/Makefile
@@ -142,3 +142,7 @@
 obj-$(CONFIG_MOBICORE_SUPPORT)  += gud/
 
 obj-$(CONFIG_CORESIGHT)		+= coresight/
+
+#sensor_class
+obj-$(CONFIG_SENSORS)		+= sensors/
+
diff --git a/drivers/sensors/Kconfig b/drivers/sensors/Kconfig
new file mode 100644
index 0000000..dad00f3
--- /dev/null
+++ b/drivers/sensors/Kconfig
@@ -0,0 +1,12 @@
+config SENSORS
+	bool "Sensors Class Support"
+	help
+	  This option enables the sensor sysfs class in /sys/class/sensors.
+	  You'll need this to do anything useful with sensorss. If unsure, say N.
+
+config SENSORS_SSC
+	bool "Enable Sensors Driver Support for SSC"
+	help
+	  Add support for sensors SSC driver.
+	  This driver is used for exercising sensors use case,
+	  time syncing with ADSP clock.
diff --git a/drivers/sensors/Makefile b/drivers/sensors/Makefile
new file mode 100644
index 0000000..658363b
--- /dev/null
+++ b/drivers/sensors/Makefile
@@ -0,0 +1,2 @@
+obj-$(CONFIG_SENSORS)		+= sensors_class.o
+obj-$(CONFIG_SENSORS_SSC)	+= sensors_ssc.o
diff --git a/drivers/sensors/sensors_class.c b/drivers/sensors/sensors_class.c
new file mode 100644
index 0000000..8cf38fe
--- /dev/null
+++ b/drivers/sensors/sensors_class.c
@@ -0,0 +1,532 @@
+/* Copyright (c) 2013-2015, The Linux Foundation. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 and
+ * only 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/module.h>
+#include <linux/kernel.h>
+#include <linux/init.h>
+#include <linux/list.h>
+#include <linux/spinlock.h>
+#include <linux/device.h>
+#include <linux/err.h>
+#include <linux/ctype.h>
+#include <linux/rwsem.h>
+#include <linux/sensors.h>
+#include <linux/string.h>
+
+#define APPLY_MASK	0x00000001
+#define CMD_W_L_MASK 0x00
+#define CMD_W_H_MASK 0x10
+#define CMD_W_H_L	0x10
+#define CMD_MASK	0xF
+#define DATA_MASK	0xFFFF0000
+#define DATA_AXIS_SHIFT	17
+#define DATA_APPLY_SHIFT	16
+/*
+ * CMD_GET_PARAMS(BIT, PARA, DATA) combine high 16 bit and low 16 bit
+ * as one params
+ */
+
+#define CMD_GET_PARAMS(BIT, PARA, DATA)	\
+	((BIT) ?	\
+		((DATA) & DATA_MASK)	\
+		: ((PARA) \
+		| (((DATA) & DATA_MASK) >> 16)))
+
+
+/*
+ * CMD_DO_CAL sensor do calibrate command, when do sensor calibrate must use
+ * this.
+ * AXIS_X,AXIS_Y,AXIS_Z write axis params to driver like accelerometer
+ * magnetometer,gyroscope etc.
+ * CMD_W_THRESHOLD_H,CMD_W_THRESHOLD_L,CMD_W_BIAS write theshold and bias
+ * params to proximity driver.
+ * CMD_W_FACTOR,CMD_W_OFFSET write factor and offset params to light
+ * sensor driver.
+ * CMD_COMPLETE when one sensor receive calibrate parameters complete, it
+ * must use this command to end receive the parameters and send the
+ * parameters to sensor.
+ */
+
+enum {
+	CMD_DO_CAL = 0x0,
+	CMD_W_OFFSET_X,
+	CMD_W_OFFSET_Y,
+	CMD_W_OFFSET_Z,
+	CMD_W_THRESHOLD_H,
+	CMD_W_THRESHOLD_L,
+	CMD_W_BIAS,
+	CMD_W_OFFSET,
+	CMD_W_FACTOR,
+	CMD_W_RANGE,
+	CMD_COMPLETE,
+	CMD_COUNT
+};
+
+int cal_map[] = {
+	0,
+	offsetof(struct cal_result_t, offset_x),
+	offsetof(struct cal_result_t, offset_y),
+	offsetof(struct cal_result_t, offset_z),
+	offsetof(struct cal_result_t, threshold_h),
+	offsetof(struct cal_result_t, threshold_l),
+	offsetof(struct cal_result_t, bias),
+	offsetof(struct cal_result_t, offset[0]),
+	offsetof(struct cal_result_t, offset[1]),
+	offsetof(struct cal_result_t, offset[2]),
+	offsetof(struct cal_result_t, factor),
+	offsetof(struct cal_result_t, range),
+};
+
+static struct class *sensors_class;
+
+DECLARE_RWSEM(sensors_list_lock);
+LIST_HEAD(sensors_list);
+
+static ssize_t sensors_name_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE, "%s\n", sensors_cdev->name);
+}
+
+static ssize_t sensors_vendor_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE, "%s\n", sensors_cdev->vendor);
+}
+
+static ssize_t sensors_version_show(struct device *dev,
+	struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE, "%d\n", sensors_cdev->version);
+}
+
+static ssize_t sensors_handle_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE, "%d\n", sensors_cdev->handle);
+}
+
+static ssize_t sensors_type_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE, "%d\n", sensors_cdev->type);
+}
+
+static ssize_t sensors_max_delay_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE, "%d\n", sensors_cdev->max_delay);
+}
+
+static ssize_t sensors_flags_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE, "%d\n", sensors_cdev->flags);
+}
+
+static ssize_t sensors_max_range_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE, "%s\n", sensors_cdev->max_range);
+}
+
+static ssize_t sensors_resolution_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE, "%s\n", sensors_cdev->resolution);
+}
+
+static ssize_t sensors_power_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE, "%s\n", sensors_cdev->sensor_power);
+}
+
+static ssize_t sensors_min_delay_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE, "%d\n", sensors_cdev->min_delay);
+}
+
+static ssize_t sensors_fifo_event_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE, "%d\n",
+			sensors_cdev->fifo_reserved_event_count);
+}
+
+static ssize_t sensors_fifo_max_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE, "%d\n",
+			sensors_cdev->fifo_max_event_count);
+}
+
+static ssize_t sensors_enable_store(struct device *dev,
+		struct device_attribute *attr, const char *buf, size_t size)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	ssize_t ret = -EINVAL;
+	unsigned long data = 0;
+
+	ret = kstrtoul(buf, 10, &data);
+	if (ret)
+		return ret;
+	if (data > 1) {
+		dev_err(dev, "Invalid value of input, input=%ld\n", data);
+		return -EINVAL;
+	}
+
+	if (sensors_cdev->sensors_enable == NULL) {
+		dev_err(dev, "Invalid sensor class enable handle\n");
+		return -EINVAL;
+	}
+	ret = sensors_cdev->sensors_enable(sensors_cdev, data);
+	if (ret)
+		return ret;
+
+	sensors_cdev->enabled = data;
+	return size;
+}
+
+
+static ssize_t sensors_enable_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE, "%u\n",
+			sensors_cdev->enabled);
+}
+
+static ssize_t sensors_delay_store(struct device *dev,
+		struct device_attribute *attr, const char *buf, size_t size)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	ssize_t ret = -EINVAL;
+	unsigned long data = 0;
+
+	ret = kstrtoul(buf, 10, &data);
+	if (ret)
+		return ret;
+	/* The data unit is millisecond, the min_delay unit is microseconds. */
+	if ((data * 1000) < sensors_cdev->min_delay) {
+		dev_err(dev, "Invalid value of delay, delay=%ld\n", data);
+		return -EINVAL;
+	}
+	if (sensors_cdev->sensors_poll_delay == NULL) {
+		dev_err(dev, "Invalid sensor class delay handle\n");
+		return -EINVAL;
+	}
+	ret = sensors_cdev->sensors_poll_delay(sensors_cdev, data);
+	if (ret)
+		return ret;
+
+	sensors_cdev->delay_msec = data;
+	return size;
+}
+
+static ssize_t sensors_delay_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE, "%u\n",
+			sensors_cdev->delay_msec);
+}
+
+static ssize_t sensors_test_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	int ret;
+
+	if (sensors_cdev->sensors_self_test == NULL) {
+		dev_err(dev, "Invalid sensor class self test handle\n");
+		return -EINVAL;
+	}
+
+	ret = sensors_cdev->sensors_self_test(sensors_cdev);
+	if (ret)
+		dev_warn(dev, "self test failed.(%d)\n", ret);
+
+	return snprintf(buf, PAGE_SIZE, "%s\n",
+			ret ? "fail" : "pass");
+}
+
+static ssize_t sensors_max_latency_store(struct device *dev,
+		struct device_attribute *attr, const char *buf, size_t size)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	unsigned long latency;
+	int ret = -EINVAL;
+
+	ret = kstrtoul(buf, 10, &latency);
+	if (ret)
+		return ret;
+
+	if (latency > sensors_cdev->max_delay) {
+		dev_err(dev, "max_latency(%lu) is greater than max_delay(%u)\n",
+				latency, sensors_cdev->max_delay);
+		return -EINVAL;
+	}
+
+	if (sensors_cdev->sensors_set_latency == NULL) {
+		dev_err(dev, "Invalid sensor calss set latency handle\n");
+		return -EINVAL;
+	}
+
+	/* Disable batching for this sensor */
+	if (latency < sensors_cdev->delay_msec) {
+		dev_err(dev, "max_latency is less than delay_msec\n");
+		return -EINVAL;
+	}
+
+	ret = sensors_cdev->sensors_set_latency(sensors_cdev, latency);
+	if (ret)
+		return ret;
+
+	sensors_cdev->max_latency = latency;
+
+	return size;
+}
+
+static ssize_t sensors_max_latency_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE,
+		"%u\n", sensors_cdev->max_latency);
+}
+
+static ssize_t sensors_flush_store(struct device *dev,
+		struct device_attribute *attr, const char *buf, size_t size)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	ssize_t ret = -EINVAL;
+	unsigned long data = 0;
+
+	ret = kstrtoul(buf, 10, &data);
+	if (ret)
+		return ret;
+	if (data != 1) {
+		dev_err(dev, "Flush: Invalid value of input, input=%ld\n",
+				data);
+		return -EINVAL;
+	}
+
+	if (sensors_cdev->sensors_flush == NULL) {
+		dev_err(dev, "Invalid sensor class flush handle\n");
+		return -EINVAL;
+	}
+	ret = sensors_cdev->sensors_flush(sensors_cdev);
+	if (ret)
+		return ret;
+
+	return size;
+}
+
+static ssize_t sensors_flush_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE,
+		"Flush handler %s\n",
+			(sensors_cdev->sensors_flush == NULL)
+				? "not exist" : "exist");
+}
+
+static ssize_t sensors_enable_wakeup_store(struct device *dev,
+		struct device_attribute *attr, const char *buf, size_t size)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	ssize_t ret;
+	unsigned long enable;
+
+	if (sensors_cdev->sensors_enable_wakeup == NULL) {
+		dev_err(dev, "Invalid sensor class enable_wakeup handle\n");
+		return -EINVAL;
+	}
+
+	ret = kstrtoul(buf, 10, &enable);
+	if (ret)
+		return ret;
+
+	enable = enable ? 1 : 0;
+	ret = sensors_cdev->sensors_enable_wakeup(sensors_cdev, enable);
+	if (ret)
+		return ret;
+
+	sensors_cdev->wakeup = enable;
+
+	return size;
+}
+
+static ssize_t sensors_enable_wakeup_show(struct device *dev,
+		struct device_attribute *attr, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	return snprintf(buf, PAGE_SIZE, "%d\n", sensors_cdev->wakeup);
+}
+
+
+static ssize_t sensors_calibrate_show(struct device *dev,
+		struct device_attribute *atte, char *buf)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	if (sensors_cdev->params == NULL) {
+		dev_err(dev, "Invalid sensor params\n");
+		return -EINVAL;
+	}
+	return snprintf(buf, PAGE_SIZE, "%s\n", sensors_cdev->params);
+}
+
+static ssize_t sensors_calibrate_store(struct device *dev,
+		struct device_attribute *attr, const char *buf, size_t size)
+{
+	struct sensors_classdev *sensors_cdev = dev_get_drvdata(dev);
+	ssize_t ret = -EINVAL;
+	long data;
+	int axis, apply_now;
+	int cmd, bit_h;
+
+	ret = kstrtol(buf, 0, &data);
+	if (ret)
+		return ret;
+	dev_dbg(dev, "data = %lx\n", data);
+	cmd = data & CMD_MASK;
+	if (cmd == CMD_DO_CAL) {
+		if (sensors_cdev->sensors_calibrate == NULL) {
+			dev_err(dev, "Invalid calibrate handle\n");
+			return -EINVAL;
+		}
+		/* parse the data to get the axis and apply_now value*/
+		apply_now = (int)(data >> DATA_APPLY_SHIFT) & APPLY_MASK;
+		axis = (int)data >> DATA_AXIS_SHIFT;
+		dev_dbg(dev, "apply_now = %d, axis = %d\n", apply_now, axis);
+		ret = sensors_cdev->sensors_calibrate(sensors_cdev,
+				axis, apply_now);
+		if (ret)
+			return ret;
+	} else {
+		if (sensors_cdev->sensors_write_cal_params == NULL) {
+			dev_err(dev,
+					"Invalid write_cal_params handle\n");
+			return -EINVAL;
+		}
+		bit_h = (data & CMD_W_H_L) >> 4;
+		if (cmd > CMD_DO_CAL && cmd < CMD_COMPLETE) {
+			char *p = (char *)(&sensors_cdev->cal_result)
+					+ cal_map[cmd];
+			*(int *)p = CMD_GET_PARAMS(bit_h, *(int *)p, data);
+		} else if (cmd == CMD_COMPLETE) {
+			ret = sensors_cdev->sensors_write_cal_params
+				(sensors_cdev, &sensors_cdev->cal_result);
+		} else {
+			dev_err(dev, "Invalid command\n");
+			return -EINVAL;
+		}
+	}
+	return size;
+}
+
+static struct device_attribute sensors_class_attrs[] = {
+	__ATTR(name, 0444, sensors_name_show, NULL),
+	__ATTR(vendor, 0444, sensors_vendor_show, NULL),
+	__ATTR(version, 0444, sensors_version_show, NULL),
+	__ATTR(handle, 0444, sensors_handle_show, NULL),
+	__ATTR(type, 0444, sensors_type_show, NULL),
+	__ATTR(max_range, 0444, sensors_max_range_show, NULL),
+	__ATTR(resolution, 0444, sensors_resolution_show, NULL),
+	__ATTR(sensor_power, 0444, sensors_power_show, NULL),
+	__ATTR(min_delay, 0444, sensors_min_delay_show, NULL),
+	__ATTR(fifo_reserved_event_count, 0444, sensors_fifo_event_show, NULL),
+	__ATTR(fifo_max_event_count, 0444, sensors_fifo_max_show, NULL),
+	__ATTR(max_delay, 0444, sensors_max_delay_show, NULL),
+	__ATTR(flags, 0444, sensors_flags_show, NULL),
+	__ATTR(enable, 0664, sensors_enable_show, sensors_enable_store),
+	__ATTR(enable_wakeup, 0664, sensors_enable_wakeup_show,
+			sensors_enable_wakeup_store),
+	__ATTR(poll_delay, 0664, sensors_delay_show, sensors_delay_store),
+	__ATTR(self_test, 0440, sensors_test_show, NULL),
+	__ATTR(max_latency, 0660, sensors_max_latency_show,
+			sensors_max_latency_store),
+	__ATTR(flush, 0660, sensors_flush_show, sensors_flush_store),
+	__ATTR(calibrate, 0664, sensors_calibrate_show,
+			sensors_calibrate_store),
+	__ATTR_NULL,
+};
+
+/**
+ * sensors_classdev_register - register a new object of sensors_classdev class.
+ * @parent: The device to register.
+ * @sensors_cdev: the sensors_classdev structure for this device.
+*/
+int sensors_classdev_register(struct device *parent,
+				struct sensors_classdev *sensors_cdev)
+{
+	sensors_cdev->dev = device_create(sensors_class, parent, 0,
+				      sensors_cdev, "%s", sensors_cdev->name);
+	if (IS_ERR(sensors_cdev->dev))
+		return PTR_ERR(sensors_cdev->dev);
+
+	down_write(&sensors_list_lock);
+	list_add_tail(&sensors_cdev->node, &sensors_list);
+	up_write(&sensors_list_lock);
+
+	pr_debug("Registered sensors device: %s\n",
+			sensors_cdev->name);
+	return 0;
+}
+EXPORT_SYMBOL(sensors_classdev_register);
+
+/**
+ * sensors_classdev_unregister - unregister a object of sensors class.
+ * @sensors_cdev: the sensor device to unregister
+ * Unregister a previously registered via sensors_classdev_register object.
+*/
+void sensors_classdev_unregister(struct sensors_classdev *sensors_cdev)
+{
+	device_unregister(sensors_cdev->dev);
+	down_write(&sensors_list_lock);
+	list_del(&sensors_cdev->node);
+	up_write(&sensors_list_lock);
+}
+EXPORT_SYMBOL(sensors_classdev_unregister);
+
+static int __init sensors_init(void)
+{
+	sensors_class = class_create(THIS_MODULE, "sensors");
+	if (IS_ERR(sensors_class))
+		return PTR_ERR(sensors_class);
+	sensors_class->dev_attrs = sensors_class_attrs;
+	return 0;
+}
+
+static void __exit sensors_exit(void)
+{
+	class_destroy(sensors_class);
+}
+
+subsys_initcall(sensors_init);
+module_exit(sensors_exit);
diff --git a/drivers/sensors/sensors_ssc.c b/drivers/sensors/sensors_ssc.c
new file mode 100644
index 0000000..0a221a3
--- /dev/null
+++ b/drivers/sensors/sensors_ssc.c
@@ -0,0 +1,208 @@
+/* Copyright (c) 2012-2015, The Linux Foundation. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 and
+ * only 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/types.h>
+#include <linux/msm_dsps.h>
+#include <linux/module.h>
+#include <linux/init.h>
+#include <linux/slab.h>
+#include <linux/platform_device.h>
+#include <linux/cdev.h>
+#include <linux/fs.h>
+#include <linux/of_device.h>
+#include <asm/arch_timer.h>
+#include <linux/uaccess.h>
+
+#define CLASS_NAME	"ssc"
+#define DRV_NAME	"sensors"
+#define DRV_VERSION	"2.00"
+#ifdef CONFIG_COMPAT
+#define DSPS_IOCTL_READ_SLOW_TIMER32 _IOR(DSPS_IOCTL_MAGIC, 3, compat_uint_t)
+#endif
+
+struct sns_ssc_control_s {
+	struct class *dev_class;
+	dev_t dev_num;
+	struct device *dev;
+	struct cdev *cdev;
+};
+static struct sns_ssc_control_s sns_ctl;
+
+/*
+ * Read QTimer clock ticks and scale down to 32KHz clock as used
+ * in DSPS
+ */
+static u32 sns_read_qtimer(void)
+{
+	u64 val;
+	val = arch_counter_get_cntpct();
+	/*
+	 * To convert ticks from 19.2 Mhz clock to 32768 Hz clock:
+	 * x = (value * 32768) / 19200000
+	 * This is same as first left shift the value by 4 bits, i.e. mutiply
+	 * by 16, and then divide by 9375. The latter is preferable since
+	 * QTimer tick (value) is 56-bit, so (value * 32768) could overflow,
+	 * while (value * 16) will never do
+	 */
+	val <<= 4;
+	do_div(val, 9375);
+
+	return (u32)val;
+}
+
+static int sensors_ssc_open(struct inode *ip, struct file *fp)
+{
+	return 0;
+}
+
+static int sensors_ssc_release(struct inode *inode, struct file *file)
+{
+	return 0;
+}
+
+static long sensors_ssc_ioctl(struct file *file,
+			unsigned int cmd, unsigned long arg)
+{
+	int ret = 0;
+	u32 val = 0;
+
+	switch (cmd) {
+	case DSPS_IOCTL_READ_SLOW_TIMER:
+#ifdef CONFIG_COMPAT
+	case DSPS_IOCTL_READ_SLOW_TIMER32:
+#endif
+		val = sns_read_qtimer();
+		ret = put_user(val, (u32 __user *) arg);
+		break;
+
+	default:
+		ret = -EINVAL;
+		break;
+	}
+
+	return ret;
+}
+
+const struct file_operations sensors_ssc_fops = {
+	.owner = THIS_MODULE,
+	.open = sensors_ssc_open,
+	.release = sensors_ssc_release,
+#ifdef CONFIG_COMPAT
+	.compat_ioctl = sensors_ssc_ioctl,
+#endif
+	.unlocked_ioctl = sensors_ssc_ioctl
+};
+
+static int sensors_ssc_probe(struct platform_device *pdev)
+{
+	int ret = 0;
+
+	sns_ctl.dev_class = class_create(THIS_MODULE, CLASS_NAME);
+	if (sns_ctl.dev_class == NULL) {
+		pr_err("%s: class_create fail.\n", __func__);
+		goto res_err;
+	}
+
+	ret = alloc_chrdev_region(&sns_ctl.dev_num, 0, 1, DRV_NAME);
+	if (ret) {
+		pr_err("%s: alloc_chrdev_region fail.\n", __func__);
+		goto alloc_chrdev_region_err;
+	}
+
+	sns_ctl.dev = device_create(sns_ctl.dev_class, NULL,
+				     sns_ctl.dev_num,
+				     &sns_ctl, DRV_NAME);
+	if (IS_ERR(sns_ctl.dev)) {
+		pr_err("%s: device_create fail.\n", __func__);
+		goto device_create_err;
+	}
+
+	sns_ctl.cdev = cdev_alloc();
+	if (sns_ctl.cdev == NULL) {
+		pr_err("%s: cdev_alloc fail.\n", __func__);
+		goto cdev_alloc_err;
+	}
+	cdev_init(sns_ctl.cdev, &sensors_ssc_fops);
+	sns_ctl.cdev->owner = THIS_MODULE;
+
+	ret = cdev_add(sns_ctl.cdev, sns_ctl.dev_num, 1);
+	if (ret) {
+		pr_err("%s: cdev_add fail.\n", __func__);
+		goto cdev_add_err;
+	}
+
+	return 0;
+
+cdev_add_err:
+	kfree(sns_ctl.cdev);
+cdev_alloc_err:
+	device_destroy(sns_ctl.dev_class, sns_ctl.dev_num);
+device_create_err:
+	unregister_chrdev_region(sns_ctl.dev_num, 1);
+alloc_chrdev_region_err:
+	class_destroy(sns_ctl.dev_class);
+res_err:
+	return -ENODEV;
+}
+
+static int sensors_ssc_remove(struct platform_device *pdev)
+{
+	cdev_del(sns_ctl.cdev);
+	kfree(sns_ctl.cdev);
+	sns_ctl.cdev = NULL;
+	device_destroy(sns_ctl.dev_class, sns_ctl.dev_num);
+	unregister_chrdev_region(sns_ctl.dev_num, 1);
+	class_destroy(sns_ctl.dev_class);
+
+	return 0;
+}
+
+static const struct of_device_id msm_ssc_sensors_dt_match[] = {
+	{.compatible = "qcom,msm-ssc-sensors"},
+	{},
+};
+MODULE_DEVICE_TABLE(of, msm_ssc_sensors_dt_match);
+
+static struct platform_driver sensors_ssc_driver = {
+	.driver = {
+		.name = "sensors-ssc",
+		.owner = THIS_MODULE,
+		.of_match_table = msm_ssc_sensors_dt_match,
+	},
+	.probe = sensors_ssc_probe,
+	.remove = sensors_ssc_remove,
+};
+
+static int __init sensors_ssc_init(void)
+{
+	int rc;
+
+	pr_debug("%s driver version %s.\n", DRV_NAME, DRV_VERSION);
+	rc = platform_driver_register(&sensors_ssc_driver);
+	if (rc) {
+		pr_err("%s: Failed to register sensors ssc driver\n",
+			__func__);
+		return rc;
+	}
+
+	return 0;
+}
+
+static void __exit sensors_ssc_exit(void)
+{
+	platform_driver_unregister(&sensors_ssc_driver);
+}
+
+module_init(sensors_ssc_init);
+module_exit(sensors_ssc_exit);
+MODULE_LICENSE("GPL v2");
+MODULE_DESCRIPTION("Sensors SSC driver");
diff --git a/include/linux/sensors.h b/include/linux/sensors.h
new file mode 100644
index 0000000..85dcbfc
--- /dev/null
+++ b/include/linux/sensors.h
@@ -0,0 +1,168 @@
+/* Copyright (c) 2013-2015, The Linux Foundation. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 and
+ * only 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.
+ */
+
+#ifndef __LINUX_SENSORS_H_INCLUDED
+#define __LINUX_SENSORS_H_INCLUDED
+
+#include <linux/list.h>
+#include <linux/spinlock.h>
+#include <linux/rwsem.h>
+
+#define SENSORS_ACCELERATION_HANDLE		0
+#define SENSORS_MAGNETIC_FIELD_HANDLE		1
+#define SENSORS_ORIENTATION_HANDLE		2
+#define SENSORS_LIGHT_HANDLE			3
+#define SENSORS_PROXIMITY_HANDLE		4
+#define SENSORS_GYROSCOPE_HANDLE		5
+#define SENSORS_PRESSURE_HANDLE			6
+
+#define SENSOR_TYPE_ACCELEROMETER		1
+#define SENSOR_TYPE_GEOMAGNETIC_FIELD		2
+#define SENSOR_TYPE_MAGNETIC_FIELD  SENSOR_TYPE_GEOMAGNETIC_FIELD
+#define SENSOR_TYPE_ORIENTATION			3
+#define SENSOR_TYPE_GYROSCOPE			4
+#define SENSOR_TYPE_LIGHT			5
+#define SENSOR_TYPE_PRESSURE			6
+#define SENSOR_TYPE_TEMPERATURE			7
+#define SENSOR_TYPE_PROXIMITY			8
+#define SENSOR_TYPE_GRAVITY			9
+#define SENSOR_TYPE_LINEAR_ACCELERATION		10
+#define SENSOR_TYPE_ROTATION_VECTOR		11
+#define SENSOR_TYPE_RELATIVE_HUMIDITY		12
+#define SENSOR_TYPE_AMBIENT_TEMPERATURE		13
+#define SENSOR_TYPE_MAGNETIC_FIELD_UNCALIBRATED	14
+#define SENSOR_TYPE_GAME_ROTATION_VECTOR	15
+#define SENSOR_TYPE_GYROSCOPE_UNCALIBRATED	16
+#define SENSOR_TYPE_SIGNIFICANT_MOTION		17
+#define SENSOR_TYPE_STEP_DETECTOR		18
+#define SENSOR_TYPE_STEP_COUNTER		19
+#define SENSOR_TYPE_GEOMAGNETIC_ROTATION_VECTOR	20
+
+enum LIS3DH_AXIS {
+	AXIS_X = 0,
+	AXIS_Y,
+	AXIS_Z,
+	AXIS_XYZ,
+};
+
+enum LIS3DH_THRES {
+	AXIS_THRESHOLD_H = 0,
+	AXIS_THRESHOLD_L,
+	AXIS_BIAS,
+};
+
+#define AXIS_FACTOR		0
+#define AXIS_OFFSET		1
+
+
+struct cal_result_t {
+	union {
+
+		struct {
+			int offset_x; /*axis offset of x axis*/
+			int offset_y; /*axis offset of x axis*/
+			int offset_z; /*axis offset of x axis*/
+		};
+		struct {
+			int threshold_h; /*proximity threshold_h*/
+			int threshold_l; /*proximity threshold_l*/
+			int bias; /*proximity measure data noise*/
+		};
+		int offset[3];
+	};
+	int factor; /*light sensor factor for real ligt strength*/
+	int range;
+	struct cal_result_t *node;
+};
+
+/**
+ * struct sensors_classdev - hold the sensor general parameters and APIs
+ * @dev:		The device to register.
+ * @node:		The list for the all the sensor drivers.
+ * @name:		Name of this sensor.
+ * @vendor:		The vendor of the hardware part.
+ * @handle:		The handle that identifies this sensors.
+ * @type:		The sensor type.
+ * @max_range:		The maximum range of this sensor's value in SI units.
+ * @resolution:		The smallest difference between two values reported by
+ *			this sensor.
+ * @sensor_power:	The rough estimate of this sensor's power consumption
+ *			in mA.
+ * @min_delay:		This value depends on the trigger mode:
+ *			continuous: minimum period allowed in microseconds
+ *			on-change : 0
+ *			one-shot :-1
+ *			special : 0, unless otherwise noted
+ * @fifo_reserved_event_count:	The number of events reserved for this sensor
+ *				in the batch mode FIFO.
+ * @fifo_max_event_count:	The maximum number of events of this sensor
+ *				that could be batched.
+ * @max_delay:		The slowest rate the sensor supports in millisecond.
+ * @flags:		Should be '1' if the sensor is a wake up sensor.
+ *			set it to '0' otherwise.
+ * @enabled:		Store the sensor driver enable status.
+ * @delay_msec:		Store the sensor driver delay value. The data unit is
+ *			millisecond.
+ * @wakeup:		Indicate if the wake up interrupt has been enabled.
+ * @max_latency:	Max report latency in millisecond
+ * @sensors_enable:	The handle for enable and disable sensor.
+ * @sensors_poll_delay:	The handle for set the sensor polling delay time.
+ * @sensors_set_latency:Set the max report latency of the sensor.
+ * @sensors_flush:	Flush sensor events in FIFO and report it to user space.
+ * @params		The sensor calibrate string format params up to userspace.
+ * @cal_result		The sensor calibrate parameters, cal_result is a struct for sensor.
+ */
+struct sensors_classdev {
+	struct device		*dev;
+	struct list_head	node;
+	const char		*name;
+	const char		*vendor;
+	int			version;
+	int			handle;
+	int			type;
+	const char		*max_range;
+	const char		*resolution;
+	const char		*sensor_power;
+	int			min_delay;
+	int			fifo_reserved_event_count;
+	int			fifo_max_event_count;
+	int32_t			max_delay;
+	uint32_t		flags;
+
+	unsigned int		enabled;
+	unsigned int		delay_msec;
+	unsigned int		wakeup;
+	unsigned int		max_latency;
+	char			*params;
+	struct cal_result_t	cal_result;
+	/* enable and disable the sensor handle*/
+	int	(*sensors_enable)(struct sensors_classdev *sensors_cdev,
+					unsigned int enabled);
+	int	(*sensors_poll_delay)(struct sensors_classdev *sensors_cdev,
+					unsigned int delay_msec);
+	int	(*sensors_self_test)(struct sensors_classdev *sensors_cdev);
+	int	(*sensors_set_latency)(struct sensors_classdev *sensor_cdev,
+					unsigned int max_latency);
+	int	(*sensors_enable_wakeup)(struct sensors_classdev *sensor_cdev,
+					unsigned int enable);
+	int	(*sensors_flush)(struct sensors_classdev *sensors_cdev);
+	int	(*sensors_calibrate)(struct sensors_classdev *sensor_cdev,
+					int axis, int apply_now);
+	int	(*sensors_write_cal_params)(struct sensors_classdev
+				*sensor_cdev, struct cal_result_t *cal_result);
+};
+
+extern int sensors_classdev_register(struct device *parent,
+				 struct sensors_classdev *sensors_cdev);
+extern void sensors_classdev_unregister(struct sensors_classdev *sensors_cdev);
+
+#endif		/* __LINUX_SENSORS_H_INCLUDED */