devicetree.vger.kernel.org archive mirror
 help / color / mirror / Atom feed
* [RFC PATCH 0/7] Add Linux Motion Control subsystem
@ 2025-02-27 16:28 David Jander
  2025-02-27 16:28 ` [RFC PATCH 1/7] drivers: Add motion control subsystem David Jander
                   ` (9 more replies)
  0 siblings, 10 replies; 59+ messages in thread
From: David Jander @ 2025-02-27 16:28 UTC (permalink / raw)
  To: linux-kernel
  Cc: linux-iio, Jonathan Corbet, Rob Herring, Krzysztof Kozlowski,
	Conor Dooley, devicetree, linux-doc, Nuno Sa, Jonathan Cameron,
	Oleksij Rempel, David Jander

Request for comments on: adding the Linux Motion Control subsystem to the
kernel.

The Linux Motion Control subsystem (LMC) is a new kernel subsystem and
associated device drivers for hardware devices that control mechanical
motion. Most often these are different types of motors, but can also be
linear actuators for example.

This subsystem defines a new UAPI for motion devices on the user-space
side, as well as common functionality for hardware device drivers on the
driver side.

The UAPI is based on a ioctl() interface on character devices representing
a specific hardware device. The hardware device can control one or more
actuators (motors), which are identified as channels in the UAPI. It is
possible to execute motions on individual channels, or combined
affecting several selected (or all) channels simutaneously. Examples of
coordinated movements of several channels could be the individual axes
of a 3D printer or CNC machine for example.

On the hardware side, this initial set of patches also includes two drivers
for two different kinds of motors. One is a stepper motor controller
device that containes a ramp generator capable of autonomously executing
controlled motions following a multi-point acceleration profile
(TMC5240), as well as a simple DC motor controller driver that can control
DC motors via a half-bridge or full H-bridge driver such as the TI DRV8873
for example.

Towards the IIO subsystem, LMC supports generating iio trigger events that
fire at certain motion events, such as passing a pre-programmed position or
when reaching the motion target position, depending on the capabilities of
the hardware device. This enables for example triggering an ADC measurement
at a certain position during a movement.

In the future, making use of PREEMPT_RT, even dumb STEP/DIR type stepper
motor controller drivers may be implemented entirely in the kernel,
depending on some characteristics of the hardware (latency jittter,
interrupt latency and CPU speed mainly).

The existence of this subsystem may affect other projects, such as
Linux-CNC and Klipper for example.

This code is already in use controlling machines with up to 16 stepper
motors and up to 4 DC motors simutaneously. Up to this point the UAPI
has shown to be adequate and sufficient. Careful thought has gone into
the UAPI design to make sure it coveres as many use-cases as possible,
while being versioned and extensible in the future, with backwards
compatibility in mind.

David Jander (7):
  drivers: Add motion control subsystem
  motion: Add ADI/Trinamic TMC5240 stepper motor controller
  motion: Add simple-pwm.c PWM based DC motor controller driver
  Documentation: Add Linux Motion Control documentation
  dt-bindings: motion: Add common motion device properties
  dt-bindings: motion: Add adi,tmc5240 bindings
  dt-bindings: motion: Add motion-simple-pwm bindings

 .../bindings/motion/adi,tmc5240.yaml          |   60 +
 .../devicetree/bindings/motion/common.yaml    |   52 +
 .../bindings/motion/motion-simple-pwm.yaml    |   55 +
 Documentation/motion/index.rst                |   18 +
 Documentation/motion/motion-uapi.rst          |  555 ++++++++
 Documentation/subsystem-apis.rst              |    1 +
 MAINTAINERS                                   |   13 +
 drivers/Kconfig                               |    2 +
 drivers/Makefile                              |    2 +
 drivers/motion/Kconfig                        |   42 +
 drivers/motion/Makefile                       |    5 +
 drivers/motion/motion-core.c                  |  823 ++++++++++++
 drivers/motion/motion-core.h                  |  172 +++
 drivers/motion/motion-helpers.c               |  590 +++++++++
 drivers/motion/motion-helpers.h               |   23 +
 drivers/motion/simple-pwm.c                   |  199 +++
 drivers/motion/tmc5240.c                      | 1157 +++++++++++++++++
 include/uapi/linux/motion.h                   |  229 ++++
 18 files changed, 3998 insertions(+)
 create mode 100644 Documentation/devicetree/bindings/motion/adi,tmc5240.yaml
 create mode 100644 Documentation/devicetree/bindings/motion/common.yaml
 create mode 100644 Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml
 create mode 100644 Documentation/motion/index.rst
 create mode 100644 Documentation/motion/motion-uapi.rst
 create mode 100644 drivers/motion/Kconfig
 create mode 100644 drivers/motion/Makefile
 create mode 100644 drivers/motion/motion-core.c
 create mode 100644 drivers/motion/motion-core.h
 create mode 100644 drivers/motion/motion-helpers.c
 create mode 100644 drivers/motion/motion-helpers.h
 create mode 100644 drivers/motion/simple-pwm.c
 create mode 100644 drivers/motion/tmc5240.c
 create mode 100644 include/uapi/linux/motion.h

-- 
2.47.2


^ permalink raw reply	[flat|nested] 59+ messages in thread

* [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-02-27 16:28 [RFC PATCH 0/7] Add Linux Motion Control subsystem David Jander
@ 2025-02-27 16:28 ` David Jander
  2025-02-28 16:44   ` Uwe Kleine-König
  2025-02-28 22:36   ` David Lechner
  2025-02-27 16:28 ` [RFC PATCH 2/7] motion: Add ADI/Trinamic TMC5240 stepper motor controller David Jander
                   ` (8 subsequent siblings)
  9 siblings, 2 replies; 59+ messages in thread
From: David Jander @ 2025-02-27 16:28 UTC (permalink / raw)
  To: linux-kernel
  Cc: linux-iio, Jonathan Corbet, Rob Herring, Krzysztof Kozlowski,
	Conor Dooley, devicetree, linux-doc, Nuno Sa, Jonathan Cameron,
	Oleksij Rempel, David Jander

The Linux Motion Control subsystem (LMC) is a new driver subsystem for
peripheral devices that control mechanical motion in some form or another.
This could be different kinds of motors (stepper, DC, AC, SRM, BLDC...)
or even linear actuators.
The subsystem presents a unified UAPI for those devices, based on char
devices with ioctl's.
It can make use of regular gpio's to function as trigger inputs, like
end-stops, fixed position- or motion start triggers and also generate
events not only to user-space but also to the IIO subsystem in the form of
IIO triggers.

Signed-off-by: David Jander <david@protonic.nl>
---
 MAINTAINERS                     |   8 +
 drivers/Kconfig                 |   2 +
 drivers/Makefile                |   2 +
 drivers/motion/Kconfig          |  19 +
 drivers/motion/Makefile         |   3 +
 drivers/motion/motion-core.c    | 823 ++++++++++++++++++++++++++++++++
 drivers/motion/motion-core.h    | 172 +++++++
 drivers/motion/motion-helpers.c | 590 +++++++++++++++++++++++
 drivers/motion/motion-helpers.h |  23 +
 include/uapi/linux/motion.h     | 229 +++++++++
 10 files changed, 1871 insertions(+)
 create mode 100644 drivers/motion/Kconfig
 create mode 100644 drivers/motion/Makefile
 create mode 100644 drivers/motion/motion-core.c
 create mode 100644 drivers/motion/motion-core.h
 create mode 100644 drivers/motion/motion-helpers.c
 create mode 100644 drivers/motion/motion-helpers.h
 create mode 100644 include/uapi/linux/motion.h

diff --git a/MAINTAINERS b/MAINTAINERS
index efee40ea589f..57267584166c 100644
--- a/MAINTAINERS
+++ b/MAINTAINERS
@@ -13418,6 +13418,14 @@ F:	Documentation/litmus-tests/
 F:	Documentation/memory-barriers.txt
 F:	tools/memory-model/
 
+LINUX MOTION CONTROL
+M:	David Jander <david@protonic.nl>
+L:	linux-kernel@vger.kernel.org
+S:	Maintained
+F:	Documentation/devicetree/bindings/motion/
+F:	Documentation/motion/
+F:	drivers/motion/
+
 LINUX-NEXT TREE
 M:	Stephen Rothwell <sfr@canb.auug.org.au>
 L:	linux-next@vger.kernel.org
diff --git a/drivers/Kconfig b/drivers/Kconfig
index 7bdad836fc62..6b3482187f38 100644
--- a/drivers/Kconfig
+++ b/drivers/Kconfig
@@ -245,4 +245,6 @@ source "drivers/cdx/Kconfig"
 
 source "drivers/dpll/Kconfig"
 
+source "drivers/motion/Kconfig"
+
 endmenu
diff --git a/drivers/Makefile b/drivers/Makefile
index 45d1c3e630f7..39476f2b5e55 100644
--- a/drivers/Makefile
+++ b/drivers/Makefile
@@ -195,3 +195,5 @@ obj-$(CONFIG_CDX_BUS)		+= cdx/
 obj-$(CONFIG_DPLL)		+= dpll/
 
 obj-$(CONFIG_S390)		+= s390/
+
+obj-$(CONFIG_MOTION)		+= motion/
diff --git a/drivers/motion/Kconfig b/drivers/motion/Kconfig
new file mode 100644
index 000000000000..085f9647b47b
--- /dev/null
+++ b/drivers/motion/Kconfig
@@ -0,0 +1,19 @@
+# SPDX-License-Identifier: GPL-2.0
+
+menuconfig MOTION
+	bool "Linux Motion Control support"
+	select IIO
+	help
+	  The Linux Motion Control subsystem contains drivers for different
+	  types of motion control hardware, like (stepper-)motor drivers and
+	  linear actuators.
+	  Say Y here if you want to chose motion control devices.
+
+if MOTION
+
+config MOTION_HELPERS
+	bool
+	depends on MOTION
+
+endif # MOTION
+
diff --git a/drivers/motion/Makefile b/drivers/motion/Makefile
new file mode 100644
index 000000000000..ed912a8ed605
--- /dev/null
+++ b/drivers/motion/Makefile
@@ -0,0 +1,3 @@
+# SPDX-License-Identifier: GPL-2.0
+obj-$(CONFIG_MOTION)		+= motion-core.o
+obj-$(CONFIG_MOTION_HELPERS)	+= motion-helpers.o
diff --git a/drivers/motion/motion-core.c b/drivers/motion/motion-core.c
new file mode 100644
index 000000000000..2963f1859e8b
--- /dev/null
+++ b/drivers/motion/motion-core.c
@@ -0,0 +1,823 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * Motion Control Subsystem - Core
+ *
+ * Copyright (C) 2024 Protonic Holland
+ *                    David Jander <david@protonic.nl>
+ */
+
+#include <asm-generic/bitops/builtin-fls.h>
+#include <asm-generic/errno-base.h>
+#include <linux/interrupt.h>
+#include <linux/irqreturn.h>
+#include <linux/container_of.h>
+#include <linux/hrtimer_types.h>
+#include <linux/gfp_types.h>
+#include <linux/module.h>
+
+#include <linux/fs.h>
+#include <linux/errno.h>
+#include <linux/kernel.h>
+#include <linux/major.h>
+#include <linux/init.h>
+#include <linux/device.h>
+#include <linux/kmod.h>
+#include <linux/motion.h>
+#include <linux/poll.h>
+#include <linux/ptrace.h>
+#include <linux/ktime.h>
+#include <linux/iio/trigger.h>
+#include <linux/gpio/consumer.h>
+
+#include "motion-core.h"
+#include "motion-helpers.h"
+#include <linux/time.h>
+#include <linux/uaccess.h>
+#include <linux/string.h>
+#include <linux/math64.h>
+#include <linux/mutex.h>
+#include <linux/math.h>
+#include <linux/math64.h>
+
+#define MOTION_PROFILE_VALID BIT(31)
+
+static LIST_HEAD(motion_list);
+static DEFINE_MUTEX(motion_mtx);
+static int motion_major;
+static DEFINE_IDA(motion_minors_ida);
+
+struct iio_motion_trigger_info {
+	unsigned int minor;
+};
+
+static int motion_minor_alloc(void)
+{
+	int ret;
+
+	ret = ida_alloc_range(&motion_minors_ida, 0, MINORMASK, GFP_KERNEL);
+	return ret;
+}
+
+static void motion_minor_free(int minor)
+{
+	ida_free(&motion_minors_ida, minor);
+}
+
+static int motion_open(struct inode *inode, struct file *file)
+{
+	int minor = iminor(inode);
+	struct motion_device *mdev = NULL, *iter;
+	int err;
+
+	mutex_lock(&motion_mtx);
+
+	list_for_each_entry(iter, &motion_list, list) {
+		if (iter->minor != minor)
+			continue;
+		mdev = iter;
+		break;
+	}
+
+	if (!mdev) {
+		err = -ENODEV;
+		goto fail;
+	}
+
+	dev_info(mdev->dev, "MOTION: open %d\n", mdev->minor);
+	file->private_data = mdev;
+
+	if (mdev->ops.device_open)
+		err = mdev->ops.device_open(mdev);
+	else
+		err = 0;
+fail:
+	mutex_unlock(&motion_mtx);
+	return err;
+}
+
+static int motion_release(struct inode *inode, struct file *file)
+{
+	struct motion_device *mdev = file->private_data;
+	int i;
+
+	if (mdev->ops.device_release)
+		mdev->ops.device_release(mdev);
+
+	for (i = 0; i < mdev->num_gpios; i++) {
+		int irq;
+		struct motion_gpio_input *gpio = &mdev->gpios[i];
+
+		if (gpio->function == MOT_INP_FUNC_NONE)
+			continue;
+		irq = gpiod_to_irq(gpio->gpio);
+		devm_free_irq(mdev->dev, irq, gpio);
+		gpio->function = MOT_INP_FUNC_NONE;
+	}
+
+	if (!kfifo_is_empty(&mdev->events))
+		kfifo_reset(&mdev->events);
+
+	/* FIXME: Stop running motions? Probably not... */
+
+	return 0;
+}
+
+static ssize_t motion_read(struct file *file, char __user *buffer,
+			  size_t count, loff_t *ppos)
+{
+	struct motion_device *mdev = file->private_data;
+	unsigned int copied = 0L;
+	int ret;
+
+	if (!mdev->dev)
+		return -ENODEV;
+
+	if (count < sizeof(struct mot_event))
+		return -EINVAL;
+
+	do {
+		if (kfifo_is_empty(&mdev->events)) {
+			if (file->f_flags & O_NONBLOCK)
+				return -EAGAIN;
+
+			ret = wait_event_interruptible(mdev->wait,
+					!kfifo_is_empty(&mdev->events) ||
+					mdev->dev == NULL);
+			if (ret)
+				return ret;
+			if (mdev->dev == NULL)
+				return -ENODEV;
+		}
+
+		if (mutex_lock_interruptible(&mdev->read_mutex))
+			return -ERESTARTSYS;
+		ret = kfifo_to_user(&mdev->events, buffer, count, &copied);
+		mutex_unlock(&mdev->read_mutex);
+
+		if (ret)
+			return ret;
+	} while (!copied);
+
+	return copied;
+}
+
+static __poll_t motion_poll(struct file *file, poll_table *wait)
+{
+	struct motion_device *mdev = file->private_data;
+	__poll_t mask = 0;
+
+	poll_wait(file, &mdev->wait, wait);
+	if (!kfifo_is_empty(&mdev->events))
+		mask = EPOLLIN | EPOLLRDNORM;
+	dev_info(mdev->dev, "Obtained POLL events: 0x%08x\n", mask);
+
+	return mask;
+}
+
+static long motion_move_distance(struct motion_device *mdev,
+		channel_mask_t ch, speed_raw_t speed, pos_raw_t distance)
+{
+	ktime_t time;
+	u64 tmp;
+	u64 tmpmul = NSEC_PER_SEC; /* Convert speed (1/s) to time in nsec */
+
+	if (mdev->ops.move_distance)
+		return mdev->ops.move_distance(mdev, ch, speed, distance);
+
+	if (!mdev->ops.move_timed)
+		return -EOPNOTSUPP;
+
+	if (!speed)
+		return -EINVAL;
+
+	/*
+	 * Handling of potential integer overflows when converting distance
+	 * to time duration without sacrificing too much precision:
+	 * speed_conv_div and speed_conv_mul can be very large, yet the
+	 * resulting quotient is most likely a lot smaller. If we do the
+	 * multiplication first we retain the highest precision, but we need
+	 * to be mindful of integer overflows, so we do one test to see if there
+	 * are enough bits left to increase the precision further.
+	 */
+	tmp = ((u64)distance * mdev->capabilities.speed_conv_div);
+	if (tmp < (1ULL << 48)) {
+		tmpmul = NSEC_PER_MSEC;
+		tmp *= MSEC_PER_SEC;
+	}
+	tmp = div_u64(tmp, mdev->capabilities.speed_conv_mul);
+	tmp = div_u64(tmp, speed);
+	time = tmp * tmpmul;
+	return mdev->ops.move_timed(mdev, ch, speed, time);
+}
+
+static long motion_move_timed(struct motion_device *mdev, channel_mask_t ch,
+		speed_raw_t speed, mot_time_t duration)
+{
+	ktime_t t;
+
+	if (mdev->ops.move_timed) {
+		t = mot_time2ktime(duration);
+		return mdev->ops.move_timed(mdev, ch, speed, t);
+	}
+
+	return -EOPNOTSUPP;
+}
+
+static long motion_set_profile_locked(struct motion_device *mdev,
+		struct mot_profile *prof)
+{
+	long ret;
+	struct mot_profile *dst;
+	int i;
+
+	lockdep_assert_held(&mdev->mutex);
+
+	if ((prof->na > mdev->capabilities.max_apoints) ||
+			(prof->nv > mdev->capabilities.max_vpoints))
+		return -EINVAL;
+
+	/* Check if used acceleration values are positive and non zero */
+	for (i = 0; i < prof->na; i++)
+		if (prof->acc[i] <= 0)
+			return -EINVAL;
+
+	if (!mdev->ops.validate_profile || !mdev->ops.set_profile)
+		return -EOPNOTSUPP;
+
+	if (prof->index >= MOT_MAX_PROFILES)
+		return -EINVAL;
+
+	ret = mdev->ops.validate_profile(mdev, prof);
+	if (ret)
+		return ret;
+
+	dst = &mdev->profiles[prof->index];
+
+	*dst = *prof;
+	dst->index |= MOTION_PROFILE_VALID;
+
+	return 0L;
+}
+
+static long motion_get_profile_locked(struct motion_device *mdev, u32 index,
+		struct mot_profile *dst)
+{
+	struct mot_profile *src;
+
+	lockdep_assert_held(&mdev->mutex);
+
+	if (index >= MOT_MAX_PROFILES)
+		return -EINVAL;
+
+	if (!(mdev->profiles[index].index & MOTION_PROFILE_VALID))
+		return -EINVAL;
+
+	src = &mdev->profiles[index];
+	*dst = *src;
+
+	return 0L;
+}
+
+static long motion_start_locked(struct motion_device *mdev, struct mot_start *s)
+{
+	long ret = 0L;
+	mot_time_t conv_duration;
+
+	lockdep_assert_held(&mdev->mutex);
+
+	if (s->reserved1 || s->reserved2)
+		return -EINVAL;
+	if (s->channel >= mdev->capabilities.num_channels)
+		return -EINVAL;
+	if ((s->index >= MOT_MAX_PROFILES) || (s->direction > MOT_DIRECTION_RIGHT))
+		return -EINVAL;
+	if (!(mdev->profiles[s->index].index & MOTION_PROFILE_VALID))
+		return -EINVAL;
+	if (s->when >= MOT_WHEN_NUM_WHENS)
+		return -EINVAL;
+	if (s->duration && s->distance)
+		return -EINVAL;
+	if (!mdev->ops.motion_distance && !mdev->ops.motion_timed)
+		return -EOPNOTSUPP;
+	if (s->duration) {
+		if (!mdev->ops.motion_timed)
+			return -EOPNOTSUPP;
+		/* FIXME: Implement time to distance conversion? */
+		return mdev->ops.motion_timed(mdev, s->channel, s->index,
+				s->direction, s->duration, s->when);
+	}
+	if (!mdev->ops.motion_distance) {
+		ret = motion_distance_to_time(mdev, s->index, s->distance,
+				&conv_duration);
+		if (ret)
+			return ret;
+		return mdev->ops.motion_timed(mdev, s->channel, s->index,
+				s->direction, conv_duration, s->when);
+	}
+	ret = mdev->ops.motion_distance(mdev, s->channel, s->index,
+			s->distance, s->when);
+
+	return ret;
+}
+
+static irqreturn_t motion_gpio_interrupt(int irq, void *dev_id)
+{
+	struct motion_gpio_input *gpio = dev_id;
+	struct motion_device *mdev = container_of(gpio, struct motion_device,
+			gpios[gpio->index]);
+	struct mot_event evt = {0};
+	struct mot_status st;
+	int val = gpiod_get_raw_value(gpio->gpio);
+	channel_mask_t chmsk;
+	channel_mask_t chmsk_l = 0;
+	channel_mask_t chmsk_r = 0;
+
+	dev_info(mdev->dev, "GPIO IRQ val=%d edge=%d\n", val, gpio->edge);
+	/* FIXME: This is racy and we shouldn't try to support shared IRQ! */
+	if ((gpio->edge == MOT_EDGE_FALLING) && val)
+		return IRQ_NONE;
+
+	if ((gpio->edge == MOT_EDGE_RISING) && !val)
+		return IRQ_NONE;
+
+	evt.event = MOT_EVENT_INPUT;
+	evt.input_index = gpio->index;
+	evt.timestamp = ktime2mot_time(ktime_get());
+
+	mutex_lock(&mdev->mutex);
+	/* FIXME: It may be possible and desirable to obtain position and
+	 * speed from multiple channels with one call to the driver.
+	 */
+	chmsk = gpio->chmask;
+	while (chmsk) {
+		unsigned int ch = ffs(chmsk) - 1;
+
+		chmsk &= ~(1 << ch);
+		evt.channel = ch;
+		st.channel = ch;
+		mdev->ops.get_status(mdev, &st);
+		evt.speed = st.speed;
+		evt.position = st.position;
+		motion_report_event(mdev, &evt);
+		if (st.speed < 0)
+			chmsk_l |= (1 << ch);
+		else if (st.speed > 0)
+			chmsk_r |= (1 << ch);
+	}
+
+	switch (gpio->function) {
+	case MOT_INP_FUNC_STOP_NEG:
+		if (chmsk_l)
+			mdev->ops.basic_stop(mdev, chmsk_l);
+		break;
+	case MOT_INP_FUNC_STOP_POS:
+		if (chmsk_r)
+			mdev->ops.basic_stop(mdev, chmsk_r);
+		break;
+	case MOT_INP_FUNC_STOP:
+		mdev->ops.basic_stop(mdev, gpio->chmask);
+		break;
+	case MOT_INP_FUNC_DECEL_NEG:
+		if (chmsk_l)
+			mdev->ops.motion_stop(mdev, chmsk_l, MOT_WHEN_IMMEDIATE);
+		break;
+	case MOT_INP_FUNC_DECEL_POS:
+		if (chmsk_r)
+			mdev->ops.motion_stop(mdev, chmsk_r, MOT_WHEN_IMMEDIATE);
+		break;
+	case MOT_INP_FUNC_DECEL:
+		mdev->ops.motion_stop(mdev, gpio->chmask, MOT_WHEN_IMMEDIATE);
+		break;
+	case MOT_INP_FUNC_START:
+		if (mdev->ops.external_trigger)
+			mdev->ops.external_trigger(mdev, gpio->index,
+					gpio->chmask);
+		break;
+	default:
+		break;
+	}
+	mutex_unlock(&mdev->mutex);
+
+	return IRQ_HANDLED;
+}
+
+static int motion_config_gpio(struct motion_device *mdev, int idx,
+		unsigned int func, unsigned int edge, channel_mask_t chmsk)
+{
+	struct motion_gpio_input *gpio = &mdev->gpios[idx];
+	bool irq_claimed = false;
+	int irq = gpiod_to_irq(gpio->gpio);
+	int flags;
+
+	if (gpio->function != MOT_INP_FUNC_NONE) {
+		if (func == MOT_INP_FUNC_NONE)
+			devm_free_irq(mdev->dev, irq, mdev);
+		irq_claimed = true;
+	}
+	gpio->chmask = chmsk;
+	gpio->function = func;
+	gpio->edge = edge;
+	if (!irq_claimed) {
+		if (edge == MOT_EDGE_FALLING)
+			flags = IRQF_TRIGGER_FALLING;
+		else
+			flags = IRQF_TRIGGER_RISING;
+		flags |= IRQF_SHARED | IRQF_ONESHOT;
+		dev_info(mdev->dev, "Claiming GPIO IRQ %d\n", irq);
+		return devm_request_threaded_irq(mdev->dev, irq, NULL,
+				motion_gpio_interrupt, flags,
+				dev_name(mdev->dev), gpio);
+	}
+
+	return 0;
+}
+
+static long motion_config_input_locked(struct motion_device *mdev, struct mot_input *inp)
+{
+	int idx;
+
+	lockdep_assert_held(&mdev->mutex);
+
+	if (!inp->external)
+		return mdev->ops.config_trigger(mdev, inp->index, inp->function,
+				inp->edge, inp->chmask);
+
+	idx = inp->index;
+	idx -= mdev->capabilities.num_ext_triggers - mdev->num_gpios;
+	/*
+	 * FIXME: idx is now the index of GPIO external trigger.
+	 * Other types of external triggers are not yet supported.
+	 */
+	if ((idx >= mdev->num_gpios) || (idx < 0)) {
+		WARN_ONCE(true, "Input index unexpectedly out of range.");
+		return -EINVAL;
+	}
+	return motion_config_gpio(mdev, idx, inp->function, inp->edge,
+			inp->chmask);
+}
+
+static long motion_ioctl(struct file *file, unsigned int cmd, unsigned long arg)
+{
+	struct motion_device *mdev = file->private_data;
+	void __user *argp = (void __user *)arg;
+	long ret;
+
+	switch (cmd) {
+	case MOT_IOCTL_APIVER:
+		force_successful_syscall_return();
+		return MOT_UAPI_VERSION;
+	case MOT_IOCTL_BASIC_RUN: {
+		struct mot_speed_duration spd;
+
+		if (copy_from_user(&spd, argp, sizeof(spd)))
+			return -EFAULT;
+		if (!mdev->ops.basic_run)
+			return -EINVAL;
+		if (spd.channel >= mdev->capabilities.num_channels)
+			return -EINVAL;
+		if (spd.distance && spd.duration)
+			return -EINVAL;
+		/* FIXME: Check reserved for zero! */
+		mutex_lock(&mdev->mutex);
+		if (!spd.distance && !spd.duration)
+			ret = mdev->ops.basic_run(mdev, spd.channel, spd.speed);
+		else if (spd.distance)
+			ret = motion_move_distance(mdev, spd.channel,
+					spd.speed, spd.distance);
+		else
+			ret = motion_move_timed(mdev, spd.channel, spd.speed,
+				mot_time2ktime(spd.duration));
+		mutex_unlock(&mdev->mutex);
+		break;
+	}
+	case MOT_IOCTL_BASIC_STOP: {
+		u32 ch;
+
+		if (copy_from_user(&ch, argp, sizeof(ch)))
+			return -EFAULT;
+		/* Stop takes channel mask as only argument */
+		if (fls(ch) > mdev->capabilities.num_channels)
+			return -EINVAL;
+		mutex_lock(&mdev->mutex);
+		ret = mdev->ops.basic_stop(mdev, ch);
+		mutex_unlock(&mdev->mutex);
+		break;
+	}
+	case MOT_IOCTL_GET_CAPA:
+		ret = copy_to_user(argp, &mdev->capabilities, sizeof(struct mot_capabilities));
+		break;
+	case MOT_IOCTL_GET_STATUS: {
+		struct mot_status st;
+
+		if (copy_from_user(&st, argp, sizeof(st)))
+			return -EFAULT;
+		if (st.channel >= mdev->capabilities.num_channels)
+			return -EINVAL;
+		if (!mdev->ops.get_status)
+			return -EINVAL;
+		mutex_lock(&mdev->mutex);
+		ret = mdev->ops.get_status(mdev, &st);
+		mutex_unlock(&mdev->mutex);
+		if (ret)
+			break;
+		ret = copy_to_user(argp, &st, sizeof(struct mot_status));
+		break;
+	}
+	case MOT_IOCTL_SET_PROFILE: {
+		struct mot_profile prof;
+
+		if (copy_from_user(&prof, argp, sizeof(prof)))
+			return -EFAULT;
+		mutex_lock(&mdev->mutex);
+		ret = motion_set_profile_locked(mdev, &prof);
+		mutex_unlock(&mdev->mutex);
+		break;
+	}
+	case MOT_IOCTL_GET_PROFILE: {
+		struct mot_profile prof;
+
+		if (copy_from_user(&prof, argp, sizeof(prof)))
+			return -EFAULT;
+		mutex_lock(&mdev->mutex);
+		ret = motion_get_profile_locked(mdev, prof.index, &prof);
+		mutex_unlock(&mdev->mutex);
+		if (ret)
+			break;
+		ret = copy_to_user(argp, &prof, sizeof(prof));
+		break;
+	}
+	case MOT_IOCTL_START: {
+		struct mot_start start;
+
+		if (copy_from_user(&start, argp, sizeof(start)))
+			return -EFAULT;
+		mutex_lock(&mdev->mutex);
+		ret = motion_start_locked(mdev, &start);
+		mutex_unlock(&mdev->mutex);
+		break;
+	}
+	case MOT_IOCTL_STOP: {
+		struct mot_stop stop;
+
+		if (copy_from_user(&stop, argp, sizeof(stop)))
+			return -EFAULT;
+		if (fls(stop.chmask) > mdev->capabilities.num_channels)
+			return -EINVAL;
+		if (stop.when >= MOT_WHEN_NUM_WHENS)
+			return -EINVAL;
+		if (!mdev->ops.motion_stop)
+			return -EINVAL;
+		mutex_lock(&mdev->mutex);
+		ret = mdev->ops.motion_stop(mdev, stop.chmask, stop.when);
+		mutex_unlock(&mdev->mutex);
+		break;
+	}
+	case MOT_IOCTL_CONFIG_INPUT: {
+		struct mot_input inp;
+
+		if (copy_from_user(&inp, argp, sizeof(inp)))
+			return -EFAULT;
+		if (fls(inp.chmask) > mdev->capabilities.num_channels)
+			return -EINVAL;
+		if ((inp.external > 1) || (inp.function > MOT_INP_FUNC_NUM_FUNCS))
+			return -EINVAL;
+		if (!inp.external && (inp.index >= mdev->capabilities.num_int_triggers))
+			return -EINVAL;
+		if (inp.external && (inp.index >= mdev->capabilities.num_ext_triggers))
+			return -EINVAL;
+		if (!inp.external && !mdev->ops.config_trigger)
+			return -EOPNOTSUPP;
+		mutex_lock(&mdev->mutex);
+		ret = motion_config_input_locked(mdev, &inp);
+		mutex_unlock(&mdev->mutex);
+		break;
+	}
+	default:
+		ret = -EINVAL;
+		break;
+	}
+
+	return ret;
+}
+
+static char *motion_devnode(const struct device *dev, umode_t *mode)
+{
+	const struct motion_device *mdev = dev_get_drvdata(dev);
+
+	if (mode && mdev->mode)
+		*mode = mdev->mode;
+	if (mdev->nodename)
+		return kstrdup(mdev->nodename, GFP_KERNEL);
+	return NULL;
+}
+
+static const struct class motion_class = {
+	.name		= "motion",
+	.devnode	= motion_devnode,
+};
+
+static const struct file_operations motion_fops = {
+	.owner		= THIS_MODULE,
+	.read		= motion_read,
+	.poll		= motion_poll,
+	.unlocked_ioctl = motion_ioctl,
+	.open		= motion_open,
+	.llseek		= noop_llseek,
+	.release	= motion_release,
+};
+
+static int motion_of_parse_gpios(struct motion_device *mdev)
+{
+	int ngpio, i;
+
+	ngpio = gpiod_count(mdev->parent, "motion,input");
+	if (ngpio < 0) {
+		if (ngpio == -ENOENT)
+			return 0;
+		return ngpio;
+	}
+
+	if (ngpio >= MOT_MAX_INPUTS)
+		return -EINVAL;
+
+	for (i = 0; i < ngpio; i++) {
+		mdev->gpios[i].gpio = devm_gpiod_get_index(mdev->parent,
+				"motion,input", i, GPIOD_IN);
+		if (IS_ERR(mdev->gpios[i].gpio))
+			return PTR_ERR(mdev->gpios[i].gpio);
+		mdev->gpios[i].function = MOT_INP_FUNC_NONE;
+		mdev->gpios[i].chmask = 0;
+		mdev->gpios[i].index = i;
+	}
+
+	mdev->num_gpios = ngpio;
+	mdev->capabilities.num_ext_triggers += ngpio;
+
+	return 0;
+}
+
+static void motion_trigger_work(struct irq_work *work)
+{
+	struct motion_device *mdev = container_of(work, struct motion_device,
+							iiowork);
+	iio_trigger_poll(mdev->iiotrig);
+}
+
+/**
+ * motion_register_device - Register a new Motion Device
+ * @mdev: description and handle of the motion device
+ *
+ * Register a new motion device with the motion subsystem core.
+ * It also handles OF parsing of external trigger GPIOs and registers an IIO
+ * trigger device if IIO support is configured.
+ *
+ * Return: 0 on success, negative errno on failure.
+ */
+int motion_register_device(struct motion_device *mdev)
+{
+	dev_t devt;
+	int err = 0;
+	struct iio_motion_trigger_info *trig_info;
+
+	if (!mdev->capabilities.num_channels)
+		mdev->capabilities.num_channels = 1;
+	if (mdev->capabilities.features | MOT_FEATURE_PROFILE)
+		mdev->capabilities.max_profiles = MOT_MAX_PROFILES;
+	if (!mdev->capabilities.speed_conv_mul)
+		mdev->capabilities.speed_conv_mul = 1;
+	if (!mdev->capabilities.speed_conv_div)
+		mdev->capabilities.speed_conv_div = 1;
+	if (!mdev->capabilities.accel_conv_mul)
+		mdev->capabilities.accel_conv_mul = 1;
+	if (!mdev->capabilities.accel_conv_div)
+		mdev->capabilities.accel_conv_div = 1;
+
+	mutex_init(&mdev->mutex);
+	mutex_init(&mdev->read_mutex);
+	INIT_KFIFO(mdev->events);
+	init_waitqueue_head(&mdev->wait);
+
+	err = motion_of_parse_gpios(mdev);
+	if (err)
+		return err;
+
+	mdev->minor = motion_minor_alloc();
+
+	mdev->iiotrig = iio_trigger_alloc(NULL, "mottrig%d", mdev->minor);
+	if (!mdev->iiotrig) {
+		err = -ENOMEM;
+		goto error_free_minor;
+	}
+
+	trig_info = kzalloc(sizeof(*trig_info), GFP_KERNEL);
+	if (!trig_info) {
+		err = -ENOMEM;
+		goto error_free_trigger;
+	}
+
+	iio_trigger_set_drvdata(mdev->iiotrig, trig_info);
+
+	trig_info->minor = mdev->minor;
+	err = iio_trigger_register(mdev->iiotrig);
+	if (err)
+		goto error_free_trig_info;
+
+	mdev->iiowork = IRQ_WORK_INIT_HARD(motion_trigger_work);
+
+	INIT_LIST_HEAD(&mdev->list);
+
+	mutex_lock(&motion_mtx);
+
+	devt = MKDEV(motion_major, mdev->minor);
+	mdev->dev = device_create_with_groups(&motion_class, mdev->parent,
+				devt, mdev, mdev->groups, "motion%d", mdev->minor);
+	if (IS_ERR(mdev->dev)) {
+		dev_err(mdev->parent, "Error creating motion device %d\n",
+				mdev->minor);
+		mutex_unlock(&motion_mtx);
+		goto error_free_trig_info;
+	}
+	list_add_tail(&mdev->list, &motion_list);
+	mutex_unlock(&motion_mtx);
+
+	return 0;
+
+error_free_trig_info:
+	kfree(trig_info);
+error_free_trigger:
+	iio_trigger_free(mdev->iiotrig);
+error_free_minor:
+	motion_minor_free(mdev->minor);
+	dev_info(mdev->parent, "Registering motion device err=%d\n", err);
+	return err;
+}
+EXPORT_SYMBOL(motion_register_device);
+
+void motion_unregister_device(struct motion_device *mdev)
+{
+	struct iio_motion_trigger_info *trig_info;
+
+	trig_info = iio_trigger_get_drvdata(mdev->iiotrig);
+	iio_trigger_unregister(mdev->iiotrig);
+	kfree(trig_info);
+	iio_trigger_free(mdev->iiotrig);
+	mutex_lock(&motion_mtx);
+	list_del(&mdev->list);
+	device_destroy(&motion_class, MKDEV(motion_major, mdev->minor));
+	motion_minor_free(mdev->minor);
+	mdev->dev = NULL; /* Trigger chardev read abort */
+	mutex_unlock(&motion_mtx);
+}
+EXPORT_SYMBOL(motion_unregister_device);
+
+/**
+ * motion_report_event - Report an event to the motion core.
+ * @mdev: The motion device reporting the event
+ * @evt: The event to be reported and queued.
+ *
+ * Drivers should call this function when there is a motion event, such as
+ * target reached or a (virtual-) stop triggered. This applies only to internal
+ * trigger inputs; external GPIO trigger events are handled by the core.
+ */
+void motion_report_event(struct motion_device *mdev, struct mot_event *evt)
+{
+	int ret;
+
+	dev_info(mdev->dev, "Report event: %d\n", evt->event);
+	switch (evt->event) {
+	case MOT_EVENT_INPUT:
+	case MOT_EVENT_TARGET:
+	case MOT_EVENT_STOP:
+		ret = kfifo_put(&mdev->events, *evt);
+		if (ret)
+			wake_up_poll(&mdev->wait, EPOLLIN);
+		irq_work_queue(&mdev->iiowork);
+		break;
+	default:
+		break;
+	}
+
+}
+EXPORT_SYMBOL(motion_report_event);
+
+static int __init motion_init(void)
+{
+	int err;
+
+	err = class_register(&motion_class);
+	if (err)
+		return err;
+
+	motion_major = register_chrdev(0, "motion", &motion_fops);
+	if (motion_major <= 0) {
+		err = -EIO;
+		goto fail;
+	}
+	return 0;
+
+fail:
+	pr_err("unable to get major number for motion devices\n");
+	class_unregister(&motion_class);
+	return err;
+}
+subsys_initcall(motion_init);
diff --git a/drivers/motion/motion-core.h b/drivers/motion/motion-core.h
new file mode 100644
index 000000000000..92d0fc816265
--- /dev/null
+++ b/drivers/motion/motion-core.h
@@ -0,0 +1,172 @@
+/* SPDX-License-Identifier: GPL-2.0-only */
+#ifndef __MOTION_CORE_H__
+#define __MOTION_CORE_H__
+
+#include <linux/major.h>
+#include <linux/list.h>
+#include <linux/types.h>
+#include <linux/device.h>
+#include <linux/kfifo.h>
+#include <linux/irq_work.h>
+#include <uapi/linux/motion.h>
+
+struct motion_device;
+
+/**
+ * struct motion_ops - Motion driver API
+ * @device_open: Called when the associated device is opened
+ * @device_release: Called when the associated device is closed
+ * @basic_run: Start a basic movement of channel @ch with speed @v. Speed is a
+ *      signed value. Sign indicates direction.
+ * @basic_stop: Immediately stops all active movements of all channels set in
+ *      channel mask @ch.
+ * @get_status: Get current speed and position (if supported) from the channel
+ *      specified in st->channel.
+ * @move_distance: Start a movement just like basic_run(), but stop after
+ *      reaching the specified distance. Optional.
+ * @move_timed: Start a movement just like basic_run(), but stop after a
+ *      specified time. Optional.
+ * @validate_profile: Check if all parameters of a specified movement profile
+ *      (acceleration/speed curve) is valid for this driver. Optional.
+ * @motion_distance: Start or prepare to start a movement following a specified
+ *      motion profile until reaching the target distance. Optional.
+ * @motion_timed: Start or prepare to start a movement following a specified
+ *      motion profile that takes exactly @t time. Optional.
+ * @motion_stop: Stop or prepare to stop a movement that was initiated with
+ *      either motion_timed() or motion_distance() prematurely while following
+ *      the deceleration segment of the profile the movement was started with.
+ *      Optional.
+ * @config_trigger: Setup a trigger @index for a certaing function @func that
+ *      applies to all channels set in channel mask @ch. Only applies to
+ *      internal triggers. Optional.
+ * @external_trigger: Initiate a movement by external trigger on all channels
+ *      set in channel mask @ch. Optional.
+ *
+ * Channel mask parameters of typo channel_mask_t are bitmasks that specify
+ * multiple channels the call applies to simultaneously.
+ *
+ * The parameter @when specifies one of the MOT_WHEN_* values defined in the
+ * motion UAPI.
+ * The parameter @func specifies one of the MOT_FUNC_* values defined in the
+ * motion UAPI.
+ * The parameter @edge can be either MOT_EDGE_FALLING or MOT_EDGE_RISING.
+ * The parameter @index either refers to the index of a motion profile, or the
+ * index of an internal trigger intput depending on the context.
+ *
+ * All function calls specified as "Optional" above need to be implemented only
+ * if the driver can support the required functionality.
+ */
+struct motion_ops {
+	int (*device_open)(struct motion_device *mdev);
+	int (*device_release)(struct motion_device *mdev);
+	int (*basic_run)(struct motion_device *mdev, unsigned int ch, s32 v);
+	int (*basic_stop)(struct motion_device *mdev, channel_mask_t ch);
+	int (*get_status)(struct motion_device *mdev, struct mot_status *st);
+	int (*move_distance)(struct motion_device *mdev, unsigned int ch,
+			s32 v, u32 d);
+	int (*move_timed)(struct motion_device *mdev, unsigned int ch, s32 v,
+			ktime_t t);
+	int (*validate_profile)(struct motion_device *mdev,
+			struct mot_profile *p);
+	int (*set_profile)(struct motion_device *mdev, struct mot_profile *p);
+	int (*motion_distance)(struct motion_device *mdev, unsigned int ch,
+			unsigned int index, s32 d, unsigned int when);
+	int (*motion_timed)(struct motion_device *mdev, unsigned int ch,
+			unsigned int index, unsigned int dir, ktime_t t,
+			unsigned int when);
+	int (*motion_stop)(struct motion_device *mdev, channel_mask_t ch,
+			unsigned int when);
+	int (*config_trigger)(struct motion_device *mdev, unsigned int index,
+			unsigned int func, unsigned int edge, channel_mask_t ch);
+	void (*external_trigger)(struct motion_device *mdev, unsigned int index,
+			channel_mask_t ch);
+};
+
+struct motion_gpio_input {
+	struct gpio_desc *gpio;
+	unsigned int function;
+	unsigned int edge;
+	unsigned int index;
+	channel_mask_t chmask;
+};
+
+/**
+ * struct motion_device - Represents a motion control subsystem device
+ * @ops: struct motion_ops implementing the functionality of the device.
+ * @parent: Parent struct device. This can be an underlying SPI/I2C device or
+ *      a platform device, etc... This is mandatory.
+ * @dev: Newly created motion device associated with the denode. Filled in
+ *      by motion_register_device().
+ * @minor: The motion device minor number allocated by motion_register_device().
+ * @list: Internal housekeeping.
+ * @groups: Attribute groups of the device. The driver can add an entry to the
+ *      attributes table if required. Should be used for all run-time parameters
+ *      of the underlying hardware, like current limits, virtual stop positions,
+ *      etc...
+ * @nodename: Optional name of the devnode. Default NULL will use motionXX
+ * @mode: Optional mode for the devnode.
+ * @mutex: Mutex for serializing access to the device. Used by the core and
+ *      locked during calls to the @ops. Should be locked by the driver if
+ *      entered from other places, like interrupt threads.
+ * @read_mutex: Mutex used by the core for serializing read() calls to the
+ *      device.
+ * @capabilities: struct mot_capabilities, describes the capabilities of the
+ *      particular driver.
+ * @profiles: Statically allocated list of motion profiles. The core stores
+ *      motion profiles supplied by user-space in this list. The @index
+ *      parameter in @ops calls is an index into this list if applicable.
+ * @gpios: Statically allocated list of external trigger inputs associated with
+ *      this device. These are specified in the fwnode.
+ * @num_gpios: Number of external GPIO trigger inputs parsed from the fwnode.
+ * @wait: poll() waitqueue for motion events to user-space.
+ * @events: KFIFO of motion events.
+ * @iiotrig: IIO trigger of motion events.
+ * @iiowork: The irq_work that dispatches the IIO trigger events.
+ * @helper_cookie: internal data for helper functions such as timed_speed
+ *      helpers.
+ *
+ * Motion device drivers should (devm_)kzalloc this struct and fill in all
+ * required information (@ops, @parent and @capabilities) and then call
+ * motion_register_device() from their probe function.
+ *
+ * @parent should hold any drvdata for the driver if needed, and the drvdata
+ * struct should contain this struct motion_device as a member, so that it can
+ * be retrieved with container_of() macros.
+ */
+struct motion_device {
+	struct motion_ops		ops;
+	struct device			*parent;
+	struct device			*dev;
+	int				minor;
+	struct list_head		list;
+	const struct attribute_group	*groups[3];
+	const char			*nodename;
+	umode_t				mode;
+	struct mutex			mutex;
+	struct mutex			read_mutex;
+	struct mot_capabilities		capabilities;
+	struct mot_profile		profiles[MOT_MAX_PROFILES];
+	struct motion_gpio_input	gpios[MOT_MAX_INPUTS];
+	unsigned int			num_gpios;
+	wait_queue_head_t		wait;
+	DECLARE_KFIFO(events, struct mot_event, 16);
+	struct iio_trigger		*iiotrig;
+	struct irq_work			iiowork;
+	void				*helper_cookie;
+};
+
+static inline ktime_t mot_time2ktime(mot_time_t t)
+{
+	return (ktime_t)t;
+}
+
+static inline mot_time_t ktime2mot_time(ktime_t t)
+{
+	return (mot_time_t)t;
+}
+
+int motion_register_device(struct motion_device *mdev);
+void motion_unregister_device(struct motion_device *mdev);
+void motion_report_event(struct motion_device *mdev, struct mot_event *evt);
+
+#endif /* __MOTION_CORE_H__ */
diff --git a/drivers/motion/motion-helpers.c b/drivers/motion/motion-helpers.c
new file mode 100644
index 000000000000..b4c8dda84aa7
--- /dev/null
+++ b/drivers/motion/motion-helpers.c
@@ -0,0 +1,590 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * Motion Control Subsystem - helper functions
+ *
+ * Copyright (C) 2024 Protonic Holland
+ *      David Jander <david@protonic.nl>
+ */
+
+#include <linux/fwnode.h>
+#include <linux/property.h>
+#include <linux/device.h>
+#include <linux/gfp_types.h>
+#include <linux/hrtimer_types.h>
+#include <linux/export.h>
+#include <linux/types.h>
+#include <linux/motion.h>
+#include "motion-helpers.h"
+#include "motion-core.h"
+
+#define MOTION_TIMER_PERIOD (20 * NSEC_PER_MSEC)
+
+struct motion_timed_speed {
+	struct motion_device *mdev;
+	struct motion_timed_speed_ops *ops;
+	unsigned int speed_full_scale;
+	spinlock_t lock;
+	struct hrtimer timer;
+	unsigned int speed_actual;
+	unsigned int dir;
+	unsigned int speed_max;
+	unsigned int speed_start;
+	unsigned int speed_end;
+	unsigned int deceleration;
+	ktime_t taccel;
+	ktime_t tdecel;
+	ktime_t duration;
+	ktime_t ts_start;
+	unsigned int next_index;
+	unsigned int next_dir;
+	ktime_t next_duration;
+	unsigned int ext_trg_index;
+	unsigned int ext_trg_dir;
+	ktime_t ext_trg_duration;
+};
+
+static inline int __to_signed_speed(unsigned int dir, unsigned int speed)
+{
+	if (dir)
+		return speed;
+	return -speed;
+}
+
+static int motion_timed_speed_open(struct motion_device *mdev)
+{
+	struct motion_timed_speed *mts =
+		(struct motion_timed_speed *)mdev->helper_cookie;
+
+	if (mts->ops->startup)
+		mts->ops->startup(mdev);
+
+	return 0;
+}
+
+static int motion_timed_speed_release(struct motion_device *mdev)
+{
+	struct motion_timed_speed *mts =
+		(struct motion_timed_speed *)mdev->helper_cookie;
+
+	dev_info(mdev->dev, "Release\n");
+	hrtimer_cancel(&mts->timer);
+	if (mts->ops->powerdown)
+		mts->ops->powerdown(mdev);
+	else
+		mts->ops->set_speed(mdev, 0, 0);
+	mts->next_duration = 0;
+	mts->speed_actual = 0;
+	mts->dir = 0;
+
+	return 0;
+}
+
+static int motion_timed_speed_get_status(struct motion_device *mdev, struct mot_status *st)
+{
+	struct motion_timed_speed *mts =
+		(struct motion_timed_speed *)mdev->helper_cookie;
+
+	st->speed = __to_signed_speed(mts->dir, mts->speed_actual);
+	st->position = 0; /* FIXME: Not yet supported */
+
+	return 0;
+}
+
+static int motion_timed_speed_basic_run(struct motion_device *mdev, unsigned int ch, s32 v)
+{
+	struct motion_timed_speed *mts =
+		(struct motion_timed_speed *)mdev->helper_cookie;
+	int ret;
+	unsigned int dir = (v < 0) ? 0 : 1;
+	unsigned int dc = abs(v);
+	unsigned long flags;
+
+	hrtimer_cancel(&mts->timer);
+
+	spin_lock_irqsave(&mts->lock, flags);
+	ret = mts->ops->check_speed(mdev, dir, dc);
+	if (!ret) {
+		mts->speed_max = dc;
+		mts->ops->set_speed(mdev, dir, dc);
+		mts->speed_actual = dc;
+		mts->dir = dir;
+	}
+	spin_unlock_irqrestore(&mts->lock, flags);
+
+	return ret;
+}
+
+static int motion_timed_speed_basic_stop(struct motion_device *mdev, channel_mask_t ch)
+{
+	struct motion_timed_speed *mts =
+		(struct motion_timed_speed *)mdev->helper_cookie;
+	unsigned long flags;
+
+	hrtimer_cancel(&mts->timer);
+
+	spin_lock_irqsave(&mts->lock, flags);
+	mts->ops->set_speed(mdev, 0, 0);
+	mts->dir = 0;
+	mts->speed_actual = 0;
+	mts->speed_max = 0;
+	spin_unlock_irqrestore(&mts->lock, flags);
+
+	return 0;
+}
+
+static int motion_timed_speed_move_timed(struct motion_device *mdev, unsigned int ch,
+		s32 v, ktime_t t)
+{
+	struct motion_timed_speed *mts =
+		(struct motion_timed_speed *)mdev->helper_cookie;
+	unsigned long flags;
+	unsigned int dir = (v < 0) ? 0 : 1;
+	unsigned int dc = abs(v);
+	int ret;
+
+	hrtimer_cancel(&mts->timer);
+
+	spin_lock_irqsave(&mts->lock, flags);
+	ret = mts->ops->check_speed(mdev, dir, dc);
+	if (!ret) {
+		mts->ops->set_speed(mdev, dir, dc);
+		mts->speed_actual = dc;
+		mts->dir = dir;
+		mts->ts_start = ktime_get();
+		mts->duration = t;
+		mts->speed_max = dc;
+		mts->deceleration = 0;
+		mts->taccel = 0;
+		mts->tdecel = 0;
+		mts->speed_start = 0;
+		mts->speed_end = 0;
+	}
+	spin_unlock_irqrestore(&mts->lock, flags);
+	if (ret)
+		return ret;
+
+	hrtimer_start(&mts->timer, MOTION_TIMER_PERIOD, HRTIMER_MODE_REL_SOFT);
+
+	return ret;
+}
+
+static int motion_timed_speed_validate_profile(struct motion_device *mdev,
+		struct mot_profile *p)
+{
+	struct motion_timed_speed *mts =
+		(struct motion_timed_speed *)mdev->helper_cookie;
+
+	if ((p->na != 2) || (p->nv != 3))
+		return -EINVAL;
+	if ((p->acc[0] <= 0) || (p->acc[1] <= 0))
+		return -EINVAL;
+	if ((p->vel[0] > p->vel[1]) || (p->vel[2] > p->vel[1]))
+		return -EINVAL;
+	if ((p->vel[0] < 0) || (p->vel[1] <= 0) || (p->vel[2] < 0))
+		return -EINVAL;
+	if (p->vel[1] > mts->speed_full_scale)
+		return -EINVAL;
+	return 0;
+}
+
+static int motion_timed_speed_set_profile(struct motion_device *mdev,
+		struct mot_profile *p)
+{
+	struct motion_timed_speed *mts =
+		(struct motion_timed_speed *)mdev->helper_cookie;
+	unsigned long flags;
+	unsigned int smd;
+	unsigned int esd;
+
+	spin_lock_irqsave(&mts->lock, flags);
+	mts->speed_start = p->vel[0];
+	mts->speed_max = p->vel[1];
+	mts->speed_end = p->vel[2];
+	mts->deceleration = p->acc[1];
+	smd = mts->speed_max - mts->speed_start;
+	esd = mts->speed_max - mts->speed_end;
+	mts->taccel = div_u64((u64)smd * NSEC_PER_SEC, p->acc[0]);
+	mts->tdecel = div_u64((u64)esd * NSEC_PER_SEC, mts->deceleration);
+	spin_unlock_irqrestore(&mts->lock, flags);
+
+	return 0;
+}
+
+static void motion_timed_with_index(struct motion_device *mdev,
+		unsigned int index, int dir, ktime_t t)
+{
+	struct motion_timed_speed *mts =
+		(struct motion_timed_speed *)mdev->helper_cookie;
+
+	motion_timed_speed_set_profile(mdev, &mdev->profiles[index]);
+	mts->ops->set_speed(mdev, dir, mts->speed_start);
+	mts->speed_actual = mts->speed_start;
+	mts->dir = dir;
+	mts->duration = t;
+	mts->ts_start = ktime_get();
+}
+
+static int calc_speed(struct motion_timed_speed *mts, ktime_t now, ktime_t trem)
+{
+	int smd = mts->speed_max - mts->speed_actual;
+	int dva = mts->speed_max - mts->speed_start;
+	int dvd = mts->speed_actual - mts->speed_end;
+	ktime_t tel = ktime_sub(now, mts->ts_start);
+
+	if (trem <= 0)
+		return 0;
+
+	mts->tdecel = mts->deceleration ?
+		      div_u64((u64)dvd * NSEC_PER_SEC, mts->deceleration) : 0;
+
+	if ((smd <= 0) && (ktime_compare(trem, mts->tdecel) > 0))
+		return mts->speed_max;
+
+	/* Due to (trem > 0), zerodivision can't happen here */
+	if (ktime_compare(trem, mts->tdecel) < 0)
+		return mts->speed_end + div64_s64((dvd * trem), mts->tdecel);
+
+	/* Due to (tel > 0) zerodivision can't happen here */
+	if (ktime_compare(tel, mts->taccel) < 0)
+		return mts->speed_start + div64_s64((dva * tel), mts->taccel);
+
+	return mts->speed_actual;
+}
+
+static enum hrtimer_restart motion_timed_speed_timer(struct hrtimer *timer)
+{
+	struct motion_timed_speed *mts = container_of(timer,
+			struct motion_timed_speed, timer);
+	struct motion_device *mdev = mts->mdev;
+	struct mot_event evt = {0};
+	unsigned long flags;
+	ktime_t now = ktime_get();
+	ktime_t trem = ktime_sub(ktime_add(mts->ts_start, mts->duration), now);
+	int speed;
+	int ret = HRTIMER_RESTART;
+
+	spin_lock_irqsave(&mts->lock, flags);
+	speed = calc_speed(mts, now, trem);
+	if (speed != mts->speed_actual) {
+		mts->ops->set_speed(mdev, mts->dir, speed);
+		mts->speed_actual = speed;
+		mts->dir = mts->dir;
+	}
+	spin_unlock_irqrestore(&mts->lock, flags);
+	if (trem <= 0) {
+		mutex_lock(&mdev->mutex);
+		if (mts->next_duration) {
+			motion_timed_with_index(mdev, mts->next_index,
+					mts->next_dir, mts->next_duration);
+			mts->next_duration = 0;
+		} else {
+			ret = HRTIMER_NORESTART;
+		}
+		evt.speed = __to_signed_speed(mts->dir, mts->speed_actual);
+		evt.timestamp = ktime2mot_time(now);
+		evt.event = MOT_EVENT_TARGET;
+		motion_report_event(mdev, &evt);
+		mutex_unlock(&mdev->mutex);
+	}
+
+	if (ret == HRTIMER_RESTART)
+		hrtimer_add_expires_ns(timer, MOTION_TIMER_PERIOD);
+
+	return ret;
+}
+
+static int motion_timed_speed_motion_timed(struct motion_device *mdev, unsigned int ch,
+			unsigned int index, unsigned int dir, ktime_t t,
+			unsigned int when)
+{
+	struct motion_timed_speed *mts =
+		(struct motion_timed_speed *)mdev->helper_cookie;
+	int ret = 0;
+
+	ret = mts->ops->check_speed(mdev, dir, 0);
+	if (ret)
+		return -EINVAL;
+
+	switch (when) {
+	case MOT_WHEN_NEXT:
+		if (mts->next_duration) {
+			ret = -EAGAIN;
+		} else {
+			mts->next_duration = t;
+			mts->next_index = index;
+			mts->next_dir = dir;
+		}
+		break;
+	case MOT_WHEN_EXT_TRIGGER:
+		if (mts->ext_trg_duration) {
+			ret = -EAGAIN;
+		} else {
+			mts->ext_trg_duration = t;
+			mts->ext_trg_index = index;
+			mts->ext_trg_dir = dir;
+		}
+		break;
+	case MOT_WHEN_IMMEDIATE:
+		motion_timed_with_index(mdev, index, dir, t);
+		hrtimer_start(&mts->timer, MOTION_TIMER_PERIOD,
+				HRTIMER_MODE_REL_SOFT);
+		break;
+	default:
+		ret = -EINVAL;
+		break;
+	}
+
+	return ret;
+}
+
+static int motion_timed_speed_motion_stop(struct motion_device *mdev, channel_mask_t ch,
+		unsigned int when)
+{
+	struct motion_timed_speed *mts =
+		(struct motion_timed_speed *)mdev->helper_cookie;
+	unsigned long flags;
+
+	if (when != MOT_WHEN_IMMEDIATE)
+		return -EINVAL;
+
+	spin_lock_irqsave(&mts->lock, flags);
+	if (hrtimer_active(&mts->timer)) {
+		mts->duration = mts->tdecel;
+		mts->ts_start = ktime_get();
+	}
+	spin_unlock_irqrestore(&mts->lock, flags);
+
+	return 0;
+}
+
+static void motion_timed_speed_ext_trigger(struct motion_device *mdev, unsigned int index,
+		channel_mask_t ch)
+{
+	struct motion_timed_speed *mts =
+		(struct motion_timed_speed *)mdev->helper_cookie;
+
+	if (mts->ext_trg_duration) {
+		hrtimer_cancel(&mts->timer);
+
+		motion_timed_with_index(mdev, mts->ext_trg_index,
+				mts->ext_trg_dir, mts->ext_trg_duration);
+		mts->ext_trg_duration = 0;
+		hrtimer_start(&mts->timer, MOTION_TIMER_PERIOD,
+				HRTIMER_MODE_REL_SOFT);
+	}
+}
+
+static struct motion_ops motion_timed_speed_motion_ops = {
+	.device_open = motion_timed_speed_open,
+	.device_release = motion_timed_speed_release,
+	.get_status = motion_timed_speed_get_status,
+	.basic_run = motion_timed_speed_basic_run,
+	.basic_stop = motion_timed_speed_basic_stop,
+	.move_timed = motion_timed_speed_move_timed,
+	.validate_profile = motion_timed_speed_validate_profile,
+	.set_profile = motion_timed_speed_set_profile,
+	.motion_timed = motion_timed_speed_motion_timed,
+	.motion_stop = motion_timed_speed_motion_stop,
+	.external_trigger = motion_timed_speed_ext_trigger
+};
+
+/**
+ * motion_timed_speed_init - Initialize a simple timed-speed motion device
+ * @mdev: Motion device that shall be initialized
+ * @ops: API functions provided by driver
+ * @full_scale: The maximum integer value for "full speed" for this device
+ *
+ * Allows a motion control driver that only has a means of adjusting motor
+ * speed and optionally -direction to augment its functionality to support
+ * trapezoidal motion profiles.
+ *
+ * Caller should create a struct motion_device and, populate
+ * capabilities.type, capabilities.subdiv and optionally the scaling factors
+ * and then call this function, which will add mdev->ops and fill in the
+ * rest. It is responsibility of the driver to call motion_register_device()
+ * afterwards.
+ *
+ * Return: 0 in case of success or a negative errno.
+ */
+int motion_timed_speed_init(struct motion_device *mdev,
+		struct motion_timed_speed_ops *ops, unsigned int full_scale)
+{
+	struct motion_timed_speed *mts;
+
+	mts = devm_kzalloc(mdev->parent, sizeof(struct motion_timed_speed),
+			GFP_KERNEL);
+	if (!mts)
+		return -ENOMEM;
+
+	mts->ops = ops;
+	mts->mdev = mdev;
+	mts->speed_full_scale = full_scale;
+	mdev->ops = motion_timed_speed_motion_ops;
+	mdev->capabilities.features |= MOT_FEATURE_SPEED | MOT_FEATURE_ACCEL |
+	    MOT_FEATURE_PROFILE;
+	mdev->capabilities.num_channels = 1;
+	mdev->capabilities.max_apoints = 2;
+	mdev->capabilities.max_vpoints = 3;
+	mdev->capabilities.num_int_triggers = 0;
+	mdev->capabilities.num_ext_triggers = 0; /* Filled in by core */
+	mdev->capabilities.subdiv = 1;
+	mdev->helper_cookie = mts;
+
+	spin_lock_init(&mts->lock);
+	hrtimer_init(&mts->timer, CLOCK_MONOTONIC, HRTIMER_MODE_REL_SOFT);
+	mts->timer.function = motion_timed_speed_timer;
+
+	return 0;
+}
+EXPORT_SYMBOL(motion_timed_speed_init);
+
+/**
+ * motion_fwnode_get_capabilities - Get motion specific properties from fwnode
+ * @mdev: Motion device to populate
+ * @fwnode: fwnode handle to read properties from.
+ *
+ * Reads motion specific properties from @fwnode and populates @mdev
+ * capabilities.
+ */
+void motion_fwnode_get_capabilities(struct motion_device *mdev,
+		struct fwnode_handle *fwnode)
+{
+	unsigned int val, err;
+
+	err = fwnode_property_read_u32(fwnode, "motion,speed-conv-mul", &val);
+	if (!err)
+		mdev->capabilities.speed_conv_mul = val;
+	err = fwnode_property_read_u32(fwnode, "motion,speed-conv-div", &val);
+	if (!err && val)
+		mdev->capabilities.speed_conv_div = val;
+	err = fwnode_property_read_u32(fwnode, "motion,acceleration-conv-mul", &val);
+	if (!err)
+		mdev->capabilities.accel_conv_mul = val;
+	err = fwnode_property_read_u32(fwnode, "motion,acceleration-conv-div", &val);
+	if (!err && val)
+		mdev->capabilities.accel_conv_div = val;
+}
+EXPORT_SYMBOL(motion_fwnode_get_capabilities);
+
+static inline int __d2t_vmax(u64 a, u64 d, u32 Vmax32, u64 Vs, u64 Ve, u64 Xt,
+		u64 t2, u64 *Vs2, u64 *Ve2, ktime_t *t)
+{
+	u64 Vmax = (u64)Vmax32;
+	u64 Vm2 = Vmax * Vmax32;
+	u64 dva = Vmax32 - Vs;
+	u64 dvd = Vmax32 - Ve;
+	u64 ta = div_u64(dva * MSEC_PER_SEC, (u32)a);
+	u64 td = div_u64(dvd * MSEC_PER_SEC, (u32)d);
+	u64 X1;
+	u64 X3;
+	u64 Xtv = div_u64(Vmax * t2, MSEC_PER_SEC);
+	u64 tms;
+
+	*Vs2 = (u64)Vs * Vs;
+	*Ve2 = (u64)Ve * Ve;
+	X1 = div64_u64(Vm2 - *Vs2, a << 1);
+	X3 = div64_u64(Vm2 - *Ve2, d << 1);
+
+	/* Check if we can reach Vmax. If not try again with new Vmax */
+	if (Xt > (X1 + X3 + Xtv)) {
+		tms = ta + td;
+		tms += div_u64(MSEC_PER_SEC * (Xt - X1 - X3), Vmax32);
+		*t = ktime_add_ms(0, tms);
+		return 0;
+	}
+
+	return -EAGAIN;
+}
+
+/**
+ * motion_distance_to_time - Convert distance to time period
+ * @mdev: Motion device
+ * @index: The index of the motion profile to use
+ * @distance: The covered distance of the complete movement
+ * @t: Pointer to ktime_t result
+ *
+ * Converts the @distance of a movement using a motion (acceleration) profile
+ * specified by @index into a time interval this movement would take.
+ *
+ * The only supported profile type is trapezoidal (3 velocity points and 2
+ * acceleration values), and it takes into account Tvmax and the case where
+ * Vmax cannot be reached because the distance is too short.
+ *
+ * Return: 0 on success and -ENOTSUPP if profile is not trapezoidal.
+ */
+long motion_distance_to_time(struct motion_device *mdev,
+		unsigned int index, int distance, ktime_t *t)
+{
+	struct mot_profile *p = &mdev->profiles[index];
+	unsigned int Vs = p->vel[0];
+	unsigned int Ve = p->vel[2];
+	u64 Vmax;
+	u64 a = p->acc[0]; /* Has been checked to be non-zero */
+	u64 d = p->acc[1]; /* Has been checked to be non-zero */
+	u64 Xt = abs(distance);
+	u64 t2 = ktime_to_ms(p->tvmax);
+	u64 Ve2, Vs2, Bt, disc;
+	s64 ACt;
+	unsigned int bl;
+
+	if ((p->na != 2) || (p->nv != 3))
+		return -EOPNOTSUPP;
+
+	if (!__d2t_vmax(a, d, p->vel[1], Vs, Ve, Xt, t2, &Vs2, &Ve2, t))
+		return 0;
+
+	/*
+	 * We can't reach Vmax, so we need to determine Vmax that
+	 * satisfies tvmax and distance, given a and d.
+	 * For that we need to solve a quadratic equation in the form:
+	 *
+	 * 0 = Vm^2*(1/2a + 1/2d) + Vm * tvmax - Vs^2/2a - Ve^2/2d - Xt
+	 *
+	 * Doing this with only 64-bit integers will require scaling to
+	 * adequate bit-lengths and an inevitable loss of precision.
+	 * Precision is not critical since this function will be used
+	 * to approximate a mechanical movement's distance by timing.
+	 */
+	bl = fls(a) + fls(d) + fls(Ve) + fls(Vs);
+	bl = max(0, (bl >> 1) - 16);
+	Bt = div_u64(a * d * t2, MSEC_PER_SEC);
+
+	/*
+	 * All terms are shifted left by bl bits *twice* (!)
+	 * This will go into the square-root, so the result needs to be
+	 * shifted right by bl bits only *once*.
+	 */
+	ACt = -((a*a) >> bl)*(Ve2 >> bl) - ((d*d) >> bl)*(Vs2 >> bl) -
+	      ((a*d) >> bl)*((2*d*Xt + 2*a*Xt + Vs2 + Ve2) >> bl);
+	disc = (Bt >> bl) * (Bt >> bl) - ACt;
+	if (disc < 0) {
+		/* This should not be possible if (Ve, Vs) < Vm */
+		WARN_ONCE(true, "Discriminator is negative!");
+		disc = 0;
+	}
+
+	/*
+	 * We have all the parts of the quadratic formula, so we can
+	 * calculate Vmax. There are some constraints we can take
+	 * for granted here:
+	 *  - The term 4AC (ACt) is strictly negative, so the
+	 *    discriminant will always be bigger than Bt^2.
+	 *  - Due to this, the result of the square root will be
+	 *    bigger than Bt, which means there will always be one
+	 *    positive real solution for Vmax.
+	 *  - The dividend (a + d) cannot be zero, since a and d are
+	 *    both tested to be positive and non zero in
+	 *    motion_set_profile().
+	 */
+	 /* NOLINTNEXTLINE(clang-analyzer-core.DivideZero) */
+	Vmax = div64_u64(-Bt + ((u64)int_sqrt64(disc) << bl), a + d);
+	Ve = min(Ve, Vmax);
+	Vs = min(Vs, Vmax);
+	dev_info(mdev->dev, "D2T: Vs=%u, Vmax=%llu, Ve=%u\n", Vs, Vmax, Ve);
+
+	/* Try again with new Vmax. This time will always succeed. */
+	__d2t_vmax(a, d, Vmax, Vs, Ve, Xt, t2, &Vs2, &Ve2, t);
+
+	return 0;
+}
+EXPORT_SYMBOL(motion_distance_to_time);
diff --git a/drivers/motion/motion-helpers.h b/drivers/motion/motion-helpers.h
new file mode 100644
index 000000000000..0752390bf33a
--- /dev/null
+++ b/drivers/motion/motion-helpers.h
@@ -0,0 +1,23 @@
+/* SPDX-License-Identifier: GPL-2.0-only */
+#ifndef __MOTION_HELPERS_H__
+#define __MOTION_HELPERS_H__
+
+#include "motion-core.h"
+
+struct motion_timed_speed_ops {
+	void (*set_speed)(struct motion_device *mdev, unsigned int dir,
+			unsigned int speed);
+	int (*check_speed)(struct motion_device *mdev, unsigned int dir,
+			unsigned int speed);
+	void (*startup)(struct motion_device *mdev);
+	void (*powerdown)(struct motion_device *mdev);
+};
+
+int motion_timed_speed_init(struct motion_device *mdev,
+		struct motion_timed_speed_ops *ops, unsigned int full_scale);
+void motion_fwnode_get_capabilities(struct motion_device *mdev,
+		struct fwnode_handle *fwnode);
+long motion_distance_to_time(struct motion_device *mdev,
+		unsigned int index, int distance, ktime_t *t);
+
+#endif /* __MOTION_HELPERS_H__ */
diff --git a/include/uapi/linux/motion.h b/include/uapi/linux/motion.h
new file mode 100644
index 000000000000..72a7e564114d
--- /dev/null
+++ b/include/uapi/linux/motion.h
@@ -0,0 +1,229 @@
+/* SPDX-License-Identifier: GPL-2.0+ WITH Linux-syscall-note */
+#ifndef _UAPI_LINUX_MOTION_H
+#define _UAPI_LINUX_MOTION_H
+
+#include <linux/const.h>
+#include <linux/ioctl.h>
+#include <linux/types.h>
+
+/* NOTE: Proposing to use IOC 'M' seq 0x80-0xc0 */
+
+#define MOT_MAX_PROFILES 32
+#define MOT_MAX_SPEEDPTS 5
+#define MOT_MAX_ACCELPTS 6
+#define MOT_MAX_INPUTS 32
+#define MOT_UAPI_VERSION 1
+
+/* Trigger inputs and End Stop functions */
+enum {
+	MOT_INP_FUNC_NONE = 0,	/* No-op, used to clear previous functions */
+	MOT_INP_FUNC_STOP,	/* Stop immediately */
+	MOT_INP_FUNC_STOP_POS,	/* Stop immediately if moving forward */
+	MOT_INP_FUNC_STOP_NEG,	/* Stop immediately if moving backward */
+	MOT_INP_FUNC_DECEL,	/* Stop by deceleration curve */
+	MOT_INP_FUNC_DECEL_POS,
+	MOT_INP_FUNC_DECEL_NEG,
+	MOT_INP_FUNC_START,	/* Start motion with preset profile */
+	MOT_INP_FUNC_SIGNAL,	/* Only produce a signal (EPOLLIN) */
+	MOT_INP_FUNC_NUM_FUNCS
+};
+
+/* Config trigger input edge */
+#define MOT_EDGE_RISING 0
+#define MOT_EDGE_FALLING 1
+
+/* Start/Stop conditions */
+enum {
+	MOT_WHEN_IMMEDIATE = 0,
+	MOT_WHEN_INT_TRIGGER,	/* On internal trigger input */
+	MOT_WHEN_EXT_TRIGGER,	/* On external trigger input */
+	MOT_WHEN_NEXT,		/* After preceding (current) motion ends */
+	MOT_WHEN_NUM_WHENS
+};
+
+/* Event types */
+enum {
+	MOT_EVENT_NONE = 0,
+	MOT_EVENT_TARGET,	/* Target position reached */
+	MOT_EVENT_STOP,		/* Endstop triggered */
+	MOT_EVENT_INPUT,	/* (Virtual-) input event */
+	MOT_EVENT_STALL,	/* Motor stalled */
+	MOT_EVENT_ERROR,	/* Other motor drive error */
+	MOT_EVENT_NUM_EVENTS
+};
+
+#define MOT_DIRECTION_LEFT 0
+#define MOT_DIRECTION_RIGHT 1
+
+/* Convention of signed position, speed and acceleration:
+ * movement of one channel is unidimensional, meaning position can be above or
+ * below the origin (positive or negative respecively). Consequently, given
+ * a positive position, a positive speed represents a movement further away
+ * from the origin (position 0), while a negative speed value represents a
+ * movement towards the origin. The opposite is valid when starting from a
+ * negative position value.
+ * Analogous to what speed does to position, is what acceletation does to speed:
+ * Given positive speed, positive acceleration increments the speed, and given
+ * "negative" speed, negative acceleration decrements the speed (increments its
+ * absolute value).
+ * For movement profiles, the convention is that profile (acceleration-, speed-)
+ * values are strictly positive. The direction of movement is solely determined
+ * by the relative position (i.e. "positive" or "negative" displacement).
+ */
+typedef __u32 channel_mask_t;
+typedef __s32 pos_raw_t;
+typedef __s32 speed_raw_t;
+typedef __s32 accel_raw_t;
+typedef __u32 torque_raw_t;
+typedef __s64 mot_time_t; /* Try to mimic ktime_t, unit is nanoseconds. */
+
+#define MOT_FEATURE_SPEED	BIT(0)
+#define MOT_FEATURE_ACCEL	BIT(1)
+#define MOT_FEATURE_ENCODER	BIT(2)
+#define MOT_FEATURE_PROFILE	BIT(3)
+#define MOT_FEATURE_VECTOR	BIT(4)
+
+enum motion_device_type {
+	MOT_TYPE_DC_MOTOR,
+	MOT_TYPE_AC_MOTOR,
+	MOT_TYPE_STEPPER,
+	MOT_TYPE_BLDC,
+	MOT_TYPE_SRM,
+	MOT_TYPE_LINEAR,
+	MOT_TYPE_NUM_TYPES
+};
+
+struct mot_capabilities {
+	__u32 features;
+	__u8 type;
+	__u8 num_channels;
+	__u8 num_int_triggers;
+	__u8 num_ext_triggers;
+	__u8 max_profiles;
+	__u8 max_vpoints;
+	__u8 max_apoints;
+	__u8 reserved1;
+	__u32 subdiv; /* Position unit sub-divisions, microsteps, etc... */
+	/*
+	 * Coefficients for converting to/from controller time <--> seconds.
+	 * Speed[1/s] = Speed[controller_units] * conv_mul / conv_div
+	 * Accel[1/s^2] = Accel[controller_units] * conv_mul / conv_div
+	 */
+	__u32 speed_conv_mul;
+	__u32 speed_conv_div;
+	__u32 accel_conv_mul;
+	__u32 accel_conv_div;
+	__u32 reserved2;
+};
+
+struct mot_speed_duration {
+	__u32 channel;
+	speed_raw_t speed;
+	mot_time_t duration;
+	pos_raw_t distance;
+	__u32 reserved[3];
+};
+
+struct mot_status {
+	__u32 channel;
+	pos_raw_t position;
+	speed_raw_t speed;
+	__u32 reserved;
+};
+
+struct mot_input {
+	__u32 index;
+	__u8 external;
+	__u8 edge;
+	__u8 reserved[2];
+	__u32 function;
+	channel_mask_t chmask;
+};
+
+/**
+ * struct mot_profile - Describe an acceleration profile
+ * @index: The index into the table of profiles to change
+ * @tvmax: Minimum time to stay at maximum velocity
+ * @tvzero: Minimum time to stay at zero velocity
+ * @na: Number of acceleration values
+ * @nv: Number of velocity values
+ * @acc: List of acceleration values. All values are absolute machine units.
+ * @vel: List of velocity values. All values are absolure machine units.
+ *
+ * 3 different types of acceleration curves are supported:
+ * 1. Trapezoidal - comprised of 3 velocity values and 2 acceleration values.
+ *    Motion starts at start velocity (vel[0]) and accelerates with acc[0]
+ *    linearly up to maximum velocity vel[1]. Maximum velocity is maintained
+ *    for at least tvmax, before decelerating with acc[1] down to stop
+ *    velocity vel[2]. After that velocity drops to zero and stays there for
+ *    at least tvzero.
+ *
+ * 2. Dual slope - comprised of 4 velocity values and 4 acceleration values.
+ *    Similar to trapezoidal profile above, but adding an intermediate
+ *    velocity vel[1]. acc[0] is the first acceleration slope between
+ *    vel[0] and vel[1]. acc[1] is the second acceleration slope between
+ *    vel[1] and vel[2] (maximum velocity). acc[2] is the first deceleration
+ *    slope between vel[2] and vel[1], and acc[3] is the final deceleration
+ *    slope between vel[1] and vel[3].
+ *
+ * 3. S-curve profile - Most advanced profile, often also called 8-point
+ *    profile, comprised of 5 velocity values and 6 acceleration values.
+ */
+struct mot_profile {
+	__u32 index;
+	mot_time_t tvmax;
+	mot_time_t tvzero;
+	__u8 na;
+	__u8 nv;
+	__u8 reserved[2];
+	accel_raw_t acc[MOT_MAX_ACCELPTS];
+	speed_raw_t vel[MOT_MAX_SPEEDPTS];
+};
+
+struct mot_start {
+	__u32 channel;
+	__u8 direction;
+	__u8 index;
+	__u8 when;
+	__u8 reserved1;
+	mot_time_t duration;
+	pos_raw_t distance;
+	__u32 reserved2;
+};
+
+struct mot_stop {
+	channel_mask_t chmask;
+	__u8 when;
+	__u8 reserved[3];
+};
+
+struct mot_event {
+	__u32 channel;
+	__u8 event;
+	__u8 reserved1[3];
+	pos_raw_t position;
+	speed_raw_t speed;
+	mot_time_t timestamp;
+	__u32 input_index;
+	__u32 reserved2;
+};
+
+/* API capabilities interrogation ioctls */
+#define MOT_IOCTL_APIVER		_IO('M', 0x80)
+#define MOT_IOCTL_GET_CAPA		_IOR('M', 0x81, struct mot_capabilities)
+
+/* Basic motion control */
+#define MOT_IOCTL_GET_STATUS		_IOWR('M', 0x82, struct mot_status)
+#define MOT_IOCTL_BASIC_RUN		_IOW('M', 0x83, struct mot_speed_duration)
+#define MOT_IOCTL_BASIC_STOP		_IOW('M', 0x84, __u32)
+
+/* Feedback control */
+#define MOT_IOCTL_CONFIG_INPUT		_IOW('W', 0x85, struct mot_input)
+
+/* Profile control */
+#define MOT_IOCTL_SET_PROFILE		_IOW('M', 0x86, struct mot_profile)
+#define MOT_IOCTL_GET_PROFILE		_IOWR('M', 0x87, struct mot_profile)
+#define MOT_IOCTL_START			_IOW('M', 0x88, struct mot_start)
+#define MOT_IOCTL_STOP			_IOW('M', 0x89, struct mot_stop)
+
+#endif /* _UAPI_LINUX_MOTION_H */
-- 
2.47.2


^ permalink raw reply related	[flat|nested] 59+ messages in thread

* [RFC PATCH 2/7] motion: Add ADI/Trinamic TMC5240 stepper motor controller
  2025-02-27 16:28 [RFC PATCH 0/7] Add Linux Motion Control subsystem David Jander
  2025-02-27 16:28 ` [RFC PATCH 1/7] drivers: Add motion control subsystem David Jander
@ 2025-02-27 16:28 ` David Jander
  2025-02-27 16:28 ` [RFC PATCH 3/7] motion: Add simple-pwm.c PWM based DC motor controller driver David Jander
                   ` (7 subsequent siblings)
  9 siblings, 0 replies; 59+ messages in thread
From: David Jander @ 2025-02-27 16:28 UTC (permalink / raw)
  To: linux-kernel
  Cc: linux-iio, Jonathan Corbet, Rob Herring, Krzysztof Kozlowski,
	Conor Dooley, devicetree, linux-doc, Nuno Sa, Jonathan Cameron,
	Oleksij Rempel, David Jander

The TMC5240 is an advanced stepper motor controller that includes a an
automatic ramp generator and target positioning. This driver makes use of
the Linux Motion Control subsystem. It can use the internal REFl/REFR
end stop inputs as trigger events and exposes setup and configuration
parameters as well as target positions of virtual end-stops as sysfs
device attributes.

Signed-off-by: David Jander <david@protonic.nl>
---
 MAINTAINERS                 |    5 +
 drivers/motion/Kconfig      |   12 +
 drivers/motion/Makefile     |    1 +
 drivers/motion/tmc5240.c    | 1157 +++++++++++++++++++++++++++++++++++
 include/uapi/linux/motion.h |    2 +-
 5 files changed, 1176 insertions(+), 1 deletion(-)
 create mode 100644 drivers/motion/tmc5240.c

diff --git a/MAINTAINERS b/MAINTAINERS
index 57267584166c..b5801db5cb8e 100644
--- a/MAINTAINERS
+++ b/MAINTAINERS
@@ -1628,6 +1628,11 @@ F:	drivers/iio/amplifiers/hmc425a.c
 F:	drivers/staging/iio/*/ad*
 X:	drivers/iio/*/adjd*
 
+ANALOG DEVICES INC TMC5240 MOTION DRIVER
+M:	David Jander <david@protonic>
+S:	Maintained
+F:	drivers/motion/tmc5240.c
+
 ANALOGBITS PLL LIBRARIES
 M:	Paul Walmsley <paul.walmsley@sifive.com>
 M:	Samuel Holland <samuel.holland@sifive.com>
diff --git a/drivers/motion/Kconfig b/drivers/motion/Kconfig
index 085f9647b47b..7715301c667e 100644
--- a/drivers/motion/Kconfig
+++ b/drivers/motion/Kconfig
@@ -11,6 +11,18 @@ menuconfig MOTION
 
 if MOTION
 
+
+config TMC5240
+	tristate "TMC5240 stepper motor driver"
+	depends on SPI
+	select REGMAP_SPI
+	help
+	  Say Y here if you have an Analog Devices TMC5240 stepper
+	  motor controller.
+
+	  To compile this driver as a module, choose M here: the
+	  module will be called tmc5240.
+
 config MOTION_HELPERS
 	bool
 	depends on MOTION
diff --git a/drivers/motion/Makefile b/drivers/motion/Makefile
index ed912a8ed605..4f4e31138503 100644
--- a/drivers/motion/Makefile
+++ b/drivers/motion/Makefile
@@ -1,3 +1,4 @@
 # SPDX-License-Identifier: GPL-2.0
 obj-$(CONFIG_MOTION)		+= motion-core.o
 obj-$(CONFIG_MOTION_HELPERS)	+= motion-helpers.o
+obj-$(CONFIG_TMC5240)		+= tmc5240.o
diff --git a/drivers/motion/tmc5240.c b/drivers/motion/tmc5240.c
new file mode 100644
index 000000000000..a6723b8ce66b
--- /dev/null
+++ b/drivers/motion/tmc5240.c
@@ -0,0 +1,1157 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * TMC5240 Stepper motor controller driver
+ *
+ * Copyright (C) 2024 Protonic Holland
+ *      David Jander <david@protonic.nl>
+ */
+
+#include <linux/bug.h>
+#include <asm-generic/errno-base.h>
+#include <linux/bitfield.h>
+#include <linux/array_size.h>
+#include <linux/delay.h>
+#include <linux/module.h>
+#include <linux/motion.h>
+#include <linux/regulator/consumer.h>
+#include <linux/spi/spi.h>
+#include <linux/gfp_types.h>
+#include <linux/types.h>
+#include <linux/regmap.h>
+#include <linux/clk.h>
+#include <asm/unaligned.h>
+
+#include "motion-core.h"
+
+/* General Configuration Registers */
+#define TMC_REG_GCONF		0x00
+#define TMC_REG_GSTAT		0x01
+#define TMC_REG_IFCNT		0x02
+#define TMC_REG_NODECONF	0x03
+#define TMC_REG_IOIN		0x04
+#define TMC_IOIN_VERSION_MASK	GENMASK(31, 24)
+#define TMC_IOIN_REVISION_MASK	GENMASK(18, 16)
+#define TMC_REG_X_COMPARE	0x05
+#define TMC_REG_X_COMPARE_REP	0x06
+#define TMC_REG_DRV_CONF	0x0a
+#define TMC_DRV_CURRENT_RANGE	GENMASK(1, 0)
+#define TMC_DRV_SLOPE_CONTROL	GENMASK(5, 4)
+#define TMC_REG_GLOBAL_SCALER	0x0b
+/* Velocity Dependent Configuration Registers */
+#define TMC_REG_IHOLD_IRUN	0x10
+#define TMC_IHOLD_IRUNDELAY	GENMASK(27, 24)
+#define TMC_IHOLD_IHOLDDELAY	GENMASK(19, 16)
+#define TMC_IHOLD_IRUN		GENMASK(12, 8)
+#define TMC_IHOLD_IHOLD		GENMASK(4, 0)
+#define TMC_REG_TPOWERDOWN	0x11
+#define TMC_REG_TSTEP		0x12
+#define TMC_REG_TPWMTHRS	0x13
+#define TMC_REG_TCOOLTHRS	0x14
+#define TMC_REG_THIGH		0x15
+/* Ramp Generator Registers */
+#define TMC_REG_RAMPMODE	0x20
+#define TMC_RAMPMODE_POSITION	0
+#define TMC_RAMPMODE_POS_VEL	1
+#define TMC_RAMPMODE_NEG_VEL	2
+#define TMC_RAMPMODE_HOLD	3
+#define TMC_REG_XACTUAL		0x21
+#define TMC_REG_VACTUAL		0x22
+#define TMC_VACTUAL_SIGN_BIT	23
+#define TMC_VACTUAL_MASK	GENMASK(TMC_VACTUAL_SIGN_BIT, 0)
+#define TMC_REG_VSTART		0x23
+#define TMC_REG_A1		0x24
+#define TMC_REG_V1		0x25
+#define TMC_REG_AMAX		0x26
+#define TMC_MAX_ACCELERATION	GENMASK(17, 0)
+#define TMC_REG_VMAX		0x27
+#define TMC_REG_DMAX		0x28
+#define TMC_REG_TVMAX		0x29
+#define TMC_REG_D1		0x2a
+#define TMC_D1_MIN		10
+#define TMC_REG_VSTOP		0x2b
+#define TMC_VSTOP_MIN		10
+#define TMC_REG_TZEROWAIT	0x2c
+#define TMC_REG_XTARGET		0x2d
+#define TMC_REG_V2		0x2e
+#define TMC_REG_A2		0x2f
+#define TMC_REG_D2		0x30
+#define TMC_D2_MIN		10
+/* Ramp Generator Driver Feature Control Registers */
+#define TMC_REG_VDCMIN		0x33
+#define TMC_REG_SW_MODE		0x34
+#define TMC_SW_VIRT_STOP_ENC	BIT(14)
+#define TMC_SW_EN_VIRT_STOP_R	BIT(13)
+#define TMC_SW_EN_VIRT_STOP_L	BIT(12)
+#define TMC_SW_EN_SOFTSTOP	BIT(11)
+#define TMC_SW_LATCH_R_ACTIVE	BIT(7)
+#define TMC_SW_LATCH_L_ACTIVE	BIT(5)
+#define TMC_SW_SWAP_LR		BIT(4)
+#define TMC_SW_STOP_R_POL	BIT(3)
+#define TMC_SW_STOP_L_POL	BIT(2)
+#define TMC_SW_STOP_R_ENABLE	BIT(1)
+#define TMC_SW_STOP_L_ENABLE	BIT(0)
+#define TMC_REG_RAMP_STAT	0x35
+#define TMC_RAMP_VIRT_R		BIT(15)
+#define TMC_RAMP_VIRT_L		BIT(14)
+#define TMC_VIRT_STOPS_MASK	GENMASK(15, 14)
+#define TMC_RAMP_SECOND_MOVE	BIT(12)
+#define TMC_RAMP_POS_REACHED	BIT(7)
+#define TMC_RAMP_STOP_SG	BIT(6)
+#define TMC_RAMP_STOP_R		BIT(5)
+#define TMC_RAMP_STOP_L		BIT(4)
+#define TMC_RAMP_LATCH_R	BIT(3)
+#define TMC_RAMP_LATCH_L	BIT(2)
+#define TMC_RAMP_ST_STOP_R	BIT(1)
+#define TMC_RAMP_ST_STOP_L	BIT(0)
+#define TMC_STOPS_MASK		GENMASK(1, 0)
+#define TMC_RAMP_CLEAR_FLAGS	(TMC_RAMP_SECOND_MOVE | TMC_RAMP_POS_REACHED | \
+		TMC_RAMP_STOP_SG | TMC_RAMP_LATCH_R | TMC_RAMP_LATCH_L)
+#define TMC_REG_XLATCH		0x36
+/* Encoder registers */
+#define TMC_REG_ENCMODE		0x38
+#define TMC_REG_X_ENC		0x39
+#define TMC_REG_ENC_CONST	0x3a
+#define TMC_REG_ENC_STATUS	0x3b
+#define TMC_REG_ENC_LATCH	0x3c
+#define TMC_REG_ENC_DEVIATION	0x3d
+#define TMC_REG_VIRTUAL_STOP_L	0x3e
+#define TMC_REG_VIRTUAL_STOP_R	0x3f
+/* ADC Registers */
+#define TMC_REG_ADC_VSUPLLY_AIN	0x50
+#define TMC_REG_ADC_TEMP	0x51
+#define TMC_REG_OTW_OV_VTH	0x52
+/* Motoro Driver Registers */
+#define TMC_REG_MSLUT(X)	(0x60+X)
+#define TMC_REG_MSLUTSEL	0x68
+#define TMC_REG_MSLUTSTART	0x69
+#define TMC_REG_MSCNT		0x6a
+#define TMC_REG_MSCURACT	0x6b
+#define TMC_REG_CHOPCONF	0x6c
+#define TMC_CHOP_DISS2VS	BIT(31)
+#define TMC_CHOP_DISS2G		BIT(30)
+#define TMC_CHOP_INTPOL		BIT(28)
+#define TMC_CHOP_MRES		GENMASK(27, 24)
+#define TMC_CHOP_TPFP		GENMASK(23, 20)
+#define TMC_CHOP_VHIGHCHM	BIT(19)
+#define TMC_CHOP_VHIGHFS	BIT(18)
+#define TMC_CHOP_TBL		GENMASK(16, 15)
+#define TMC_CHOP_CHM		BIT(14)
+#define TMC_CHOP_DISFDCC	BIT(12)
+#define TMC_CHOP_FD3		BIT(11)
+#define TMC_CHOP_HEND_OFFSET	GENMASK(10, 7)
+#define TMC_CHOP_HSTRT_TFD210	GENMASK(6, 4)
+#define TMC_CHOP_TOFF		GENMASK(3, 0)
+#define TMC_REG_COOLCONF	0x6d
+#define TMC_REG_DCCTRL		0x6e
+#define TMC_REG_DRV_STATUS	0x6f
+#define TMC_REG_PWMCONF		0x70
+#define TMC_REG_PWM_SCALE	0x71
+#define TMC_REG_PWM_AUTO	0x72
+#define TMC_REG_SG4_THRS	0x74
+#define TMC_REG_SG4_RESULT	0x75
+#define TMC_REG_SG4_IND		0x76
+
+/*
+ * Internal triggers: REFL, REFR, VIRTL, VIRTR and X_COMPARE
+ * FIXME: For now X_COMPARE is not yet supported
+ */
+enum {
+	TMC_STOP_REFL = 0,
+	TMC_STOP_REFR,
+	TMC_STOP_VIRTL,
+	TMC_STOP_VIRTR,
+	TMC_MAX_INTERNAL_STOPS
+};
+
+struct tmc_spi_buf {
+	u8 buf[5];
+} ____cacheline_aligned;
+
+struct tmc5240 {
+	struct spi_device *spi;
+	struct motion_device mdev;
+	struct spi_transfer wxfer;
+	struct spi_transfer rxfers[2];
+	struct spi_message wmsg;
+	struct spi_message rmsg;
+	struct tmc_spi_buf rtxbuf[2]; /* read buffers contain 2 40bit transfers */
+	struct tmc_spi_buf rrxbuf[2];
+	struct tmc_spi_buf wtxbuf;
+	struct tmc_spi_buf wrxbuf;
+	struct regmap *map;
+	u8 spi_status;
+	struct clk *clk;
+	u32 clk_rate;
+	bool use_encoder;
+	int current_index;
+	s32 next_dist;
+	unsigned int next_index;
+	s32 int_trig_dist;
+	unsigned int int_trg_index;
+	s32 ext_trig_dist;
+	unsigned int ext_trg_index;
+	ktime_t irq_ts;
+	unsigned int stop_functions[TMC_MAX_INTERNAL_STOPS];
+};
+
+static int tmc5240_read_reg(void *ctx, unsigned int reg, unsigned int *val)
+{
+	struct tmc5240 *tmc = (struct tmc5240 *)ctx;
+	int ret;
+	u8 *rxb0 = &tmc->rrxbuf[0].buf[0];
+	u8 *rxb1 = &tmc->rrxbuf[1].buf[0];
+	u8 *txb0 = &tmc->rtxbuf[0].buf[0];
+	u8 *txb1 = &tmc->rtxbuf[1].buf[0];
+
+	txb0[0] = reg;
+	txb1[0] = reg;
+	ret = spi_sync(tmc->spi, &tmc->rmsg);
+	if (ret)
+		return ret;
+	*val = get_unaligned_be32(&rxb1[1]);
+	tmc->spi_status = rxb0[0];
+
+	return 0;
+}
+
+static int tmc5240_write_reg(void *ctx, unsigned int reg, unsigned int val)
+{
+	struct tmc5240 *tmc = (struct tmc5240 *)ctx;
+	u8 *txb = &tmc->wtxbuf.buf[0];
+
+	txb[0] = reg | 0x80;
+	put_unaligned_be32(val, &txb[1]);
+
+	return spi_sync(tmc->spi, &tmc->wmsg);
+}
+
+/* regmap wrappers */
+static int tmc5240_read(struct tmc5240 *tmc, unsigned int reg, unsigned int *val)
+{
+	int ret = regmap_read(tmc->map, reg, val);
+
+	if (ret)
+		dev_err_ratelimited(tmc->mdev.dev,
+				"Regmap read error %d at reg: %04x.\n",
+				ret, reg);
+	return ret;
+}
+
+static int tmc5240_write(struct tmc5240 *tmc, unsigned int reg, unsigned int val)
+{
+	int ret = regmap_write(tmc->map, reg, val);
+
+	if (ret)
+		dev_err_ratelimited(tmc->mdev.dev,
+				"Regmap write error %d at reg: %04x.\n",
+				ret, reg);
+	return ret;
+}
+
+static int tmc5240_update_bits(struct tmc5240 *tmc, unsigned int reg,
+		unsigned int mask, unsigned int val)
+{
+	int ret = regmap_update_bits(tmc->map, reg, mask, val);
+
+	if (ret)
+		dev_err_ratelimited(tmc->mdev.dev,
+				"Regmap update bits error %d at reg: %04x.\n",
+				ret, reg);
+	return ret;
+}
+
+/* FIXME: Maybe make this into MOTION_ATTR_XX() macro's? */
+#define _tmc_attr_show(_name, _reg, _mask) \
+static ssize_t _name##_show(struct device *dev, \
+				    struct device_attribute *dev_attr, \
+				    char *buf) \
+{ \
+	struct motion_device *mdev = dev_get_drvdata(dev); \
+	struct tmc5240 *tmc = container_of(mdev, struct tmc5240, mdev); \
+	unsigned int val; \
+	ssize_t err; \
+	err = tmc5240_read(tmc, _reg, &val); \
+	if (err) \
+		return err; \
+	/* NOLINTNEXTLINE(clang-analyzer-security.insecureAPI*) */ \
+	return sprintf(buf, "%lu\n", FIELD_GET(_mask, val)); \
+}
+
+#define _tmc_attr_store(_name, _reg, _mask) \
+static ssize_t _name##_store(struct device *dev, \
+				     struct device_attribute *dev_attr, \
+				     const char *buf, size_t len) \
+{ \
+	struct motion_device *mdev = dev_get_drvdata(dev); \
+	struct tmc5240 *tmc = container_of(mdev, struct tmc5240, mdev); \
+	unsigned long val; \
+	ssize_t err; \
+	err = kstrtoul(buf, 10, &val); \
+	if (err) \
+		return err; \
+	if (!FIELD_FIT(_mask, val)) \
+		return -EINVAL; \
+	mutex_lock(&mdev->mutex); \
+	err = tmc5240_update_bits(tmc, _reg, _mask, FIELD_PREP(_mask, val)); \
+	mutex_unlock(&mdev->mutex); \
+	if (err) \
+		return err; \
+	return len; \
+}
+
+#define TMC_ATTR_RW(_name, _reg, _mask) \
+	_tmc_attr_show(_name, _reg, _mask) \
+	_tmc_attr_store(_name, _reg, _mask) \
+	static DEVICE_ATTR_RW(_name)
+
+#define TMC_ATTR_RO(_name, _reg, _mask) \
+	_tmc_attr_show(_name, _reg, _mask) \
+	static DEVICE_ATTR_RO(_name)
+
+TMC_ATTR_RW(sw_mode_swap_lr, TMC_REG_SW_MODE, TMC_SW_SWAP_LR);
+TMC_ATTR_RW(drv_conf_current_range, TMC_REG_DRV_CONF, TMC_DRV_CURRENT_RANGE);
+TMC_ATTR_RW(drv_conf_slope_control, TMC_REG_DRV_CONF, TMC_DRV_SLOPE_CONTROL);
+TMC_ATTR_RW(global_scaler, TMC_REG_GLOBAL_SCALER, GENMASK(7, 0));
+TMC_ATTR_RW(t_power_down, TMC_REG_TPOWERDOWN, GENMASK(7, 0));
+TMC_ATTR_RO(t_step, TMC_REG_TSTEP, GENMASK(19, 0));
+TMC_ATTR_RW(t_pwm_threshold, TMC_REG_TPWMTHRS, GENMASK(19, 0));
+TMC_ATTR_RW(t_cool_threshold, TMC_REG_TCOOLTHRS, GENMASK(19, 0));
+TMC_ATTR_RW(t_high, TMC_REG_THIGH, GENMASK(19, 0));
+TMC_ATTR_RW(irun_delay, TMC_REG_IHOLD_IRUN, TMC_IHOLD_IRUNDELAY);
+TMC_ATTR_RW(ihold_delay, TMC_REG_IHOLD_IRUN, TMC_IHOLD_IHOLDDELAY);
+TMC_ATTR_RW(irun, TMC_REG_IHOLD_IRUN, TMC_IHOLD_IRUN);
+TMC_ATTR_RW(ihold, TMC_REG_IHOLD_IRUN, TMC_IHOLD_IHOLD);
+TMC_ATTR_RO(x_latch, TMC_REG_XLATCH, GENMASK(31, 0));
+TMC_ATTR_RW(x_encoder, TMC_REG_X_ENC, GENMASK(31, 0));
+TMC_ATTR_RW(encoder_constant, TMC_REG_ENC_CONST, GENMASK(31, 0));
+TMC_ATTR_RO(encoder_latch, TMC_REG_ENC_LATCH, GENMASK(31, 0));
+TMC_ATTR_RO(x_actual, TMC_REG_XACTUAL, GENMASK(31, 0));
+TMC_ATTR_RW(virtual_stop_l, TMC_REG_VIRTUAL_STOP_L, GENMASK(31, 0));
+TMC_ATTR_RW(virtual_stop_r, TMC_REG_VIRTUAL_STOP_R, GENMASK(31, 0));
+
+static struct attribute *tmc5240_attributes[] = {
+	&dev_attr_sw_mode_swap_lr.attr,
+	&dev_attr_drv_conf_current_range.attr,
+	&dev_attr_drv_conf_slope_control.attr,
+	&dev_attr_global_scaler.attr,
+	&dev_attr_t_power_down.attr,
+	&dev_attr_t_step.attr,
+	&dev_attr_t_pwm_threshold.attr,
+	&dev_attr_t_cool_threshold.attr,
+	&dev_attr_t_high.attr,
+	&dev_attr_irun_delay.attr,
+	&dev_attr_ihold_delay.attr,
+	&dev_attr_irun.attr,
+	&dev_attr_ihold.attr,
+	&dev_attr_x_latch.attr,
+	&dev_attr_x_encoder.attr,
+	&dev_attr_encoder_constant.attr,
+	&dev_attr_encoder_latch.attr,
+	&dev_attr_x_actual.attr,
+	&dev_attr_virtual_stop_l.attr,
+	&dev_attr_virtual_stop_r.attr,
+	NULL
+};
+
+static const struct attribute_group tmc5240_group = {
+	.attrs = tmc5240_attributes,
+};
+
+static irqreturn_t tmc5240_hard_irq(int irq, void *handle)
+{
+	struct tmc5240 *tmc = handle;
+
+	dev_info(tmc->mdev.dev, "Hard IRQ spistat = 0x%02x\n", tmc->spi_status);
+	tmc->irq_ts = ktime_get();
+
+	return IRQ_WAKE_THREAD;
+}
+
+static int tmc5240_motion_with_index(struct motion_device *mdev,
+		unsigned int index, s32 d);
+
+static irqreturn_t tmc5240_irq(int irq, void *handle)
+{
+	struct tmc5240 *tmc = handle;
+	struct motion_device *mdev = &tmc->mdev;
+	struct mot_event evt = {0};
+	u32 val;
+
+	evt.timestamp = ktime2mot_time(tmc->irq_ts);
+	tmc5240_read(tmc, TMC_REG_RAMP_STAT, &val);
+	tmc5240_read(tmc, TMC_REG_XACTUAL, &evt.position);
+	tmc5240_read(tmc, TMC_REG_VACTUAL, &evt.speed);
+
+	if (val & (TMC_RAMP_STOP_L | TMC_RAMP_STOP_R)) {
+		if ((val & TMC_RAMP_VIRT_L) &&
+				(tmc->stop_functions[TMC_STOP_VIRTL]))
+			evt.input_index = TMC_STOP_VIRTL;
+		else if ((val & TMC_RAMP_VIRT_R) &&
+				(tmc->stop_functions[TMC_STOP_VIRTR]))
+			evt.input_index = TMC_STOP_VIRTR;
+		else
+			evt.input_index = (val & TMC_RAMP_STOP_R) ?
+				TMC_STOP_REFR : TMC_STOP_REFL;
+		evt.event = MOT_EVENT_STOP;
+
+		/* Check if we have a trigger motion waiting */
+		mutex_lock(&mdev->mutex);
+		if (tmc->int_trig_dist) {
+			tmc5240_motion_with_index(mdev, tmc->int_trg_index,
+					tmc->int_trig_dist);
+			tmc->int_trig_dist = 0;
+		}
+		motion_report_event(mdev, &evt);
+		mutex_unlock(&mdev->mutex);
+	} else if (val & TMC_RAMP_POS_REACHED) {
+		evt.event = MOT_EVENT_TARGET;
+
+		/* Check if we have a next motion waiting */
+		mutex_lock(&mdev->mutex);
+		if (tmc->next_dist) {
+			tmc5240_motion_with_index(mdev, tmc->next_index,
+					tmc->next_dist);
+			tmc->next_dist = 0;
+		}
+		motion_report_event(mdev, &evt);
+		mutex_unlock(&mdev->mutex);
+	} else {
+		dev_info(tmc->mdev.dev,
+			"Unknown IRQ source 0x%04x. SPI status = 0x%02x\n",
+			val, tmc->spi_status);
+	}
+
+	/* Clear interrupt flags */
+	tmc5240_write(tmc, TMC_REG_RAMP_STAT, val & TMC_RAMP_CLEAR_FLAGS);
+
+	return IRQ_HANDLED;
+}
+
+static void tmc5240_prepare_message(struct tmc5240 *tmc)
+{
+	/*
+	 * TMC5240 sends back read register contents in the _next_ transfer,
+	 * so for read actions we need to do 2 transfers with a CS change in
+	 * between.
+	 */
+	tmc->rxfers[0].tx_buf = &tmc->rtxbuf[0].buf[0];
+	tmc->rxfers[0].rx_buf = &tmc->rrxbuf[0].buf[0];
+	tmc->rxfers[0].len = 5;
+	tmc->rxfers[0].cs_change = 1;
+	tmc->rxfers[1].tx_buf = &tmc->rtxbuf[1].buf[0];
+	tmc->rxfers[1].rx_buf = &tmc->rrxbuf[1].buf[0];
+	tmc->rxfers[1].len = 5;
+	spi_message_init_with_transfers(&tmc->rmsg, &tmc->rxfers[0], 2);
+
+	/*
+	 * For write register operations, a single transfer is sufficient.
+	 * We do not re-use the same buffers, in order to avoid clobbering
+	 * bytes 1-4 of the _read_ TX buffer, so we don't need to clear it
+	 * on each _read_ transfer.
+	 */
+	tmc->wxfer.tx_buf = &tmc->wtxbuf.buf[0];
+	tmc->wxfer.rx_buf = &tmc->wrxbuf.buf[0];
+	tmc->wxfer.len = 5;
+	spi_message_init_with_transfers(&tmc->wmsg, &tmc->wxfer, 1);
+}
+
+static int tmc5240_ramp_set_vel(struct tmc5240 *tmc, u32 vstart, u32 v1, u32 v2,
+		u32 vmax, u32 vstop)
+{
+	int ret;
+
+	ret = tmc5240_write(tmc, TMC_REG_VSTART, vstart);
+	if (ret)
+		return ret;
+	ret = tmc5240_write(tmc, TMC_REG_V1, v1);
+	if (ret)
+		return ret;
+	ret = tmc5240_write(tmc, TMC_REG_V2, v2);
+	if (ret)
+		return ret;
+	ret = tmc5240_write(tmc, TMC_REG_VMAX, vmax);
+	if (ret)
+		return ret;
+	return tmc5240_write(tmc, TMC_REG_VSTOP, max(vstop, TMC_VSTOP_MIN));
+}
+
+static int tmc5240_ramp_set_acc(struct tmc5240 *tmc, u32 a0, u32 a1, u32 a2,
+		u32 a3, u32 a4, u32 a5)
+{
+	int ret;
+
+	ret = tmc5240_write(tmc, TMC_REG_A1, a0);
+	if (ret)
+		return ret;
+	ret = tmc5240_write(tmc, TMC_REG_A2, a1);
+	if (ret)
+		return ret;
+	ret = tmc5240_write(tmc, TMC_REG_AMAX, a2);
+	if (ret)
+		return ret;
+	ret = tmc5240_write(tmc, TMC_REG_DMAX, a3);
+	if (ret)
+		return ret;
+	ret = tmc5240_write(tmc, TMC_REG_D2, max(a4, TMC_D2_MIN));
+	if (ret)
+		return ret;
+	return tmc5240_write(tmc, TMC_REG_D1, max(a5, TMC_D1_MIN));
+}
+
+static int tmc5240_set_ramp_simple(struct tmc5240 *tmc, u32 vmax, u32 amax)
+{
+	int ret;
+
+	/*
+	 * Setup the most simple profile with only one acceleration and
+	 * one speed value. Meant to be used in basic movements without
+	 * profile support.
+	 */
+	ret = tmc5240_ramp_set_vel(tmc, 0, 0, 0, vmax, 0);
+	if (ret)
+		return ret;
+	ret = tmc5240_ramp_set_acc(tmc, 0, 0, amax, amax, 0, 0);
+
+	return ret;
+}
+
+static int tmc5240_open(struct motion_device *mdev)
+{
+	struct tmc5240 *tmc = container_of(mdev, struct tmc5240, mdev);
+	u32 val;
+	int ret;
+
+	tmc->next_dist = 0;
+	tmc->int_trig_dist = 0;
+	tmc->ext_trig_dist = 0;
+
+	ret = tmc5240_read(tmc, TMC_REG_GSTAT, &val);
+	if (ret)
+		return ret;
+	/* Clear reset condition */
+	ret = tmc5240_write(tmc, TMC_REG_GSTAT, val);
+	if (ret)
+		return ret;
+	ret = tmc5240_write(tmc, TMC_REG_GCONF, 0x00000000);
+	if (ret)
+		return ret;
+	ret = tmc5240_update_bits(tmc, TMC_REG_CHOPCONF, TMC_CHOP_TOFF,
+			FIELD_PREP(TMC_CHOP_TOFF, 3));
+	if (ret)
+		return ret;
+	ret = tmc5240_read(tmc, TMC_REG_SW_MODE, &val);
+	if (ret)
+		return ret;
+	if (tmc->use_encoder)
+		val |= TMC_SW_VIRT_STOP_ENC;
+	else
+		val &= ~TMC_SW_VIRT_STOP_ENC;
+	return tmc5240_write(tmc, TMC_REG_SW_MODE, val);
+}
+
+static int tmc5240_release(struct motion_device *mdev)
+{
+	struct tmc5240 *tmc = container_of(mdev, struct tmc5240, mdev);
+	u32 val;
+
+	tmc->current_index = -1;
+
+	/* Turn off RAMP and chopper */
+	tmc5240_write(tmc, TMC_REG_RAMPMODE, TMC_RAMPMODE_POS_VEL);
+	tmc5240_write(tmc, TMC_REG_VMAX, 0);
+	tmc5240_update_bits(tmc, TMC_REG_CHOPCONF, TMC_CHOP_TOFF,
+			FIELD_PREP(TMC_CHOP_TOFF, 0));
+
+	/* Disable event interrupts sources */
+	tmc5240_read(tmc, TMC_REG_SW_MODE, &val);
+	val &= ~(TMC_SW_EN_VIRT_STOP_L | TMC_SW_EN_VIRT_STOP_R |
+			TMC_SW_STOP_L_ENABLE | TMC_SW_STOP_R_ENABLE);
+	return tmc5240_write(tmc, TMC_REG_SW_MODE, val);
+}
+
+static int _sign_extend(u32 val, u8 sbit)
+{
+	return ((int)(val << (31 - sbit)) >> (31 - sbit));
+}
+
+static int tmc5240_get_status(struct motion_device *mdev, struct mot_status *st)
+{
+	struct tmc5240 *tmc = container_of(mdev, struct tmc5240, mdev);
+	u32 val;
+	int ret;
+
+	ret = tmc5240_read(tmc, TMC_REG_XACTUAL, &val);
+	if (ret)
+		return ret;
+	st->position = val;
+	ret = tmc5240_read(tmc, TMC_REG_VACTUAL, &val);
+	if (ret)
+		return ret;
+	st->speed = _sign_extend(val, TMC_VACTUAL_SIGN_BIT);
+	ret = tmc5240_read(tmc, TMC_REG_RAMP_STAT, &val);
+	if (ret)
+		return ret;
+	st->local_inputs = (FIELD_GET(TMC_VIRT_STOPS_MASK, val) << 2) |
+		FIELD_GET(TMC_STOPS_MASK, val);
+
+	return 0;
+}
+
+static int tmc5240_basic_run(struct motion_device *mdev, u32 ch, s32 v)
+{
+	struct tmc5240 *tmc = container_of(mdev, struct tmc5240, mdev);
+	int ret;
+
+	tmc->current_index = -1; /* Invalidate current index */
+	if (v >= 0) {
+		ret = tmc5240_write(tmc, TMC_REG_RAMPMODE, TMC_RAMPMODE_POS_VEL);
+		if (ret)
+			return ret;
+	} else {
+		v = -v;
+		ret = tmc5240_write(tmc, TMC_REG_RAMPMODE, TMC_RAMPMODE_NEG_VEL);
+		if (ret)
+			return ret;
+	}
+	ret = tmc5240_write(tmc, TMC_REG_AMAX, TMC_MAX_ACCELERATION / 2);
+	if (ret)
+		return ret;
+	return tmc5240_write(tmc, TMC_REG_VMAX, v);
+}
+
+static int tmc5240_basic_stop(struct motion_device *mdev, channel_mask_t ch)
+{
+	struct tmc5240 *tmc = container_of(mdev, struct tmc5240, mdev);
+
+	tmc5240_write(tmc, TMC_REG_RAMPMODE, TMC_RAMPMODE_POS_VEL);
+	tmc5240_write(tmc, TMC_REG_AMAX, TMC_MAX_ACCELERATION / 2);
+	tmc->current_index = -1; /* Invalidate current index */
+
+	return tmc5240_write(tmc, TMC_REG_VMAX, 0);
+}
+
+static int tmc5240_set_distance(struct tmc5240 *tmc, s32 d)
+{
+	u32 x;
+	int ret;
+
+	ret = tmc5240_write(tmc, TMC_REG_RAMPMODE, TMC_RAMPMODE_POSITION);
+	if (ret)
+		return ret;
+
+	/* Clear position reached */
+	ret = tmc5240_write(tmc, TMC_REG_RAMP_STAT, TMC_RAMP_POS_REACHED);
+	if (ret)
+		return ret;
+	ret = tmc5240_read(tmc, TMC_REG_XACTUAL, &x);
+	if (ret)
+		return ret;
+	return tmc5240_write(tmc, TMC_REG_XTARGET, x + d);
+}
+
+static int tmc5240_move_distance(struct motion_device *mdev, u32 ch, s32 v, u32 d)
+{
+	struct tmc5240 *tmc = container_of(mdev, struct tmc5240, mdev);
+	int ret;
+
+	ret = tmc5240_set_ramp_simple(tmc, v, 1<<17);
+	if (ret)
+		return ret;
+	return tmc5240_set_distance(tmc, d);
+}
+
+static int tmc5240_move_timed(struct motion_device *mdev, u32 ch, s32 v, ktime_t t)
+{
+	struct tmc5240 *tmc = container_of(mdev, struct tmc5240, mdev);
+
+	dev_info(mdev->dev, "timed ch: 0x%08x: v: %d, duration: %llu\n", ch, v, t);
+	return 0;
+}
+
+#define _check_u(v, n) ((v < 0) || (v >= (1 << n)))
+
+static int tmc5240_validate_profile(struct motion_device *mdev,
+		struct mot_profile *p)
+{
+	speed_raw_t *v = &p->vel[0];
+	accel_raw_t *a = &p->acc[0];
+
+	if (_check_u(v[0], 18) || _check_u(a[0], 18) || _check_u(a[1], 18))
+		return -EINVAL;
+
+	/* Trapezoidal profile */
+	if ((p->na == 2) && (p->nv == 3)) {
+		if (_check_u(v[1], 23) || _check_u(v[2], 18))
+			return -EINVAL;
+		v[2] = max(v[2], TMC_VSTOP_MIN); /* VSTOP (see DS), can't be 0 */
+		return 0;
+	}
+
+	if (_check_u(v[1], 20) || _check_u(a[2], 18) || _check_u(a[3], 18))
+		return -EINVAL;
+
+	/* Dual slope profile */
+	if ((p->na == 4) && (p->nv == 4)) {
+		if (_check_u(v[2], 23) || _check_u(v[3], 18))
+			return -EINVAL;
+		a[3] = max(a[3], TMC_D1_MIN); /* D1 (see DS), can't be 0 */
+		v[3] = max(v[3], TMC_VSTOP_MIN); /* VSTOP (see DS), can't be 0 */
+		return 0;
+
+	}
+
+	/* S-curve (8-point) profile */
+	if ((p->na == 6) && (p->nv == 5)) {
+		if (_check_u(v[2], 20) || _check_u(v[3], 23) || _check_u(v[4], 18))
+			return -EINVAL;
+		if (_check_u(a[4], 18) || _check_u(a[5], 18))
+			return -EINVAL;
+		a[4] = max(a[4], TMC_D2_MIN); /* D2 (see DS), can't be 0 */
+		a[5] = max(a[5], TMC_D1_MIN); /* D1 (see DS), can't be 0 */
+		v[4] = max(v[4], TMC_VSTOP_MIN); /* VSTOP (see DS), can't be 0 */
+		return 0;
+	}
+
+	return -EINVAL;
+}
+
+static inline u32 tmc5240_time2tv(struct tmc5240 *tmc, mot_time_t t)
+{
+	/* TMC5240 time values are in 512 clock cycle units */
+	return (u32)div_u64((t >> 9) * tmc->clk_rate, NSEC_PER_SEC);
+}
+
+static int tmc5240_set_profile(struct motion_device *mdev, struct mot_profile *p)
+{
+	struct tmc5240 *tmc = container_of(mdev, struct tmc5240, mdev);
+	speed_raw_t *v = &p->vel[0];
+	accel_raw_t *a = &p->acc[0];
+	int ret;
+
+	ret = tmc5240_write(tmc, TMC_REG_TVMAX,
+			tmc5240_time2tv(tmc, p->tvmax));
+	if (ret)
+		return ret;
+	ret = tmc5240_write(tmc, TMC_REG_TZEROWAIT,
+			tmc5240_time2tv(tmc, p->tvzero));
+	if (ret)
+		return ret;
+
+	/* Trapezoidal profile */
+	if ((p->na == 2) && (p->nv == 3)) {
+		ret = tmc5240_ramp_set_vel(tmc, v[0], 0, 0, v[1], v[2]);
+		if (ret)
+			return ret;
+		return tmc5240_ramp_set_acc(tmc, 0, 0, a[0], a[1], 0, 0);
+	}
+
+	/* Dual slope profile */
+	if ((p->na == 4) && (p->nv == 4)) {
+		ret = tmc5240_ramp_set_vel(tmc, v[0], v[1], 0, v[2], v[3]);
+		if (ret)
+			return ret;
+		return tmc5240_ramp_set_acc(tmc, a[0], 0, a[1], a[2], 0, a[3]);
+	}
+
+	/* S-curve (8-point) profile */
+	if ((p->na == 6) && (p->nv == 5)) {
+		tmc5240_ramp_set_vel(tmc, v[0], v[1], v[2], v[3], v[4]);
+		if (ret)
+			return ret;
+		return tmc5240_ramp_set_acc(tmc, a[0], a[1], a[2], a[3], a[4],
+				a[5]);
+	}
+
+	/* We should never get here, since the validate handler
+	 * is supposed to have been called on this profile before.
+	 */
+	WARN_ONCE(1, "motion profile should be valid, but isn't.");
+
+	return -EINVAL;
+}
+
+static int tmc5240_motion_with_index(struct motion_device *mdev,
+		unsigned int index, s32 d)
+{
+	struct tmc5240 *tmc = container_of(mdev, struct tmc5240, mdev);
+	int ret;
+
+	if (tmc->current_index != index) {
+		ret = tmc5240_set_profile(mdev, &mdev->profiles[index]);
+		if (ret)
+			return ret;
+	}
+	tmc->current_index = index;
+
+	return tmc5240_set_distance(tmc, d);
+}
+
+static int tmc5240_motion_distance(struct motion_device *mdev,
+		unsigned int channel, unsigned int index, s32 d, unsigned int when)
+{
+	struct tmc5240 *tmc = container_of(mdev, struct tmc5240, mdev);
+	int ret = 0;
+
+	switch (when) {
+	case MOT_WHEN_NEXT:
+		if (tmc->next_dist) {
+			ret = -EAGAIN;
+		} else {
+			tmc->next_dist = d;
+			tmc->next_index = index;
+		}
+		break;
+	case MOT_WHEN_EXT_TRIGGER:
+		if (tmc->ext_trig_dist) {
+			ret = -EAGAIN;
+		} else {
+			tmc->ext_trig_dist = d;
+			tmc->ext_trg_index = index;
+		}
+		break;
+	case MOT_WHEN_INT_TRIGGER:
+		if (tmc->int_trig_dist) {
+			ret = -EAGAIN;
+		} else {
+			tmc->int_trig_dist = d;
+			tmc->int_trg_index = index;
+		}
+		break;
+	case MOT_WHEN_IMMEDIATE:
+		tmc5240_motion_with_index(mdev, index, d);
+		break;
+	default:
+		ret = -EINVAL;
+		break;
+	}
+
+	return ret;
+}
+
+static int tmc5240_motion_stop(struct motion_device *mdev, channel_mask_t chmsk,
+		unsigned int when)
+{
+	struct tmc5240 *tmc = container_of(mdev, struct tmc5240, mdev);
+
+	if (when != MOT_WHEN_IMMEDIATE)
+		return -EINVAL;
+	/*
+	 * See DS page 55 "Early Ramp Termination".
+	 * The correct way to stop using all *decelaration* parameters is
+	 * weirdly complex and not practial. Best thing we can do here, is to
+	 * use the second closest option which uses AMAX, A1 and A2:
+	 */
+	tmc->current_index = -1; /* Invalidate current index */
+	tmc5240_write(tmc, TMC_REG_VSTART, 0);
+
+	return tmc5240_write(tmc, TMC_REG_VMAX, 0);
+
+}
+
+static int tmc5240_config_trigger(struct motion_device *mdev, unsigned int index,
+		unsigned int func, unsigned int edge, channel_mask_t ch)
+{
+	struct tmc5240 *tmc = container_of(mdev, struct tmc5240, mdev);
+	u32 val;
+	int idxbit;
+	int ret;
+
+	ret = tmc5240_read(tmc, TMC_REG_SW_MODE, &val);
+	if (ret)
+		return ret;
+
+	switch (index) {
+	case TMC_STOP_REFL:
+		idxbit = TMC_SW_STOP_L_ENABLE;
+		if (edge == MOT_EDGE_FALLING)
+			val |= TMC_SW_STOP_L_POL;
+		else
+			val &= ~TMC_SW_STOP_L_POL;
+		break;
+	case TMC_STOP_REFR:
+		idxbit = TMC_SW_STOP_R_ENABLE;
+		if (edge == MOT_EDGE_FALLING)
+			val |= TMC_SW_STOP_R_POL;
+		else
+			val &= ~TMC_SW_STOP_R_POL;
+		break;
+	case TMC_STOP_VIRTL:
+		idxbit = TMC_SW_EN_VIRT_STOP_L;
+		break;
+	case TMC_STOP_VIRTR:
+		idxbit = TMC_SW_EN_VIRT_STOP_R;
+		break;
+	default:
+		/* Should never occur */
+		return -EINVAL;
+	}
+
+	/* Store stop function for interrupt handler */
+	tmc->stop_functions[index] = func;
+
+	switch (func) {
+	case MOT_INP_FUNC_NONE:
+		val &= ~idxbit;
+		break;
+	case MOT_INP_FUNC_DECEL:
+	case MOT_INP_FUNC_DECEL_NEG:
+	case MOT_INP_FUNC_DECEL_POS:
+		val |= TMC_SW_EN_SOFTSTOP;
+		val |= idxbit;
+		break;
+	case MOT_INP_FUNC_STOP:
+	case MOT_INP_FUNC_STOP_NEG:
+	case MOT_INP_FUNC_STOP_POS:
+		val &= ~TMC_SW_EN_SOFTSTOP;
+		val |= idxbit;
+		break;
+	default:
+		return -EINVAL;
+	}
+	return tmc5240_write(tmc, TMC_REG_SW_MODE, val);
+}
+
+static void tmc5240_ext_trigger(struct motion_device *mdev, unsigned int index,
+			channel_mask_t ch)
+{
+	struct tmc5240 *tmc = container_of(mdev, struct tmc5240, mdev);
+
+	if (tmc->ext_trig_dist) {
+		tmc5240_motion_with_index(mdev, tmc->ext_trg_index,
+				tmc->ext_trig_dist);
+		tmc->ext_trig_dist = 0;
+	}
+}
+
+static const struct motion_ops tmc5240_motion_ops = {
+	.device_open = tmc5240_open,
+	.device_release = tmc5240_release,
+	.get_status = tmc5240_get_status,
+	.basic_run = tmc5240_basic_run,
+	.basic_stop = tmc5240_basic_stop,
+	.move_timed = tmc5240_move_timed,
+	.move_distance = tmc5240_move_distance,
+	.validate_profile = tmc5240_validate_profile,
+	.set_profile = tmc5240_set_profile,
+	.motion_distance = tmc5240_motion_distance,
+	.motion_stop = tmc5240_motion_stop,
+	.config_trigger = tmc5240_config_trigger,
+	.external_trigger = tmc5240_ext_trigger
+};
+
+static const struct regmap_range tmc_readable_reg_ranges[] = {
+	regmap_reg_range(TMC_REG_GCONF, TMC_REG_X_COMPARE_REP),
+	regmap_reg_range(TMC_REG_DRV_CONF, TMC_REG_GLOBAL_SCALER),
+	regmap_reg_range(TMC_REG_IHOLD_IRUN, TMC_REG_THIGH),
+	regmap_reg_range(TMC_REG_RAMPMODE, TMC_REG_D2),
+	regmap_reg_range(TMC_REG_VDCMIN, TMC_REG_XLATCH),
+	regmap_reg_range(TMC_REG_ENCMODE, TMC_REG_VIRTUAL_STOP_R),
+	regmap_reg_range(TMC_REG_ADC_VSUPLLY_AIN, TMC_REG_OTW_OV_VTH),
+	regmap_reg_range(TMC_REG_MSLUT(0), TMC_REG_PWM_AUTO),
+	regmap_reg_range(TMC_REG_SG4_THRS, TMC_REG_SG4_IND),
+};
+
+static const struct regmap_access_table tmc_regmap_readable_regs = {
+	.yes_ranges = tmc_readable_reg_ranges,
+	.n_yes_ranges = ARRAY_SIZE(tmc_readable_reg_ranges),
+};
+
+static const struct regmap_range tmc_readonly_reg_ranges[] = {
+	regmap_reg_range(TMC_REG_IFCNT, TMC_REG_IFCNT),
+	regmap_reg_range(TMC_REG_IOIN, TMC_REG_IOIN),
+	regmap_reg_range(TMC_REG_TSTEP, TMC_REG_TSTEP),
+	regmap_reg_range(TMC_REG_VACTUAL, TMC_REG_VACTUAL),
+	regmap_reg_range(TMC_REG_XLATCH, TMC_REG_XLATCH),
+	regmap_reg_range(TMC_REG_ENC_LATCH, TMC_REG_ENC_LATCH),
+	regmap_reg_range(TMC_REG_ADC_VSUPLLY_AIN, TMC_REG_ADC_TEMP),
+	regmap_reg_range(TMC_REG_MSCNT, TMC_REG_MSCURACT),
+	regmap_reg_range(TMC_REG_DRV_STATUS, TMC_REG_DRV_STATUS),
+	regmap_reg_range(TMC_REG_PWM_SCALE, TMC_REG_PWM_AUTO),
+	regmap_reg_range(TMC_REG_SG4_RESULT, TMC_REG_SG4_IND),
+};
+
+static const struct regmap_access_table tmc_regmap_writeable_regs = {
+	.no_ranges = tmc_readonly_reg_ranges,
+	.n_no_ranges = ARRAY_SIZE(tmc_readonly_reg_ranges),
+};
+
+static const struct regmap_range tmc_non_volatile_reg_ranges[] = {
+	regmap_reg_range(TMC_REG_GCONF, TMC_REG_GCONF),
+	regmap_reg_range(TMC_REG_NODECONF, TMC_REG_NODECONF),
+	regmap_reg_range(TMC_REG_X_COMPARE, TMC_REG_TPOWERDOWN),
+	regmap_reg_range(TMC_REG_TPWMTHRS, TMC_REG_RAMPMODE),
+	regmap_reg_range(TMC_REG_VSTART, TMC_REG_SW_MODE),
+	regmap_reg_range(TMC_REG_ENCMODE, TMC_REG_ENCMODE),
+	regmap_reg_range(TMC_REG_ENC_CONST, TMC_REG_ENC_CONST),
+	regmap_reg_range(TMC_REG_ENC_DEVIATION, TMC_REG_VIRTUAL_STOP_R),
+	regmap_reg_range(TMC_REG_OTW_OV_VTH, TMC_REG_MSLUTSTART),
+	regmap_reg_range(TMC_REG_CHOPCONF, TMC_REG_DCCTRL),
+	regmap_reg_range(TMC_REG_PWMCONF, TMC_REG_PWMCONF),
+	regmap_reg_range(TMC_REG_SG4_THRS, TMC_REG_SG4_THRS),
+};
+
+static const struct regmap_access_table tmc_regmap_volatile_regs = {
+	.no_ranges = tmc_non_volatile_reg_ranges,
+	.n_no_ranges = ARRAY_SIZE(tmc_non_volatile_reg_ranges),
+};
+
+static const struct regmap_config mapcfg = {
+	.reg_bits = 8,
+	.val_bits = 32,
+	.max_register = TMC_REG_SG4_IND,
+	.write_flag_mask = BIT(7),
+	.reg_read = tmc5240_read_reg,
+	.reg_write = tmc5240_write_reg,
+	.use_single_read = true,
+	.use_single_write = true,
+	.rd_table = &tmc_regmap_readable_regs,
+	.wr_table = &tmc_regmap_writeable_regs,
+	.volatile_table = &tmc_regmap_volatile_regs,
+	// .cache_type = REGCACHE_MAPLE,
+	.cache_type = REGCACHE_NONE,
+};
+
+static int tmc5240_probe(struct spi_device *spi)
+{
+	struct tmc5240 *tmc;
+	struct device *dev = &spi->dev;
+	unsigned long irq_flags;
+	int err;
+	u32 val, ver, rev;
+
+	/* FIXME: Limited functionality should be possible without IRQ */
+	if (spi->irq <= 0) {
+		dev_dbg(dev, "no IRQ?\n");
+		return -EINVAL;
+	}
+
+	spi->bits_per_word = 8;
+	spi->mode &= ~SPI_MODE_X_MASK;
+	spi->mode |= SPI_MODE_3;
+	err = spi_setup(spi);
+	if (err < 0)
+		return err;
+
+	tmc = devm_kzalloc(dev, sizeof(struct tmc5240), GFP_KERNEL);
+	if (!tmc)
+		return -ENOMEM;
+
+	tmc->mdev.parent = dev;
+	tmc->mdev.ops = tmc5240_motion_ops;
+	tmc->mdev.groups[0] = &tmc5240_group;
+	tmc->mdev.capabilities.features = MOT_FEATURE_SPEED |
+		MOT_FEATURE_ACCEL | MOT_FEATURE_ENCODER | MOT_FEATURE_PROFILE;
+	tmc->mdev.capabilities.num_channels = 1;
+	tmc->mdev.capabilities.max_apoints = 6;
+	tmc->mdev.capabilities.max_vpoints = 5;
+	tmc->mdev.capabilities.num_int_triggers = TMC_MAX_INTERNAL_STOPS;
+	tmc->mdev.capabilities.num_ext_triggers = 0; /* Filled in by core */
+	tmc->mdev.capabilities.type = MOT_TYPE_STEPPER;
+	tmc->mdev.capabilities.subdiv = 256;
+
+	tmc->current_index = -1;
+
+	spi_set_drvdata(spi, tmc);
+	tmc->spi = spi;
+
+	tmc->clk = devm_clk_get(dev, NULL);
+	if (IS_ERR(tmc->clk)) {
+		err = PTR_ERR(tmc->clk);
+		dev_err(dev, "clk get failed: %d\n", err);
+		return err;
+	}
+
+	err = clk_prepare_enable(tmc->clk);
+	if (err) {
+		dev_err(dev, "clk enable failed: %d\n", err);
+		return err;
+	}
+	tmc->clk_rate = clk_get_rate(tmc->clk);
+	if (!tmc->clk_rate) {
+		dev_err(dev, "clk rate = 0\n");
+		err = -EINVAL;
+		goto err_clk_disable;
+	}
+
+	/*
+	 * See datasheet table 19:
+	 * v[Hz] = v[TMC5240] * ( fCLK[Hz] / 2^24 )
+	 * a[Hz/s] = a[TMC5240] * ( fCLK[Hz]^2 / 2^42 )
+	 * Since for acceleration, numbers are squared and too big for u32,
+	 * we need to pre-scale both operands by the same amount.
+	 * Clock frequencies are almost always whole kHz values, so we can
+	 * divide by 1000 without losing precision. The divider would then
+	 * become (1ULL<<42)/1000000, which is (rounded) 4398047.
+	 */
+	tmc->mdev.capabilities.speed_conv_mul = tmc->clk_rate;
+	tmc->mdev.capabilities.speed_conv_div = (1UL << 24);
+	tmc->mdev.capabilities.accel_conv_mul = (tmc->clk_rate / 1000); /* Pre-scale */
+	tmc->mdev.capabilities.accel_conv_mul *=
+		tmc->mdev.capabilities.accel_conv_mul; /* squared */
+	tmc->mdev.capabilities.accel_conv_div = 4398047; /* (1 << 42) / 1000000 */
+
+	tmc->map = devm_regmap_init(&spi->dev, NULL, tmc, &mapcfg);
+	if (IS_ERR(tmc->map)) {
+		err = PTR_ERR(tmc->map);
+		goto err_clk_disable;
+	}
+
+	tmc5240_prepare_message(tmc);
+	err = tmc5240_read(tmc, TMC_REG_IOIN, &val);
+	if (err)
+		goto err_clk_disable;
+
+	ver = FIELD_GET(TMC_IOIN_VERSION_MASK, val);
+
+	/* Sanity check. Currently 0x40 and 0x41 are known valid versions */
+	if ((ver < 0x40) || (ver > 0x5f)) {
+		dev_err(dev, "TMC5240 version number invalid (%02x)\n", ver);
+		err = -EINVAL;
+		goto err_clk_disable;
+	}
+
+	rev = FIELD_GET(TMC_IOIN_REVISION_MASK, val);
+	dev_info(dev, "TMC5240 version %02x, rev %d, clock %dHz detected.\n",
+			ver, rev, tmc->clk_rate);
+
+	irq_flags = IRQF_TRIGGER_FALLING | IRQF_ONESHOT;
+
+	err = devm_request_threaded_irq(dev, spi->irq,
+					tmc5240_hard_irq, tmc5240_irq,
+					irq_flags, dev->driver->name, tmc);
+	if (err)
+		goto err_clk_disable;
+
+	return motion_register_device(&tmc->mdev);
+err_clk_disable:
+	clk_disable_unprepare(tmc->clk);
+
+	return err;
+}
+
+static void tmc5240_remove(struct spi_device *spi)
+{
+	struct tmc5240 *tmc = spi_get_drvdata(spi);
+
+	clk_disable_unprepare(tmc->clk);
+}
+
+static const struct of_device_id tmc5240_of_match[] = {
+	{ .compatible = "adi,tmc5240" },
+	{}
+};
+MODULE_DEVICE_TABLE(of, tmc5240_of_match);
+
+static struct spi_driver tmc5240_driver = {
+	.driver = {
+		.name = "tmc5240",
+		.of_match_table = tmc5240_of_match,
+	},
+	.probe = tmc5240_probe,
+	.remove = tmc5240_remove,
+};
+module_spi_driver(tmc5240_driver);
+
+MODULE_AUTHOR("David Jander <david@protonic.nl>");
+MODULE_DESCRIPTION("Analog Devices TMC5240 stepper motor controller driver");
+MODULE_LICENSE("GPL");
diff --git a/include/uapi/linux/motion.h b/include/uapi/linux/motion.h
index 72a7e564114d..64cea65cd7f4 100644
--- a/include/uapi/linux/motion.h
+++ b/include/uapi/linux/motion.h
@@ -128,7 +128,7 @@ struct mot_status {
 	__u32 channel;
 	pos_raw_t position;
 	speed_raw_t speed;
-	__u32 reserved;
+	__u32 local_inputs;
 };
 
 struct mot_input {
-- 
2.47.2


^ permalink raw reply related	[flat|nested] 59+ messages in thread

* [RFC PATCH 3/7] motion: Add simple-pwm.c PWM based DC motor controller driver
  2025-02-27 16:28 [RFC PATCH 0/7] Add Linux Motion Control subsystem David Jander
  2025-02-27 16:28 ` [RFC PATCH 1/7] drivers: Add motion control subsystem David Jander
  2025-02-27 16:28 ` [RFC PATCH 2/7] motion: Add ADI/Trinamic TMC5240 stepper motor controller David Jander
@ 2025-02-27 16:28 ` David Jander
  2025-02-27 16:28 ` [RFC PATCH 4/7] Documentation: Add Linux Motion Control documentation David Jander
                   ` (6 subsequent siblings)
  9 siblings, 0 replies; 59+ messages in thread
From: David Jander @ 2025-02-27 16:28 UTC (permalink / raw)
  To: linux-kernel
  Cc: linux-iio, Jonathan Corbet, Rob Herring, Krzysztof Kozlowski,
	Conor Dooley, devicetree, linux-doc, Nuno Sa, Jonathan Cameron,
	Oleksij Rempel, David Jander

This is a simple DC-motor motion control driver that implements
 - 1 or 2 PWM channels for uni-directional or bi-directional drive
 - Trapezoidal acceleration profiles
 - Time-based movements
 - External trigger support

Tested with TI DRV8873

Signed-off-by: David Jander <david@protonic.nl>
---
 drivers/motion/Kconfig      |  13 ++-
 drivers/motion/Makefile     |   1 +
 drivers/motion/simple-pwm.c | 199 ++++++++++++++++++++++++++++++++++++
 3 files changed, 212 insertions(+), 1 deletion(-)
 create mode 100644 drivers/motion/simple-pwm.c

diff --git a/drivers/motion/Kconfig b/drivers/motion/Kconfig
index 7715301c667e..63c4bdedb12a 100644
--- a/drivers/motion/Kconfig
+++ b/drivers/motion/Kconfig
@@ -11,7 +11,6 @@ menuconfig MOTION
 
 if MOTION
 
-
 config TMC5240
 	tristate "TMC5240 stepper motor driver"
 	depends on SPI
@@ -23,6 +22,18 @@ config TMC5240
 	  To compile this driver as a module, choose M here: the
 	  module will be called tmc5240.
 
+config MOTION_SIMPLE_PWM
+	tristate "Simple PWM base DC motor driver"
+	depends on PWM
+	select MOTION_HELPERS
+	help
+	  Say Y here is you have a DC motor driver you wish to control
+	  with 1 or 2 PWM outputs. Typically this is an H-bridge or similar
+	  driver, like the TI DRV8873 for example.
+
+	  To compile this driver as a module, choose M here: the
+	  module will be called "motion-simple-pwm".
+
 config MOTION_HELPERS
 	bool
 	depends on MOTION
diff --git a/drivers/motion/Makefile b/drivers/motion/Makefile
index 4f4e31138503..6b13b527fa17 100644
--- a/drivers/motion/Makefile
+++ b/drivers/motion/Makefile
@@ -2,3 +2,4 @@
 obj-$(CONFIG_MOTION)		+= motion-core.o
 obj-$(CONFIG_MOTION_HELPERS)	+= motion-helpers.o
 obj-$(CONFIG_TMC5240)		+= tmc5240.o
+obj-$(CONFIG_MOTION_SIMPLE_PWM)	+= simple-pwm.o
diff --git a/drivers/motion/simple-pwm.c b/drivers/motion/simple-pwm.c
new file mode 100644
index 000000000000..89626c792235
--- /dev/null
+++ b/drivers/motion/simple-pwm.c
@@ -0,0 +1,199 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * Motion Control Subsystem - Simple speed proportional-PWM based motor driver
+ *
+ * Copyright (C) 2024 Protonic Holland
+ *      David Jander <david@protonic.nl>
+ */
+
+#include <asm-generic/errno-base.h>
+#include <linux/err.h>
+#include <linux/device.h>
+#include <linux/module.h>
+#include <linux/init.h>
+#include <linux/platform_device.h>
+#include <linux/of.h>
+#include <linux/of_platform.h>
+#include <linux/motion.h>
+#include <linux/types.h>
+#include <linux/pm.h>
+#include <linux/pwm.h>
+#include <asm/unaligned.h>
+
+#include "motion-core.h"
+#include "motion-helpers.h"
+
+#define MOTPWM_PWM_SCALE 100000
+#define MOTPWM_TIMER_PERIOD (20 * NSEC_PER_MSEC)
+
+struct motpwm {
+	struct pwm_device *pwms[2];
+	struct motion_device mdev;
+	struct platform_device *pdev;
+	bool pwm_inverted;
+};
+
+static inline int __effective_dc(struct motpwm *mp, unsigned int dc)
+{
+	if (mp->pwm_inverted)
+		return MOTPWM_PWM_SCALE - dc;
+	return dc;
+}
+
+static inline int __motpwm_set_speed_locked(struct motpwm *mp, unsigned int dir,
+		unsigned int dc, bool enable)
+{
+	struct pwm_state ps;
+	int cidx = !dir;
+	struct pwm_device *pwm, *cpwm;
+
+	dir = !!dir;
+	pwm = mp->pwms[dir];
+	cpwm = mp->pwms[cidx];
+
+	if (cpwm) {
+		pwm_init_state(cpwm, &ps);
+		ps.duty_cycle = __effective_dc(mp, 0);
+		ps.enabled = enable;
+		pwm_apply_might_sleep(cpwm, &ps);
+	}
+	if (!pwm)
+		return -EINVAL;
+
+	pwm_init_state(pwm, &ps);
+	pwm_set_relative_duty_cycle(&ps, __effective_dc(mp, dc), MOTPWM_PWM_SCALE);
+	ps.enabled = enable;
+	pwm_apply_might_sleep(pwm, &ps);
+
+	return 0;
+}
+
+static void motpwm_startup(struct motion_device *mdev)
+{
+	dev_info(mdev->dev, "Startup\n");
+}
+
+static void motpwm_powerdown(struct motion_device *mdev)
+{
+	struct motpwm *mp = container_of(mdev, struct motpwm, mdev);
+
+	dev_info(mdev->dev, "Shutdown\n");
+	__motpwm_set_speed_locked(mp, 0, 0, false);
+}
+
+static int motpwm_check_speed(struct motion_device *mdev, unsigned int dir,
+		unsigned int speed)
+{
+	struct motpwm *mp = container_of(mdev, struct motpwm, mdev);
+
+	if (!mp->pwms[!!dir])
+		return -EINVAL;
+
+	if (speed > MOTPWM_PWM_SCALE)
+		return -EINVAL;
+
+	return 0;
+}
+
+static void motpwm_set_speed(struct motion_device *mdev, unsigned int dir,
+		unsigned int speed)
+{
+	struct motpwm *mp = container_of(mdev, struct motpwm, mdev);
+
+	__motpwm_set_speed_locked(mp, dir, speed, true);
+}
+
+static struct motion_timed_speed_ops motpwm_mts_ops = {
+	.startup = motpwm_startup,
+	.powerdown = motpwm_powerdown,
+	.check_speed = motpwm_check_speed,
+	.set_speed = motpwm_set_speed
+};
+
+static int motpwm_probe(struct platform_device *pdev)
+{
+	struct motpwm *mp;
+	struct device *dev = &pdev->dev;
+	struct fwnode_handle *fwnode = dev_fwnode(dev);
+
+	mp = devm_kzalloc(dev, sizeof(struct motpwm), GFP_KERNEL);
+	if (!mp)
+		return -ENOMEM;
+
+	mp->pwms[0] = devm_fwnode_pwm_get(dev, fwnode, "left");
+	if (IS_ERR(mp->pwms[0])) {
+		int err = PTR_ERR(mp->pwms[0]);
+
+		if (err == -ENODEV)
+			mp->pwms[0] = NULL;
+		else
+			return err;
+	}
+	mp->pwms[1] = devm_fwnode_pwm_get(dev, fwnode, "right");
+	if (IS_ERR(mp->pwms[1])) {
+		int err = PTR_ERR(mp->pwms[1]);
+
+		if (err == -ENODEV)
+			mp->pwms[1] = NULL;
+		else
+			return err;
+	}
+	if (!mp->pwms[0] && !mp->pwms[1]) {
+		dev_err(dev, "Need at least one PWM");
+		return -ENODEV;
+	}
+
+	mp->pwm_inverted = fwnode_property_read_bool(fwnode, "motion,pwm-inverted");
+
+	mp->pdev = pdev;
+	platform_set_drvdata(pdev, mp);
+
+	mp->mdev.parent = &pdev->dev;
+	motion_timed_speed_init(&mp->mdev, &motpwm_mts_ops, MOTPWM_PWM_SCALE);
+	mp->mdev.capabilities.type = MOT_TYPE_DC_MOTOR;
+	mp->mdev.capabilities.subdiv = 1;
+	motion_fwnode_get_capabilities(&mp->mdev, fwnode);
+
+	return motion_register_device(&mp->mdev);
+}
+
+static void motpwm_shutdown(struct platform_device *pdev)
+{
+	struct motpwm *mp = platform_get_drvdata(pdev);
+
+	motion_unregister_device(&mp->mdev);
+}
+
+static int motpwm_suspend(struct device *dev)
+{
+	return 0;
+}
+
+static int motpwm_resume(struct device *dev)
+{
+	return 0;
+}
+
+static DEFINE_SIMPLE_DEV_PM_OPS(motpwm_pm, motpwm_suspend, motpwm_resume);
+
+static const struct of_device_id motpwm_of_match[] = {
+	{ .compatible = "motion-simple-pwm" },
+	{}
+};
+MODULE_DEVICE_TABLE(of, motpwm_of_match);
+
+static struct platform_driver motpwm_driver = {
+	.probe = motpwm_probe,
+	.shutdown = motpwm_shutdown,
+	.driver = {
+		.name = "motion-simple-pwm",
+		.pm = pm_sleep_ptr(&motpwm_pm),
+		.of_match_table = motpwm_of_match,
+	},
+};
+
+module_platform_driver(motpwm_driver);
+
+MODULE_AUTHOR("David Jander <david@protonic.nl>");
+MODULE_DESCRIPTION("Simple PWM based DC motor motion control driver");
+MODULE_LICENSE("GPL");
-- 
2.47.2


^ permalink raw reply related	[flat|nested] 59+ messages in thread

* [RFC PATCH 4/7] Documentation: Add Linux Motion Control documentation
  2025-02-27 16:28 [RFC PATCH 0/7] Add Linux Motion Control subsystem David Jander
                   ` (2 preceding siblings ...)
  2025-02-27 16:28 ` [RFC PATCH 3/7] motion: Add simple-pwm.c PWM based DC motor controller driver David Jander
@ 2025-02-27 16:28 ` David Jander
  2025-02-27 16:37   ` Jonathan Corbet
  2025-02-27 16:28 ` [RFC PATCH 5/7] dt-bindings: motion: Add common motion device properties David Jander
                   ` (5 subsequent siblings)
  9 siblings, 1 reply; 59+ messages in thread
From: David Jander @ 2025-02-27 16:28 UTC (permalink / raw)
  To: linux-kernel
  Cc: linux-iio, Jonathan Corbet, Rob Herring, Krzysztof Kozlowski,
	Conor Dooley, devicetree, linux-doc, Nuno Sa, Jonathan Cameron,
	Oleksij Rempel, David Jander

Add general- and UAPI documentation for the Linux Motion Control
subsystem.

Signed-off-by: David Jander <david@protonic.nl>
---
 Documentation/motion/index.rst       |  18 +
 Documentation/motion/motion-uapi.rst | 555 +++++++++++++++++++++++++++
 Documentation/subsystem-apis.rst     |   1 +
 3 files changed, 574 insertions(+)
 create mode 100644 Documentation/motion/index.rst
 create mode 100644 Documentation/motion/motion-uapi.rst

diff --git a/Documentation/motion/index.rst b/Documentation/motion/index.rst
new file mode 100644
index 000000000000..eee1c180478d
--- /dev/null
+++ b/Documentation/motion/index.rst
@@ -0,0 +1,18 @@
+.. SPDX-License-Identifier: GPL-2.0
+
+==============================
+Linux Motion Control Subsystem
+==============================
+
+.. toctree::
+   :maxdepth: 1
+
+   motion-uapi
+   motion-drivers
+
+.. only::  subproject and html
+
+   Indices
+   =======
+
+   * :ref:`genindex`
diff --git a/Documentation/motion/motion-uapi.rst b/Documentation/motion/motion-uapi.rst
new file mode 100644
index 000000000000..f57d62bcacb3
--- /dev/null
+++ b/Documentation/motion/motion-uapi.rst
@@ -0,0 +1,555 @@
+.. SPDX-License-Identifier: GPL-2.0
+
+===================================
+Linux Motion Control Subsystem UAPI
+===================================
+
+The User-space API for the Linux Motion Control (LMC) subsystem consists of
+a device node ioctl() interface and driver-specific sysfs attributes. The
+devnodes use dynamically allocated MAJOR numbers and are named /dev/motionX
+by default, where X is the ordinal of the device in probe order starting at
+zero. The entries in /sys/class/motion/... can be used to further identify
+each device.
+
+If CONFIG_IIO is defined, then also a IIO trigger device is created, that
+can be accessed via /sys/bus/iio/devices/iiotriggerX and the usual IIO API.
+
+Motion Control Background
+=========================
+
+A motion controller device can control one or more actuators (motors), that
+can move individually or synchronously. To accommodate for that, the API
+has two distinct ways of specifying the actuator channel a specific function
+applies to. Some structs take a single channel number as an unsigned integer,
+while others apply to a set of channels represented in the form of a bitmask.
+A "motion" in general can be any type of mechanical movement or displacement.
+This can be carried out by any sort of motor or linear actuator. Types of
+motors can be (but not limited to) brushed- or brushless DC motors, induction
+motors, switched-reluctance motors, stepper motors, etc...
+The mechanical movement can be coupled directly to a position sensor, such as
+a linear encoder for example. Some actuators (such as stepper motors) can be
+absolutely positioned without the need of a sensor.
+A mechanical movement (motion) can be described by a (multi-dimensional-)
+position and its two common time-derivatives, speed and acceleration.
+Depending on the motion controller's capabilities, these can be specified in
+more or less detail. For example a motor connected to a simple on-off switch
+can only be conrolled at zero or maximum speed. If an encoder is present,
+position control becomes possible. A stepper motor controller OTOH, can
+often precisely control all three, position, speed and acceleration, and
+sometimes even higher order time-derivatives, such as jerk.
+
+.. _motion-profiles:
+
+Motion profiles
+===============
+
+Some motion controllers have means of specifying a motion (or acceleration)
+profile. This is generally represented by a curve of speed versus time. The
+most common types of such a curve are triangular, trapezoidal, dual-slope and
+S-curve (or an 8-point approximation thereof).
+A triangular profile is in essence a special case of the trapezoidal profile,
+where constant maximum speed is never reached. LMC supports the following 3
+types of motion profiles:
+
+1. Trapezoidal
+--------------
+
+A trapezoidal profile is comprised of 3 speed values: Start-, maximum- and
+stop speed. 2 acceleration values determine the start and ending slopes of
+the trapezoid. Start- and stop speed need not be zero, nor equal. Specific
+constraints may depend on the underlying conroller, but often speed below
+a certain value is hard to attain for example with a stepper motor controller
+if the interval time between steps is limited. In addition to the 3 speed
+and 2 acceleration values, a value for minimum constant speed time can also
+be specified. This time value determines the minimum time the movement needs
+to have a constant speed after acceleration, before deceleration begins.
+
+2. Dual-slope
+-------------
+
+A dual-slope profile, is similar to a trapezoidal profile, but both the
+acceleration and deceleration phase is split in two sections. The transition
+point is determined by a 4th speed value which lies between max(Vs, Ve)
+and Vmax, where Vs, Vmax and Ve are the trapezoidal profile values for
+Start-, maximum- and stop speed respectively. Since there are two segments
+to each acceleration phase, this profile has 4 acceleration values.
+
+3. S-curve (8-point) profile
+----------------------------
+
+An 8-point profile (approximation of an S-curve) takes the dual-slope profile
+one step further by adding a second intermediate speed value, which results
+in acceleration and deceleration phases split into 3 segments each. This
+profile type thus has 5 speed values and 6 acceleration values.
+
+Units
+=====
+
+The LMC subsystem measures all time values in nanoseconds, in the format
+mot_time_t (signed 64-bit integer). This is similar to the current
+imoplementation of ktime_t, so conversion to/from mot_time_t is simple.
+Internally ktime_t is used, but since ktime_t cannot be interfaced to
+user-space directly, the mot_time_t type is defined for use in the user-
+space API, but it currently is equivalent to ktime_t.
+
+All position, speed and acceleration values are assumed in machine-units by
+the kernel.
+Machine-units are defined by the respective motion controller hardware.
+For example for a stepper motor controller with 1/256 microstepping,
+one unit of distance is equivalent to one microstep. Each driver can specify
+scaling factors to convert units in user-space if needed. Since speed and
+acceleration values have an implied time component, these conversion factors
+also have an implied time conversion from machine-time units to nanoseconds.
+These conversion factors are each specified by a rational number represented
+by a numerator and a denominator. Both are unsigned 32bit integers.
+
+Machine units for position, speed and acceleration are signed 32-bit integers,
+but have a type definition as pos_raw_t, speed_raw_t and accel_raw_t
+respectively.
+
+Convention of signed position, speed and acceleration:
+Movement of one channel is unidimensional, meaning position can be above or
+below the origin (positive or negative respecively). Consequently, given
+a positive position, a positive speed represents a movement further away
+from the origin (position 0), while a negative speed value represents a
+movement towards the origin. The opposite is valid when starting from a
+negative position value.
+Analogous to what speed does to position, is what acceletation does to speed:
+Given positive speed, positive acceleration increments the speed, and given
+"negative" speed, negative acceleration decrements the speed (increments its
+absolute value).
+For movement profiles, the convention is that profile (acceleration-, speed-)
+values are strictly positive. The direction of movement is solely determined
+by the relative position (i.e. "positive" or "negative" displacement).
+
+
+IOCTL based interface description
+=================================
+
+API capabilities interrogation
+------------------------------
+
+``ioctl(fd, MOT_IOCTL_APIVER, null)``
+ Function return value is the LMC API version number, or -1 on error.
+
+``ioctl(fd, MOT_IOCTL_GET_CAPA, struct mot_capabilities *capa)``
+ Returns a struct mot_capabilities filled in.
+
+Basic motion control
+--------------------
+
+``ioctl(fd, MOT_IOCTL_GET_STATUS, struct mot_status *st)``
+ Takes a struct mot_status with the channel parameter filled in and
+ specifying the channel number for which to retrieve the status.
+ Returns the current speed and position (if supported) in the same
+ struct.
+
+``ioctl(fd, MOT_IOCTL_BASIC_RUN, struct mot_speed_duration *s)``
+ Takes a struct mot_speed_duration with the channel number, the speed and
+ optionally either a non-zero value of duration or a non-zero value of
+ distance. Note that one of these two values *must* be zero, otherwise
+ an error is returned. If both are zero, then a movement is started
+ with speed abs(speed) and direction the sign of speed for an indefinite
+ amount of time. If duration is non-zero, then the movement is stopped
+ at most after duration (in nanoseconds).
+
+``ioctl(fd, MOT_IOCTL_BASIC_STOP, u32 chmsk)``
+ Takes an unsigned 32-bit integer argument chmsk, which represents a bit-mask
+ of channels. All current movements of all specified channels are stopped at
+ once.
+
+Feedback control
+----------------
+
+``ioctl(fd, MOT_IOCTL_CONFIG_INPUT, struct mot_input *inp)``
+ Takes a struct mot_input with an index number, a function value and a channel
+ bit-mask among other flags. This configures one of the internal or external
+ feedback inputs of the motion controller for a certain function to act on a
+ set of channels as specified by the chmask bit-mask. A common type of feedback
+ input for example are end-stop switches on a 3D printer. If the function
+ parameter is set to MOT_INP_FUNC_NONE (0) then the specified input is
+ deconfigured.
+
+Profile-based control
+---------------------
+
+``ioctl(fd, MOT_IOCTL_SET_PROFILE, struct mot_profile *p)``
+ Adjust a motion profile for the specified slot index to the values supplied
+ by this struct. (MOT_MAX_PROFILES-1) is the highest accepted value for index.
+ The only values allowed for na (number of acceleration values) are 2, 4 or 6.
+ The only values allowed for nv (number of speed values) are 3, 4 or 5. A
+ specific driver can restrict these parameters even further. This is
+ communicated in the struct mot_capabilities data.
+
+``ioctl(fd, MOT_IOCTL_GET_PROFILE, struct mot_profile *p)``
+ Takes the index from the provided struct mot_profile and returns a the same
+ struct with the profile values filled in for that index. Returns an erro if
+ the index does not point to a valid profile.
+
+``ioctl(fd, MOT_IOCTL_START, struct mot_start *s)``
+ Takes a struct mot_start, that programs a motion to start immediately or
+ triggered by an event. The motion can be time-based if the duration parameter
+ is non-zero - in this case also the direction parameter is taken into
+ account - or distance-base. In the latter case the duration value must be
+ zero and in the former case, the distance value must be zero. The parameter
+ index specifies a motion profile to use for this movement.
+
+``ioctl(fd, MOT_IOCTL_START, struct mot_start *s)``
+ Takes a struct mot_stop. This struct contains a channel mask parameter chmask,
+ which contains a bit-mask of all channels this command applis to. All motions
+ of selected channels are stopped or prepared to be stopped by an event,
+ following the deceleration path of the selected motion profile that started
+ each respective motion or immediately, depending on the function of the
+ trigger input that has been armed for each respective channel (if applicable).
+
+Unimplemented future functionality
+----------------------------------
+
+``ioctl(fd, MOT_IOCTL_TORQUE_LIMITS, struct mot_torque *t)``
+ Analogous to motion profiles, torque limit curves can augment a motion profile
+ with a time-sectioned or position-sectioned profile of torque limit values.
+ Background for torque limit curves: In some cases, it is desired to limit the
+ torque (or force) of a movement depending on the position. For example when
+ hitting an end-stop. In the case of a sliding door for example, one might
+ require higher torque initially, while limiting torque during the reminder of
+ the movement, in order to detect stalls due to a person standing in the way
+ of the door without causing injuries. Torque control isn't always possible,
+ and sometimes only in a limited fashion. For example, on AC motors, the
+ controller could vary the gain of the V/f curve to reduce or increase the
+ stall or slip limit. Stepper- or BLDC motor could vary the run current limit,
+ or stall detect threshold.
+
+``ioctl(fd, MOT_IOCTL_VECTOR_START, struct mot_vector *v)``
+ Takes a struct mot_vector, that defines a multi-channel coordinated multi-
+ dimensional linear movement along an n-dimensional space vector following a
+ motion profile and optional torque curve. The chmask bit-mask specifies the
+ channels that participate in this movement. The vector dist[] has the same
+ size as the number of bits set in chmask and specifies the nth coordinate
+ of the vector. This would be the prime application for controlling 3D
+ printers, where tight coordination of several axes is required.
+
+Constants used in the ioctl API
+-------------------------------
+
+The following constants are used in different field of the structs provided
+to or returned by the ioctl API:
+
+.. code-block:: C
+
+   /* Trigger inputs and End Stop functions */
+   enum {
+           MOT_INP_FUNC_NONE = 0,
+           MOT_INP_FUNC_STOP,
+           MOT_INP_FUNC_STOP_POS,
+           MOT_INP_FUNC_STOP_NEG,
+           MOT_INP_FUNC_DECEL,
+           MOT_INP_FUNC_DECEL_POS,
+           MOT_INP_FUNC_DECEL_NEG,
+           MOT_INP_FUNC_START,
+           MOT_INP_FUNC_SIGNAL,
+           MOT_INP_FUNC_LAST
+   };
+
+These constants are used in for the field function of struct mot_input.
+This field specicies the function that a specified trigger input or end-stop
+should have on the selected channels. FUNC_STOP means immediately set the
+speed to zero, not following an acceleration curve, whereas FUNC_DECEL means
+stopping by folowwing the deceleration slope(s) specified in the motion
+profile that started the motion. _NEG and _POS restrict the action of the
+trigger to act on backwards (_NEG, into negative distance) or forwards (_POS,
+into positive distance) motion. If this is specified and the controller
+supports this, this will avoid a situation in which an actuator that has
+two end-stops for example at each extreme of the actuation range will stop
+a movement to "the left" when the "right" end-stop is accidentally triggered.
+MOT_INP_FUNC_SIGNAL will only generate an event to user-space or the IIO
+trigger and not affect the motion directly.
+
+.. code-block:: C
+
+   /* Config trigger input edge */
+   #define MOT_EDGE_RISING 0
+   #define MOT_EDGE_FALLING 1
+
+These constants are used for the edge parameter in ioctl structs. It specifies
+the trigger input to be high-active (MOT_EDGE_RISING) or low-active
+(MOT_EDGE_FALLING).
+
+.. code-block:: C
+
+   /* Start/Stop conditions */
+   enum {
+           MOT_WHEN_IMMEDIATE = 0,
+           MOT_WHEN_INT_TRIGGER,
+           MOT_WHEN_EXT_TRIGGER,
+           MOT_WHEN_NEXT,
+           MOT_WHEN_LAST
+   };
+
+Each parameter called "when" in the ioctl structs can potentially take one
+of the MOT_WHEN_xxx values. INT_TRIGGER will execute the corresponding action
+on an internal trigger signal, while EXT_TRIGGER will execute the
+corresponding action on an external trigger signal (GPIO specified in fwnode).
+MOT_WHEN_NEXT makes it possible to prepare a new motion that will start when
+the currently active motion ends. By listening to poll() events of type
+MOT_EVENT_TARGET and then sending the next motion start command with
+MOT_WHEN_NEXT, it is possible to produce an uninterrupted stream of
+consecutive movements. In that case MOT_EVENT_TARGET correspondes to the
+end of the preceding motion that ended when the current "next" motion is
+started, freeing the slot for the new "next" motion after that.
+
+.. code-block:: C
+
+   /* Event types */
+   enum {
+           MOT_EVENT_NONE = 0,
+           MOT_EVENT_TARGET,
+           MOT_EVENT_STOP,
+           MOT_EVENT_INPUT,
+           MOT_EVENT_STALL,
+           MOT_EVENT_ERROR,
+           MOT_EVENT_LAST
+   };
+
+These are constants for the event field of struct mot_event. See below for
+a description of events ingeneral. The type of events reported to user space
+are "target reached" (MOT_EVENT_TARGET), "stopped by internal trigger"
+(MOT_EVENT_STOP), "external trigger" (MOT_EVENT_INPUT) or different fault
+conditions (stall or generic error event). MOT_EVENT_STALL can be produced by
+some motion controllers that can react to motor stalls in a natural way, for
+example in the case of force-based obstacle- or end stop detection.
+
+.. code-block:: C
+
+   #define MOT_DIRECTION_LEFT 0
+   #define MOT_DIRECTION_RIGHT 1
+
+These constants are used for specifying direction of movement. LEFT in this
+case means decreasing position value, while RIGHT is increasing position
+value.
+
+Structs used in the ioctl API
+-----------------------------
+
+.. code-block:: C
+
+   #define MOT_FEATURE_SPEED	BIT(0)
+   #define MOT_FEATURE_ACCEL	BIT(1)
+   #define MOT_FEATURE_ENCODER	BIT(2)
+   #define MOT_FEATURE_PROFILE	BIT(3)
+   #define MOT_FEATURE_VECTOR	BIT(4)
+
+   enum motion_device_type {
+           MOT_TYPE_DC_MOTOR,
+           MOT_TYPE_AC_MOTOR,
+           MOT_TYPE_STEPPER,
+           MOT_TYPE_BLDC,
+           MOT_TYPE_SRM,
+           MOT_TYPE_LINEAR,
+           MOT_TYPE_LAST
+   };
+
+   struct mot_capabilities {
+           __u32 features;
+           __u8 type;
+           __u8 num_channels;
+           __u8 num_int_triggers;
+           __u8 num_ext_triggers;
+           __u8 max_profiles;
+           __u8 max_vpoints;
+           __u8 max_apoints;
+           __u8 reserved1;
+           __u32 subdiv;
+           __u32 speed_conv_mul;
+           __u32 speed_conv_div;
+           __u32 accel_conv_mul;
+           __u32 accel_conv_div;
+           __u32 reserved2;
+   };
+
+The field ``features`` is a bit-mask of MOT_FEATURE_XX flags. The feature
+SPEED means that the motion controller supports adjustable speed. All but the
+most simple (on/off switch) controllers will have this bit set.
+ACCEL means that the motion controller supports specifying acceleration
+values. Not that this is not sufficient to indicate that motion profiles can
+be used.
+ENCODER meaans that the motion controller has a built-in or fixed connected
+position encoder. If this bit is set, the position values returned by
+MOT_IOCTL_GET_STATUS can be assumed to be accurate. I.e. slip and/or skipped
+steps are properly taken into account.
+PROFILE means that the motion controller supports setting motion profiles.
+How many profiles, and how many speed and/or acceleration values are supported
+is inticated by the fields ``max_profiles``, ``max_vpoints`` and
+``max_apoints``.
+The field ``type`` can take any of the values MOT_TYPE_XX and is only
+informative. The fields ``num_channels``, ``num_int_triggers`` and
+``num_ext_triggers`` specify the supported number of channels, internal
+triggers and configured external triggers respectively.
+The field ``subdiv`` can have a different meaning, depending on the type of
+motion controller. For example for stepper motors, this typically indicates
+the microstepping divider. If this number is not 1, this means that the value
+of distance divided by ``subdiv`` will give the amount of machine-natural
+mechanical units of distance (whole steps in case of a stepper motor).
+The 4 different ``_conv_`` fields specify two rational conversion factors for
+speed and acceleration respectively. All unit conversions of speed and
+acceleration are done in user-space. The kernel only provides these numbers
+to user-space as part of physical characteristics of the motion controller.
+If the driver does not specify these values, or they lack a defined meaning,
+all four of these fields will have a value of 1, so no zero-division can
+happen and the conversion is just 1:1.
+
+.. code-block:: C
+
+   struct mot_speed_duration {
+           __u32 channel;
+           speed_raw_t speed;
+           mot_time_t duration;
+           pos_raw_t distance;
+           __u32 reserved[3];
+   };
+
+This struct is used int the ioctl MOT_IOCTL_BASIC_RUN to start a new motion.
+There are different ways of using BASIC_RUN:
+
+ 1. Specify only ``channel`` and ``speed``. All other fields are zero. This
+    starts a new motion for indefinte amount of time.
+
+ 2. Additionally to 1. specify non-zero ``duration``. Starts a timed motion
+    that will stop after the specified time.
+
+ 3. Additionally to 1. specify non-zero ``distance``. Starts a motion until
+    the position specified by distance from starting point is reached.
+
+Non zero values for both ``duration`` and ``distance`` will result in an
+error (-EINVAL).
+
+.. code-block:: C
+
+   struct mot_status {
+           __u32 channel;
+           pos_raw_t position;
+           speed_raw_t speed;
+           __u32 local_inputs;
+   };
+
+This struct is used for the ioctl MOT_IOCTL_GET_STATUS. The caller needs to
+set the field ``channel`` to the channel number it wants to request status
+information from. After a successful call, the field ``speed`` will contain
+the current speed of movement of the channel, and ``position`` will contain
+the actual position if this is supported by the hardware. The field
+``local_inputs`` contains a bit-mask of the state of all internal trigger
+inputs.
+
+.. code-block:: C
+
+   struct mot_input {
+           __u32 index;
+           __u8 external;
+           __u8 edge;
+           __u8 reserved[2];
+           __u32 function;
+           channel_mask_t chmask;
+   };
+
+This struct is used for configuring internal or external trigger inputs. The
+input ``index`` is specific to the flag ``external``. This means that internal
+and external trigger inputs can have the same ``index`` value. The exact
+``index`` value for internal inputs is determined by the driver and should be
+enumerated from 0 onwards. For external GPIO intputs the index number is the
+order in which they appear in the fwnode (DT property "motion,gpios").
+``edge`` indicates the polarity of the input electrical signal,
+MOT_EDGE_FALLING or MOT_EDGE_RISING. Please note, that any GPIO polarity is
+also applied. So if a GPIO input is GPIO_ACTIVE_LOW and ``edge`` is
+MOT_EDGE_FALLING, the resulting trigger will occur on the rising edge of the
+electrical input signal.
+``function`` takes any of the MOT_INP_FUNC_XX values mentioned above.
+``chmask`` is a bit-mask of all motion channels this input will affect.
+
+.. code-block:: C
+
+   struct mot_profile {
+           __u32 index;
+           mot_time_t tvmax;
+           mot_time_t tvzero;
+           __u8 na;
+           __u8 nv;
+           __u8 reserved[2];
+           accel_raw_t acc[MOT_MAX_ACCELPTS];
+           speed_raw_t vel[MOT_MAX_SPEEDPTS];
+   };
+
+Used to define a motion profile. See :ref:`motion-profiles` for a general
+explanation of motion profiles. ``nv`` and ``na`` are the number of valid
+entries in the ``velp[]`` and ``acc[]`` arrays respectively. ``tvmax`` is the
+minimum amount of time the constant (maximum) speed needs to be maintained
+after ending the acceleration phase, and before beginning the deceleration
+phase. ``tvzero`` is the minimum amount of time the speed needs to be 0,
+before a new motion is started in the same direction as the preceding motion.
+In other words, analogous to ``tvmax``, a new acceleration with opposite sign
+of the preceding deceleration. This time value is not applied if the next
+motion is into the opposite direction, since there will be no change in the
+sign of the resulting acceleration.
+
+.. code-block:: C
+
+   struct mot_start {
+           __u32 channel;
+           __u8 direction;
+           __u8 index;
+           __u8 when;
+           __u8 reserved1;
+           mot_time_t duration;
+           pos_raw_t distance;
+           __u32 reserved2;
+   };
+
+Used for the MOT_IOCTL_START ioctl. The ``index`` parameter is the index
+number of the motion profile that will be used for the motion. ``when``
+determines when (under which condition) the motion is started, and takes
+the value of any of the MOT_WHEN_XX constants. Like in the case of struct
+mot_speed_duration, here also ``duration`` and ``distance`` are mutually
+exclusive, meaning that one of both must always be zero.
+
+.. code-block:: C
+
+   struct mot_stop {
+           channel_mask_t chmask;
+           __u8 when;
+           __u8 reserved[3];
+   };
+
+This struct is used to schedule a deceleration of a running motion of all
+channels specified by ``chmask``, by following the deceleration part of their
+respecive motion profiles. ``when`` takes any of the MOT_WHEN_XX constants and
+determines the condition that triggers the deceleration.
+
+Event handling with (e)poll/select
+----------------------------------
+
+When user-space opens the devnode for reading, (e)poll() can be used to wait
+for motion events, using the (E)POLLIN flag. These events can then be read by
+calling read() on the file-descriptor with a buffer size equal to the size of
+struct mot_event. Make sure the file is opened in non-blocking mode for
+for reliable event processing. read() will return -EAGAIN in this case.
+
+.. code-block:: C
+
+   struct mot_event {
+           __u32 channel;
+           __u8 event;
+           __u8 reserved1[3];
+           pos_raw_t position;
+           speed_raw_t speed;
+           mot_time_t timestamp;
+           __u32 input_index;
+           __u32 reserved2;
+   };
+
+``event`` can take any of the MOT_EVENT_XX constants, and is used to determine
+the type of event. The values of ``position``, ``speed`` and ``timestamp`` are
+the corresponding motion position, speed and time at which the event ocurred.
+Not all drivers support reporting a position value. If they don't that field
+will always be zero. ``input_index`` is the index number of the external input
+(in the case of a MOT_EVENT_INPUT event), or the index number of the internal
+input (in the case of a MOT_EVENT_STOP event), that caused the event. For
+other event types than MOT_EVENT_INPUT or MOT_EVENT_STOP, this field has no
+meaning and will be zero.
diff --git a/Documentation/subsystem-apis.rst b/Documentation/subsystem-apis.rst
index b52ad5b969d4..0707b297f150 100644
--- a/Documentation/subsystem-apis.rst
+++ b/Documentation/subsystem-apis.rst
@@ -90,3 +90,4 @@ Other subsystems
    peci/index
    wmi/index
    tee/index
+   motion/index
-- 
2.47.2


^ permalink raw reply related	[flat|nested] 59+ messages in thread

* [RFC PATCH 5/7] dt-bindings: motion: Add common motion device properties
  2025-02-27 16:28 [RFC PATCH 0/7] Add Linux Motion Control subsystem David Jander
                   ` (3 preceding siblings ...)
  2025-02-27 16:28 ` [RFC PATCH 4/7] Documentation: Add Linux Motion Control documentation David Jander
@ 2025-02-27 16:28 ` David Jander
  2025-02-28  7:06   ` Krzysztof Kozlowski
  2025-02-28  7:13   ` Krzysztof Kozlowski
  2025-02-27 16:28 ` [RFC PATCH 6/7] dt-bindings: motion: Add adi,tmc5240 bindings David Jander
                   ` (4 subsequent siblings)
  9 siblings, 2 replies; 59+ messages in thread
From: David Jander @ 2025-02-27 16:28 UTC (permalink / raw)
  To: linux-kernel
  Cc: linux-iio, Jonathan Corbet, Rob Herring, Krzysztof Kozlowski,
	Conor Dooley, devicetree, linux-doc, Nuno Sa, Jonathan Cameron,
	Oleksij Rempel, David Jander

Add device-tree binding documentation for common Linux Motion Control
device properties.

Signed-off-by: David Jander <david@protonic.nl>
---
 .../devicetree/bindings/motion/common.yaml    | 52 +++++++++++++++++++
 1 file changed, 52 insertions(+)
 create mode 100644 Documentation/devicetree/bindings/motion/common.yaml

diff --git a/Documentation/devicetree/bindings/motion/common.yaml b/Documentation/devicetree/bindings/motion/common.yaml
new file mode 100644
index 000000000000..e92b360a0698
--- /dev/null
+++ b/Documentation/devicetree/bindings/motion/common.yaml
@@ -0,0 +1,52 @@
+# SPDX-License-Identifier: (GPL-2.0 OR BSD-2-Clause)
+%YAML 1.2
+---
+$id: http://devicetree.org/schemas/motion/common.yaml#
+$schema: http://devicetree.org/meta-schemas/core.yaml#
+
+title: Common properties for motion control devices
+
+maintainers:
+  - David Jander <david@protonic.nl>
+
+description: |
+  This document defines device tree properties common to several motion control
+  devices. It doesn't constitute a device tree binding specification by itself but
+  is meant to be referenced by device tree bindings.
+
+  When referenced from motion device tree bindings the properties defined in this
+  document are defined as follows. The motion device tree bindings are responsible
+  for defining whether each property is required or optional.
+
+properties:
+  motion,speed-conv-mul:
+    $ref: /schemas/types.yaml#/definitions/uint32
+    default: 1
+    description: |
+      Numerator of a fractional representation of a speed conversion factor.
+      The speed conversion factor (represented by numerator and denominator)
+      is multiplied with the internal speed unit to obtain the physical speed
+      unit of the controller. For example, for a stepper motor controller, the
+      physical speed unit is microsteps/second (Hz).
+
+  motion,speed-conv-div:
+    $ref: /schemas/types.yaml#/definitions/uint32
+    default: 1
+    description: |
+      Denominator of fractional representation of a speed conversion factor.
+
+  motion,acceleration-conv-mul:
+    $ref: /schemas/types.yaml#/definitions/uint32
+    default: 1
+    description: |
+      Numerator of a fractional representation of an acceleration conversion
+      factor.
+
+  motion,acceleration-conv-div:
+    $ref: /schemas/types.yaml#/definitions/uint32
+    default: 1
+    description: |
+      Denominator of fractional representation of an acceleration conversion
+      factor.
+
+additionalProperties: true
-- 
2.47.2


^ permalink raw reply related	[flat|nested] 59+ messages in thread

* [RFC PATCH 6/7] dt-bindings: motion: Add adi,tmc5240 bindings
  2025-02-27 16:28 [RFC PATCH 0/7] Add Linux Motion Control subsystem David Jander
                   ` (4 preceding siblings ...)
  2025-02-27 16:28 ` [RFC PATCH 5/7] dt-bindings: motion: Add common motion device properties David Jander
@ 2025-02-27 16:28 ` David Jander
  2025-02-28  7:11   ` Krzysztof Kozlowski
  2025-02-28 22:38   ` David Lechner
  2025-02-27 16:28 ` [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings David Jander
                   ` (3 subsequent siblings)
  9 siblings, 2 replies; 59+ messages in thread
From: David Jander @ 2025-02-27 16:28 UTC (permalink / raw)
  To: linux-kernel
  Cc: linux-iio, Jonathan Corbet, Rob Herring, Krzysztof Kozlowski,
	Conor Dooley, devicetree, linux-doc, Nuno Sa, Jonathan Cameron,
	Oleksij Rempel, David Jander

Add device-tree bindings for Analog Devices TMC5240 stepper controllers.

Signed-off-by: David Jander <david@protonic.nl>
---
 .../bindings/motion/adi,tmc5240.yaml          | 60 +++++++++++++++++++
 1 file changed, 60 insertions(+)
 create mode 100644 Documentation/devicetree/bindings/motion/adi,tmc5240.yaml

diff --git a/Documentation/devicetree/bindings/motion/adi,tmc5240.yaml b/Documentation/devicetree/bindings/motion/adi,tmc5240.yaml
new file mode 100644
index 000000000000..3364f9dfccb1
--- /dev/null
+++ b/Documentation/devicetree/bindings/motion/adi,tmc5240.yaml
@@ -0,0 +1,60 @@
+# SPDX-License-Identifier: (GPL-2.0 OR BSD-2-Clause)
+%YAML 1.2
+---
+$id: http://devicetree.org/schemas/motion/adi,tmc5240.yaml#
+$schema: http://devicetree.org/meta-schemas/core.yaml#
+
+title: Analog Devices TMC5240 Stepper Motor controller
+
+maintainers:
+  - David Jander <david@protonic>
+
+description: |
+   Stepper motor controller with motion engine and SPI interface.
+
+properties:
+  compatible:
+    enum:
+      - adi,tmc5240
+
+  reg:
+    maxItems: 1
+
+  interrupts:
+    maxItems: 1
+
+  enable-supply:
+    description: Optional external enable supply to control SLEEPn pin. Can
+      be shared between several controllers.
+
+  clocks:
+    maxItems: 1
+
+required:
+  - compatible
+  - reg
+  - interrupts
+  - clocks
+
+allOf:
+  - $ref: /schemas/spi/spi-peripheral-props.yaml#
+  - $ref: /schemas/motion/common.yaml#
+
+unevaluatedProperties: false
+
+examples:
+  - |
+    spi {
+        #address-cells = <1>;
+        #size-cells = <0>;
+
+        motor@0 {
+            compatible = "adi,tmc5240";
+            reg = <0>;
+            interrupts-extended = <&gpiok 7 0>;
+            clocks = <&clock_tmc5240>;
+            enable-supply = <&stpsleepn>;
+            spi-max-frequency = <1000000>;
+        };
+    };
+
-- 
2.47.2


^ permalink raw reply related	[flat|nested] 59+ messages in thread

* [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings
  2025-02-27 16:28 [RFC PATCH 0/7] Add Linux Motion Control subsystem David Jander
                   ` (5 preceding siblings ...)
  2025-02-27 16:28 ` [RFC PATCH 6/7] dt-bindings: motion: Add adi,tmc5240 bindings David Jander
@ 2025-02-27 16:28 ` David Jander
  2025-02-27 17:38   ` Rob Herring (Arm)
                     ` (2 more replies)
  2025-02-28  9:34 ` [RFC PATCH 0/7] Add Linux Motion Control subsystem Pavel Pisa
                   ` (2 subsequent siblings)
  9 siblings, 3 replies; 59+ messages in thread
From: David Jander @ 2025-02-27 16:28 UTC (permalink / raw)
  To: linux-kernel
  Cc: linux-iio, Jonathan Corbet, Rob Herring, Krzysztof Kozlowski,
	Conor Dooley, devicetree, linux-doc, Nuno Sa, Jonathan Cameron,
	Oleksij Rempel, David Jander

Add device-tree bindings for simple Linux Motion Control devices that
are based on 1 or 2 PWM outputs.

Signed-off-by: David Jander <david@protonic.nl>
---
 .../bindings/motion/motion-simple-pwm.yaml    | 55 +++++++++++++++++++
 1 file changed, 55 insertions(+)
 create mode 100644 Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml

diff --git a/Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml b/Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml
new file mode 100644
index 000000000000..409e3aef6f3f
--- /dev/null
+++ b/Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml
@@ -0,0 +1,55 @@
+# SPDX-License-Identifier: (GPL-2.0 OR BSD-2-Clause)
+%YAML 1.2
+---
+$id: http://devicetree.org/schemas/motion/motion-simple-pwm.yaml#
+$schema: http://devicetree.org/meta-schemas/core.yaml#
+
+title: Simple PWM based motor controller
+
+maintainers:
+  - David Jander <david@protonic>
+
+description: |
+   Simple motor control device based on 1 or 2 PWM outputs
+
+properties:
+  compatible:
+    enum:
+      - motion-simple-pwm
+
+  pwms:
+    maxItems: 2
+
+  pwm-names:
+    maxItems: 2
+
+  motion,pwm-inverted:
+    $ref: /schemas/types.yaml#/definitions/flag
+    description:
+      If present, this flag indicates that the PWM signal should be inverted.
+      The duty-cycle will be scaled from 100% down to 0% instead 0% to 100%.
+
+required:
+  - compatible
+  - pwms
+
+allOf:
+  - $ref: /schemas/motion/common.yaml#
+
+unevaluatedProperties: false
+
+examples:
+  - |
+    // This example shows how to use the TI DRV8873 or similar motor controllers
+    // with this driver
+    motion-simple-pwm0 {
+      compatible = "motion-simple-pwm";
+      pwms = <&hpdcm0_pwm 0 50000 0>,
+             <&hpdcm0_pwm 1 50000 0>;
+      pwm-names = "left", "right";
+      motion,pwm-inverted;
+      motion,speed-conv-mul = <3600>;
+      motion,speed-conv-div = <100000>;
+      motion,acceleration-conv-mul = <3600>;
+      motion,acceleration-conv-div = <100000>;
+    };
-- 
2.47.2


^ permalink raw reply related	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 4/7] Documentation: Add Linux Motion Control documentation
  2025-02-27 16:28 ` [RFC PATCH 4/7] Documentation: Add Linux Motion Control documentation David Jander
@ 2025-02-27 16:37   ` Jonathan Corbet
  2025-02-28 13:02     ` David Jander
  0 siblings, 1 reply; 59+ messages in thread
From: Jonathan Corbet @ 2025-02-27 16:37 UTC (permalink / raw)
  To: David Jander, linux-kernel
  Cc: linux-iio, Rob Herring, Krzysztof Kozlowski, Conor Dooley,
	devicetree, linux-doc, Nuno Sa, Jonathan Cameron, Oleksij Rempel,
	David Jander

David Jander <david@protonic.nl> writes:

> Add general- and UAPI documentation for the Linux Motion Control
> subsystem.
>
> Signed-off-by: David Jander <david@protonic.nl>
> ---
>  Documentation/motion/index.rst       |  18 +
>  Documentation/motion/motion-uapi.rst | 555 +++++++++++++++++++++++++++
>  Documentation/subsystem-apis.rst     |   1 +
>  3 files changed, 574 insertions(+)
>  create mode 100644 Documentation/motion/index.rst
>  create mode 100644 Documentation/motion/motion-uapi.rst

I am glad to see this feature coming with documentation!  Please,
though, do not create a top-level "motion" directory for it - that is
just the kind of organization I've been trying to get us away from for a
while.  This document is clearly aimed at user-space developers, and
thus should be part of the userspace-api book ... please?

Thanks,

jon

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings
  2025-02-27 16:28 ` [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings David Jander
@ 2025-02-27 17:38   ` Rob Herring (Arm)
  2025-02-28  7:12   ` Krzysztof Kozlowski
  2025-02-28 22:41   ` David Lechner
  2 siblings, 0 replies; 59+ messages in thread
From: Rob Herring (Arm) @ 2025-02-27 17:38 UTC (permalink / raw)
  To: David Jander
  Cc: Krzysztof Kozlowski, devicetree, Jonathan Corbet, Nuno Sa,
	linux-iio, linux-doc, Jonathan Cameron, Conor Dooley,
	linux-kernel, Oleksij Rempel


On Thu, 27 Feb 2025 17:28:23 +0100, David Jander wrote:
> Add device-tree bindings for simple Linux Motion Control devices that
> are based on 1 or 2 PWM outputs.
> 
> Signed-off-by: David Jander <david@protonic.nl>
> ---
>  .../bindings/motion/motion-simple-pwm.yaml    | 55 +++++++++++++++++++
>  1 file changed, 55 insertions(+)
>  create mode 100644 Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml
> 

My bot found errors running 'make dt_binding_check' on your patch:

yamllint warnings/errors:

dtschema/dtc warnings/errors:
/builds/robherring/dt-review-ci/linux/Documentation/devicetree/bindings/motion/motion-simple-pwm.example.dtb: motion-simple-pwm0: 'motion,acceleration-conv-div', 'motion,acceleration-conv-mul', 'motion,pwm-inverted', 'motion,speed-conv-div', 'motion,speed-conv-mul' do not match any of the regexes: '^#.*', '^(at25|bm|devbus|dmacap|dsa|exynos|fsi[ab]|gpio-fan|gpio-key|gpio|gpmc|hdmi|i2c-gpio),.*', '^(keypad|m25p|max8952|max8997|max8998|mpmc),.*', '^(pinctrl-single|#pinctrl-single|PowerPC),.*', '^(pl022|pxa-mmc|rcar_sound|rotary-encoder|s5m8767|sdhci),.*', '^(simple-audio-card|st-plgpio|st-spics|ts),.*', '^100ask,.*', '^70mai,.*', '^8dev,.*', '^GEFanuc,.*', '^IBM,.*', '^ORCL,.*', '^SUNW,.*', '^[a-zA-Z0-9#_][a-zA-Z0-9+\\-._@]{0,63}$', '^[a-zA-Z0-9+\\-._]*@[0-9a-zA-Z,]*$', '^abb,.*', '^abilis,.*', '^abracon,.*', '^abt,.*', '^acbel,.*', '^acelink,.*', '^acer,.*', '^acme,.*', '^actions,.*', '^active-semi,.*', '^ad,.*', '^adafruit,.*', '^adapteva,.*', '^adaptrum,.*', '^adh,.*', '^adi,.*', '^adieng,.*', '^admatec,.*', '^advantech,.*', '^aeroflexgaisler,.*', '^aesop,.*', '^airoha,.*', '^al,.*', '^alcatel,.*', '^aldec,.*', '^alfa-network,.*', '^allegro,.*', '^allegromicro,.*', '^alliedvision,.*', '^allo,.*', '^allwinner,.*', '^alphascale,.*', '^alps,.*', '^alt,.*', '^altr,.*', '^amarula,.*', '^amazon,.*', '^amcc,.*', '^amd,.*', '^amediatech,.*', '^amlogic,.*', '^ampere,.*', '^amphenol,.*', '^ampire,.*', '^ams,.*', '^amstaos,.*', '^analogix,.*', '^anbernic,.*', '^andestech,.*', '^anvo,.*', '^aosong,.*', '^apm,.*', '^apple,.*', '^aptina,.*', '^arasan,.*', '^archermind,.*', '^arcom,.*', '^arctic,.*', '^arcx,.*', '^aries,.*', '^arm,.*', '^armadeus,.*', '^armsom,.*', '^arrow,.*', '^artesyn,.*', '^asahi-kasei,.*', '^asc,.*', '^asix,.*', '^aspeed,.*', '^asrock,.*', '^asteralabs,.*', '^asus,.*', '^atheros,.*', '^atlas,.*', '^atmel,.*', '^auo,.*', '^auvidea,.*', '^avago,.*', '^avia,.*', '^avic,.*', '^avnet,.*', '^awinic,.*', '^axentia,.*', '^axis,.*', '^azoteq,.*', '^azw,.*', '^baikal,.*', '^bananapi,.*', '^beacon,.*', '^beagle,.*', '^belling,.*', '^bhf,.*', '^bigtreetech,.*', '^bitmain,.*', '^blaize,.*', '^blutek,.*', '^boe,.*', '^bosch,.*', '^boundary,.*', '^brcm,.*', '^broadmobi,.*', '^bsh,.*', '^bticino,.*', '^buffalo,.*', '^bur,.*', '^bytedance,.*', '^calamp,.*', '^calao,.*', '^calaosystems,.*', '^calxeda,.*', '^cameo,.*', '^canaan,.*', '^caninos,.*', '^capella,.*', '^cascoda,.*', '^catalyst,.*', '^cavium,.*', '^cct,.*', '^cdns,.*', '^cdtech,.*', '^cellwise,.*', '^ceva,.*', '^chargebyte,.*', '^checkpoint,.*', '^chefree,.*', '^chipidea,.*', '^chipone,.*', '^chipspark,.*', '^chongzhou,.*', '^chrontel,.*', '^chrp,.*', '^chunghwa,.*', '^chuwi,.*', '^ciaa,.*', '^cirrus,.*', '^cisco,.*', '^clockwork,.*', '^cloos,.*', '^cloudengines,.*', '^cnm,.*', '^cnxt,.*', '^colorfly,.*', '^compulab,.*', '^comvetia,.*', '^congatec,.*', '^coolpi,.*', '^coreriver,.*', '^corpro,.*', '^cortina,.*', '^cosmic,.*', '^crane,.*', '^creative,.*', '^crystalfontz,.*', '^csky,.*', '^csq,.*', '^ctera,.*', '^ctu,.*', '^cubietech,.*', '^cudy,.*', '^cui,.*', '^cypress,.*', '^cyx,.*', '^cznic,.*', '^dallas,.*', '^dataimage,.*', '^davicom,.*', '^deepcomputing,.*', '^dell,.*', '^delta,.*', '^densitron,.*', '^denx,.*', '^devantech,.*', '^dfi,.*', '^dfrobot,.*', '^dh,.*', '^difrnce,.*', '^digi,.*', '^digilent,.*', '^dimonoff,.*', '^diodes,.*', '^dioo,.*', '^dlc,.*', '^dlg,.*', '^dlink,.*', '^dmo,.*', '^domintech,.*', '^dongwoon,.*', '^dptechnics,.*', '^dragino,.*', '^dream,.*', '^ds,.*', '^dserve,.*', '^dynaimage,.*', '^ea,.*', '^ebang,.*', '^ebbg,.*', '^ebs-systart,.*', '^ebv,.*', '^eckelmann,.*', '^edgeble,.*', '^edimax,.*', '^edt,.*', '^ees,.*', '^eeti,.*', '^einfochips,.*', '^eink,.*', '^elan,.*', '^element14,.*', '^elgin,.*', '^elida,.*', '^elimo,.*', '^elpida,.*', '^embedfire,.*', '^embest,.*', '^emcraft,.*', '^emlid,.*', '^emmicro,.*', '^empire-electronix,.*', '^emtrion,.*', '^enclustra,.*', '^endless,.*', '^ene,.*', '^energymicro,.*', '^engicam,.*', '^engleder,.*', '^epcos,.*', '^epfl,.*', '^epson,.*', '^esp,.*', '^est,.*', '^ettus,.*', '^eukrea,.*', '^everest,.*', '^everspin,.*', '^evervision,.*', '^exar,.*', '^excito,.*', '^exegin,.*', '^ezchip,.*', '^facebook,.*', '^fairchild,.*', '^fairphone,.*', '^faraday,.*', '^fascontek,.*', '^fastrax,.*', '^fcs,.*', '^feixin,.*', '^feiyang,.*', '^fii,.*', '^firefly,.*', '^focaltech,.*', '^forlinx,.*', '^freebox,.*', '^freecom,.*', '^frida,.*', '^friendlyarm,.*', '^fsl,.*', '^fujitsu,.*', '^fxtec,.*', '^galaxycore,.*', '^gameforce,.*', '^gardena,.*', '^gateway,.*', '^gateworks,.*', '^gcw,.*', '^ge,.*', '^geekbuying,.*', '^gef,.*', '^gehc,.*', '^gemei,.*', '^gemtek,.*', '^genesys,.*', '^genexis,.*', '^geniatech,.*', '^giantec,.*', '^giantplus,.*', '^glinet,.*', '^globalscale,.*', '^globaltop,.*', '^gmt,.*', '^goldelico,.*', '^goodix,.*', '^google,.*', '^goramo,.*', '^gplus,.*', '^grinn,.*', '^grmn,.*', '^gumstix,.*', '^gw,.*', '^hannstar,.*', '^haochuangyi,.*', '^haoyu,.*', '^hardkernel,.*', '^hechuang,.*', '^hideep,.*', '^himax,.*', '^hirschmann,.*', '^hisi,.*', '^hisilicon,.*', '^hit,.*', '^hitex,.*', '^holt,.*', '^holtek,.*', '^honestar,.*', '^honeywell,.*', '^hoperf,.*', '^hoperun,.*', '^hp,.*', '^hpe,.*', '^hsg,.*', '^htc,.*', '^huawei,.*', '^hugsun,.*', '^hwacom,.*', '^hxt,.*', '^hycon,.*', '^hydis,.*', '^hynitron,.*', '^hynix,.*', '^hyundai,.*', '^i2se,.*', '^ibm,.*', '^icplus,.*', '^idt,.*', '^iei,.*', '^ifi,.*', '^ilitek,.*', '^imagis,.*', '^img,.*', '^imi,.*', '^inanbo,.*', '^incircuit,.*', '^indiedroid,.*', '^inet-tek,.*', '^infineon,.*', '^inforce,.*', '^ingenic,.*', '^ingrasys,.*', '^injoinic,.*', '^innocomm,.*', '^innolux,.*', '^inside-secure,.*', '^insignal,.*', '^inspur,.*', '^intel,.*', '^intercontrol,.*', '^invensense,.*', '^inventec,.*', '^inversepath,.*', '^iom,.*', '^irondevice,.*', '^isee,.*', '^isil,.*', '^issi,.*', '^ite,.*', '^itead,.*', '^itian,.*', '^ivo,.*', '^iwave,.*', '^jadard,.*', '^jasonic,.*', '^jdi,.*', '^jedec,.*', '^jenson,.*', '^jesurun,.*', '^jethome,.*', '^jianda,.*', '^jide,.*', '^joz,.*', '^kam,.*', '^karo,.*', '^keithkoep,.*', '^keymile,.*', '^khadas,.*', '^kiebackpeter,.*', '^kinetic,.*', '^kingdisplay,.*', '^kingnovel,.*', '^kionix,.*', '^kobo,.*', '^kobol,.*', '^koe,.*', '^kontron,.*', '^kosagi,.*', '^kvg,.*', '^kyo,.*', '^lacie,.*', '^laird,.*', '^lamobo,.*', '^lantiq,.*', '^lattice,.*', '^lckfb,.*', '^lctech,.*', '^leadtek,.*', '^leez,.*', '^lego,.*', '^lemaker,.*', '^lenovo,.*', '^lg,.*', '^lgphilips,.*', '^libretech,.*', '^licheepi,.*', '^linaro,.*', '^lincolntech,.*', '^lineartechnology,.*', '^linksprite,.*', '^linksys,.*', '^linutronix,.*', '^linux,.*', '^linx,.*', '^liteon,.*', '^litex,.*', '^lltc,.*', '^logicpd,.*', '^logictechno,.*', '^longcheer,.*', '^lontium,.*', '^loongmasses,.*', '^loongson,.*', '^lsi,.*', '^lunzn,.*', '^luxul,.*', '^lwn,.*', '^lxa,.*', '^m5stack,.*', '^macnica,.*', '^mantix,.*', '^mapleboard,.*', '^marantec,.*', '^marvell,.*', '^maxbotix,.*', '^maxim,.*', '^maxlinear,.*', '^mbvl,.*', '^mcube,.*', '^meas,.*', '^mecer,.*', '^mediatek,.*', '^megachips,.*', '^mele,.*', '^melexis,.*', '^melfas,.*', '^mellanox,.*', '^memsensing,.*', '^memsic,.*', '^menlo,.*', '^mentor,.*', '^meraki,.*', '^merrii,.*', '^methode,.*', '^micrel,.*', '^microchip,.*', '^microcrystal,.*', '^micron,.*', '^microsoft,.*', '^microsys,.*', '^microtips,.*', '^mikroe,.*', '^mikrotik,.*', '^milkv,.*', '^miniand,.*', '^minix,.*', '^mips,.*', '^miramems,.*', '^mitsubishi,.*', '^mitsumi,.*', '^mixel,.*', '^miyoo,.*', '^mntre,.*', '^mobileye,.*', '^modtronix,.*', '^moortec,.*', '^mosaixtech,.*', '^motorcomm,.*', '^motorola,.*', '^moxa,.*', '^mpl,.*', '^mps,.*', '^mqmaker,.*', '^mrvl,.*', '^mscc,.*', '^msi,.*', '^mstar,.*', '^mti,.*', '^multi-inno,.*', '^mundoreader,.*', '^murata,.*', '^mxic,.*', '^mxicy,.*', '^myir,.*', '^national,.*', '^neardi,.*', '^nec,.*', '^neofidelity,.*', '^neonode,.*', '^netgear,.*', '^netlogic,.*', '^netron-dy,.*', '^netronix,.*', '^netxeon,.*', '^neweast,.*', '^newhaven,.*', '^newvision,.*', '^nexbox,.*', '^nextthing,.*', '^ni,.*', '^nintendo,.*', '^nlt,.*', '^nokia,.*', '^nordic,.*', '^nothing,.*', '^novatek,.*', '^novtech,.*', '^numonyx,.*', '^nutsboard,.*', '^nuvoton,.*', '^nvd,.*', '^nvidia,.*', '^nxp,.*', '^oceanic,.*', '^ocs,.*', '^oct,.*', '^okaya,.*', '^oki,.*', '^olimex,.*', '^olpc,.*', '^oneplus,.*', '^onie,.*', '^onion,.*', '^onnn,.*', '^ontat,.*', '^opalkelly,.*', '^openailab,.*', '^opencores,.*', '^openembed,.*', '^openpandora,.*', '^openrisc,.*', '^openwrt,.*', '^option,.*', '^oranth,.*', '^orisetech,.*', '^ortustech,.*', '^osddisplays,.*', '^osmc,.*', '^ouya,.*', '^overkiz,.*', '^ovti,.*', '^oxsemi,.*', '^ozzmaker,.*', '^panasonic,.*', '^parade,.*', '^parallax,.*', '^pda,.*', '^pericom,.*', '^pervasive,.*', '^phicomm,.*', '^phytec,.*', '^picochip,.*', '^pine64,.*', '^pineriver,.*', '^pixcir,.*', '^plantower,.*', '^plathome,.*', '^plda,.*', '^plx,.*', '^ply,.*', '^pni,.*', '^pocketbook,.*', '^polaroid,.*', '^polyhex,.*', '^portwell,.*', '^poslab,.*', '^pov,.*', '^powertip,.*', '^powervr,.*', '^powkiddy,.*', '^primeview,.*', '^primux,.*', '^probox2,.*', '^prt,.*', '^pulsedlight,.*', '^purism,.*', '^puya,.*', '^qca,.*', '^qcom,.*', '^qemu,.*', '^qi,.*', '^qiaodian,.*', '^qihua,.*', '^qishenglong,.*', '^qnap,.*', '^quanta,.*', '^radxa,.*', '^raidsonic,.*', '^ralink,.*', '^ramtron,.*', '^raspberrypi,.*', '^raydium,.*', '^rda,.*', '^realtek,.*', '^relfor,.*', '^remarkable,.*', '^renesas,.*', '^rervision,.*', '^revotics,.*', '^rex,.*', '^richtek,.*', '^ricoh,.*', '^rikomagic,.*', '^riot,.*', '^riscv,.*', '^rockchip,.*', '^rocktech,.*', '^rohm,.*', '^ronbo,.*', '^roofull,.*', '^roseapplepi,.*', '^rve,.*', '^saef,.*', '^samsung,.*', '^samtec,.*', '^sancloud,.*', '^sandisk,.*', '^satoz,.*', '^sbs,.*', '^schindler,.*', '^schneider,.*', '^sciosense,.*', '^seagate,.*', '^seeed,.*', '^seirobotics,.*', '^semtech,.*', '^senseair,.*', '^sensirion,.*', '^sensortek,.*', '^sercomm,.*', '^sff,.*', '^sgd,.*', '^sgmicro,.*', '^sgx,.*', '^sharp,.*', '^shift,.*', '^shimafuji,.*', '^shineworld,.*', '^shiratech,.*', '^si-en,.*', '^si-linux,.*', '^siemens,.*', '^sifive,.*', '^siflower,.*', '^sigma,.*', '^sii,.*', '^sil,.*', '^silabs,.*', '^silan,.*', '^silead,.*', '^silergy,.*', '^silex-insight,.*', '^siliconfile,.*', '^siliconmitus,.*', '^silvaco,.*', '^simtek,.*', '^sinlinx,.*', '^sinovoip,.*', '^sinowealth,.*', '^sipeed,.*', '^sirf,.*', '^sis,.*', '^sitronix,.*', '^skov,.*', '^skyworks,.*', '^smartlabs,.*', '^smartrg,.*', '^smi,.*', '^smsc,.*', '^snps,.*', '^sochip,.*', '^socionext,.*', '^solidrun,.*', '^solomon,.*', '^sony,.*', '^sophgo,.*', '^sourceparts,.*', '^spacemit,.*', '^spansion,.*', '^sparkfun,.*', '^spinalhdl,.*', '^sprd,.*', '^square,.*', '^ssi,.*', '^sst,.*', '^sstar,.*', '^st,.*', '^st-ericsson,.*', '^starfive,.*', '^starry,.*', '^startek,.*', '^starterkit,.*', '^ste,.*', '^stericsson,.*', '^storlink,.*', '^storm,.*', '^storopack,.*', '^summit,.*', '^sunchip,.*', '^sundance,.*', '^sunplus,.*', '^supermicro,.*', '^swir,.*', '^syna,.*', '^synology,.*', '^synopsys,.*', '^tbs,.*', '^tbs-biometrics,.*', '^tcg,.*', '^tcl,.*', '^tcs,.*', '^tdo,.*', '^team-source-display,.*', '^technexion,.*', '^technologic,.*', '^techstar,.*', '^techwell,.*', '^teejet,.*', '^teltonika,.*', '^tempo,.*', '^terasic,.*', '^tesla,.*', '^test,.*', '^tfc,.*', '^thead,.*', '^thine,.*', '^thingyjp,.*', '^thundercomm,.*', '^thwc,.*', '^ti,.*', '^tianma,.*', '^tlm,.*', '^tmt,.*', '^topeet,.*', '^topic,.*', '^topland,.*', '^toppoly,.*', '^topwise,.*', '^toradex,.*', '^toshiba,.*', '^toumaz,.*', '^tpk,.*', '^tplink,.*', '^tpo,.*', '^tq,.*', '^transpeed,.*', '^traverse,.*', '^tronfy,.*', '^tronsmart,.*', '^truly,.*', '^tsd,.*', '^turing,.*', '^tyan,.*', '^tyhx,.*', '^u-blox,.*', '^u-boot,.*', '^ubnt,.*', '^ucrobotics,.*', '^udoo,.*', '^ufispace,.*', '^ugoos,.*', '^uni-t,.*', '^uniwest,.*', '^upisemi,.*', '^urt,.*', '^usi,.*', '^usr,.*', '^utoo,.*', '^v3,.*', '^vaisala,.*', '^vamrs,.*', '^variscite,.*', '^vdl,.*', '^vertexcom,.*', '^via,.*', '^vialab,.*', '^vicor,.*', '^videostrong,.*', '^virtio,.*', '^virtual,.*', '^vishay,.*', '^visionox,.*', '^vitesse,.*', '^vivante,.*', '^vivax,.*', '^vocore,.*', '^voipac,.*', '^voltafield,.*', '^vot,.*', '^vscom,.*', '^vxt,.*', '^wacom,.*', '^wanchanglong,.*', '^wand,.*', '^waveshare,.*', '^wd,.*', '^we,.*', '^welltech,.*', '^wetek,.*', '^wexler,.*', '^whwave,.*', '^wi2wi,.*', '^widora,.*', '^wiligear,.*', '^willsemi,.*', '^winbond,.*', '^wingtech,.*', '^winlink,.*', '^winstar,.*', '^wirelesstag,.*', '^wits,.*', '^wlf,.*', '^wm,.*', '^wobo,.*', '^wolfvision,.*', '^x-powers,.*', '^xen,.*', '^xes,.*', '^xiaomi,.*', '^xillybus,.*', '^xingbangda,.*', '^xinpeng,.*', '^xiphera,.*', '^xlnx,.*', '^xnano,.*', '^xunlong,.*', '^xylon,.*', '^yadro,.*', '^yamaha,.*', '^yes-optoelectronics,.*', '^yic,.*', '^yiming,.*', '^ylm,.*', '^yna,.*', '^yones-toptech,.*', '^ys,.*', '^ysoft,.*', '^zarlink,.*', '^zealz,.*', '^zeitec,.*', '^zidoo,.*', '^zii,.*', '^zinitix,.*', '^zkmagic,.*', '^zte,.*', '^zyxel,.*', 'pinctrl-[0-9]+'
	from schema $id: http://devicetree.org/schemas/vendor-prefixes.yaml#

doc reference errors (make refcheckdocs):

See https://patchwork.ozlabs.org/project/devicetree-bindings/patch/20250227162823.3585810-8-david@protonic.nl

The base for the series is generally the latest rc1. A different dependency
should be noted in *this* patch.

If you already ran 'make dt_binding_check' and didn't see the above
error(s), then make sure 'yamllint' is installed and dt-schema is up to
date:

pip3 install dtschema --upgrade

Please check and re-submit after running the above command yourself. Note
that DT_SCHEMA_FILES can be set to your schema file to speed up checking
your schema. However, it must be unset to test all examples with your schema.


^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 5/7] dt-bindings: motion: Add common motion device properties
  2025-02-27 16:28 ` [RFC PATCH 5/7] dt-bindings: motion: Add common motion device properties David Jander
@ 2025-02-28  7:06   ` Krzysztof Kozlowski
  2025-02-28  7:13   ` Krzysztof Kozlowski
  1 sibling, 0 replies; 59+ messages in thread
From: Krzysztof Kozlowski @ 2025-02-28  7:06 UTC (permalink / raw)
  To: David Jander
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel

On Thu, Feb 27, 2025 at 05:28:21PM +0100, David Jander wrote:
> +title: Common properties for motion control devices
> +
> +maintainers:
> +  - David Jander <david@protonic.nl>
> +
> +description: |
> +  This document defines device tree properties common to several motion control
> +  devices. It doesn't constitute a device tree binding specification by itself but

Wrap at coding style, so at 80.

> +  is meant to be referenced by device tree bindings.
> +
> +  When referenced from motion device tree bindings the properties defined in this
> +  document are defined as follows. The motion device tree bindings are responsible
> +  for defining whether each property is required or optional.
> +
> +properties:
> +  motion,speed-conv-mul:

Drop incorrect motion prefix.

> +    $ref: /schemas/types.yaml#/definitions/uint32
> +    default: 1
> +    description: |

Do not need '|' unless you need to preserve formatting.

Best regards,
Krzysztof


^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 6/7] dt-bindings: motion: Add adi,tmc5240 bindings
  2025-02-27 16:28 ` [RFC PATCH 6/7] dt-bindings: motion: Add adi,tmc5240 bindings David Jander
@ 2025-02-28  7:11   ` Krzysztof Kozlowski
  2025-02-28  8:48     ` David Jander
  2025-02-28 22:38   ` David Lechner
  1 sibling, 1 reply; 59+ messages in thread
From: Krzysztof Kozlowski @ 2025-02-28  7:11 UTC (permalink / raw)
  To: David Jander
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel

On Thu, Feb 27, 2025 at 05:28:22PM +0100, David Jander wrote:
> +$id: http://devicetree.org/schemas/motion/adi,tmc5240.yaml#
> +$schema: http://devicetree.org/meta-schemas/core.yaml#
> +
> +title: Analog Devices TMC5240 Stepper Motor controller
> +
> +maintainers:
> +  - David Jander <david@protonic>
> +
> +description: |

Do not need '|' unless you need to preserve formatting.

> +   Stepper motor controller with motion engine and SPI interface.
> +
> +properties:
> +  compatible:
> +    enum:
> +      - adi,tmc5240
> +
> +  reg:
> +    maxItems: 1
> +
> +  interrupts:
> +    maxItems: 1
> +
> +  enable-supply:
> +    description: Optional external enable supply to control SLEEPn pin. Can

That's odd. regular pins are not supplies. This must be named after
physical supplies. There is vdd18, vcc, vcp but nothing about enable
supply in datasheet.


> +      be shared between several controllers.

Second sentence is both redundant and really not relevant to this
binding. It's not this binding which decides about sharing.


> +
> +  clocks:
> +    maxItems: 1
> +
> +required:
> +  - compatible
> +  - reg
> +  - interrupts
> +  - clocks
> +
> +allOf:
> +  - $ref: /schemas/spi/spi-peripheral-props.yaml#
> +  - $ref: /schemas/motion/common.yaml#
> +
> +unevaluatedProperties: false
> +
> +examples:
> +  - |
> +    spi {
> +        #address-cells = <1>;
> +        #size-cells = <0>;
> +
> +        motor@0 {
> +            compatible = "adi,tmc5240";
> +            reg = <0>;
> +            interrupts-extended = <&gpiok 7 0>;

Include header and use standard defines for flags.

> +            clocks = <&clock_tmc5240>;
> +            enable-supply = <&stpsleepn>;
> +            spi-max-frequency = <1000000>;

Where are any other properties from common schema?

Best regards,
Krzysztof


^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings
  2025-02-27 16:28 ` [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings David Jander
  2025-02-27 17:38   ` Rob Herring (Arm)
@ 2025-02-28  7:12   ` Krzysztof Kozlowski
  2025-02-28  9:22     ` David Jander
  2025-02-28 22:41   ` David Lechner
  2 siblings, 1 reply; 59+ messages in thread
From: Krzysztof Kozlowski @ 2025-02-28  7:12 UTC (permalink / raw)
  To: David Jander
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel

On Thu, Feb 27, 2025 at 05:28:23PM +0100, David Jander wrote:
> Add device-tree bindings for simple Linux Motion Control devices that
> are based on 1 or 2 PWM outputs.
> 
> Signed-off-by: David Jander <david@protonic.nl>
> ---
>  .../bindings/motion/motion-simple-pwm.yaml    | 55 +++++++++++++++++++
>  1 file changed, 55 insertions(+)
>  create mode 100644 Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml
> 
> diff --git a/Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml b/Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml
> new file mode 100644
> index 000000000000..409e3aef6f3f
> --- /dev/null
> +++ b/Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml
> @@ -0,0 +1,55 @@
> +# SPDX-License-Identifier: (GPL-2.0 OR BSD-2-Clause)
> +%YAML 1.2
> +---
> +$id: http://devicetree.org/schemas/motion/motion-simple-pwm.yaml#
> +$schema: http://devicetree.org/meta-schemas/core.yaml#
> +
> +title: Simple PWM based motor controller
> +
> +maintainers:
> +  - David Jander <david@protonic>
> +
> +description: |

Do not need '|' unless you need to preserve formatting.

> +   Simple motor control device based on 1 or 2 PWM outputs

Your schema does not allow 1. Test it.

> +
> +properties:
> +  compatible:
> +    enum:
> +      - motion-simple-pwm
> +
> +  pwms:
> +    maxItems: 2

List and describe items instead.

> +
> +  pwm-names:
> +    maxItems: 2

List items instead.

> +
> +  motion,pwm-inverted:
> +    $ref: /schemas/types.yaml#/definitions/flag

And PWM flag does not work?

Anyway, there is no "motion" company.

> +    description:
> +      If present, this flag indicates that the PWM signal should be inverted.
> +      The duty-cycle will be scaled from 100% down to 0% instead 0% to 100%.
> +
> +required:
> +  - compatible
> +  - pwms
> +
> +allOf:
> +  - $ref: /schemas/motion/common.yaml#
> +
> +unevaluatedProperties: false
> +
> +examples:
> +  - |
> +    // This example shows how to use the TI DRV8873 or similar motor controllers
> +    // with this driver
> +    motion-simple-pwm0 {

Node names should be generic. See also an explanation and list of
examples (not exhaustive) in DT specification:
https://devicetree-specification.readthedocs.io/en/latest/chapter2-devicetree-basics.html#generic-names-recommendation

e.g. motor {

Best regards,
Krzysztof


^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 5/7] dt-bindings: motion: Add common motion device properties
  2025-02-27 16:28 ` [RFC PATCH 5/7] dt-bindings: motion: Add common motion device properties David Jander
  2025-02-28  7:06   ` Krzysztof Kozlowski
@ 2025-02-28  7:13   ` Krzysztof Kozlowski
  1 sibling, 0 replies; 59+ messages in thread
From: Krzysztof Kozlowski @ 2025-02-28  7:13 UTC (permalink / raw)
  To: David Jander, linux-kernel
  Cc: linux-iio, Jonathan Corbet, Rob Herring, Krzysztof Kozlowski,
	Conor Dooley, devicetree, linux-doc, Nuno Sa, Jonathan Cameron,
	Oleksij Rempel

On 27/02/2025 17:28, David Jander wrote:
> +properties:
> +  motion,speed-conv-mul:
> +    $ref: /schemas/types.yaml#/definitions/uint32
> +    default: 1
> +    description: |
> +      Numerator of a fractional representation of a speed conversion factor.
> +      The speed conversion factor (represented by numerator and denominator)
> +      is multiplied with the internal speed unit to obtain the physical speed
> +      unit of the controller. For example, for a stepper motor controller, the
> +      physical speed unit is microsteps/second (Hz).
> +
> +  motion,speed-conv-div:
> +    $ref: /schemas/types.yaml#/definitions/uint32
> +    default: 1

And I guess: minimum: 1

Best regards,
Krzysztof

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 6/7] dt-bindings: motion: Add adi,tmc5240 bindings
  2025-02-28  7:11   ` Krzysztof Kozlowski
@ 2025-02-28  8:48     ` David Jander
  2025-02-28  9:35       ` Krzysztof Kozlowski
  0 siblings, 1 reply; 59+ messages in thread
From: David Jander @ 2025-02-28  8:48 UTC (permalink / raw)
  To: Krzysztof Kozlowski
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel


Dear Krzysztof,

Thanks for reviewing...

On Fri, 28 Feb 2025 08:11:04 +0100
Krzysztof Kozlowski <krzk@kernel.org> wrote:

> On Thu, Feb 27, 2025 at 05:28:22PM +0100, David Jander wrote:
> [...]
> > +
> > +  enable-supply:
> > +    description: Optional external enable supply to control SLEEPn pin. Can  
> 
> That's odd. regular pins are not supplies. This must be named after
> physical supplies. There is vdd18, vcc, vcp but nothing about enable
> supply in datasheet.
> 
> > +      be shared between several controllers.  
> 
> Second sentence is both redundant and really not relevant to this
> binding. It's not this binding which decides about sharing.

Good point. I think I should drop the whole property, since it is indeed
irrelevant. If extra supplies need to be specified, they always can be, right?

> > +
> > +  clocks:
> > +    maxItems: 1
> > +
> > +required:
> > +  - compatible
> > +  - reg
> > +  - interrupts
> > +  - clocks
> > +
> > +allOf:
> > +  - $ref: /schemas/spi/spi-peripheral-props.yaml#
> > +  - $ref: /schemas/motion/common.yaml#
> > +
> > +unevaluatedProperties: false
> > +
> > +examples:
> > +  - |
> > +    spi {
> > +        #address-cells = <1>;
> > +        #size-cells = <0>;
> > +
> > +        motor@0 {
> > +            compatible = "adi,tmc5240";
> > +            reg = <0>;
> > +            interrupts-extended = <&gpiok 7 0>;  
> 
> Include header and use standard defines for flags.

Thanks. I didn't know I could include them here... will fix this.

> 
> > +            clocks = <&clock_tmc5240>;
> > +            enable-supply = <&stpsleepn>;
> > +            spi-max-frequency = <1000000>;  
> 
> Where are any other properties from common schema?

The properties in common.yaml are optional. Do I need to explicitly specify
this somehow (they are not listed under "required:")?
In fact, the tmc5240 driver has its own known constants for these properties
that it fills in. One can overrule them here if needed, but I suppose in the
case of the tmc5240 the regular use-case is not to do that. Should I maybe add
a second example that overrules the defaults?

Best regards,

-- 
David Jander


^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings
  2025-02-28  7:12   ` Krzysztof Kozlowski
@ 2025-02-28  9:22     ` David Jander
  2025-02-28  9:37       ` Krzysztof Kozlowski
  0 siblings, 1 reply; 59+ messages in thread
From: David Jander @ 2025-02-28  9:22 UTC (permalink / raw)
  To: Krzysztof Kozlowski
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel


Dear Krzysztof,

Thanks for reviewing...

On Fri, 28 Feb 2025 08:12:45 +0100
Krzysztof Kozlowski <krzk@kernel.org> wrote:

> On Thu, Feb 27, 2025 at 05:28:23PM +0100, David Jander wrote:
> [...]
> > +description: |  
> 
> Do not need '|' unless you need to preserve formatting.
> 
> > +   Simple motor control device based on 1 or 2 PWM outputs  
> 
> Your schema does not allow 1. Test it.

Ok, that came as a surprise to me. Thanks!

> > +
> > +properties:
> > +  compatible:
> > +    enum:
> > +      - motion-simple-pwm
> > +
> > +  pwms:
> > +    maxItems: 2  
> 
> List and describe items instead.
> 
> > +
> > +  pwm-names:
> > +    maxItems: 2  
> 
> List items instead.

Will do in next iteration. Thanks.

> > +
> > +  motion,pwm-inverted:
> > +    $ref: /schemas/types.yaml#/definitions/flag  
> 
> And PWM flag does not work?

I have seen PWM controllers that don't seem to support the
PWM_POLARITY_INVERTED flag and those where it just doesn't work. Should all
PWM controller drivers always support the PWM_POLARITY_INVERTED flag, even if
it needs to be inverted in software? If so, there are some drivers that need
fixing.

> Anyway, there is no "motion" company.

Got it. Dropped all the "motion," prefixes.

> > +    description:
> > +      If present, this flag indicates that the PWM signal should be inverted.
> > +      The duty-cycle will be scaled from 100% down to 0% instead 0% to 100%.
> > +
> > +required:
> > +  - compatible
> > +  - pwms
> > +
> > +allOf:
> > +  - $ref: /schemas/motion/common.yaml#
> > +
> > +unevaluatedProperties: false
> > +
> > +examples:
> > +  - |
> > +    // This example shows how to use the TI DRV8873 or similar motor controllers
> > +    // with this driver
> > +    motion-simple-pwm0 {  
> 
> Node names should be generic. See also an explanation and list of
> examples (not exhaustive) in DT specification:
> https://devicetree-specification.readthedocs.io/en/latest/chapter2-devicetree-basics.html#generic-names-recommendation
> 
> e.g. motor {

Will change. Thanks.

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 0/7] Add Linux Motion Control subsystem
  2025-02-27 16:28 [RFC PATCH 0/7] Add Linux Motion Control subsystem David Jander
                   ` (6 preceding siblings ...)
  2025-02-27 16:28 ` [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings David Jander
@ 2025-02-28  9:34 ` Pavel Pisa
  2025-02-28  9:35 ` Pavel Pisa
  2025-02-28 22:36 ` David Lechner
  9 siblings, 0 replies; 59+ messages in thread
From: Pavel Pisa @ 2025-02-28  9:34 UTC (permalink / raw)
  To: David Jander
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel

Hello David and others

On Thursday 27 of February 2025 17:28:16 David Jander wrote:
> Request for comments on: adding the Linux Motion Control subsystem to the
> kernel.

I have noticed on Phoronix, that the new system is emerging.
This is area where I have lot (more than 30 years) of experience
at my company and I have done even lot with my studnets at university.
I have big interest that this interface fits our use neeeds
and offers for future integration of our already open-source
systems/components.

This is preliminary reply, I want to find time for more discussion
and analysis (which is quite hard during summer term where I have
lot of teaching and even ongoing project now).

I would like to discuse even future subsystem evolution
which would allow coordinates axes groups creation, smooth
segments based on N-th order splines incremental attachment,
the path planning and re-planning if the target changes
as reaction to camera or other sensor needs etc.

At this moment I have interrest if there is site which
would start to collect these ideas and where can be
some references added.

I think that I have quite some stuff to offer.

To have idea about my direction of thinking and needs
of interface I would provide some references even
to our often commercially sold but mostly conceived
as hobby projects.

Coordinated axes groups movement with incremental spline
segment addition into command queue (our COORDMV componet
of PXMC library) is demonstrated on old BOSCH SR 450 SCARA
system. The robot has never fully worked at Skoda Auto
with original BOSH control unit. But when it has been donated
to Czech Technical University, we have build control
unit at my copany based on Motorola 68376 MCU in around
2000 year. I have later paid one student to prepare
demo in Python to demonstrate the system.

You can click on video

  MARS 8 BigBot and Robot Bosch SR 450 Drawing Roses 
  http://pikron.com/pages/products/motion_control.html

The related python application is there

  https://github.com/cvut/pyrocon

In the far future, I can imagine that it can connect
to proposed LMC API and achieve the same results.

The related control unit MARS 8 page

  http://pikron.com/pages/products/motion_control/mars_8.html

CPU board for museum or curiosity

  http://pikron.com/pages/products/cpu_boards/mo_cpu1.html

The firmware main application

  https://gitlab.com/pikron/projects/mo_cpu1/mars-mo_cpu1

which uses our PXMC motion control library

  https://gitlab.com/pikron/sw-base/pxmc

There is basic documentation for it on its site

  https://pxmc.org/
  https://pxmc.org/files/pxmc.pdf

It is used in system less environment on the MARS 8 system
and actual control at fixed sampling frequency is done
in timer interrupt at 1 kHz.

More such units serve our studnets to control CRS
A465 robots for more than 20 years already.
Their original control units have broken by age...

The same library has been used in our design of HW and SW
for infusion systems (MSP430 + iMX1 with RTEMS)

  https://pikron.com/pages/devel/medinst.html

HPL systems (LPC1768 HW)

  http://pikron.com/pages/products/hplc/lcp_5024.html

and on newer system less LPC4088 + Xilinx XC6SLX9
system used for example for more ESA and ADS projects

  https://www.esa.int/ESA_Multimedia/Images/2023/06/W-band_on_the_run
  https://github.com/esa/lxrmount
  https://gitlab.com/pikron/projects/lx_cpu/rocon-commander/-/wikis/lxr-lisa-com

The LX_RoCoN is based on FPGA design with up to 8 IRC inputs, 16 arbitrarily
assignable PWM H-bridge output, TUMBL (open source Microblaze variant) co-processor
for up to four electronic commutations for PMSM, stepper or IRC equipped steppers
there 

  https://gitlab.com/pikron/projects/lx_cpu/lx-rocon

The commutation ((forward + inverse) x (Park + Clarke)) by co-processor
runs on PMW frequency (20 kHz), D+Q current PI, position PID and COORMV
at 4 kHz.

FPGA design has been started in the frame of the next thesis

  https://dspace.cvut.cz/bitstream/handle/10467/23347/F3-DP-2014-Meloun-Martin-prace.pdf

More Linux, RTEMS, NuttX, etc. theses led by me there

  https://gitlab.fel.cvut.cz/otrees/org/-/wikis/theses-defend

More information often about RT, motion control there

   https://gitlab.fel.cvut.cz/otrees/org/-/wikis/knowbase

Back to the GNU/Linux

Experiment to run our PXMC library on Linux, demonstration on Raspberry Pi,
AM4300, Xilinx Zynq with DC and PMSM motors

  https://gitlab.com/pikron/projects/pxmc-linux

The HW with small FPGA implementing IRC, 3x PWM and current ADC
commanding and collection which is connected to Raspberry Pi
by SPI there

  https://gitlab.com/pikron/projects/rpi/rpi-mc-1

It is intended for demonstration to enthusiasts, not for
industry. (I am not happy to see H2 filling stations
controlled by RPi today...)

But the same code can be run on Xilinx Zynq with DC motor
peripheral

  https://gitlab.fel.cvut.cz/canbus/zynq/zynq-can-sja1000-top/-/tree/master/system/ip/dcsimpledrv_1.0

and PMSM peripheral

  https://gitlab.fel.cvut.cz/canbus/zynq/zynq-can-sja1000-top/-/tree/master/system/ip/pmsm_3pmdrv1_to_pins

but there are even more advanced option even for Linux.
The TUMBL coprocessor has been replaced by small RISC-V
developed in the frame of our Advanced Computer Architectures
course by my studnets

   https://gitlab.fel.cvut.cz/otrees/fpga/rvapo-vhdl

and the 3 phase motor peripheral has been combined
with this coprocessor on Zynq, So PREEMP_RT Linux (or even RETMS)
can deliver D and Q PWM values to shared memory and coprocessor
takes care about commutation at 20 kHz, then collects A, B, C
currents and convert them at 20 kHz to D Q and filters
them to deliver cumulative sum and accumulated samples
count to the slower Linux control loop. But ARM core can
access peripherals directly as well for debugging purposes
etc.

The Linux, RTEMS application source

  https://gitlab.fel.cvut.cz/otrees/fpga/rvapo-apps/-/tree/master/apps/rvapo-pmsm
  
co-processor firware source

  https://gitlab.fel.cvut.cz/otrees/fpga/rvapo-vhdl/-/blob/main/software/c/firmware_fresh/firmware.c

The 3-phase peripheral can be synthesized even by fully open source
tool chain to iCE40 and PMSM motor control has been demonstrated
even on cheap ICE-V Wireless (ESP32C3+iCE40)) with SW running NuttX

  https://gitlab.fel.cvut.cz/otrees/risc-v-esp32/ice-v-pmsm

We have tatgets for the most of these peripherals under Linux
and NuttX for pysimCoder

  https://github.com/robertobucher/pysimCoder

Some examples ow pysimCoder is used by independed
company there

  https://www.youtube.com/@robots5/videos

It is on NuttX, but on RPi and Zynq it works even better
on GNU/Linux.

So in general, I think that we have large portfolio
of building blocks which would allow to build motion,
robotic controllers, communications etc. and I would be happy
if they are reused and even some project conceived
together with others to join the forces.

It would be ideal if the all motion control related
resources and links could be somehow collected
that wheel is not reinvented unnecessarily.

The most of my code is Mozilla, GPL etc... I have
right to relicence my company stuff if the license does
not fit. On the other hand, I do not intend to follow
such offers as of one well funded chip related association,
which offered us to relicense all to them with no retain
of any control and additional right and they would not
take care about the valuable project at all no looking
for funding etc... no promise for developmet etc...
So there are some limits.

Best wishes,

                Pavel

                Pavel Pisa

    phone:      +420 603531357
    e-mail:     pisa@cmp.felk.cvut.cz
    Department of Control Engineering FEE CVUT
    Karlovo namesti 13, 121 35, Prague 2
    university: http://control.fel.cvut.cz/
    personal:   http://cmp.felk.cvut.cz/~pisa
    company:    https://pikron.com/ PiKRON s.r.o.
    Kankovskeho 1235, 182 00 Praha 8, Czech Republic
    projects:   https://www.openhub.net/accounts/ppisa
    social:     https://social.kernel.org/ppisa
    CAN related:http://canbus.pages.fel.cvut.cz/
    RISC-V education: https://comparch.edu.cvut.cz/
    Open Technologies Research Education and Exchange Services
    https://gitlab.fel.cvut.cz/otrees/org/-/wikis/home

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 6/7] dt-bindings: motion: Add adi,tmc5240 bindings
  2025-02-28  8:48     ` David Jander
@ 2025-02-28  9:35       ` Krzysztof Kozlowski
  2025-02-28  9:51         ` David Jander
  0 siblings, 1 reply; 59+ messages in thread
From: Krzysztof Kozlowski @ 2025-02-28  9:35 UTC (permalink / raw)
  To: David Jander
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel

On 28/02/2025 09:48, David Jander wrote:
> 
> Dear Krzysztof,
> 
> Thanks for reviewing...
> 
> On Fri, 28 Feb 2025 08:11:04 +0100
> Krzysztof Kozlowski <krzk@kernel.org> wrote:
> 
>> On Thu, Feb 27, 2025 at 05:28:22PM +0100, David Jander wrote:
>> [...]
>>> +
>>> +  enable-supply:
>>> +    description: Optional external enable supply to control SLEEPn pin. Can  
>>
>> That's odd. regular pins are not supplies. This must be named after
>> physical supplies. There is vdd18, vcc, vcp but nothing about enable
>> supply in datasheet.
>>
>>> +      be shared between several controllers.  
>>
>> Second sentence is both redundant and really not relevant to this
>> binding. It's not this binding which decides about sharing.
> 
> Good point. I think I should drop the whole property, since it is indeed
> irrelevant. If extra supplies need to be specified, they always can be, right?

You should specify all supplies now, because hardware should be fully
described by binding and DTS.

What's more, the necessary supplies (according to datasheet) should be
required, not optional.

> 
>>> +
>>> +  clocks:
>>> +    maxItems: 1
>>> +
>>> +required:
>>> +  - compatible
>>> +  - reg
>>> +  - interrupts
>>> +  - clocks
>>> +
>>> +allOf:
>>> +  - $ref: /schemas/spi/spi-peripheral-props.yaml#
>>> +  - $ref: /schemas/motion/common.yaml#
>>> +
>>> +unevaluatedProperties: false
>>> +
>>> +examples:
>>> +  - |
>>> +    spi {
>>> +        #address-cells = <1>;
>>> +        #size-cells = <0>;
>>> +
>>> +        motor@0 {
>>> +            compatible = "adi,tmc5240";
>>> +            reg = <0>;
>>> +            interrupts-extended = <&gpiok 7 0>;  
>>
>> Include header and use standard defines for flags.
> 
> Thanks. I didn't know I could include them here... will fix this.
> 
>>
>>> +            clocks = <&clock_tmc5240>;
>>> +            enable-supply = <&stpsleepn>;
>>> +            spi-max-frequency = <1000000>;  
>>
>> Where are any other properties from common schema?
> 
> The properties in common.yaml are optional. Do I need to explicitly specify
> this somehow (they are not listed under "required:")?

The common says default=1, so it is fine to skip them if that default
makes sense here.

Anyway, it's fine.


> In fact, the tmc5240 driver has its own known constants for these properties
> that it fills in. One can overrule them here if needed, but I suppose in the
> case of the tmc5240 the regular use-case is not to do that. Should I maybe add
> a second example that overrules the defaults?

Not necessarily, one real-world, complete example is enough.

Best regards,
Krzysztof

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 0/7] Add Linux Motion Control subsystem
  2025-02-27 16:28 [RFC PATCH 0/7] Add Linux Motion Control subsystem David Jander
                   ` (7 preceding siblings ...)
  2025-02-28  9:34 ` [RFC PATCH 0/7] Add Linux Motion Control subsystem Pavel Pisa
@ 2025-02-28  9:35 ` Pavel Pisa
  2025-02-28 11:57   ` David Jander
  2025-02-28 22:36 ` David Lechner
  9 siblings, 1 reply; 59+ messages in thread
From: Pavel Pisa @ 2025-02-28  9:35 UTC (permalink / raw)
  To: David Jander
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel

Hello David and others

On Thursday 27 of February 2025 17:28:16 David Jander wrote:
> Request for comments on: adding the Linux Motion Control subsystem to the
> kernel.

I have noticed on Phoronix, that the new system is emerging.
This is area where I have lot (more than 30 years) of experience
at my company and I have done even lot with my studnets at university.
I have big interest that this interface fits our use neeeds
and offers for future integration of our already open-source
systems/components.

This is preliminary reply, I want to find time for more discussion
and analysis (which is quite hard during summer term where I have
lot of teaching and even ongoing project now).

I would like to discuse even future subsystem evolution
which would allow coordinates axes groups creation, smooth
segments based on N-th order splines incremental attachment,
the path planning and re-planning if the target changes
as reaction to camera or other sensor needs etc.

At this moment I have interrest if there is site which
would start to collect these ideas and where can be
some references added.

I think that I have quite some stuff to offer.

To have idea about my direction of thinking and needs
of interface I would provide some references even
to our often commercially sold but mostly conceived
as hobby projects.

Coordinated axes groups movement with incremental spline
segment addition into command queue (our COORDMV componet
of PXMC library) is demonstrated on old BOSCH SR 450 SCARA
system. The robot has never fully worked at Skoda Auto
with original BOSH control unit. But when it has been donated
to Czech Technical University, we have build control
unit at my copany based on Motorola 68376 MCU in around
2000 year. I have later paid one student to prepare
demo in Python to demonstrate the system.

You can click on video

  MARS 8 BigBot and Robot Bosch SR 450 Drawing Roses 
  http://pikron.com/pages/products/motion_control.html

The related python application is there

  https://github.com/cvut/pyrocon

In the far future, I can imagine that it can connect
to proposed LMC API and achieve the same results.

The related control unit MARS 8 page

  http://pikron.com/pages/products/motion_control/mars_8.html

CPU board for museum or curiosity

  http://pikron.com/pages/products/cpu_boards/mo_cpu1.html

The firmware main application

  https://gitlab.com/pikron/projects/mo_cpu1/mars-mo_cpu1

which uses our PXMC motion control library

  https://gitlab.com/pikron/sw-base/pxmc

There is basic documentation for it on its site

  https://pxmc.org/
  https://pxmc.org/files/pxmc.pdf

It is used in system less environment on the MARS 8 system
and actual control at fixed sampling frequency is done
in timer interrupt at 1 kHz.

More such units serve our studnets to control CRS
A465 robots for more than 20 years already.
Their original control units have broken by age...

The same library has been used in our design of HW and SW
for infusion systems (MSP430 + iMX1 with RTEMS)

  https://pikron.com/pages/devel/medinst.html

HPL systems (LPC1768 HW)

  http://pikron.com/pages/products/hplc/lcp_5024.html

and on newer system less LPC4088 + Xilinx XC6SLX9
system used for example for more ESA and ADS projects

  https://www.esa.int/ESA_Multimedia/Images/2023/06/W-band_on_the_run
  https://github.com/esa/lxrmount
  
https://gitlab.com/pikron/projects/lx_cpu/rocon-commander/-/wikis/lxr-lisa-com

The LX_RoCoN is based on FPGA design with up to 8 IRC inputs, 16 arbitrarily
assignable PWM H-bridge output, TUMBL (open source Microblaze variant) 
co-processor
for up to four electronic commutations for PMSM, stepper or IRC equipped 
steppers
there 

  https://gitlab.com/pikron/projects/lx_cpu/lx-rocon

The commutation ((forward + inverse) x (Park + Clarke)) by co-processor
runs on PMW frequency (20 kHz), D+Q current PI, position PID and COORMV
at 4 kHz.

FPGA design has been started in the frame of the next thesis

  
https://dspace.cvut.cz/bitstream/handle/10467/23347/F3-DP-2014-Meloun-Martin-prace.pdf

More Linux, RTEMS, NuttX, etc. theses led by me there

  https://gitlab.fel.cvut.cz/otrees/org/-/wikis/theses-defend

More information often about RT, motion control there

   https://gitlab.fel.cvut.cz/otrees/org/-/wikis/knowbase

Back to the GNU/Linux

Experiment to run our PXMC library on Linux, demonstration on Raspberry Pi,
AM4300, Xilinx Zynq with DC and PMSM motors

  https://gitlab.com/pikron/projects/pxmc-linux

The HW with small FPGA implementing IRC, 3x PWM and current ADC
commanding and collection which is connected to Raspberry Pi
by SPI there

  https://gitlab.com/pikron/projects/rpi/rpi-mc-1

It is intended for demonstration to enthusiasts, not for
industry. (I am not happy to see H2 filling stations
controlled by RPi today...)

But the same code can be run on Xilinx Zynq with DC motor
peripheral

  
https://gitlab.fel.cvut.cz/canbus/zynq/zynq-can-sja1000-top/-/tree/master/system/ip/dcsimpledrv_1.0

and PMSM peripheral

  
https://gitlab.fel.cvut.cz/canbus/zynq/zynq-can-sja1000-top/-/tree/master/system/ip/pmsm_3pmdrv1_to_pins

but there are even more advanced option even for Linux.
The TUMBL coprocessor has been replaced by small RISC-V
developed in the frame of our Advanced Computer Architectures
course by my studnets

   https://gitlab.fel.cvut.cz/otrees/fpga/rvapo-vhdl

and the 3 phase motor peripheral has been combined
with this coprocessor on Zynq, So PREEMP_RT Linux (or even RETMS)
can deliver D and Q PWM values to shared memory and coprocessor
takes care about commutation at 20 kHz, then collects A, B, C
currents and convert them at 20 kHz to D Q and filters
them to deliver cumulative sum and accumulated samples
count to the slower Linux control loop. But ARM core can
access peripherals directly as well for debugging purposes
etc.

The Linux, RTEMS application source

  
https://gitlab.fel.cvut.cz/otrees/fpga/rvapo-apps/-/tree/master/apps/rvapo-pmsm
  
co-processor firware source

  
https://gitlab.fel.cvut.cz/otrees/fpga/rvapo-vhdl/-/blob/main/software/c/firmware_fresh/firmware.c

The 3-phase peripheral can be synthesized even by fully open source
tool chain to iCE40 and PMSM motor control has been demonstrated
even on cheap ICE-V Wireless (ESP32C3+iCE40)) with SW running NuttX

  https://gitlab.fel.cvut.cz/otrees/risc-v-esp32/ice-v-pmsm

We have tatgets for the most of these peripherals under Linux
and NuttX for pysimCoder

  https://github.com/robertobucher/pysimCoder

Some examples ow pysimCoder is used by independed
company there

  https://www.youtube.com/@robots5/videos

It is on NuttX, but on RPi and Zynq it works even better
on GNU/Linux.

So in general, I think that we have large portfolio
of building blocks which would allow to build motion,
robotic controllers, communications etc. and I would be happy
if they are reused and even some project conceived
together with others to join the forces.

It would be ideal if the all motion control related
resources and links could be somehow collected
that wheel is not reinvented unnecessarily.

The most of my code is Mozilla, GPL etc... I have
right to relicence my company stuff if the license does
not fit. On the other hand, I do not intend to follow
such offers as of one well funded chip related association,
which offered us to relicense all to them with no retain
of any control and additional right and they would not
take care about the valuable project at all no looking
for funding etc... no promise for developmet etc...
So there are some limits.

Best wishes,

                Pavel

                Pavel Pisa

    phone:      +420 603531357
    e-mail:     pisa@cmp.felk.cvut.cz
    Department of Control Engineering FEE CVUT
    Karlovo namesti 13, 121 35, Prague 2
    university: http://control.fel.cvut.cz/
    personal:   http://cmp.felk.cvut.cz/~pisa
    company:    https://pikron.com/ PiKRON s.r.o.
    Kankovskeho 1235, 182 00 Praha 8, Czech Republic
    projects:   https://www.openhub.net/accounts/ppisa
    social:     https://social.kernel.org/ppisa
    CAN related:http://canbus.pages.fel.cvut.cz/
    RISC-V education: https://comparch.edu.cvut.cz/
    Open Technologies Research Education and Exchange Services
    https://gitlab.fel.cvut.cz/otrees/org/-/wikis/home

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings
  2025-02-28  9:22     ` David Jander
@ 2025-02-28  9:37       ` Krzysztof Kozlowski
  2025-02-28 10:09         ` David Jander
  0 siblings, 1 reply; 59+ messages in thread
From: Krzysztof Kozlowski @ 2025-02-28  9:37 UTC (permalink / raw)
  To: David Jander
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel

On 28/02/2025 10:22, David Jander wrote:
> 
>>> +
>>> +  motion,pwm-inverted:
>>> +    $ref: /schemas/types.yaml#/definitions/flag  
>>
>> And PWM flag does not work?
> 
> I have seen PWM controllers that don't seem to support the
> PWM_POLARITY_INVERTED flag and those where it just doesn't work. Should all


Shouldn't the controllers be fixed? Or let's rephrase the question: why
only this PWM consumer needs this property and none of others need it?


Best regards,
Krzysztof

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 6/7] dt-bindings: motion: Add adi,tmc5240 bindings
  2025-02-28  9:35       ` Krzysztof Kozlowski
@ 2025-02-28  9:51         ` David Jander
  2025-02-28 14:01           ` Krzysztof Kozlowski
  0 siblings, 1 reply; 59+ messages in thread
From: David Jander @ 2025-02-28  9:51 UTC (permalink / raw)
  To: Krzysztof Kozlowski
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel, david

On Fri, 28 Feb 2025 10:35:38 +0100
Krzysztof Kozlowski <krzk@kernel.org> wrote:

> On 28/02/2025 09:48, David Jander wrote:
> > 
> > Dear Krzysztof,
> > 
> > Thanks for reviewing...
> > 
> > On Fri, 28 Feb 2025 08:11:04 +0100
> > Krzysztof Kozlowski <krzk@kernel.org> wrote:
> >   
> >> On Thu, Feb 27, 2025 at 05:28:22PM +0100, David Jander wrote:
> >> [...]  
> >>> +
> >>> +  enable-supply:
> >>> +    description: Optional external enable supply to control SLEEPn pin. Can    
> >>
> >> That's odd. regular pins are not supplies. This must be named after
> >> physical supplies. There is vdd18, vcc, vcp but nothing about enable
> >> supply in datasheet.
> >>  
> >>> +      be shared between several controllers.    
> >>
> >> Second sentence is both redundant and really not relevant to this
> >> binding. It's not this binding which decides about sharing.  
> > 
> > Good point. I think I should drop the whole property, since it is indeed
> > irrelevant. If extra supplies need to be specified, they always can be, right?  
> 
> You should specify all supplies now, because hardware should be fully
> described by binding and DTS.

In the case of the hardware I use for testing all of this, there are several
tmc5240 chips which have their "SLEEPN" pin tied together controlled by a
single GPIO pin that needs to be pulled high before any of these chips can be
talked to. The usual way I know of solving this is by specifying a common
"virtual" supply of type "regulator-fixed" with an enable gpio.
But this isn't strictly a supply that has to do with this chip or driver, so I
don't think it should be specified in the schema. I do need to use it in my
particular case though. Is there a better way of doing this?

> What's more, the necessary supplies (according to datasheet) should be
> required, not optional.

Do you mean that they should be in the binding definition as well? I.e. add
all of Vs, Vdd1v8 and Vcc_io here?

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings
  2025-02-28  9:37       ` Krzysztof Kozlowski
@ 2025-02-28 10:09         ` David Jander
  2025-02-28 15:18           ` Uwe Kleine-König
  0 siblings, 1 reply; 59+ messages in thread
From: David Jander @ 2025-02-28 10:09 UTC (permalink / raw)
  To: Krzysztof Kozlowski
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel, Uwe Kleine-König,
	linux-pwm

On Fri, 28 Feb 2025 10:37:48 +0100
Krzysztof Kozlowski <krzk@kernel.org> wrote:

> On 28/02/2025 10:22, David Jander wrote:
> >   
> >>> +
> >>> +  motion,pwm-inverted:
> >>> +    $ref: /schemas/types.yaml#/definitions/flag    
> >>
> >> And PWM flag does not work?  
> > 
> > I have seen PWM controllers that don't seem to support the
> > PWM_POLARITY_INVERTED flag and those where it just doesn't work. Should all  
> 
> 
> Shouldn't the controllers be fixed? Or let's rephrase the question: why
> only this PWM consumer needs this property and none of others need it?

CCing Uwe Kleine-Koenig and linux-pwm mailing list.

I know that at least in kernel 6.11 the pwm-stm32.c PWM driver doesn't
properly invert the PWM signal when specifying PWM_POLARITY_INVERTED. I agree
this is a probably bug that needs fixing if still present in 6.14-rc. Besides
that, if linux-pwm agrees that every single PWM driver _must_ properly support
this flag, I will drop this consumer flag an start fixing broken PWM drivers
that I encounter. I agree that it makes more sense this way, but I wanted to
be sure.

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 0/7] Add Linux Motion Control subsystem
  2025-02-28  9:35 ` Pavel Pisa
@ 2025-02-28 11:57   ` David Jander
  2025-02-28 15:23     ` Pavel Pisa
  0 siblings, 1 reply; 59+ messages in thread
From: David Jander @ 2025-02-28 11:57 UTC (permalink / raw)
  To: Pavel Pisa
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel


Dear Pavel,

Thanks a lot for starting the discussion...

On Fri, 28 Feb 2025 10:35:57 +0100
Pavel Pisa <ppisa@pikron.com> wrote:

> Hello David and others
> 
> On Thursday 27 of February 2025 17:28:16 David Jander wrote:
> > Request for comments on: adding the Linux Motion Control subsystem to the
> > kernel.  
> 
> I have noticed on Phoronix, that the new system is emerging.

Being featured on Phoronix on day one wasn't on my bingo card for this year, to
be honest... :-)

> This is area where I have lot (more than 30 years) of experience
> at my company and I have done even lot with my studnets at university.
> I have big interest that this interface fits our use neeeds
> and offers for future integration of our already open-source
> systems/components.

This is very impressive and I am honored to have gotten your attention. I am
looking forward to discussing this, although I am not sure whether all of this
should happen here on LKML?

> This is preliminary reply, I want to find time for more discussion
> and analysis (which is quite hard during summer term where I have
> lot of teaching and even ongoing project now).
> 
> I would like to discuse even future subsystem evolution
> which would allow coordinates axes groups creation, smooth
> segments based on N-th order splines incremental attachment,
> the path planning and re-planning if the target changes
> as reaction to camera or other sensor needs etc.

Right now LMC should be able to support hardware that has multiple channels
(axes) per device. Its UAPI can describe position-based movements and
time-based movements along any arbitrary combination of those channels using a
pre-defined speed/acceleration profile.

The profiles can be specified as an arbitrary number of speed and acceleration
values. The idea is to describe a segmented profile with different
acceleration values for segments between two different speed values. Simple
examples are trapezoidal (accelerate from (near-)zero to Vmax with A1, and
decelerate from Vmax back to zero with D1), dual-slope or S-curve, but the
UAPI in theory permits an arbitrary number of segments if the underlying
hardware supports it.

I have some ideas for future extensions to the API that make coordinated
multi-channel movements a bit easier, but that will not be in the initial push
of LMC: For example torque-limit profiles for controlled torque movements,
usable for example in sliding door controllers with AC machines or BLDC
motors; or an ioctl to send a distance vector to a selected number of channels
at once and apply a motion profile to the whole coordinated movement. In the
current version you have to set up the distances and profiles for the
individual channels and then trigger the start of the motion, which is more
cumbersome. You can already use the finish event of a preceding motion to
trigger the next one though.

Another idea that has been floating in my head is to make a "virtual" motion
device driver that combines individual "real" single-channel hardware drivers
into one multi-channel device, but I am unsure whether it is really needed. It
all depends on the latency limit differences between kernel-space and
user-space whether there is something to gain.

I think it is best to keep this initial version more limited in scope though,
as long as the needed extensions are possible in the future without breaking
existing UAPI.

So I propose: Let's craft a draft UAPI (in a different place, not on LKML) that
can do everything we can come up with and then reduce it to the basics for the
first version. Otherwise it will get too complex to review, I'm afraid.

> At this moment I have interrest if there is site which
> would start to collect these ideas and where can be
> some references added.

I may put this on github and create a wiki there if you think that's a good
enough place to discuss?

> I think that I have quite some stuff to offer.

That would be great! Looking forward to it :-)

> To have idea about my direction of thinking and needs
> of interface I would provide some references even
> to our often commercially sold but mostly conceived
> as hobby projects.

I'll have to take some time to look into those more closely. My own experience
as far as FOSS or OSHW concerns includes the reprap Kamaq project:

https://reprap.org/wiki/Kamaq

TL;DR: It is a 3D printer running only Linux and the whole controller software
is entirely written in python (except for very little Cython/C code).
This is still my 3D printer on which I satisfy all of my 3D print needs. I
will need to port it to LMC one day.

> Coordinated axes groups movement with incremental spline
> segment addition into command queue (our COORDMV componet
> of PXMC library) is demonstrated on old BOSCH SR 450 SCARA
> system. The robot has never fully worked at Skoda Auto
> with original BOSH control unit. But when it has been donated
> to Czech Technical University, we have build control
> unit at my copany based on Motorola 68376 MCU in around
> 2000 year. I have later paid one student to prepare
> demo in Python to demonstrate the system.
> 
> You can click on video
> 
>   MARS 8 BigBot and Robot Bosch SR 450 Drawing Roses 
>   http://pikron.com/pages/products/motion_control.html

Very impressive! Can you explain how the spline-segment information could be
conveyed to the controller? Does the controller really do an infinitesimal
spline interpolation, or does it create many small linear vectors?

LMC will try to limit math operations in kernel space as much as possible, so
hopefully all the calculations can be done in user-space (or on the controller
if that is the case).

Right now, my way of thinking was that of regular 3D printers which usually
only implement G0/G1 G-codes (linear interpolation). G2/G3 (circular
interpolation) doesn't sound practically very useful since it is special but
not very flexible. Something like generalized spline interpolation sounds more
valuable, but I hadn't seen any hardware that can do it.

> The related python application is there
> 
>   https://github.com/cvut/pyrocon
> 
> In the far future, I can imagine that it can connect
> to proposed LMC API and achieve the same results.

Let's make it so!

>[...]
> which uses our PXMC motion control library
> 
>   https://gitlab.com/pikron/sw-base/pxmc
> 
> There is basic documentation for it on its site
> 
>   https://pxmc.org/
>   https://pxmc.org/files/pxmc.pdf

At first glance, this looks like a piece of hardware that would fit as a LMC
device. What needs to be determined is where the boundaries lie between
controller firmware, kernel-space and user-space code.

Generally speaking, as a rough guideline, microsecond work is better done in
the controller firmware if possible. millisecond work can be done in the kernel
and 10's or more millisecond work can be done in user-space, notwithstanding
latency limit requirements of course.

>[...]
> So in general, I think that we have large portfolio
> of building blocks which would allow to build motion,
> robotic controllers, communications etc. and I would be happy
> if they are reused and even some project conceived
> together with others to join the forces.

This sounds very interesting. Ideally one would end up with LMC capable of
interfacing all of those devices.

> It would be ideal if the all motion control related
> resources and links could be somehow collected
> that wheel is not reinvented unnecessarily.

I completely agree.

> The most of my code is Mozilla, GPL etc... I have
> right to relicence my company stuff if the license does
> not fit. On the other hand, I do not intend to follow
> such offers as of one well funded chip related association,
> which offered us to relicense all to them with no retain
> of any control and additional right and they would not
> take care about the valuable project at all no looking
> for funding etc... no promise for developmet etc...
> So there are some limits.

Understandable.

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 4/7] Documentation: Add Linux Motion Control documentation
  2025-02-27 16:37   ` Jonathan Corbet
@ 2025-02-28 13:02     ` David Jander
  2025-02-28 14:42       ` Jonathan Corbet
  0 siblings, 1 reply; 59+ messages in thread
From: David Jander @ 2025-02-28 13:02 UTC (permalink / raw)
  To: Jonathan Corbet
  Cc: linux-kernel, linux-iio, Rob Herring, Krzysztof Kozlowski,
	Conor Dooley, devicetree, linux-doc, Nuno Sa, Jonathan Cameron,
	Oleksij Rempel


Dear Jonathan,

Thanks for reviewing...

On Thu, 27 Feb 2025 09:37:00 -0700
Jonathan Corbet <corbet@lwn.net> wrote:

> David Jander <david@protonic.nl> writes:
> 
> > Add general- and UAPI documentation for the Linux Motion Control
> > subsystem.
> >
> > Signed-off-by: David Jander <david@protonic.nl>
> > ---
> >  Documentation/motion/index.rst       |  18 +
> >  Documentation/motion/motion-uapi.rst | 555 +++++++++++++++++++++++++++
> >  Documentation/subsystem-apis.rst     |   1 +
> >  3 files changed, 574 insertions(+)
> >  create mode 100644 Documentation/motion/index.rst
> >  create mode 100644 Documentation/motion/motion-uapi.rst  
> 
> I am glad to see this feature coming with documentation!  Please,
> though, do not create a top-level "motion" directory for it - that is
> just the kind of organization I've been trying to get us away from for a
> while.  This document is clearly aimed at user-space developers, and
> thus should be part of the userspace-api book ... please?

Ok, I understood UAPI documentation should go in
Documentation/userspace-api/motion.rst. Will fix that.

What I am unsure of is the rest of the documentation (which arguably still
needs to be written). I initially selected this place because of
Documentation/subsystem-apis.rst. LMC being a new "subsystem", made me think it
was the right thing to follow the structure of the contents there.
What I mean to put there is documentation of the driver API for motion
control drivers. I understand that while it doesn't really exist yet, I should
leave it out of this patch set, but when I am going to write it, should it
still go there, or is there now a better place?

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 6/7] dt-bindings: motion: Add adi,tmc5240 bindings
  2025-02-28  9:51         ` David Jander
@ 2025-02-28 14:01           ` Krzysztof Kozlowski
  0 siblings, 0 replies; 59+ messages in thread
From: Krzysztof Kozlowski @ 2025-02-28 14:01 UTC (permalink / raw)
  To: David Jander
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel

On 28/02/2025 10:51, David Jander wrote:

>>>>
>>>> Second sentence is both redundant and really not relevant to this
>>>> binding. It's not this binding which decides about sharing.  
>>>
>>> Good point. I think I should drop the whole property, since it is indeed
>>> irrelevant. If extra supplies need to be specified, they always can be, right?  
>>
>> You should specify all supplies now, because hardware should be fully
>> described by binding and DTS.
> 
> In the case of the hardware I use for testing all of this, there are several
> tmc5240 chips which have their "SLEEPN" pin tied together controlled by a
> single GPIO pin that needs to be pulled high before any of these chips can be
> talked to. The usual way I know of solving this is by specifying a common
> "virtual" supply of type "regulator-fixed" with an enable gpio.

No, that is not usual way. Representing pin as fake supply is hack and
not correct hardware description.

> But this isn't strictly a supply that has to do with this chip or driver, so I
> don't think it should be specified in the schema. I do need to use it in my
> particular case though. Is there a better way of doing this?

I speak about voltage and current supplies. These you must specify.

> 
>> What's more, the necessary supplies (according to datasheet) should be
>> required, not optional.
> 
> Do you mean that they should be in the binding definition as well? I.e. add
> all of Vs, Vdd1v8 and Vcc_io here?

Yes, all expected supplies must be in the binding.


Best regards,
Krzysztof

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 4/7] Documentation: Add Linux Motion Control documentation
  2025-02-28 13:02     ` David Jander
@ 2025-02-28 14:42       ` Jonathan Corbet
  2025-02-28 15:06         ` David Jander
  0 siblings, 1 reply; 59+ messages in thread
From: Jonathan Corbet @ 2025-02-28 14:42 UTC (permalink / raw)
  To: David Jander
  Cc: linux-kernel, linux-iio, Rob Herring, Krzysztof Kozlowski,
	Conor Dooley, devicetree, linux-doc, Nuno Sa, Jonathan Cameron,
	Oleksij Rempel

David Jander <david@protonic.nl> writes:

> What I am unsure of is the rest of the documentation (which arguably still
> needs to be written). I initially selected this place because of
> Documentation/subsystem-apis.rst. LMC being a new "subsystem", made me think it
> was the right thing to follow the structure of the contents there.
> What I mean to put there is documentation of the driver API for motion
> control drivers. I understand that while it doesn't really exist yet, I should
> leave it out of this patch set, but when I am going to write it, should it
> still go there, or is there now a better place?

I've really been pushing to organize our documentation by the audience
it is addressing, rather than by the developers who write it.  So
driver-api documentation is best put into ... the driver-api book,
Documentation/driver-api.

My plan, that I haven't yet acted on, is to create Documentation/devices
for device-specific docs that don't go anywhere else, then move a lot of
stuff into it.  Much like what was done with Documentation/arch.  But
anything that can go into the existing audience-focused manuals should
go there.

Thanks,

jon

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 4/7] Documentation: Add Linux Motion Control documentation
  2025-02-28 14:42       ` Jonathan Corbet
@ 2025-02-28 15:06         ` David Jander
  0 siblings, 0 replies; 59+ messages in thread
From: David Jander @ 2025-02-28 15:06 UTC (permalink / raw)
  To: Jonathan Corbet
  Cc: linux-kernel, linux-iio, Rob Herring, Krzysztof Kozlowski,
	Conor Dooley, devicetree, linux-doc, Nuno Sa, Jonathan Cameron,
	Oleksij Rempel

On Fri, 28 Feb 2025 07:42:39 -0700
Jonathan Corbet <corbet@lwn.net> wrote:

> David Jander <david@protonic.nl> writes:
> 
> > What I am unsure of is the rest of the documentation (which arguably still
> > needs to be written). I initially selected this place because of
> > Documentation/subsystem-apis.rst. LMC being a new "subsystem", made me think it
> > was the right thing to follow the structure of the contents there.
> > What I mean to put there is documentation of the driver API for motion
> > control drivers. I understand that while it doesn't really exist yet, I should
> > leave it out of this patch set, but when I am going to write it, should it
> > still go there, or is there now a better place?  
> 
> I've really been pushing to organize our documentation by the audience
> it is addressing, rather than by the developers who write it.  So
> driver-api documentation is best put into ... the driver-api book,
> Documentation/driver-api.

Sounds reasonable. I will put the driver api docs there once I come around to
writing them (I have the code commented already so that could be a start).

> My plan, that I haven't yet acted on, is to create Documentation/devices
> for device-specific docs that don't go anywhere else, then move a lot of
> stuff into it.  Much like what was done with Documentation/arch.  But
> anything that can go into the existing audience-focused manuals should
> go there.

Ok, I'll keep that in mind. Thanks.

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings
  2025-02-28 10:09         ` David Jander
@ 2025-02-28 15:18           ` Uwe Kleine-König
  2025-03-03 10:53             ` Maud Spierings
  2025-03-03 11:40             ` David Jander
  0 siblings, 2 replies; 59+ messages in thread
From: Uwe Kleine-König @ 2025-02-28 15:18 UTC (permalink / raw)
  To: David Jander
  Cc: Krzysztof Kozlowski, linux-kernel, linux-iio, Jonathan Corbet,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, devicetree,
	linux-doc, Nuno Sa, Jonathan Cameron, Oleksij Rempel, linux-pwm

[-- Attachment #1: Type: text/plain, Size: 2391 bytes --]

Hey David,

On Fri, Feb 28, 2025 at 11:09:31AM +0100, David Jander wrote:
> On Fri, 28 Feb 2025 10:37:48 +0100
> Krzysztof Kozlowski <krzk@kernel.org> wrote:
> 
> > On 28/02/2025 10:22, David Jander wrote:
> > >   
> > >>> +
> > >>> +  motion,pwm-inverted:
> > >>> +    $ref: /schemas/types.yaml#/definitions/flag    
> > >>
> > >> And PWM flag does not work?  
> > > 
> > > I have seen PWM controllers that don't seem to support the
> > > PWM_POLARITY_INVERTED flag and those where it just doesn't work. Should all  
> > 
> > 
> > Shouldn't the controllers be fixed? Or let's rephrase the question: why
> > only this PWM consumer needs this property and none of others need it?
> 
> CCing Uwe Kleine-Koenig and linux-pwm mailing list.
> 
> I know that at least in kernel 6.11 the pwm-stm32.c PWM driver doesn't
> properly invert the PWM signal when specifying PWM_POLARITY_INVERTED. I agree
> this is a probably bug that needs fixing if still present in 6.14-rc. Besides
> that, if linux-pwm agrees that every single PWM driver _must_ properly support
> this flag, I will drop this consumer flag an start fixing broken PWM drivers
> that I encounter. I agree that it makes more sense this way, but I wanted to
> be sure.

Some hardwares cannot support PWM_POLARITY_INVERTED. Affected drivers
include:

	pwm-adp5585
	pwm-ntxec
	pwm-raspberrypi-poe
	pwm-rz-mtu3 (software limitation only)
	pwm-sunplus
	pwm-twl-led (not completely sure, that one is strange)

. ISTR that there is a driver that does only support inverted polarity,
but I don't find it. For an overview I recommend reading through the
output of:

	for f in drivers/pwm/pwm-*; do
		echo $f;
		sed -rn '/Limitations:/,/\*\/?$/p' $f;
		echo;
	done | less

. (Note not all drivers have commentary in the right format to unveil
their limitations.)

For most use-cases you can just do

	.duty_cycle = .period - .duty_cycle

instead of inverting polarity, but there is no abstraction in the PWM
bindings for that and also no helpers in the PWM framework. The problem
is more or less ignored, so if you have a device with

	pwms = <&pwm0 0 PWM_POLARITY_INVERTED>;

and the PWM chip in question doesn't support that, the pwm API functions
will fail. So the system designer better makes sure that the PWM
hardware can cope with the needed polarity.

Best regards
Uwe

[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 488 bytes --]

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 0/7] Add Linux Motion Control subsystem
  2025-02-28 11:57   ` David Jander
@ 2025-02-28 15:23     ` Pavel Pisa
  2025-03-03 10:45       ` David Jander
  0 siblings, 1 reply; 59+ messages in thread
From: Pavel Pisa @ 2025-02-28 15:23 UTC (permalink / raw)
  To: David Jander
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel, Carsten Emde

Hello David,

On Friday 28 of February 2025 12:57:27 David Jander wrote:
> Dear Pavel,
>
> Thanks a lot for starting the discussion...
>
> On Fri, 28 Feb 2025 10:35:57 +0100
>
> Pavel Pisa <ppisa@pikron.com> wrote:
> > Hello David and others
> >
> > On Thursday 27 of February 2025 17:28:16 David Jander wrote:
> > > Request for comments on: adding the Linux Motion Control subsystem to
> > > the kernel.
> >
> > I have noticed on Phoronix, that the new system is emerging.
>
> Being featured on Phoronix on day one wasn't on my bingo card for this
> year, to be honest... :-)
>
> > This is area where I have lot (more than 30 years) of experience
> > at my company and I have done even lot with my studnets at university.
> > I have big interest that this interface fits our use neeeds
> > and offers for future integration of our already open-source
> > systems/components.
>
> This is very impressive and I am honored to have gotten your attention. I
> am looking forward to discussing this, although I am not sure whether all
> of this should happen here on LKML?

We should move somewhere else and invite people from Linux
CNC etc...

GitHub project would work well if there is not some reluctance
to commercially controlled and closed environment.

Gitlab even in Gitlab.com case has option to move to own
infrastructure in the future. We have Gitlab at university,
companies I work with has Gitlab instances. But I think that
we should stay on neutral ground.

The critical is some central hub where links to specific
mailinglist etc. can be placed. May it be we can ask
Linux foundation to provide wiki space for Linux Motion Control
Subsystem same as it is for RT

  https://wiki.linuxfoundation.org/realtime/start

We can ask OSADL.org as likely neutral space...

Or wiki at kernel.org, may it the most neutral...

 https://www.wiki.kernel.org/

I am not in the core teams but may it be there on LKLM
somebody would suggest the direction. I can ask people
from OSADL, CIPS, RT projects etc. directly...

But I am not the authority and would be happy if somebody
steers us.

To not load others, if there is no response then I suggest
to limit followup e-mails only to linux-iio and those
who already communicated in this thread.

> > This is preliminary reply, I want to find time for more discussion
> > and analysis (which is quite hard during summer term where I have
> > lot of teaching and even ongoing project now).
> >
> > I would like to discuse even future subsystem evolution
> > which would allow coordinates axes groups creation, smooth
> > segments based on N-th order splines incremental attachment,
> > the path planning and re-planning if the target changes
> > as reaction to camera or other sensor needs etc.
>
> Right now LMC should be able to support hardware that has multiple channels
> (axes) per device. Its UAPI can describe position-based movements and
> time-based movements along any arbitrary combination of those channels
> using a pre-defined speed/acceleration profile.
>
> The profiles can be specified as an arbitrary number of speed and
> acceleration values. The idea is to describe a segmented profile with
> different acceleration values for segments between two different speed
> values. Simple examples are trapezoidal (accelerate from (near-)zero to
> Vmax with A1, and decelerate from Vmax back to zero with D1), dual-slope or
> S-curve, but the UAPI in theory permits an arbitrary number of segments if
> the underlying hardware supports it.

Yes, when I have read that it reminded me my API between non-RT
and RT control task in Linux and IRQs in sysless case of our system.

> I have some ideas for future extensions to the API that make coordinated
> multi-channel movements a bit easier, but that will not be in the initial
> push of LMC: For example torque-limit profiles for controlled torque
> movements, usable for example in sliding door controllers with AC machines
> or BLDC motors; or an ioctl to send a distance vector to a selected number
> of channels at once and apply a motion profile to the whole coordinated
> movement. In the current version you have to set up the distances and
> profiles for the individual channels and then trigger the start of the
> motion, which is more cumbersome. You can already use the finish event of a
> preceding motion to trigger the next one though.

It would worth to have some commands queue for specified
(prefigured/setup) xis group.

Our system allows to add segments to the group queue but the
timing for segment only specifies shortest time in which it can
be executed.

Then there is three passes optimization then.

The first pass is performed at the insertion time. It checks and
finds normalized change of speeds  (divided by maximal accel/deccel
of given axis) at vertex and finds limiting exes, one which accelerates
the most and another which needs to decelerate the most. Then it
computes speed discontinuity at the given sample period and it limits
maximal final speed of the preceding segment such way, that the speed
change is kept under COORDDISCONT multiple of accel/decel step. This
way, if the straight segments are almost in line, the small change
of the direction is not limiting the speed. The discontinuity is
computed same way for the vertex between two N-order spline segments,
but optimally computed spline segments can be joint with such
discontinuity near to zero. This non RT computation as well as all
non-RT a RT one on the control unit side is done in the fixed
math (the most 32-bits, sometime 64-bits). Actual code of this
pass are the functions pxmc_coordmv_seg_add(), pxmc_coordmv_seg_add_line()
and pxmc_coordmv_seg_add_spline()

  https://gitlab.com/pikron/sw-base/pxmc/-/blob/master/libs4c/pxmc_coordmv/coordmv_base.c?ref_type=heads#L394

The new segment final vertex limiting speed and planned speed are
set to zero.

In the second pass, the queue of segments is examined from the last
added one and its initial planned vertex/edge speed is updated,
increased up to the minimum of limit give by discontinuity and
the limit to decelerate over segment to the planned final speed
of the segment. If the start vertex limit is increased then
the algorithm proceeds with previous segment

 https://gitlab.com/pikron/sw-base/pxmc/-/blob/master/libs4c/pxmc_coordmv/coordmv_base.c?ref_type=heads#L682

There are some rules and trick to do that long free in the respect
to the IRQ executor etc...

Then the actual execution at the sampling frequency advances
the normalized parameter going through segment from 0 to 2^32
in 2^32 modulo arithmetic. The increase is limited by smallest
maximal speed of the axes recomputed over distance to parameter
change and maximal allowed accelerations recomputed to the parameter
change. Then the final speed is limited by to final deceleration
to the end of the segment the pxmc_coordmv_upda() in

  https://gitlab.com/pikron/sw-base/pxmc/-/blob/master/libs4c/pxmc_coordmv/coordmv_base.c?ref_type=heads#L351

Then the actual positions of the axes are computed based on the
parameter, see pxmc_coordmv_line_gen() or pxmc_coordmv_spline_gen()

  https://gitlab.com/pikron/sw-base/pxmc/-/blob/master/libs4c/pxmc_coordmv/coordmv_base.c?ref_type=heads#L87
  https://gitlab.com/pikron/sw-base/pxmc/-/blob/master/libs4c/pxmc_coordmv/coordmv_base.c?ref_type=heads#L151
 
This approach ensures that if non RT part or even some commander,
in demo case python sending segments to be added over 19200 bit/s
serial line, does not keep with the segments execution, then
the robot will stop at the final position without exceeding deceleration
at any axis. So it is safe, even busback in some axis can control
slow down or even slight move back in the parameter etc... but
with system/actuator/tool keeping the path.

If there is interrest I would find more detailed description
of the optimizations and computations. I have even code for
its testing and checking correctness on the command line.

> Another idea that has been floating in my head is to make a "virtual"
> motion device driver that combines individual "real" single-channel
> hardware drivers into one multi-channel device, but I am unsure whether it
> is really needed. It all depends on the latency limit differences between
> kernel-space and user-space whether there is something to gain.

In the fact this is the similar idea programmed and in use 25 years
already. All computation is in 32-bit units specific for the each axis
and only in fixed arithmetic. Some problem was fast 64-bit root square
at that time.  All has been computed on 21 MHz CPU with 16-bit bus with
no caches with instrauctions taking from 2 to many cycles. It was capable
to do that for all eight axes plus some other control tasks as flashing
lights at specific positions for example for gems inspections by camera
connected to PC and then cotrolling their sorting to the right pocket by air
streams by MARS 8 control unit when it advanced to given location etc.
So some parts of the code has been rewritten to assembly. But today,
even on not so fast LPC4088 it can do this and D-Q PMSM motors
control without need of assembly optimizations. 

> I think it is best to keep this initial version more limited in scope
> though, as long as the needed extensions are possible in the future without
> breaking existing UAPI.

Yes, but I would be happy if the API is designed such way, that
it is not obstacle when it would be extended and I have idea
what would be such further goal for these applications
I have already solved and running for decades at industry
level.

> So I propose: Let's craft a draft UAPI (in a different place, not on LKML)
> that can do everything we can come up with and then reduce it to the basics
> for the first version. Otherwise it will get too complex to review, I'm
> afraid.

Yes, I agree.

To have some idea of the command set of our system, there is documentation
in English for our older system which was capable to control three
axes by 8-bit 80552

   http://cmp.felk.cvut.cz/~pisa/mars/mars_man_en.pdf

Unfortunately, I need to translate manual with coordinated
movement to English still, but command set is listed
(by unit itself) there

  https://cmp.felk.cvut.cz/~pisa/mars8/mo_help.txt

There is even PXMC documented in Konrad Skup's thesis  

  https://wiki.control.fel.cvut.cz/mediawiki/images/8/83/Dp_2007_skup_konrad.pdf

I hoped and have received a promise from my former colleague
leading the thesis based on my company's documentation
and code that the text will be a base for the open documentation
for the  https://www.pxmc.org/ site. I have fulfilled my
part, bought the domain, and opened the PXMC code.
However, he and his student did not mention the source
of the code in my company; instead, they sold the text for
commercial (paid only) publication and access. So, my hopes
to build community has faded in the stream of need to real
projects that need to be solved. So broader introduction
to the community has been postponed... by 18 years...

> > At this moment I have interrest if there is site which
> > would start to collect these ideas and where can be
> > some references added.
>
> I may put this on github and create a wiki there if you think that's a good
> enough place to discuss?

If there is no feedback with better place to my initial
list of options, I am OK with project group on GitHub
where the initial project will be located with Wiki
and issue tracker to start the communication
and I would be happy to participate (as my time, teaching,
projects allows).

> > I think that I have quite some stuff to offer.
>
> That would be great! Looking forward to it :-)
>
> > To have idea about my direction of thinking and needs
> > of interface I would provide some references even
> > to our often commercially sold but mostly conceived
> > as hobby projects.
>
> I'll have to take some time to look into those more closely. My own
> experience as far as FOSS or OSHW concerns includes the reprap Kamaq
> project:
>
> https://reprap.org/wiki/Kamaq

OK, nice target but I would like to support 5 D CNCs with
precise machining, haptic human machine systems etc...
with DC, stepper and PMSM motors with vector control
high resolution positional feedback etc. We control for
example up to 30 kg spherical lenses positioning in
the interferometric system with precision of micro fractions.
The system allows inspection which thanks to multiple
angles reaches lens surface reconstruction at level of
nanometres 

  https://toptec.eu/export/sites/toptec/.content/projects/finished/measuring-instrument.pdf

We use optical linear sensors combined with 10k per revolution
incremental sensors on the cheap stepper motor actuators and
precise mechanics.. and more tricks... And I can see use
of some cheap linux board, i.e. Zynq, Beagle-V Fire,
which I have on my table, there in future...

> TL;DR: It is a 3D printer running only Linux and the whole controller
> software is entirely written in python (except for very little Cython/C
> code). This is still my 3D printer on which I satisfy all of my 3D print
> needs. I will need to port it to LMC one day.
>
> > Coordinated axes groups movement with incremental spline
> > segment addition into command queue (our COORDMV componet
> > of PXMC library) is demonstrated on old BOSCH SR 450 SCARA
> > system. The robot has never fully worked at Skoda Auto
> > with original BOSH control unit. But when it has been donated
> > to Czech Technical University, we have build control
> > unit at my copany based on Motorola 68376 MCU in around
> > 2000 year. I have later paid one student to prepare
> > demo in Python to demonstrate the system.
> >
> > You can click on video
> >
> >   MARS 8 BigBot and Robot Bosch SR 450 Drawing Roses
> >   http://pikron.com/pages/products/motion_control.html
>
> Very impressive! Can you explain how the spline-segment information could
> be conveyed to the controller? Does the controller really do an
> infinitesimal spline interpolation, or does it create many small linear
> vectors?

As I referenced above, the spines are interpreted at sampling frequency
all parameters are represented as 32-bit signed numbers etc...
So no conversion to the straight segments. The precise postions
are recomputed with even high resolution over IKT, then some
intervals of these points are interpolated by spline segments
with controlled error and these segments are send to the unit
to keep command FIFO full but not overflow it. Unit reports
how much space is left...

> LMC will try to limit math operations in kernel space as much as possible,
> so hopefully all the calculations can be done in user-space (or on the
> controller if that is the case).

All computation is fixed point only so no problem for the kernel
even for interrupt. But yes, on fully preemptive kernel where
user space task can be guaranteed to achieve 5 kHz sampling even
on cheaper ARM hardware, the interface to the kernel can be
only on D-Q PWM command and actual IRC and currents readback.

But if you have API for more intelligent controllers then there
s no problem to put there "SoftMAC" to represent dumb ones the
same way to userspace.

> Right now, my way of thinking was that of regular 3D printers which usually
> only implement G0/G1 G-codes (linear interpolation). G2/G3 (circular
> interpolation) doesn't sound practically very useful since it is special
> but not very flexible. Something like generalized spline interpolation
> sounds more valuable, but I hadn't seen any hardware that can do it.
>
> > The related python application is there
> >
> >   https://github.com/cvut/pyrocon
> >
> > In the far future, I can imagine that it can connect
> > to proposed LMC API and achieve the same results.
>
> Let's make it so!
>
> >[...]
> > which uses our PXMC motion control library
> >
> >   https://gitlab.com/pikron/sw-base/pxmc
> >
> > There is basic documentation for it on its site
> >
> >   https://pxmc.org/
> >   https://pxmc.org/files/pxmc.pdf
>
> At first glance, this looks like a piece of hardware that would fit as a
> LMC device. What needs to be determined is where the boundaries lie between
> controller firmware, kernel-space and user-space code.

I propose to have that boundary fully configurable.
So all can be implemented by software emulation
in the kernel if the sampling is under 5 or 10 kHz.
The interface from GNU/Linux system to hardware
is set PWM A, B, C, read actual IRC and currents.

Or some part can be moved to external controller
or FPGA with coprocessor (the commutation fits
in 2 kB of RISC-V C programmed firmware). 
I.e. 20  kHz or even faster Park, Clarke
transformations. In this case 4 to 10 kHz
command port would be D-Q PWM or current set points
and back IRC position, D-Q currents.

Or your proposed LMC interface can be delivered
allmost directly to more complex controller
which would realize whole segments processing.

> Generally speaking, as a rough guideline, microsecond work is better done
> in the controller firmware if possible. millisecond work can be done in the
> kernel and 10's or more millisecond work can be done in user-space,
> notwithstanding latency limit requirements of course.

OK, I agree, the RT_PREEMPT is requiremet and no broken
SMI on x86 HW. 1 kHz is enough for DC motors controller
robots to go all on Linux. 5 kHz for PMSM D-Q can be
done in kernel or even userspace with platform
suitable for PREEMPT_RT if without some issues.

Above 10 kHz should go to FPGA or external HW. 

> >[...]
> > So in general, I think that we have large portfolio
> > of building blocks which would allow to build motion,
> > robotic controllers, communications etc. and I would be happy
> > if they are reused and even some project conceived
> > together with others to join the forces.
>
> This sounds very interesting. Ideally one would end up with LMC capable of
> interfacing all of those devices.

Yes.

> > It would be ideal if the all motion control related
> > resources and links could be somehow collected
> > that wheel is not reinvented unnecessarily.
>
> I completely agree.
>
> > The most of my code is Mozilla, GPL etc... I have
> > right to relicence my company stuff if the license does
> > not fit. On the other hand, I do not intend to follow
> > such offers as of one well funded chip related association,
> > which offered us to relicense all to them with no retain
> > of any control and additional right and they would not
> > take care about the valuable project at all no looking
> > for funding etc... no promise for developmet etc...
> > So there are some limits.
>
> Understandable.

Best wishes,

                Pavel
-- 
                Pavel Pisa

    phone:      +420 603531357
    e-mail:     pisa@cmp.felk.cvut.cz
    Department of Control Engineering FEE CVUT
    Karlovo namesti 13, 121 35, Prague 2
    university: http://control.fel.cvut.cz/
    personal:   http://cmp.felk.cvut.cz/~pisa
    company:    https://pikron.com/ PiKRON s.r.o.
    Kankovskeho 1235, 182 00 Praha 8, Czech Republic
    projects:   https://www.openhub.net/accounts/ppisa
    social:     https://social.kernel.org/ppisa
    CAN related:http://canbus.pages.fel.cvut.cz/
    RISC-V education: https://comparch.edu.cvut.cz/
    Open Technologies Research Education and Exchange Services
    https://gitlab.fel.cvut.cz/otrees/org/-/wikis/home

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-02-27 16:28 ` [RFC PATCH 1/7] drivers: Add motion control subsystem David Jander
@ 2025-02-28 16:44   ` Uwe Kleine-König
  2025-03-05 15:40     ` David Jander
  2025-02-28 22:36   ` David Lechner
  1 sibling, 1 reply; 59+ messages in thread
From: Uwe Kleine-König @ 2025-02-28 16:44 UTC (permalink / raw)
  To: David Jander
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel

[-- Attachment #1: Type: text/plain, Size: 12472 bytes --]

Hello David,

just a few highlevel review comments inline.

On Thu, Feb 27, 2025 at 05:28:17PM +0100, David Jander wrote:
> diff --git a/drivers/motion/motion-core.c b/drivers/motion/motion-core.c
> new file mode 100644
> index 000000000000..2963f1859e8b
> --- /dev/null
> +++ b/drivers/motion/motion-core.c
> @@ -0,0 +1,823 @@
> +// SPDX-License-Identifier: GPL-2.0
> +/*
> + * Motion Control Subsystem - Core
> + *
> + * Copyright (C) 2024 Protonic Holland
> + *                    David Jander <david@protonic.nl>
> + */
> +
> +#include <asm-generic/bitops/builtin-fls.h>
> +#include <asm-generic/errno-base.h>
> +#include <linux/interrupt.h>
> +#include <linux/irqreturn.h>
> +#include <linux/container_of.h>
> +#include <linux/hrtimer_types.h>
> +#include <linux/gfp_types.h>
> +#include <linux/module.h>
> +
> +#include <linux/fs.h>
> +#include <linux/errno.h>
> +#include <linux/kernel.h>
> +#include <linux/major.h>
> +#include <linux/init.h>
> +#include <linux/device.h>
> +#include <linux/kmod.h>
> +#include <linux/motion.h>
> +#include <linux/poll.h>
> +#include <linux/ptrace.h>
> +#include <linux/ktime.h>
> +#include <linux/iio/trigger.h>
> +#include <linux/gpio/consumer.h>
> +
> +#include "motion-core.h"
> +#include "motion-helpers.h"
> +#include <linux/time.h>
> +#include <linux/uaccess.h>
> +#include <linux/string.h>
> +#include <linux/math64.h>
> +#include <linux/mutex.h>
> +#include <linux/math.h>
> +#include <linux/math64.h>

Order all <...> includes over the "..." ones.

> +#define MOTION_PROFILE_VALID BIT(31)
> +
> +static LIST_HEAD(motion_list);
> +static DEFINE_MUTEX(motion_mtx);
> +static int motion_major;
> +static DEFINE_IDA(motion_minors_ida);
> +
> +struct iio_motion_trigger_info {
> +	unsigned int minor;
> +};
> +
> +static int motion_minor_alloc(void)
> +{
> +	int ret;
> +
> +	ret = ida_alloc_range(&motion_minors_ida, 0, MINORMASK, GFP_KERNEL);
> +	return ret;

This could be a one-liner.

> +}
> +
> +static void motion_minor_free(int minor)
> +{
> +	ida_free(&motion_minors_ida, minor);
> +}
> +
> +static int motion_open(struct inode *inode, struct file *file)
> +{
> +	int minor = iminor(inode);
> +	struct motion_device *mdev = NULL, *iter;
> +	int err;
> +
> +	mutex_lock(&motion_mtx);

If you use guard(), error handling gets a bit easier.

> +	list_for_each_entry(iter, &motion_list, list) {
> +		if (iter->minor != minor)
> +			continue;
> +		mdev = iter;
> +		break;
> +	}

This should be easier. If you use a cdev you can just do
container_of(inode->i_cdev, ...);

> +	if (!mdev) {
> +		err = -ENODEV;
> +		goto fail;
> +	}
> +
> +	dev_info(mdev->dev, "MOTION: open %d\n", mdev->minor);

degrade to dev_dbg.

> +	file->private_data = mdev;
> +
> +	if (mdev->ops.device_open)
> +		err = mdev->ops.device_open(mdev);
> +	else
> +		err = 0;
> +fail:
> +	mutex_unlock(&motion_mtx);
> +	return err;
> +}
> +
> +static int motion_release(struct inode *inode, struct file *file)
> +{
> +	struct motion_device *mdev = file->private_data;
> +	int i;
> +
> +	if (mdev->ops.device_release)
> +		mdev->ops.device_release(mdev);
> +
> +	for (i = 0; i < mdev->num_gpios; i++) {
> +		int irq;
> +		struct motion_gpio_input *gpio = &mdev->gpios[i];
> +
> +		if (gpio->function == MOT_INP_FUNC_NONE)
> +			continue;
> +		irq = gpiod_to_irq(gpio->gpio);
> +		devm_free_irq(mdev->dev, irq, gpio);

It seems devm is just overhead here if you release by hand anyhow.

> +		gpio->function = MOT_INP_FUNC_NONE;
> +	}
> +
> +	if (!kfifo_is_empty(&mdev->events))
> +		kfifo_reset(&mdev->events);
> +
> +	/* FIXME: Stop running motions? Probably not... */
> +
> +	return 0;
> +}
> +
> +static ssize_t motion_read(struct file *file, char __user *buffer,
> +			  size_t count, loff_t *ppos)
> +{
> +	struct motion_device *mdev = file->private_data;
> +	unsigned int copied = 0L;
> +	int ret;
> +
> +	if (!mdev->dev)
> +		return -ENODEV;
> +
> +	if (count < sizeof(struct mot_event))
> +		return -EINVAL;
> +
> +	do {
> +		if (kfifo_is_empty(&mdev->events)) {
> +			if (file->f_flags & O_NONBLOCK)
> +				return -EAGAIN;
> +
> +			ret = wait_event_interruptible(mdev->wait,
> +					!kfifo_is_empty(&mdev->events) ||
> +					mdev->dev == NULL);
> +			if (ret)
> +				return ret;
> +			if (mdev->dev == NULL)
> +				return -ENODEV;
> +		}
> +
> +		if (mutex_lock_interruptible(&mdev->read_mutex))
> +			return -ERESTARTSYS;
> +		ret = kfifo_to_user(&mdev->events, buffer, count, &copied);
> +		mutex_unlock(&mdev->read_mutex);
> +
> +		if (ret)
> +			return ret;
> +	} while (!copied);
> +
> +	return copied;
> +}
> +
> +static __poll_t motion_poll(struct file *file, poll_table *wait)
> +{
> +	struct motion_device *mdev = file->private_data;
> +	__poll_t mask = 0;
> +
> +	poll_wait(file, &mdev->wait, wait);
> +	if (!kfifo_is_empty(&mdev->events))
> +		mask = EPOLLIN | EPOLLRDNORM;
> +	dev_info(mdev->dev, "Obtained POLL events: 0x%08x\n", mask);

dev_dbg

> +
> +	return mask;
> +}
> +
> [...]
> +
> +static long motion_start_locked(struct motion_device *mdev, struct mot_start *s)
> +{
> +	long ret = 0L;
> +	mot_time_t conv_duration;
> +
> +	lockdep_assert_held(&mdev->mutex);
> +
> +	if (s->reserved1 || s->reserved2)
> +		return -EINVAL;
> +	if (s->channel >= mdev->capabilities.num_channels)
> +		return -EINVAL;
> +	if ((s->index >= MOT_MAX_PROFILES) || (s->direction > MOT_DIRECTION_RIGHT))
> +		return -EINVAL;
> +	if (!(mdev->profiles[s->index].index & MOTION_PROFILE_VALID))
> +		return -EINVAL;
> +	if (s->when >= MOT_WHEN_NUM_WHENS)
> +		return -EINVAL;
> +	if (s->duration && s->distance)
> +		return -EINVAL;
> +	if (!mdev->ops.motion_distance && !mdev->ops.motion_timed)
> +		return -EOPNOTSUPP;

I would add empty lines between these ifs to improve readability. Maybe
thats subjective though.

> +	if (s->duration) {
> +		if (!mdev->ops.motion_timed)
> +			return -EOPNOTSUPP;
> +		/* FIXME: Implement time to distance conversion? */
> +		return mdev->ops.motion_timed(mdev, s->channel, s->index,
> +				s->direction, s->duration, s->when);
> +	}
> +	if (!mdev->ops.motion_distance) {
> +		ret = motion_distance_to_time(mdev, s->index, s->distance,
> +				&conv_duration);
> +		if (ret)
> +			return ret;
> +		return mdev->ops.motion_timed(mdev, s->channel, s->index,
> +				s->direction, conv_duration, s->when);
> +	}
> +	ret = mdev->ops.motion_distance(mdev, s->channel, s->index,
> +			s->distance, s->when);
> +
> +	return ret;
> +}
> [...]
> +
> +static long motion_ioctl(struct file *file, unsigned int cmd, unsigned long arg)
> +{
> +	struct motion_device *mdev = file->private_data;
> +	void __user *argp = (void __user *)arg;
> +	long ret;
> +
> +	switch (cmd) {
> +	case MOT_IOCTL_APIVER:
> +		force_successful_syscall_return();
> +		return MOT_UAPI_VERSION;

force_successful_syscall_return() is only needed if the return value is
negative but no error.

> +	case MOT_IOCTL_BASIC_RUN: {
> +		struct mot_speed_duration spd;
> +
> +		if (copy_from_user(&spd, argp, sizeof(spd)))
> +			return -EFAULT;
> +		if (!mdev->ops.basic_run)
> +			return -EINVAL;
> [...]
> +
> +static const struct class motion_class = {
> +	.name		= "motion",
> +	.devnode	= motion_devnode,

IIRC it's recommended to not create new classes, but a bus.

> +};
> +
> +static const struct file_operations motion_fops = {
> +	.owner		= THIS_MODULE,
> +	.read		= motion_read,
> +	.poll		= motion_poll,
> +	.unlocked_ioctl = motion_ioctl,
> +	.open		= motion_open,
> +	.llseek		= noop_llseek,
> +	.release	= motion_release,
> +};
> +
> +static int motion_of_parse_gpios(struct motion_device *mdev)
> +{
> +	int ngpio, i;
> +
> +	ngpio = gpiod_count(mdev->parent, "motion,input");
> +	if (ngpio < 0) {
> +		if (ngpio == -ENOENT)
> +			return 0;
> +		return ngpio;
> +	}
> +
> +	if (ngpio >= MOT_MAX_INPUTS)
> +		return -EINVAL;
> +
> +	for (i = 0; i < ngpio; i++) {
> +		mdev->gpios[i].gpio = devm_gpiod_get_index(mdev->parent,
> +				"motion,input", i, GPIOD_IN);
> +		if (IS_ERR(mdev->gpios[i].gpio))
> +			return PTR_ERR(mdev->gpios[i].gpio);
> +		mdev->gpios[i].function = MOT_INP_FUNC_NONE;
> +		mdev->gpios[i].chmask = 0;
> +		mdev->gpios[i].index = i;
> +	}
> +
> +	mdev->num_gpios = ngpio;
> +	mdev->capabilities.num_ext_triggers += ngpio;
> +
> +	return 0;
> +}
> +
> +static void motion_trigger_work(struct irq_work *work)
> +{
> +	struct motion_device *mdev = container_of(work, struct motion_device,
> +							iiowork);
> +	iio_trigger_poll(mdev->iiotrig);
> +}
> +
> +/**
> + * motion_register_device - Register a new Motion Device
> + * @mdev: description and handle of the motion device
> + *
> + * Register a new motion device with the motion subsystem core.
> + * It also handles OF parsing of external trigger GPIOs and registers an IIO
> + * trigger device if IIO support is configured.
> + *
> + * Return: 0 on success, negative errno on failure.
> + */
> +int motion_register_device(struct motion_device *mdev)
> +{
> +	dev_t devt;
> +	int err = 0;
> +	struct iio_motion_trigger_info *trig_info;
> +
> +	if (!mdev->capabilities.num_channels)
> +		mdev->capabilities.num_channels = 1;
> +	if (mdev->capabilities.features | MOT_FEATURE_PROFILE)
> +		mdev->capabilities.max_profiles = MOT_MAX_PROFILES;
> +	if (!mdev->capabilities.speed_conv_mul)
> +		mdev->capabilities.speed_conv_mul = 1;
> +	if (!mdev->capabilities.speed_conv_div)
> +		mdev->capabilities.speed_conv_div = 1;
> +	if (!mdev->capabilities.accel_conv_mul)
> +		mdev->capabilities.accel_conv_mul = 1;
> +	if (!mdev->capabilities.accel_conv_div)
> +		mdev->capabilities.accel_conv_div = 1;
> +
> +	mutex_init(&mdev->mutex);
> +	mutex_init(&mdev->read_mutex);
> +	INIT_KFIFO(mdev->events);
> +	init_waitqueue_head(&mdev->wait);
> +
> +	err = motion_of_parse_gpios(mdev);
> +	if (err)
> +		return err;
> +
> +	mdev->minor = motion_minor_alloc();
> +
> +	mdev->iiotrig = iio_trigger_alloc(NULL, "mottrig%d", mdev->minor);
> +	if (!mdev->iiotrig) {
> +		err = -ENOMEM;
> +		goto error_free_minor;
> +	}
> +
> +	trig_info = kzalloc(sizeof(*trig_info), GFP_KERNEL);
> +	if (!trig_info) {
> +		err = -ENOMEM;
> +		goto error_free_trigger;
> +	}
> +
> +	iio_trigger_set_drvdata(mdev->iiotrig, trig_info);
> +
> +	trig_info->minor = mdev->minor;
> +	err = iio_trigger_register(mdev->iiotrig);
> +	if (err)
> +		goto error_free_trig_info;
> +
> +	mdev->iiowork = IRQ_WORK_INIT_HARD(motion_trigger_work);
> +
> +	INIT_LIST_HEAD(&mdev->list);
> +
> +	mutex_lock(&motion_mtx);
> +
> +	devt = MKDEV(motion_major, mdev->minor);
> +	mdev->dev = device_create_with_groups(&motion_class, mdev->parent,
> +				devt, mdev, mdev->groups, "motion%d", mdev->minor);

What makes sure that mdev doesn't go away while one of the attributes is
accessed?

> +	if (IS_ERR(mdev->dev)) {
> +		dev_err(mdev->parent, "Error creating motion device %d\n",
> +				mdev->minor);
> +		mutex_unlock(&motion_mtx);
> +		goto error_free_trig_info;
> +	}
> +	list_add_tail(&mdev->list, &motion_list);
> +	mutex_unlock(&motion_mtx);
> +
> +	return 0;
> +
> +error_free_trig_info:
> +	kfree(trig_info);
> +error_free_trigger:
> +	iio_trigger_free(mdev->iiotrig);
> +error_free_minor:
> +	motion_minor_free(mdev->minor);
> +	dev_info(mdev->parent, "Registering motion device err=%d\n", err);
> +	return err;
> +}
> +EXPORT_SYMBOL(motion_register_device);
> [...]
> +struct mot_capabilities {
> +	__u32 features;
> +	__u8 type;
> +	__u8 num_channels;
> +	__u8 num_int_triggers;
> +	__u8 num_ext_triggers;
> +	__u8 max_profiles;
> +	__u8 max_vpoints;
> +	__u8 max_apoints;
> +	__u8 reserved1;
> +	__u32 subdiv; /* Position unit sub-divisions, microsteps, etc... */
> +	/*
> +	 * Coefficients for converting to/from controller time <--> seconds.
> +	 * Speed[1/s] = Speed[controller_units] * conv_mul / conv_div
> +	 * Accel[1/s^2] = Accel[controller_units] * conv_mul / conv_div
> +	 */
> +	__u32 speed_conv_mul;
> +	__u32 speed_conv_div;
> +	__u32 accel_conv_mul;
> +	__u32 accel_conv_div;
> +	__u32 reserved2;
> +};

https://docs.kernel.org/gpu/imagination/uapi.html (which has some
generic bits that apply here, too) has: "The overall struct must be
padded to 64-bit alignment." If you drop reserved2 the struct is
properly sized (or I counted wrongly).

> +struct mot_speed_duration {
> +	__u32 channel;
> +	speed_raw_t speed;

What is the unit here?

> +	mot_time_t duration;

duration_ns? That makes usage much more ideomatic and there should be no
doubts what the unit is.

> +	pos_raw_t distance;

What is the unit here?

> +	__u32 reserved[3];

Again the padding is wrong here.

> +};

Best regards
Uwe

[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 488 bytes --]

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 0/7] Add Linux Motion Control subsystem
  2025-02-27 16:28 [RFC PATCH 0/7] Add Linux Motion Control subsystem David Jander
                   ` (8 preceding siblings ...)
  2025-02-28  9:35 ` Pavel Pisa
@ 2025-02-28 22:36 ` David Lechner
  2025-03-03  8:28   ` David Jander
  9 siblings, 1 reply; 59+ messages in thread
From: David Lechner @ 2025-02-28 22:36 UTC (permalink / raw)
  To: David Jander, linux-kernel
  Cc: linux-iio, Jonathan Corbet, Rob Herring, Krzysztof Kozlowski,
	Conor Dooley, devicetree, linux-doc, Nuno Sa, Jonathan Cameron,
	Oleksij Rempel

On 2/27/25 10:28 AM, David Jander wrote:
> Request for comments on: adding the Linux Motion Control subsystem to the
> kernel.
> 
> The Linux Motion Control subsystem (LMC) is a new kernel subsystem and
> associated device drivers for hardware devices that control mechanical
> motion. Most often these are different types of motors, but can also be
> linear actuators for example.

This is something that I played around with when I first got into Linux
kernel hacking as a hobbyist. It's something I've always wanted to see get
upstreamed, so feel free to cc me on any future revisions of this series.
I'm very interested. :-)

We made drivers for basic DC motors driven by an H-bridge both with and without
position feedback and also a driver for hobby-type servo motors. For those
interested, there is code [1] and docs [2]. One thing we would do different
if doing it over again is use a character device instead of sysfs attributes
as the interface for starting/stopping/adjusting actuation.

[1]: https://github.com/ev3dev/lego-linux-drivers/tree/ev3dev-stretch/motors
[2]: http://docs.ev3dev.org/projects/lego-linux-drivers/en/ev3dev-stretch/motors.html

> 
> This subsystem defines a new UAPI for motion devices on the user-space
> side, as well as common functionality for hardware device drivers on the
> driver side.
> 
> The UAPI is based on a ioctl() interface on character devices representing
> a specific hardware device. The hardware device can control one or more
> actuators (motors), which are identified as channels in the UAPI. It is
> possible to execute motions on individual channels, or combined
> affecting several selected (or all) channels simutaneously. Examples of
> coordinated movements of several channels could be the individual axes
> of a 3D printer or CNC machine for example.
> 
> On the hardware side, this initial set of patches also includes two drivers
> for two different kinds of motors. One is a stepper motor controller
> device that containes a ramp generator capable of autonomously executing
> controlled motions following a multi-point acceleration profile
> (TMC5240), as well as a simple DC motor controller driver that can control
> DC motors via a half-bridge or full H-bridge driver such as the TI DRV8873
> for example.
> 
> Towards the IIO subsystem, LMC supports generating iio trigger events that
> fire at certain motion events, such as passing a pre-programmed position or
> when reaching the motion target position, depending on the capabilities of
> the hardware device. This enables for example triggering an ADC measurement
> at a certain position during a movement.

I would expect to be using the counter subsystem for position, at least in
cases where there is something like a quadrature encoder involved.

> 
> In the future, making use of PREEMPT_RT, even dumb STEP/DIR type stepper
> motor controller drivers may be implemented entirely in the kernel,
> depending on some characteristics of the hardware (latency jittter,
> interrupt latency and CPU speed mainly).
> 
> The existence of this subsystem may affect other projects, such as
> Linux-CNC and Klipper for example.
> 
> This code is already in use controlling machines with up to 16 stepper
> motors and up to 4 DC motors simutaneously. Up to this point the UAPI
> has shown to be adequate and sufficient. Careful thought has gone into
> the UAPI design to make sure it coveres as many use-cases as possible,
> while being versioned and extensible in the future, with backwards
> compatibility in mind.
> 
> David Jander (7):
>   drivers: Add motion control subsystem

Would it be too broad to call this an actuation subsystem instead where motion
is just one kind of actuation?

>   motion: Add ADI/Trinamic TMC5240 stepper motor controller
>   motion: Add simple-pwm.c PWM based DC motor controller driver
>   Documentation: Add Linux Motion Control documentation
>   dt-bindings: motion: Add common motion device properties
>   dt-bindings: motion: Add adi,tmc5240 bindings
>   dt-bindings: motion: Add motion-simple-pwm bindings
> 

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-02-27 16:28 ` [RFC PATCH 1/7] drivers: Add motion control subsystem David Jander
  2025-02-28 16:44   ` Uwe Kleine-König
@ 2025-02-28 22:36   ` David Lechner
  2025-03-03  8:36     ` David Jander
  1 sibling, 1 reply; 59+ messages in thread
From: David Lechner @ 2025-02-28 22:36 UTC (permalink / raw)
  To: David Jander, linux-kernel
  Cc: linux-iio, Jonathan Corbet, Rob Herring, Krzysztof Kozlowski,
	Conor Dooley, devicetree, linux-doc, Nuno Sa, Jonathan Cameron,
	Oleksij Rempel

On 2/27/25 10:28 AM, David Jander wrote:
> The Linux Motion Control subsystem (LMC) is a new driver subsystem for
> peripheral devices that control mechanical motion in some form or another.
> This could be different kinds of motors (stepper, DC, AC, SRM, BLDC...)
> or even linear actuators.
> The subsystem presents a unified UAPI for those devices, based on char
> devices with ioctl's.
> It can make use of regular gpio's to function as trigger inputs, like
> end-stops, fixed position- or motion start triggers and also generate
> events not only to user-space but also to the IIO subsystem in the form of
> IIO triggers.
> 
> Signed-off-by: David Jander <david@protonic.nl>
> ---
>  MAINTAINERS                     |   8 +
>  drivers/Kconfig                 |   2 +
>  drivers/Makefile                |   2 +
>  drivers/motion/Kconfig          |  19 +
>  drivers/motion/Makefile         |   3 +
>  drivers/motion/motion-core.c    | 823 ++++++++++++++++++++++++++++++++
>  drivers/motion/motion-core.h    | 172 +++++++
>  drivers/motion/motion-helpers.c | 590 +++++++++++++++++++++++
>  drivers/motion/motion-helpers.h |  23 +
>  include/uapi/linux/motion.h     | 229 +++++++++
>  10 files changed, 1871 insertions(+)

Ooof, this is really a lot for one patch. Makes it hard to review. 500 lines in
a patch is much easier to digest.

But before commenting on the details of the code I have some more high-level
comments. As I mentioned in my reply to the cover letter, I've gone through the
exercise of writing some motor control divers in the Linux kernel that have been
used by 1000s of people that used them to build everything imaginable using LEGO
robotics over the last 10+ years.

From what I see here (I didn't have time to really get into the details of it
yet, so maybe missed some important details), it looks like you are trying to
do motor control stuff in the kernel so that the interface for a basic H-bridge
will be close to the same as a fancy stepper motor controller. We tried doing
something very similar because it sounds like a really nice thing to do. The
kernel does everything and makes it really easy for the users. But what we
actually found is that it is not possible to make a solution in the kernel that
can handle every possible use case. In the end, we wished that we had a much
more low-level interface to the motor controllers to give us more flexibility
for the many different types of applications this ended up getting used for.
Having to modify the kernel for your use case is too high of a bar for most
users and not practical even if you are a kernel hacker.

When writing kernel drivers for this sort of thing, I think the rule of thumb
should be to keep the driver as "thin" as possible. If the hardware doesn't
provide a feature, the kernel should not be trying to emulate it. So for an
H-bridge I would want something that just provides a way to tell it I want
fast-decay mode with some normalized duty cycle between -1 and 1 (obviously we
will have to multiply this by some factor since the kernel doesn't do floating
point). A duty cycle of 0 will "brake" the motor. And then we would need one
more control parameter to tell it to remove power completely to "coast" the
motor. I guess this is what the "basic_run" and "basic_stop" are other than
the run seems to have speed instead of duty cycle? The kernel shouldn't be
trying to convert this duty cycle to speed or have a background task that tries
to provide an acceleration profile or turn off the power after some time. Just
let the kernel provide direct, low-level access to the hardware and let
userspace handle all of the rest in a way that makes the most sense for the
specific application. Sometimes they might not even be connected to a motor!
With the LEGO MINDSTORMS and BeableBone Blue, the H-bridge outputs are
hot-pluggable, so they can even be connected to things like LEDs or used as a
general power supply. (A reason to call this subsystem "actuation" rather than
"motion".)

Another way of putting this is that it was very tempting to model the actual
motor in the kernel. But that didn't work well because there are so many
different kinds of motors and related mechanical systems that you can connect
to the same motor driver chip. So the driver really should just be for the
H-bridge chip itself and not care about the motor. And the rest can be put in
a libmotion userspace library and have that be the convenient API for users
that want to get something up and running quickly.


^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 6/7] dt-bindings: motion: Add adi,tmc5240 bindings
  2025-02-27 16:28 ` [RFC PATCH 6/7] dt-bindings: motion: Add adi,tmc5240 bindings David Jander
  2025-02-28  7:11   ` Krzysztof Kozlowski
@ 2025-02-28 22:38   ` David Lechner
  2025-03-03 11:22     ` David Jander
  1 sibling, 1 reply; 59+ messages in thread
From: David Lechner @ 2025-02-28 22:38 UTC (permalink / raw)
  To: David Jander, linux-kernel
  Cc: linux-iio, Jonathan Corbet, Rob Herring, Krzysztof Kozlowski,
	Conor Dooley, devicetree, linux-doc, Nuno Sa, Jonathan Cameron,
	Oleksij Rempel

On 2/27/25 10:28 AM, David Jander wrote:
> Add device-tree bindings for Analog Devices TMC5240 stepper controllers.
> 
> Signed-off-by: David Jander <david@protonic.nl>
> ---
>  .../bindings/motion/adi,tmc5240.yaml          | 60 +++++++++++++++++++
>  1 file changed, 60 insertions(+)
>  create mode 100644 Documentation/devicetree/bindings/motion/adi,tmc5240.yaml
> 
> diff --git a/Documentation/devicetree/bindings/motion/adi,tmc5240.yaml b/Documentation/devicetree/bindings/motion/adi,tmc5240.yaml
> new file mode 100644
> index 000000000000..3364f9dfccb1
> --- /dev/null
> +++ b/Documentation/devicetree/bindings/motion/adi,tmc5240.yaml
> @@ -0,0 +1,60 @@
> +# SPDX-License-Identifier: (GPL-2.0 OR BSD-2-Clause)
> +%YAML 1.2
> +---
> +$id: http://devicetree.org/schemas/motion/adi,tmc5240.yaml#
> +$schema: http://devicetree.org/meta-schemas/core.yaml#
> +
> +title: Analog Devices TMC5240 Stepper Motor controller
> +
> +maintainers:
> +  - David Jander <david@protonic>
> +
> +description: |
> +   Stepper motor controller with motion engine and SPI interface.

Please include a link to the datasheet.

> +
> +properties:
> +  compatible:
> +    enum:
> +      - adi,tmc5240
> +
> +  reg:
> +    maxItems: 1
> +
> +  interrupts:
> +    maxItems: 1

I assume that this is the overvoltage output (OV pin). Would be nice to have
a description here saying that. There are also NAO and DIAG0/1 output pins, so
it's a bit ambiguous otherwise.

> +
> +  enable-supply:
> +    description: Optional external enable supply to control SLEEPn pin. Can
> +      be shared between several controllers.
> +

This doesn't look like a supply, but krzk already discussed that. But there
should be actual power supplies: vs-supply, vdd1v8-supply, vcc-io-supply. And
a reference voltage supply: iref-supply

And if there are any pins would make sense to connect to a gpio, we can add
those even if the driver doesn't use it currently.

> +  clocks:
> +    maxItems: 1
> +
> +required:
> +  - compatible
> +  - reg
> +  - interrupts
> +  - clocks
> +
> +allOf:
> +  - $ref: /schemas/spi/spi-peripheral-props.yaml#
> +  - $ref: /schemas/motion/common.yaml#

If we need to know about what is connected to the output of a motor controller
I would expect it to be done with child node for each output. That way each
output can be unique, if needed. Basically, similar to iio/adc.yaml is used to
provide common properties for channel@ child nodes on iio devices.

> +
> +unevaluatedProperties: false
> +
> +examples:
> +  - |
> +    spi {
> +        #address-cells = <1>;
> +        #size-cells = <0>;
> +
> +        motor@0 {

motor-controller@ or actuator-controller@

The chip is the controller/driver, it is not a motor.

> +            compatible = "adi,tmc5240";
> +            reg = <0>;
> +            interrupts-extended = <&gpiok 7 0>;
> +            clocks = <&clock_tmc5240>;
> +            enable-supply = <&stpsleepn>;
> +            spi-max-frequency = <1000000>;
> +        };
> +    };
> +


^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings
  2025-02-27 16:28 ` [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings David Jander
  2025-02-27 17:38   ` Rob Herring (Arm)
  2025-02-28  7:12   ` Krzysztof Kozlowski
@ 2025-02-28 22:41   ` David Lechner
  2025-03-03 12:54     ` David Jander
  2 siblings, 1 reply; 59+ messages in thread
From: David Lechner @ 2025-02-28 22:41 UTC (permalink / raw)
  To: David Jander, linux-kernel
  Cc: linux-iio, Jonathan Corbet, Rob Herring, Krzysztof Kozlowski,
	Conor Dooley, devicetree, linux-doc, Nuno Sa, Jonathan Cameron,
	Oleksij Rempel

On 2/27/25 10:28 AM, David Jander wrote:
> Add device-tree bindings for simple Linux Motion Control devices that
> are based on 1 or 2 PWM outputs.
> 
> Signed-off-by: David Jander <david@protonic.nl>
> ---
>  .../bindings/motion/motion-simple-pwm.yaml    | 55 +++++++++++++++++++
>  1 file changed, 55 insertions(+)
>  create mode 100644 Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml
> 
> diff --git a/Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml b/Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml
> new file mode 100644
> index 000000000000..409e3aef6f3f
> --- /dev/null
> +++ b/Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml
> @@ -0,0 +1,55 @@
> +# SPDX-License-Identifier: (GPL-2.0 OR BSD-2-Clause)
> +%YAML 1.2
> +---
> +$id: http://devicetree.org/schemas/motion/motion-simple-pwm.yaml#
> +$schema: http://devicetree.org/meta-schemas/core.yaml#
> +
> +title: Simple PWM based motor controller

I think it has been said many times before, in DT, there is no such thing as
a simple device! It will be much more future-proof if we write bindings for
actual individual motor controller chips than try to generalize all in a single
binding. The chip you gave as an example is far from the simplest H-bridge I
have seen!

> +
> +maintainers:
> +  - David Jander <david@protonic>
> +
> +description: |
> +   Simple motor control device based on 1 or 2 PWM outputs
> +
> +properties:
> +  compatible:
> +    enum:
> +      - motion-simple-pwm

This should be e.g. ti,drv8873-q1. This device has much more pins that is given
in these bindings.

If we find more devices that have similar functionality/pinout we can add them
to the same bindings, but we will likely find that trying to cram all H-bridges
into a single binding is too much.

For starters, every H-bridge chip is going to have one or more power supplies.
ti,drv8873-q1 would need dvdd-supply and vm-supply properties for the DVDD and
VM pins.

Many have inputs for disabling the chip, e.g. for power management. And some
have outputs to indicate faults.

The TI DRV8873 in particular has an nSLEEP, DISABLE, nOL, SR, MODE and nITRIP
inputs in addition to the IN1 and IN2 that would be connected to the PWMs.
So we would have properties for all of these to either say how the pin is
hardwired or a *-gpios property if it needs to be controlled by the driver.

The fault output would generally be an interrupts property.

The IPROPI1 and IPROPI2 output pins look like they would be connected to an
ADC, so it would make sense to have an io-channels property show that
connection.

This chip also has a SPI interface. So it needs to have the possibility of
being a SPI peripheral node.

And even if the Linux driver doesn't implement all of these features, we still
want the DT bindings to be as complete as possible, so we shouldn't be leaving
these out, at least for the trivial ones where there is an obvious correct
binding (which I think is the case for most of what I suggested).

> +
> +  pwms:
> +    maxItems: 2
> +
> +  pwm-names:
> +    maxItems: 2

Specifying what is wired up to the IN pins can be tricky. Using two PWMs is
the most sensible. But I've also seen devices where there was a single PWM
gated by two gpios. And for very basic H-bridges, there might not even be a
PWM. Just gpios to turn it on or off.

> +
> +  motion,pwm-inverted:
> +    $ref: /schemas/types.yaml#/definitions/flag
> +    description:
> +      If present, this flag indicates that the PWM signal should be inverted.
> +      The duty-cycle will be scaled from 100% down to 0% instead 0% to 100%.
> +
> +required:
> +  - compatible
> +  - pwms
> +
> +allOf:
> +  - $ref: /schemas/motion/common.yaml#
> +
> +unevaluatedProperties: false
> +
> +examples:
> +  - |
> +    // This example shows how to use the TI DRV8873 or similar motor controllers
> +    // with this driver
> +    motion-simple-pwm0 {
> +      compatible = "motion-simple-pwm";
> +      pwms = <&hpdcm0_pwm 0 50000 0>,
> +             <&hpdcm0_pwm 1 50000 0>;
> +      pwm-names = "left", "right";
> +      motion,pwm-inverted;


> +      motion,speed-conv-mul = <3600>;
> +      motion,speed-conv-div = <100000>;
> +      motion,acceleration-conv-mul = <3600>;
> +      motion,acceleration-conv-div = <100000>;

This H-bridge controller doesn't have any kind of speed sensors that I can see
so these properties don't make sense to me. The H-bridge can control the voltage
sent to the motor, but there are more variables involved to convert voltage to
speed. It isn't a constant.

> +    };


^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 0/7] Add Linux Motion Control subsystem
  2025-02-28 22:36 ` David Lechner
@ 2025-03-03  8:28   ` David Jander
  0 siblings, 0 replies; 59+ messages in thread
From: David Jander @ 2025-03-03  8:28 UTC (permalink / raw)
  To: David Lechner
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel


Dear David,

Thanks for reviewing!

On Fri, 28 Feb 2025 16:36:31 -0600
David Lechner <dlechner@baylibre.com> wrote:

> On 2/27/25 10:28 AM, David Jander wrote:
> > Request for comments on: adding the Linux Motion Control subsystem to the
> > kernel.
> > 
> > The Linux Motion Control subsystem (LMC) is a new kernel subsystem and
> > associated device drivers for hardware devices that control mechanical
> > motion. Most often these are different types of motors, but can also be
> > linear actuators for example.  
> 
> This is something that I played around with when I first got into Linux
> kernel hacking as a hobbyist. It's something I've always wanted to see get
> upstreamed, so feel free to cc me on any future revisions of this series.
> I'm very interested. :-)

Cool! Will keep you posted.

> We made drivers for basic DC motors driven by an H-bridge both with and without
> position feedback and also a driver for hobby-type servo motors. For those
> interested, there is code [1] and docs [2]. One thing we would do different
> if doing it over again is use a character device instead of sysfs attributes
> as the interface for starting/stopping/adjusting actuation.
> 
> [1]: https://github.com/ev3dev/lego-linux-drivers/tree/ev3dev-stretch/motors
> [2]: http://docs.ev3dev.org/projects/lego-linux-drivers/en/ev3dev-stretch/motors.html
> 
> > 
> > This subsystem defines a new UAPI for motion devices on the user-space
> > side, as well as common functionality for hardware device drivers on the
> > driver side.
> > 
> > The UAPI is based on a ioctl() interface on character devices representing
> > a specific hardware device. The hardware device can control one or more
> > actuators (motors), which are identified as channels in the UAPI. It is
> > possible to execute motions on individual channels, or combined
> > affecting several selected (or all) channels simutaneously. Examples of
> > coordinated movements of several channels could be the individual axes
> > of a 3D printer or CNC machine for example.
> > 
> > On the hardware side, this initial set of patches also includes two drivers
> > for two different kinds of motors. One is a stepper motor controller
> > device that containes a ramp generator capable of autonomously executing
> > controlled motions following a multi-point acceleration profile
> > (TMC5240), as well as a simple DC motor controller driver that can control
> > DC motors via a half-bridge or full H-bridge driver such as the TI DRV8873
> > for example.
> > 
> > Towards the IIO subsystem, LMC supports generating iio trigger events that
> > fire at certain motion events, such as passing a pre-programmed position or
> > when reaching the motion target position, depending on the capabilities of
> > the hardware device. This enables for example triggering an ADC measurement
> > at a certain position during a movement.  
> 
> I would expect to be using the counter subsystem for position, at least in
> cases where there is something like a quadrature encoder involved.

I will have to think about it. Since there are some Linux capable SoC's that
have counter inputs able to do quadrature decoding, it might make sense to
support that. For now, the TMC5240 controller for example has support for
encoders and while in this patch-set support for it is minimal, the idea was
that a motion controller that supports an encoder would just offer the option
to use the encoder as the authoritative source for position information. So
let's say you have a DC motor for example. Without an encoder or any other
means for of speed/position feedback, the best one can do is establish a 1:1
relationship between duty-cycle and speed, obviating all inaccuracies of doing
so. So a motion controller using a DC motor would just do that if it has no
encoder. OTOH, if there is an encoder as a source of position and speed
information, the driver could work with more accurate data. It all depends, but
in the end the interface towards the user is the same: move with some speed
towards some position or for some amount of time.

> > In the future, making use of PREEMPT_RT, even dumb STEP/DIR type stepper
> > motor controller drivers may be implemented entirely in the kernel,
> > depending on some characteristics of the hardware (latency jittter,
> > interrupt latency and CPU speed mainly).
> > 
> > The existence of this subsystem may affect other projects, such as
> > Linux-CNC and Klipper for example.
> > 
> > This code is already in use controlling machines with up to 16 stepper
> > motors and up to 4 DC motors simutaneously. Up to this point the UAPI
> > has shown to be adequate and sufficient. Careful thought has gone into
> > the UAPI design to make sure it coveres as many use-cases as possible,
> > while being versioned and extensible in the future, with backwards
> > compatibility in mind.
> > 
> > David Jander (7):
> >   drivers: Add motion control subsystem  
> 
> Would it be too broad to call this an actuation subsystem instead where motion
> is just one kind of actuation?

I think it is hard enough already to make a UAPI for motion that is general
enough to encompass all types of different motors and motion actuators.
Generalizing even further without a serious risk of shortcomings seems almost
impossible, but I am open to suggestions.

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-02-28 22:36   ` David Lechner
@ 2025-03-03  8:36     ` David Jander
  2025-03-03 11:01       ` Pavel Pisa
  0 siblings, 1 reply; 59+ messages in thread
From: David Jander @ 2025-03-03  8:36 UTC (permalink / raw)
  To: David Lechner
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel, Pavel Pisa

On Fri, 28 Feb 2025 16:36:41 -0600
David Lechner <dlechner@baylibre.com> wrote:

> On 2/27/25 10:28 AM, David Jander wrote:
> > The Linux Motion Control subsystem (LMC) is a new driver subsystem for
> > peripheral devices that control mechanical motion in some form or another.
> > This could be different kinds of motors (stepper, DC, AC, SRM, BLDC...)
> > or even linear actuators.
> > The subsystem presents a unified UAPI for those devices, based on char
> > devices with ioctl's.
> > It can make use of regular gpio's to function as trigger inputs, like
> > end-stops, fixed position- or motion start triggers and also generate
> > events not only to user-space but also to the IIO subsystem in the form of
> > IIO triggers.
> > 
> > Signed-off-by: David Jander <david@protonic.nl>
> > ---
> >  MAINTAINERS                     |   8 +
> >  drivers/Kconfig                 |   2 +
> >  drivers/Makefile                |   2 +
> >  drivers/motion/Kconfig          |  19 +
> >  drivers/motion/Makefile         |   3 +
> >  drivers/motion/motion-core.c    | 823 ++++++++++++++++++++++++++++++++
> >  drivers/motion/motion-core.h    | 172 +++++++
> >  drivers/motion/motion-helpers.c | 590 +++++++++++++++++++++++
> >  drivers/motion/motion-helpers.h |  23 +
> >  include/uapi/linux/motion.h     | 229 +++++++++
> >  10 files changed, 1871 insertions(+)  
> 
> Ooof, this is really a lot for one patch. Makes it hard to review. 500 lines in
> a patch is much easier to digest.

Sorry for that. I wouldn't know how to split up this patch to make it any
easier. It's just a complete new subsystem, and I think it is the bare minimum
to start and also to give a good idea of what it is supposed to be able to do.

> But before commenting on the details of the code I have some more high-level
> comments. As I mentioned in my reply to the cover letter, I've gone through the
> exercise of writing some motor control divers in the Linux kernel that have been
> used by 1000s of people that used them to build everything imaginable using LEGO
> robotics over the last 10+ years.
> 
> From what I see here (I didn't have time to really get into the details of it
> yet, so maybe missed some important details), it looks like you are trying to
> do motor control stuff in the kernel so that the interface for a basic H-bridge
> will be close to the same as a fancy stepper motor controller. We tried doing
> something very similar because it sounds like a really nice thing to do. The
> kernel does everything and makes it really easy for the users. But what we
> actually found is that it is not possible to make a solution in the kernel that
> can handle every possible use case. In the end, we wished that we had a much
> more low-level interface to the motor controllers to give us more flexibility
> for the many different types of applications this ended up getting used for.
> Having to modify the kernel for your use case is too high of a bar for most
> users and not practical even if you are a kernel hacker.

The idea for LMC is to be able to support hardware that realistically can be
used by an OS as complex as the Linux kernel. There are a lot of motor
controllers out there that suit that category, like the TMC5240 chip for
example. But also many bigger systems, like the ones Pavel Pisa works with.
That said, I think the Linux kernel on modestly modern SoC's, like the
STM32MP1xx is pretty capable of doing more than that, but we have to draw the
line somewhere. Like I hinted in the cover letter, I think it might even be
possible to do crazy stuff like bit-banging STEP/DIR type controllers in the
kernel, possibly aided by PREEMPT_RT, but that is not the main purpose of LMC.
The main purpose is to talk to controllers that can receive motion profiles
and execute movements (semi-)autonomously. Going just one step lower is the
simple PWM based driver in this patch set: It takes the execution of the
profile into the kernel by using a HRTIMER to sample the profile curve using a
sample period of 20ms, which is fast enough for most applications while not
imposing a high CPU load on the kernel on slower CPU cores.
motion-helper.c contains the trapezoidal ramp generator code that can be used
by any LMC driver that can work with speed information but doesn't have its
own ramp generator in hardware. It could be extended to support other type of
profiles if needed in the future, which would automatically upgrade all
drivers that use it.

> When writing kernel drivers for this sort of thing, I think the rule of thumb
> should be to keep the driver as "thin" as possible. If the hardware doesn't
> provide a feature, the kernel should not be trying to emulate it.

In general I would agree with this, but in this case some limited "emulation"
seems adequate. As a rule of thumb, code is better placed in an FPGA/uC, the
kernel or in user-space according to its latency requirements. Microsecond
stuff shouldn't be done on the application SoC at all, millisecond stuff (or
maybe 100s of microseconds if you like) can be done in the kernel, 10s of
milliseconds or slower is good for user-space. A very general guideline.

So if you have a device that can take a speed-setpoint but doesn't have a
ramp generator, that is not a device that LMC is made for in the first place,
but still pretty usable if we do the ramp generator in the kernel.
To steal Pavel's analogy: Think of the TMC5240 driver as a FullMAC Wifi device
and the simple PWM driver as a SoftMAC Wifi device.
For an LMC device, same as for a wifi interface, we want to talk TCP/IP to it
from user-space, not radio-packets. ;-)

> So for an
> H-bridge I would want something that just provides a way to tell it I want
> fast-decay mode with some normalized duty cycle between -1 and 1 (obviously we
> will have to multiply this by some factor since the kernel doesn't do floating
> point). A duty cycle of 0 will "brake" the motor. And then we would need one
> more control parameter to tell it to remove power completely to "coast" the
> motor. I guess this is what the "basic_run" and "basic_stop" are other than
> the run seems to have speed instead of duty cycle? The kernel shouldn't be
> trying to convert this duty cycle to speed or have a background task that tries
> to provide an acceleration profile or turn off the power after some time. Just
> let the kernel provide direct, low-level access to the hardware and let
> userspace handle all of the rest in a way that makes the most sense for the
> specific application. Sometimes they might not even be connected to a motor!
> With the LEGO MINDSTORMS and BeableBone Blue, the H-bridge outputs are
> hot-pluggable, so they can even be connected to things like LEDs or used as a
> general power supply. (A reason to call this subsystem "actuation" rather than
> "motion".)

LMC aims to offer a common interface to different sorts of motion devices
(think different types of motors), so offering access to the lowest level of
each device is kinda defeating of that purpose. Nevertheless, all of the
things you mention are possible with LMC. The relationship between speed and
the PWM duty-cycle of a simple DC motor H-bridge for example, is determined by
the speed_conv* and accel_conv* parameters. If you want a 1:1 relation, just
make them 1 in your device tree.
OTOH, if you had only a duty-cycle setting from user-space, you would need to
have code that generates an acceleration profile in user-space, which would be
a much higher CPU load and have a much higher latency jitter, much more likely
to cause mechanical and audible effects than if done in the kernel.
It's still possible though.
And talking about mis-using a motor driver for something else, that's exactly
what one of our customers is doing with a DC motor H-bridge via LMC. They just
set each output to 0% or 100% duty-cycle (max speed without profile) to control
2 warning lights.

> Another way of putting this is that it was very tempting to model the actual
> motor in the kernel. But that didn't work well because there are so many
> different kinds of motors and related mechanical systems that you can connect
> to the same motor driver chip.

Yes, but on the other side, you have many different driver chips that all
control motors that do the same thing: move in different directions with
different speeds and different acceleration profiles. As a user, I want to be
able to tell that to the motor in the same sense as I want to send a data
through an ethernet interface without having to know what kind of interface I
have to an extend reasonably possible. Of course each motor/driver has
different limitations (just as different network interfaces have), and more
often than not I will have to know some of those in user-space, but the whole
idea of a subsystem UAPI is to abstract as much as possible of that from
user-space.

With LMC I could easily swap a stepper motor for a BLDC or DC motor for
example. If they have an encoder to provide accurate position feedback, it
could even work as well as a stepper for many applications. No changes in
user-space code required.

> So the driver really should just be for the
> H-bridge chip itself and not care about the motor. And the rest can be put in
> a libmotion userspace library and have that be the convenient API for users
> that want to get something up and running quickly.

I get your point, and from the standpoint of Lego hardware and hobby tinkerers
doing all sorts of stuff with it, I can understand the desire to have
low-level access from user-space to the H-bridge. It is similar to how
Raspberry-pi exposes direct access to their GPIO controllers to user-space. It
is nice for tinkerers, but it is inadequate for anything else, not to mention
potentially unsafe. I remember when I first installed Linux on my PC in 1994,
we had the X server access the video card directly from user-space. That was a
really bad idea. ;-)

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 0/7] Add Linux Motion Control subsystem
  2025-02-28 15:23     ` Pavel Pisa
@ 2025-03-03 10:45       ` David Jander
  0 siblings, 0 replies; 59+ messages in thread
From: David Jander @ 2025-03-03 10:45 UTC (permalink / raw)
  To: Pavel Pisa
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel, Carsten Emde


Hi Pavel,

On Fri, 28 Feb 2025 16:23:33 +0100
Pavel Pisa <ppisa@pikron.com> wrote:

> Hello David,
> 
> On Friday 28 of February 2025 12:57:27 David Jander wrote:
> > Dear Pavel,
> >
> > Thanks a lot for starting the discussion...
> >
> > On Fri, 28 Feb 2025 10:35:57 +0100
> >
> > Pavel Pisa <ppisa@pikron.com> wrote:  
> > > Hello David and others
> > >
> > > On Thursday 27 of February 2025 17:28:16 David Jander wrote:  
> > > > Request for comments on: adding the Linux Motion Control subsystem to
> > > > the kernel.  
> > >
> > > I have noticed on Phoronix, that the new system is emerging.  
> >
> > Being featured on Phoronix on day one wasn't on my bingo card for this
> > year, to be honest... :-)
> >  
> > > This is area where I have lot (more than 30 years) of experience
> > > at my company and I have done even lot with my studnets at university.
> > > I have big interest that this interface fits our use neeeds
> > > and offers for future integration of our already open-source
> > > systems/components.  
> >
> > This is very impressive and I am honored to have gotten your attention. I
> > am looking forward to discussing this, although I am not sure whether all
> > of this should happen here on LKML?  
> 
> We should move somewhere else and invite people from Linux
> CNC etc...

I agree.

> GitHub project would work well if there is not some reluctance
> to commercially controlled and closed environment.

I am open to suggestions. I just happen to have a github account and also have
my code there:

https://github.com/yope/linux/tree/mainline-lmc-preparation

> Gitlab even in Gitlab.com case has option to move to own
> infrastructure in the future. We have Gitlab at university,
> companies I work with has Gitlab instances. But I think that
> we should stay on neutral ground.
> 
> The critical is some central hub where links to specific
> mailinglist etc. can be placed. May it be we can ask
> Linux foundation to provide wiki space for Linux Motion Control
> Subsystem same as it is for RT
> 
>   https://wiki.linuxfoundation.org/realtime/start
> 
> We can ask OSADL.org as likely neutral space...

That sounds really great. We were bronze members of OSADL, so maybe that's a
good idea. I see you added Carsten Emde in CC ;-)

> Or wiki at kernel.org, may it the most neutral...
> 
>  https://www.wiki.kernel.org/

Yes, that may be even a better place than OSADL.

> I am not in the core teams but may it be there on LKLM
> somebody would suggest the direction. I can ask people
> from OSADL, CIPS, RT projects etc. directly...
> 
> But I am not the authority and would be happy if somebody
> steers us.
> 
> To not load others, if there is no response then I suggest
> to limit followup e-mails only to linux-iio and those
> who already communicated in this thread.

Agree. This will probably be my last reply to this thread with LMKL in CC.

Is there anybody here willing to help with contact information?

> > > This is preliminary reply, I want to find time for more discussion
> > > and analysis (which is quite hard during summer term where I have
> > > lot of teaching and even ongoing project now).
> > >
> > > I would like to discuse even future subsystem evolution
> > > which would allow coordinates axes groups creation, smooth
> > > segments based on N-th order splines incremental attachment,
> > > the path planning and re-planning if the target changes
> > > as reaction to camera or other sensor needs etc.  
> >
> > Right now LMC should be able to support hardware that has multiple channels
> > (axes) per device. Its UAPI can describe position-based movements and
> > time-based movements along any arbitrary combination of those channels
> > using a pre-defined speed/acceleration profile.
> >
> > The profiles can be specified as an arbitrary number of speed and
> > acceleration values. The idea is to describe a segmented profile with
> > different acceleration values for segments between two different speed
> > values. Simple examples are trapezoidal (accelerate from (near-)zero to
> > Vmax with A1, and decelerate from Vmax back to zero with D1), dual-slope or
> > S-curve, but the UAPI in theory permits an arbitrary number of segments if
> > the underlying hardware supports it.  
> 
> Yes, when I have read that it reminded me my API between non-RT
> and RT control task in Linux and IRQs in sysless case of our system.
>
> > I have some ideas for future extensions to the API that make coordinated
> > multi-channel movements a bit easier, but that will not be in the initial
> > push of LMC: For example torque-limit profiles for controlled torque
> > movements, usable for example in sliding door controllers with AC machines
> > or BLDC motors; or an ioctl to send a distance vector to a selected number
> > of channels at once and apply a motion profile to the whole coordinated
> > movement. In the current version you have to set up the distances and
> > profiles for the individual channels and then trigger the start of the
> > motion, which is more cumbersome. You can already use the finish event of a
> > preceding motion to trigger the next one though.  
> 
> It would worth to have some commands queue for specified
> (prefigured/setup) xis group.

I thought about this, and while queuing commands for a 3D printer seems like a
great idea, since it is strictly feed-forward for the most part, queuing
commands in the kernel is complicating things a lot when you also want to be
able to react to real-time events in user-space, like end-stop switches and
such. I think the current GPIO UAPI with support for epoll events is
fantastic, and people should use it. :-)

OTOH, I think that the speed and timing accuracy with which one would send
individual movement commands (vectors or splines) to a motion controller is
perfectly adequate for user-space, specially if you have the option of a
1-deep queue like this mechanism of triggering the next movement when the
current one finishes, which basically gives you the time the current movement
takes as latency-slack for user-space. I think that is enough, but let me know
if you disagree. Maybe it is possible to make the N-dimensional vector
interface (optionally) queued?

> Our system allows to add segments to the group queue but the
> timing for segment only specifies shortest time in which it can
> be executed.
> 
> Then there is three passes optimization then.
> 
> The first pass is performed at the insertion time. It checks and
> finds normalized change of speeds  (divided by maximal accel/deccel
> of given axis) at vertex and finds limiting exes, one which accelerates
> the most and another which needs to decelerate the most. Then it
> computes speed discontinuity at the given sample period and it limits
> maximal final speed of the preceding segment such way, that the speed
> change is kept under COORDDISCONT multiple of accel/decel step. This
> way, if the straight segments are almost in line, the small change
> of the direction is not limiting the speed. The discontinuity is
> computed same way for the vertex between two N-order spline segments,
> but optimally computed spline segments can be joint with such
> discontinuity near to zero. This non RT computation as well as all
> non-RT a RT one on the control unit side is done in the fixed
> math (the most 32-bits, sometime 64-bits). Actual code of this
> pass are the functions pxmc_coordmv_seg_add(), pxmc_coordmv_seg_add_line()
> and pxmc_coordmv_seg_add_spline()

Yes, this maps very well with what I had in mind when designing LMC. I haven't
thought about supporting engines capable of real-time spline interpolation
because I hadn't seen one before. I thought that just dividing a spline into
(many) linear segments would be good enough, but if there are motion engines
that can handle spline parameters, I guess we should try to support that.

The motion profiles LMC supports have 2 extra parameters for limiting speed
discontinuities which can be found in many common motion engines: tvmax and
tvzero.

https://github.com/yope/linux/blob/mainline-lmc-preparation/include/uapi/linux/motion.h#L146

Tvmax is important for situations where the maximum speed of a given profile
is not reached because the distance is too short. It will make sure there is
at least some period of constant speed before decelerating again.

Tvzero is important for motions that starts accelerating into an opposite
direction of a preceding motion, to insert a minimum time at zero velocity.

But I guess you are more than familiar with these, since they are pretty
common concepts. ;-)

>   https://gitlab.com/pikron/sw-base/pxmc/-/blob/master/libs4c/pxmc_coordmv/coordmv_base.c?ref_type=heads#L394
> 
> The new segment final vertex limiting speed and planned speed are
> set to zero.
> 
> In the second pass, the queue of segments is examined from the last
> added one and its initial planned vertex/edge speed is updated,
> increased up to the minimum of limit give by discontinuity and
> the limit to decelerate over segment to the planned final speed
> of the segment. If the start vertex limit is increased then
> the algorithm proceeds with previous segment

AFAICS, these are all motion planning tasks that should be done in user-space,
right?

>  https://gitlab.com/pikron/sw-base/pxmc/-/blob/master/libs4c/pxmc_coordmv/coordmv_base.c?ref_type=heads#L682
> 
> There are some rules and trick to do that long free in the respect
> to the IRQ executor etc...
> 
> Then the actual execution at the sampling frequency advances
> the normalized parameter going through segment from 0 to 2^32
> in 2^32 modulo arithmetic. The increase is limited by smallest
> maximal speed of the axes recomputed over distance to parameter
> change and maximal allowed accelerations recomputed to the parameter
> change. Then the final speed is limited by to final deceleration
> to the end of the segment the pxmc_coordmv_upda() in
> 
>   https://gitlab.com/pikron/sw-base/pxmc/-/blob/master/libs4c/pxmc_coordmv/coordmv_base.c?ref_type=heads#L351

AFAICS, this is probably better done in the controller itself, right?

The most complex math I feel comfortable doing in kernel space is converting a
distance-based motion given a trapezoidal acceleration profile (whith its
limiting factors tvmin and tvmax, see above) into a time based motion:

https://github.com/yope/linux/blob/mainline-lmc-preparation/drivers/motion/motion-helpers.c#L515

This is a helper function for drivers that want to use the internal time-based
ramp generator.

>[...]
> > Another idea that has been floating in my head is to make a "virtual"
> > motion device driver that combines individual "real" single-channel
> > hardware drivers into one multi-channel device, but I am unsure whether it
> > is really needed. It all depends on the latency limit differences between
> > kernel-space and user-space whether there is something to gain.  
> 
> In the fact this is the similar idea programmed and in use 25 years
> already. All computation is in 32-bit units specific for the each axis
> and only in fixed arithmetic. Some problem was fast 64-bit root square
> at that time.  All has been computed on 21 MHz CPU with 16-bit bus with
> no caches with instrauctions taking from 2 to many cycles. It was capable
> to do that for all eight axes plus some other control tasks as flashing
> lights at specific positions for example for gems inspections by camera
> connected to PC and then cotrolling their sorting to the right pocket by air
> streams by MARS 8 control unit when it advanced to given location etc.
> So some parts of the code has been rewritten to assembly. But today,
> even on not so fast LPC4088 it can do this and D-Q PMSM motors
> control without need of assembly optimizations.

I think that if we support different kinds of profiles on N-dimensions with
support for spline parameters if the hardware supports it, we could solve for
any use-case without much complexity in the kernel.

> > I think it is best to keep this initial version more limited in scope
> > though, as long as the needed extensions are possible in the future without
> > breaking existing UAPI.  
> 
> Yes, but I would be happy if the API is designed such way, that
> it is not obstacle when it would be extended and I have idea
> what would be such further goal for these applications
> I have already solved and running for decades at industry
> level.

That's great. I am confident that with your help, we can make this API as
universally usable as possible, while still keeping it simple and generic.

> > So I propose: Let's craft a draft UAPI (in a different place, not on LKML)
> > that can do everything we can come up with and then reduce it to the basics
> > for the first version. Otherwise it will get too complex to review, I'm
> > afraid.  
> 
> Yes, I agree.
> 
> To have some idea of the command set of our system, there is documentation
> in English for our older system which was capable to control three
> axes by 8-bit 80552
> 
>    http://cmp.felk.cvut.cz/~pisa/mars/mars_man_en.pdf

This API looks pretty straight-forward, and should be easy to implement with
LMC. Controller specific settings in LMC are set using a sysfs attributes
interface. An example of the settings for the TMC5240:

https://github.com/yope/linux/blob/mainline-lmc-preparation/drivers/motion/tmc5240.c#L311

> > > At this moment I have interrest if there is site which
> > > would start to collect these ideas and where can be
> > > some references added.  
> >
> > I may put this on github and create a wiki there if you think that's a good
> > enough place to discuss?  
> 
> If there is no feedback with better place to my initial
> list of options, I am OK with project group on GitHub
> where the initial project will be located with Wiki
> and issue tracker to start the communication
> and I would be happy to participate (as my time, teaching,
> projects allows).

Sounds good. Let's see if we can get some attention from OSADL or Linux
Foundation. If you have some contacts there, I'd be great if you could help
get something set up. If not, we just use github or maybe even gitlab for now.

> > > I think that I have quite some stuff to offer.  
> >
> > That would be great! Looking forward to it :-)
> >  
> > > To have idea about my direction of thinking and needs
> > > of interface I would provide some references even
> > > to our often commercially sold but mostly conceived
> > > as hobby projects.  
> >
> > I'll have to take some time to look into those more closely. My own
> > experience as far as FOSS or OSHW concerns includes the reprap Kamaq
> > project:
> >
> > https://reprap.org/wiki/Kamaq  
> 
> OK, nice target but I would like to support 5 D CNCs with
> precise machining, haptic human machine systems etc...

Sure!

> with DC, stepper and PMSM motors with vector control
> high resolution positional feedback etc. We control for
> example up to 30 kg spherical lenses positioning in
> the interferometric system with precision of micro fractions.
> The system allows inspection which thanks to multiple
> angles reaches lens surface reconstruction at level of
> nanometres 
> 
>   https://toptec.eu/export/sites/toptec/.content/projects/finished/measuring-instrument.pdf
> 
> We use optical linear sensors combined with 10k per revolution
> incremental sensors on the cheap stepper motor actuators and
> precise mechanics.. and more tricks... And I can see use
> of some cheap linux board, i.e. Zynq, Beagle-V Fire,
> which I have on my table, there in future...

Yes, this sounds really awesome. It sounds like a great challenge for getting
LMC into a good enough shape for that sort of applications. It is exactly what
I had in mind.

>[...]
> As I referenced above, the spines are interpreted at sampling frequency
> all parameters are represented as 32-bit signed numbers etc...
> So no conversion to the straight segments. The precise postions
> are recomputed with even high resolution over IKT, then some
> intervals of these points are interpolated by spline segments
> with controlled error and these segments are send to the unit
> to keep command FIFO full but not overflow it. Unit reports
> how much space is left...
> 
> > LMC will try to limit math operations in kernel space as much as possible,
> > so hopefully all the calculations can be done in user-space (or on the
> > controller if that is the case).  
> 
> All computation is fixed point only so no problem for the kernel
> even for interrupt. But yes, on fully preemptive kernel where
> user space task can be guaranteed to achieve 5 kHz sampling even
> on cheaper ARM hardware, the interface to the kernel can be
> only on D-Q PWM command and actual IRC and currents readback.
> 
> But if you have API for more intelligent controllers then there
> s no problem to put there "SoftMAC" to represent dumb ones the
> same way to userspace.

That's exactly what I thought of. Thanks for the analogy, I am going to
shamelessly steal it from you if you don't mind ;-)

That's also why I included 2 different drivers as example for LMC: One that
does all the fast computations in hardware, and one that uses a "SoftMAC", in
motion-helpers.c to generate time-based speed ramps from acceleration profiles.

But I think we should limit the "SoftMAC" device capabilities to basic
trapezoidal motion profiles, since it is not the main purpose of LMC to
convert the Linux kernel into a high-resolution, hard-RT motion-planning
engine... even if it is a tempting technical challenge to do so ;-)

> > Right now, my way of thinking was that of regular 3D printers which usually
> > only implement G0/G1 G-codes (linear interpolation). G2/G3 (circular
> > interpolation) doesn't sound practically very useful since it is special
> > but not very flexible. Something like generalized spline interpolation
> > sounds more valuable, but I hadn't seen any hardware that can do it.
> >  
> > > The related python application is there
> > >
> > >   https://github.com/cvut/pyrocon
> > >
> > > In the far future, I can imagine that it can connect
> > > to proposed LMC API and achieve the same results.  
> >
> > Let's make it so!
> >  
> > >[...]
> > > which uses our PXMC motion control library
> > >
> > >   https://gitlab.com/pikron/sw-base/pxmc
> > >
> > > There is basic documentation for it on its site
> > >
> > >   https://pxmc.org/
> > >   https://pxmc.org/files/pxmc.pdf  
> >
> > At first glance, this looks like a piece of hardware that would fit as a
> > LMC device. What needs to be determined is where the boundaries lie between
> > controller firmware, kernel-space and user-space code.  
> 
> I propose to have that boundary fully configurable.
> So all can be implemented by software emulation
> in the kernel if the sampling is under 5 or 10 kHz.
> The interface from GNU/Linux system to hardware
> is set PWM A, B, C, read actual IRC and currents.

5-10kHz in the kernel is quite demanding already, although I agree that it is
possible with many modern SoC's. The question is whether we really want to
go that far. It is starting to get to levels of stress where really a small
microcontroller of FPGA would be more adequate, don't you agree?

And also, for what purpose do you want to read currents in real-time in the
kernel? Isn't that something for closed-loop control inside a uC or FPGA?
Or do you mean just to report to user-space as a filtered average?
IRC (encoder feedback) could be implemented with timers that support
quadrature decoding, and I can certainly envision reading them out in the
kernel in order to have a simple PID controller adjust duty-cycle setpoint to
match a motion profile at a lower sample rate (1kHz or lower), but isn't that
more something for the controller hardware to do? Especially if done at even
higher sample-rates?
 
> Or some part can be moved to external controller
> or FPGA with coprocessor (the commutation fits
> in 2 kB of RISC-V C programmed firmware). 
> I.e. 20  kHz or even faster Park, Clarke
> transformations. In this case 4 to 10 kHz
> command port would be D-Q PWM or current set points
> and back IRC position, D-Q currents.
> 
> Or your proposed LMC interface can be delivered
> allmost directly to more complex controller
> which would realize whole segments processing.

I think the latter is more suitable for Linux.

Although, given the fact that many embedded Linux SoC's nowadays incorporate
small microcontroller cores that support the linux remoteproc interface, maybe
some drivers could make use of that for the hard-RT part. On a STM32MP15x SoC
for example there are advanced timers and ADC's that are very well suited for
motor-control applications. They can be used directly from Linux for
not-so-hard-and-fast RT applications, but potentially also for microsecond
work in the M4 core.
Let's first focus on the UAPI, and make the interface able to deal with these
kind of engines.

> > Generally speaking, as a rough guideline, microsecond work is better done
> > in the controller firmware if possible. millisecond work can be done in the
> > kernel and 10's or more millisecond work can be done in user-space,
> > notwithstanding latency limit requirements of course.  
> 
> OK, I agree, the RT_PREEMPT is requiremet and no broken
> SMI on x86 HW. 1 kHz is enough for DC motors controller
> robots to go all on Linux. 5 kHz for PMSM D-Q can be
> done in kernel or even userspace with platform
> suitable for PREEMPT_RT if without some issues.
> 
> Above 10 kHz should go to FPGA or external HW.

Yes, I agree. Although I'd lower the limits a bit to not make the drivers too
dependent on very specific hardware platforms.

> > >[...]
> > > So in general, I think that we have large portfolio
> > > of building blocks which would allow to build motion,
> > > robotic controllers, communications etc. and I would be happy
> > > if they are reused and even some project conceived
> > > together with others to join the forces.  
> >
> > This sounds very interesting. Ideally one would end up with LMC capable of
> > interfacing all of those devices.  
> 
> Yes.

Good. Let's do it ;-)
 
Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings
  2025-02-28 15:18           ` Uwe Kleine-König
@ 2025-03-03 10:53             ` Maud Spierings
  2025-03-03 11:40             ` David Jander
  1 sibling, 0 replies; 59+ messages in thread
From: Maud Spierings @ 2025-03-03 10:53 UTC (permalink / raw)
  To: Uwe Kleine-König, David Jander
  Cc: Krzysztof Kozlowski, linux-kernel, linux-iio, Jonathan Corbet,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, devicetree,
	linux-doc, Nuno Sa, Jonathan Cameron, Oleksij Rempel, linux-pwm


On 2/28/25 4:18 PM, Uwe Kleine-König wrote:
> Hey David,
>
> On Fri, Feb 28, 2025 at 11:09:31AM +0100, David Jander wrote:
>> On Fri, 28 Feb 2025 10:37:48 +0100
>> Krzysztof Kozlowski <krzk@kernel.org> wrote:
>>
>>> On 28/02/2025 10:22, David Jander wrote:
>>>>    
>>>>>> +
>>>>>> +  motion,pwm-inverted:
>>>>>> +    $ref: /schemas/types.yaml#/definitions/flag
>>>>> And PWM flag does not work?
>>>> I have seen PWM controllers that don't seem to support the
>>>> PWM_POLARITY_INVERTED flag and those where it just doesn't work. Should all
>>>
>>> Shouldn't the controllers be fixed? Or let's rephrase the question: why
>>> only this PWM consumer needs this property and none of others need it?
>> CCing Uwe Kleine-Koenig and linux-pwm mailing list.
>>
>> I know that at least in kernel 6.11 the pwm-stm32.c PWM driver doesn't
>> properly invert the PWM signal when specifying PWM_POLARITY_INVERTED. I agree
>> this is a probably bug that needs fixing if still present in 6.14-rc. Besides
>> that, if linux-pwm agrees that every single PWM driver _must_ properly support
>> this flag, I will drop this consumer flag an start fixing broken PWM drivers
>> that I encounter. I agree that it makes more sense this way, but I wanted to
>> be sure.
> Some hardwares cannot support PWM_POLARITY_INVERTED. Affected drivers
> include:
>
> 	pwm-adp5585
> 	pwm-ntxec
> 	pwm-raspberrypi-poe
> 	pwm-rz-mtu3 (software limitation only)
> 	pwm-sunplus
> 	pwm-twl-led (not completely sure, that one is strange)
>
> . ISTR that there is a driver that does only support inverted polarity,
> but I don't find it. For an overview I recommend reading through the
> output of:


The only one that I know of is the opencores pwm driver that the 
starfive jh71xx uses, I remember talking with you there. That one does 
still need a proper review I believe:
https://lore.kernel.org/all/20250106103540.10079-1-william.qiu@starfivetech.com/

It is kind of in a limbo right now


>
> 	for f in drivers/pwm/pwm-*; do
> 		echo $f;
> 		sed -rn '/Limitations:/,/\*\/?$/p' $f;
> 		echo;
> 	done | less
>
> . (Note not all drivers have commentary in the right format to unveil
> their limitations.)
>
> For most use-cases you can just do
>
> 	.duty_cycle = .period - .duty_cycle
>
> instead of inverting polarity, but there is no abstraction in the PWM
> bindings for that and also no helpers in the PWM framework. The problem
> is more or less ignored, so if you have a device with
>
> 	pwms = <&pwm0 0 PWM_POLARITY_INVERTED>;
>
> and the PWM chip in question doesn't support that, the pwm API functions
> will fail. So the system designer better makes sure that the PWM
> hardware can cope with the needed polarity.
>
> Best regards
> Uwe

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-03-03  8:36     ` David Jander
@ 2025-03-03 11:01       ` Pavel Pisa
  2025-03-03 16:04         ` David Jander
  0 siblings, 1 reply; 59+ messages in thread
From: Pavel Pisa @ 2025-03-03 11:01 UTC (permalink / raw)
  To: David Jander
  Cc: David Lechner, linux-kernel, linux-iio, Jonathan Corbet,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, devicetree,
	linux-doc, Nuno Sa, Jonathan Cameron, Oleksij Rempel,
	Carsten Emde, Jan Kiszka, Pavel Machek

Hello Davids,

On Monday 03 of March 2025 09:36:11 David Jander wrote:
> On Fri, 28 Feb 2025 16:36:41 -0600
>
> David Lechner <dlechner@baylibre.com> wrote:
> > On 2/27/25 10:28 AM, David Jander wrote:
> > > The Linux Motion Control subsystem (LMC) is a new driver subsystem for
> > > peripheral devices that control mechanical motion in some form or
> > > another. This could be different kinds of motors (stepper, DC, AC, SRM,
> > > BLDC...) or even linear actuators.
> > > The subsystem presents a unified UAPI for those devices, based on char
> > > devices with ioctl's.
> > > It can make use of regular gpio's to function as trigger inputs, like
> > > end-stops, fixed position- or motion start triggers and also generate
> > > events not only to user-space but also to the IIO subsystem in the form
> > > of IIO triggers.
> > >
> > > Signed-off-by: David Jander <david@protonic.nl>
> > > ---
> > >  MAINTAINERS                     |   8 +
> > >  drivers/Kconfig                 |   2 +
> > >  drivers/Makefile                |   2 +
> > >  drivers/motion/Kconfig          |  19 +
> > >  drivers/motion/Makefile         |   3 +
> > >  drivers/motion/motion-core.c    | 823 ++++++++++++++++++++++++++++++++
> > >  drivers/motion/motion-core.h    | 172 +++++++
> > >  drivers/motion/motion-helpers.c | 590 +++++++++++++++++++++++
> > >  drivers/motion/motion-helpers.h |  23 +
> > >  include/uapi/linux/motion.h     | 229 +++++++++
> > >  10 files changed, 1871 insertions(+)
> >
> > Ooof, this is really a lot for one patch. Makes it hard to review. 500
> > lines in a patch is much easier to digest.
>
> Sorry for that. I wouldn't know how to split up this patch to make it any
> easier. It's just a complete new subsystem, and I think it is the bare
> minimum to start and also to give a good idea of what it is supposed to be
> able to do.
>
> > But before commenting on the details of the code I have some more
> > high-level comments. As I mentioned in my reply to the cover letter, I've
> > gone through the exercise of writing some motor control divers in the
> > Linux kernel that have been used by 1000s of people that used them to
> > build everything imaginable using LEGO robotics over the last 10+ years.
> >
> > From what I see here (I didn't have time to really get into the details
> > of it yet, so maybe missed some important details), it looks like you are
> > trying to do motor control stuff in the kernel so that the interface for
> > a basic H-bridge will be close to the same as a fancy stepper motor
> > controller. We tried doing something very similar because it sounds like
> > a really nice thing to do. The kernel does everything and makes it really
> > easy for the users. But what we actually found is that it is not possible
> > to make a solution in the kernel that can handle every possible use case.
> > In the end, we wished that we had a much more low-level interface to the
> > motor controllers to give us more flexibility for the many different
> > types of applications this ended up getting used for. Having to modify
> > the kernel for your use case is too high of a bar for most users and not
> > practical even if you are a kernel hacker.
>
> The idea for LMC is to be able to support hardware that realistically can
> be used by an OS as complex as the Linux kernel. There are a lot of motor
> controllers out there that suit that category, like the TMC5240 chip for
> example. But also many bigger systems, like the ones Pavel Pisa works with.
> That said, I think the Linux kernel on modestly modern SoC's, like the
> STM32MP1xx is pretty capable of doing more than that, but we have to draw
> the line somewhere. Like I hinted in the cover letter, I think it might
> even be possible to do crazy stuff like bit-banging STEP/DIR type
> controllers in the kernel, possibly aided by PREEMPT_RT, but that is not
> the main purpose of LMC.

I look even to take into account these options for the hobbyist projects.
But stepper motors drivers step, dir interface is really demanding
case. With microstepping it can require pulse control with frequency
100 kHz or even MHz and corresponding jitter demand. So that is really
not area for PREEMPT_RT in userspace nor kernel space.

On the other hand, I can imagine that some SoftMAC like controller
for Raspberry Pi 1 to 4 to combine its specific DMA and GPIO
capabilities could be good target for some LMC like abstraction.
Doing DMA from userspace is pain for regular users, yes we use
that for Marek Peca's Zlogan https://github.com/eltvor/zlogan
and other projects, but that is not for users which I see
between our studnets to attempt to stepper motors by step, dir
from RPi without previous RT knowledge. The question is if the
API to RPi and its DMA should be covered by kernel LMC
or some more generic DMA interface.

I have found some links for students working on the
project (it is project led by my colleagues not mine,

  https://github.com/hzeller/rpi-gpio-dma-demo

  https://github.com/innot/AdvPiStepper

  https://github.com/richardghirst/PiBits/tree/master/ServoBlaster

I would be happy for pointers for alive and newwer project
if somebody has some more links for these kind of users.

I prefer other approaches myself, i.e. small RTOS based
solution with background and IRQ tasks and D/Q control
where the risk to lose step is much smaller, because you
control at sin, cos level, so you have more time at high
speeds where current control is not realized on these MHz
periods required by dumb step, dir driver with microstepping.
Se my previously reported project SaMoCon project for
idea. It has four outputs per each axis and can drive
PMSM, DC, stepper etc... 

  https://gitlab.fel.cvut.cz/otrees/motion/samocon

The PID or even D-Q DC, PMSM and may it be stepper
motors at something like 5 kHz is achievable
in userspace or kernel RT_REEMPT therad. May it be
even with commutation for stepper, but 20 kHz
is probably only for kernel and not for professional
use according to my taste. If the commutation
is pushed even to small FPGA, then some interface
as NuttX FOC

  https://nuttx.apache.org/docs/12.1.0/components/drivers/character/foc.html

is good match and yes, proposed LMC pushes much more
complexity into the kernel. 

But for these people who want to stuck on step, dir
because it is like that should be done in 3D printers
and other hobbits world could profit a lot from
some segments list controlled motion and I can image
to combine it with that RPi or some simple FPGA
block on Zynq, Beagle or iCE40 connected to SPI.

So I see value of some unification under LMC  

> The main purpose is to talk to controllers that 
> can receive motion profiles and execute movements (semi-)autonomously.
> Going just one step lower is the simple PWM based driver in this patch set:
> It takes the execution of the profile into the kernel by using a HRTIMER to
> sample the profile curve using a sample period of 20ms, which is fast
> enough for most applications while not imposing a high CPU load on the
> kernel on slower CPU cores.
> motion-helper.c contains the trapezoidal ramp generator code that can be
> used by any LMC driver that can work with speed information but doesn't
> have its own ramp generator in hardware. It could be extended to support
> other type of profiles if needed in the future, which would automatically
> upgrade all drivers that use it.

I agree, but on the other hand, the optimal combination of HW and matching 
upper abstraction level is extremely variable, and finding a good API for 
LMC, which would not be a root to stumble upon in the future, is a really 
demanding task. On the other hand, if some, even suboptimal, solution is 
available in staging drivers kernel area without guarantee of having fixed 
API forever, then it can evolve slowly to something valuable. There would be 
incompatible changes, but the transition can be smooth. 

So may it be some COMEDI like approach. And there should be matching
userspace library which could choose between APIs at different level
of abstraction according to the target HW and some these APIs can
be emulated by SoftMAC approach in the kernel. Usually for there
more hobbits like solutions.

I would personally tend to something like our PXMC at these API
level but I am predetermined/skewed as author and its 25 years
use and connection to older assembly API with more than 30 years
history.

But I hope I am critical enough to be able to say what is problematic
on our design and what can be designed better today. I.e. there
is compromise to keep all positions 32 bits, sometimes even
reduced to allows IRC sensors position subdivision on ramps
generators side, some there is often range reduced to +/-2^23
bits. On the other hand, all is computed in modulo arithmetic,
so there is no problem to control speed for infinite time...
For very precise and slow syringe piston control in infusion
systems, we have used 32 bits position where 8 bits have been
fractions and in generators another short extended fractions
to 24 bits. It has been able to run with this precision
even on 16-bit MSP430. But if that is ported and used in our
solutions on 32-bit ARMs or even 64-bit chips like PoalFire,
then it loses purpose... So it would worth to reinvent/redefine
APIs...

But I would tend to this userspace lib and multiple API levels
approach... 

> > When writing kernel drivers for this sort of thing, I think the rule of
> > thumb should be to keep the driver as "thin" as possible. If the hardware
> > doesn't provide a feature, the kernel should not be trying to emulate it.
>
> In general I would agree with this, but in this case some limited
> "emulation" seems adequate. As a rule of thumb, code is better placed in an
> FPGA/uC, the kernel or in user-space according to its latency requirements.
> Microsecond stuff shouldn't be done on the application SoC at all,

Sure

> millisecond stuff (or maybe 100s of microseconds if you like) can be done
> in the kernel, 10s of milliseconds or slower is good for user-space. A very
> general guideline.

I would be open to higher frequencies in userspace with PREEMPT_RT
on Zynq, iMX6,7,8,9 or AM3,4,... industrial targetting hardware.
We have run complex Simulik generated models on x86 at 30 kHz
many years ago without missing code. But with our Simulink RT
target https://github.com/aa4cc/ert_linux not with Mathwork's
offer. But even serious, rich company came to us to solve their
problems on RPi with CAN controller on SPI with sticking
on Mathwork's delivered Windows supported target and it has been
problem

https://dspace.cvut.cz/bitstream/handle/10467/68605/F3-DP-2017-Prudek-Martin-Dp_2017_prudek_martin.pdf

So if we speak about enthusiasts with common x86 without
SMI interrupt checking before buying the motherboard or even
attempting to use laptops or sticking on Raspberry Pi where
some versions have used FIQ to solve HW deficiencies, then
I would agree to stay even with PREEMP_RT on safe side
i.e. under 1 kHz... 

> So if you have a device that can take a speed-setpoint but doesn't have a
> ramp generator, that is not a device that LMC is made for in the first
> place, but still pretty usable if we do the ramp generator in the kernel.
> To steal Pavel's analogy: Think of the TMC5240 driver as a FullMAC Wifi
> device and the simple PWM driver as a SoftMAC Wifi device.
> For an LMC device, same as for a wifi interface, we want to talk TCP/IP to
> it from user-space, not radio-packets. ;-)

Somebody mentioned to me ASICy Nova MCX314 or NPM PCD4541
as reaction to my discussion, I am not sure about their API,
but may it be some segmented API with fast, guaranteed,
IRQ driven switch/preparation of next segment would support
for LMC API.

> > So for an
> > H-bridge I would want something that just provides a way to tell it I
> > want fast-decay mode with some normalized duty cycle between -1 and 1
> > (obviously we will have to multiply this by some factor since the kernel
> > doesn't do floating point). A duty cycle of 0 will "brake" the motor. And
> > then we would need one more control parameter to tell it to remove power
> > completely to "coast" the motor. I guess this is what the "basic_run" and
> > "basic_stop" are other than the run seems to have speed instead of duty
> > cycle? The kernel shouldn't be trying to convert this duty cycle to speed
> > or have a background task that tries to provide an acceleration profile
> > or turn off the power after some time. Just let the kernel provide
> > direct, low-level access to the hardware and let userspace handle all of
> > the rest in a way that makes the most sense for the specific application.
> > Sometimes they might not even be connected to a motor! With the LEGO
> > MINDSTORMS and BeableBone Blue, the H-bridge outputs are hot-pluggable,
> > so they can even be connected to things like LEDs or used as a general
> > power supply. (A reason to call this subsystem "actuation" rather than
> > "motion".)
>
> LMC aims to offer a common interface to different sorts of motion devices
> (think different types of motors), so offering access to the lowest level
> of each device is kinda defeating of that purpose. Nevertheless, all of the
> things you mention are possible with LMC. The relationship between speed
> and the PWM duty-cycle of a simple DC motor H-bridge for example, is
> determined by the speed_conv* and accel_conv* parameters. If you want a 1:1
> relation, just make them 1 in your device tree.

But you need full PID or even current D-Q multiple PI and procession,
sines, cosines for commutation etc. to connect higher level with lower
level. We have all these in fixed point and focused on processing
not only in RTOSes kernel but even in IRQs. So it can be done
in Linux kernel as we ported, demonstrated it in GNU/Linux userspace...

> OTOH, if you had only a duty-cycle setting from user-space, you would need
> to have code that generates an acceleration profile in user-space, which
> would be a much higher CPU load and have a much higher latency jitter, much
> more likely to cause mechanical and audible effects than if done in the
> kernel. It's still possible though.
> And talking about mis-using a motor driver for something else, that's
> exactly what one of our customers is doing with a DC motor H-bridge via
> LMC. They just set each output to 0% or 100% duty-cycle (max speed without
> profile) to control 2 warning lights.
>
> > Another way of putting this is that it was very tempting to model the
> > actual motor in the kernel. But that didn't work well because there are
> > so many different kinds of motors and related mechanical systems that you
> > can connect to the same motor driver chip.
>
> Yes, but on the other side, you have many different driver chips that all
> control motors that do the same thing: move in different directions with
> different speeds and different acceleration profiles. As a user, I want to
> be able to tell that to the motor in the same sense as I want to send a
> data through an ethernet interface without having to know what kind of
> interface I have to an extend reasonably possible. Of course each
> motor/driver has different limitations (just as different network
> interfaces have), and more often than not I will have to know some of those
> in user-space, but the whole idea of a subsystem UAPI is to abstract as
> much as possible of that from user-space.
>
> With LMC I could easily swap a stepper motor for a BLDC or DC motor for
> example. If they have an encoder to provide accurate position feedback, it
> could even work as well as a stepper for many applications. No changes in
> user-space code required.
>
> > So the driver really should just be for the
> > H-bridge chip itself and not care about the motor. And the rest can be
> > put in a libmotion userspace library and have that be the convenient API
> > for users that want to get something up and running quickly.
>
> I get your point, and from the standpoint of Lego hardware and hobby
> tinkerers doing all sorts of stuff with it, I can understand the desire to
> have low-level access from user-space to the H-bridge. It is similar to how
> Raspberry-pi exposes direct access to their GPIO controllers to user-space.
> It is nice for tinkerers, but it is inadequate for anything else, not to
> mention potentially unsafe. I remember when I first installed Linux on my
> PC in 1994, we had the X server access the video card directly from
> user-space. That was a really bad idea. ;-)

It is questionable, some solution where kernel is RT, allows fast delivery
of data and events between kernel and userspace memory contexts,
like IO-uring and DRI, shared memory, PRIME buffers etc. is often
better than push of all into kernel. In the fact, today lot of graphic
stack is pushed directly into applications through acceleration API
libraries which talks directly with allocated context in GPUs
and the result is combined by compositor, again in userspace.

So this is not so convicing argument. But SoftMAC and 802.11
is the case which supports push of more levels of LMC
into kernel.

Anyway, the motion control is really broad area, there are companies
with experience with Linux in their highest range of CNC machines,
laser cutters, welding robots etc... So there is lot of prior
experience. Question is, how much they are willing to share.

But preparing some common guidelines and collect information
to not reinvent wheel again and again and then proposing
some more generally reusable APIs and drivers etc. would be
great win for all and would make GNU/Linux much easier
and cheaper usable in the are in future.

So my actual vote is to find location where the already
available knowledge and projects could be collected
and where input even from PREEMP_RT and other professionals
can be obtained...

May it be somebody from LinuxCNC should step in and may it
be there are such resources collected. Linux Foundation
or similar body should be contacted to check if such
project is already there. I am adding some PREEMP_RT
experts which I am in contact with, if they have idea
about right place for motion control on Linux discussion,
coordination.

Best wishes,

                Pavel
-
                Pavel Pisa

    phone:      +420 603531357
    e-mail:     pisa@cmp.felk.cvut.cz
    Department of Control Engineering FEE CVUT
    Karlovo namesti 13, 121 35, Prague 2
    university: http://control.fel.cvut.cz/
    personal:   http://cmp.felk.cvut.cz/~pisa
    company:    https://pikron.com/ PiKRON s.r.o.
    Kankovskeho 1235, 182 00 Praha 8, Czech Republic
    projects:   https://www.openhub.net/accounts/ppisa
    social:     https://social.kernel.org/ppisa
    CAN related:http://canbus.pages.fel.cvut.cz/
    RISC-V education: https://comparch.edu.cvut.cz/
    Open Technologies Research Education and Exchange Services
    https://gitlab.fel.cvut.cz/otrees/org/-/wikis/home

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 6/7] dt-bindings: motion: Add adi,tmc5240 bindings
  2025-02-28 22:38   ` David Lechner
@ 2025-03-03 11:22     ` David Jander
  2025-03-03 12:28       ` David Lechner
  0 siblings, 1 reply; 59+ messages in thread
From: David Jander @ 2025-03-03 11:22 UTC (permalink / raw)
  To: David Lechner
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel


Dear David,

On Fri, 28 Feb 2025 16:38:51 -0600
David Lechner <dlechner@baylibre.com> wrote:

> On 2/27/25 10:28 AM, David Jander wrote:
> > Add device-tree bindings for Analog Devices TMC5240 stepper controllers.
> > 
> > Signed-off-by: David Jander <david@protonic.nl>
> > ---
> >  .../bindings/motion/adi,tmc5240.yaml          | 60 +++++++++++++++++++
> >  1 file changed, 60 insertions(+)
> >  create mode 100644 Documentation/devicetree/bindings/motion/adi,tmc5240.yaml
> > 
> > diff --git a/Documentation/devicetree/bindings/motion/adi,tmc5240.yaml b/Documentation/devicetree/bindings/motion/adi,tmc5240.yaml
> > new file mode 100644
> > index 000000000000..3364f9dfccb1
> > --- /dev/null
> > +++ b/Documentation/devicetree/bindings/motion/adi,tmc5240.yaml
> > @@ -0,0 +1,60 @@
> > +# SPDX-License-Identifier: (GPL-2.0 OR BSD-2-Clause)
> > +%YAML 1.2
> > +---
> > +$id: http://devicetree.org/schemas/motion/adi,tmc5240.yaml#
> > +$schema: http://devicetree.org/meta-schemas/core.yaml#
> > +
> > +title: Analog Devices TMC5240 Stepper Motor controller
> > +
> > +maintainers:
> > +  - David Jander <david@protonic>
> > +
> > +description: |
> > +   Stepper motor controller with motion engine and SPI interface.  
> 
> Please include a link to the datasheet.

Will do.

> > +
> > +properties:
> > +  compatible:
> > +    enum:
> > +      - adi,tmc5240
> > +
> > +  reg:
> > +    maxItems: 1
> > +
> > +  interrupts:
> > +    maxItems: 1  
> 
> I assume that this is the overvoltage output (OV pin). Would be nice to have
> a description here saying that. There are also NAO and DIAG0/1 output pins, so
> it's a bit ambiguous otherwise.

This is the DIAG0 output pin which on this chip has a dual function as either
a STEP output or an interrupt output. The pin name is a bit misleading, but it
is the "interrupt" function that is meant here. The datasheet documents all
the different events that can trigger this interrupt.
I will add a description to clarify this.

> > +
> > +  enable-supply:
> > +    description: Optional external enable supply to control SLEEPn pin. Can
> > +      be shared between several controllers.
> > +  
> 
> This doesn't look like a supply, but krzk already discussed that. But there
> should be actual power supplies: vs-supply, vdd1v8-supply, vcc-io-supply. And
> a reference voltage supply: iref-supply

I have added vs-supply and vcc-io-supply to the binding. These are the only
supply pins that can be connected to the outside world or otherwise be of
concern to the software.

vdd1v8-supply is an internal power rail that must not have a connection to the
outside of the chip (besides an external filtering capacitor) and also doesn't
have any bearing to the software at all. It cannot be disabled, adjusted or
anything, so I don't think it needs to be mentioned.

IREF isn't a supply pin. It is merely a pin for connecting an external
reference resistor that is used internally for current scaling and it too has
no interaction with the software in any way.

The resistor connected to the IREF pin (Rref) OTOH does have an implication to
the software, as it sets the full-range current of the output stage.

How should we specify that? Is it adequate to add an optional DT property
"rref" or "rref-ohm" with an int32 value in Ohm? The default value if
unspecified is 12000 Ohm.

> And if there are any pins would make sense to connect to a gpio, we can add
> those even if the driver doesn't use it currently.
> 
> > +  clocks:
> > +    maxItems: 1
> > +
> > +required:
> > +  - compatible
> > +  - reg
> > +  - interrupts
> > +  - clocks
> > +
> > +allOf:
> > +  - $ref: /schemas/spi/spi-peripheral-props.yaml#
> > +  - $ref: /schemas/motion/common.yaml#  
> 
> If we need to know about what is connected to the output of a motor controller
> I would expect it to be done with child node for each output. That way each
> output can be unique, if needed. Basically, similar to iio/adc.yaml is used to
> provide common properties for channel@ child nodes on iio devices.

This controller chip only has one single output for one stepper motor (4
wires). While technically you could connect something else to those 4 wires, I
don't think it is the scope of LMC to support that. The chip itself isn't
designed for that purpose and it would clearly go far beyond the intended
purpose of this device.

That being said, your suggestion of supporting child nodes may actually be a
good idea. Right now, we specify the type of motor (basically nominal- and hold
current settings) in user-space and set the IRUN/IHOLD parameters from
user-space via the sysfs attributes interface. It might make sense to have a DT
child node to specify this, although in our current application this is not
very practical, since there are many motor controllers on one board, and it is
configurable in software (runtime) which motor is connected to which output.

But I can imagine a situation where it may be fixed and thus can be described
in the DT of a board.

Then again I don't know if it would be over-complicating things with something
like this:

	motor-controller@0 {
		...
		motor@0 {
			compatible = "nanotec,st4118s1006";
			irun-ma = <1800>;
			ihold-ma = <270>;
		};
	};

where we'd possibly have a stepper-motors.c file with a lot of structs and
matching tables for the different motor types.... sounds like overkill to me,
but maybe not?

> > +
> > +unevaluatedProperties: false
> > +
> > +examples:
> > +  - |
> > +    spi {
> > +        #address-cells = <1>;
> > +        #size-cells = <0>;
> > +
> > +        motor@0 {  
> 
> motor-controller@ or actuator-controller@
> 
> The chip is the controller/driver, it is not a motor.

Make sense. Will change this.

> > +            compatible = "adi,tmc5240";
> > +            reg = <0>;
> > +            interrupts-extended = <&gpiok 7 0>;
> > +            clocks = <&clock_tmc5240>;
> > +            enable-supply = <&stpsleepn>;
> > +            spi-max-frequency = <1000000>;
> > +        };
> > +    };

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings
  2025-02-28 15:18           ` Uwe Kleine-König
  2025-03-03 10:53             ` Maud Spierings
@ 2025-03-03 11:40             ` David Jander
  2025-03-03 14:18               ` Krzysztof Kozlowski
  1 sibling, 1 reply; 59+ messages in thread
From: David Jander @ 2025-03-03 11:40 UTC (permalink / raw)
  To: Uwe Kleine-König
  Cc: Krzysztof Kozlowski, linux-kernel, linux-iio, Jonathan Corbet,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, devicetree,
	linux-doc, Nuno Sa, Jonathan Cameron, Oleksij Rempel, linux-pwm


Dear Uwe,

Thanks for chiming in!

On Fri, 28 Feb 2025 16:18:05 +0100
Uwe Kleine-König <ukleinek@kernel.org> wrote:

> Hey David,
> 
> On Fri, Feb 28, 2025 at 11:09:31AM +0100, David Jander wrote:
> > On Fri, 28 Feb 2025 10:37:48 +0100
> > Krzysztof Kozlowski <krzk@kernel.org> wrote:
> >   
> > > On 28/02/2025 10:22, David Jander wrote:  
> > > >     
> > > >>> +
> > > >>> +  motion,pwm-inverted:
> > > >>> +    $ref: /schemas/types.yaml#/definitions/flag      
> > > >>
> > > >> And PWM flag does not work?    
> > > > 
> > > > I have seen PWM controllers that don't seem to support the
> > > > PWM_POLARITY_INVERTED flag and those where it just doesn't work. Should all    
> > > 
> > > 
> > > Shouldn't the controllers be fixed? Or let's rephrase the question: why
> > > only this PWM consumer needs this property and none of others need it?  
> > 
> > CCing Uwe Kleine-Koenig and linux-pwm mailing list.
> > 
> > I know that at least in kernel 6.11 the pwm-stm32.c PWM driver doesn't
> > properly invert the PWM signal when specifying PWM_POLARITY_INVERTED. I agree
> > this is a probably bug that needs fixing if still present in 6.14-rc. Besides
> > that, if linux-pwm agrees that every single PWM driver _must_ properly support
> > this flag, I will drop this consumer flag an start fixing broken PWM drivers
> > that I encounter. I agree that it makes more sense this way, but I wanted to
> > be sure.  
> 
> Some hardwares cannot support PWM_POLARITY_INVERTED. Affected drivers
> include:
> 
> 	pwm-adp5585
> 	pwm-ntxec
> 	pwm-raspberrypi-poe
> 	pwm-rz-mtu3 (software limitation only)
> 	pwm-sunplus
> 	pwm-twl-led (not completely sure, that one is strange)
> 
> . ISTR that there is a driver that does only support inverted polarity,
> but I don't find it. For an overview I recommend reading through the
> output of:
> 
> 	for f in drivers/pwm/pwm-*; do
> 		echo $f;
> 		sed -rn '/Limitations:/,/\*\/?$/p' $f;
> 		echo;
> 	done | less
> 
> . (Note not all drivers have commentary in the right format to unveil
> their limitations.)
> 
> For most use-cases you can just do
> 
> 	.duty_cycle = .period - .duty_cycle

Yes, that is exactly what the relevant code in motion/simple-pwm.c does when
the "pwm-inverted" flag is present in the DT node.

> instead of inverting polarity, but there is no abstraction in the PWM
> bindings for that and also no helpers in the PWM framework. The problem
> is more or less ignored, so if you have a device with
> 
> 	pwms = <&pwm0 0 PWM_POLARITY_INVERTED>;
> 
> and the PWM chip in question doesn't support that, the pwm API functions
> will fail. So the system designer better makes sure that the PWM
> hardware can cope with the needed polarity.

Thanks for clarifying this!

@Krzysztof, do you think that given this situation it is acceptable to include
the "pwm-inverted" flag in the dt-schema of the simple PWM motor driver?

The need for an inverted PWM signal is something very common in the case of
H-bridge motor drivers, where the PWM signal represents the actual logical
output level of each of the two halves of the bridge. Often the high-side
switches are used as the free-wheel position, so that 100% duty-cycle on both
channels is actually standstill, while 0% duty-cycle on one channel is full
speed in either direction. This isn't always the case though, hence the
importance for this to be able to be selected.

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 6/7] dt-bindings: motion: Add adi,tmc5240 bindings
  2025-03-03 11:22     ` David Jander
@ 2025-03-03 12:28       ` David Lechner
  2025-03-03 13:18         ` David Jander
  0 siblings, 1 reply; 59+ messages in thread
From: David Lechner @ 2025-03-03 12:28 UTC (permalink / raw)
  To: David Jander
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel

(Sorry if you get this twice. I don't have my regular computer today
and didn't realize I was sending HTML the first time. Resending in
plain text so the lists pick it up.)

On Mon, Mar 3, 2025 at 12:22 PM David Jander <david@protonic.nl> wrote:
>
>
> Dear David,
>
> On Fri, 28 Feb 2025 16:38:51 -0600
> David Lechner <dlechner@baylibre.com> wrote:
>
> > On 2/27/25 10:28 AM, David Jander wrote:
> > > Add device-tree bindings for Analog Devices TMC5240 stepper controllers.
> > >
> > > Signed-off-by: David Jander <david@protonic.nl>
> > > ---
> > >  .../bindings/motion/adi,tmc5240.yaml          | 60 +++++++++++++++++++
> > >  1 file changed, 60 insertions(+)
> > >  create mode 100644 Documentation/devicetree/bindings/motion/adi,tmc5240.yaml
> > >
> > > diff --git a/Documentation/devicetree/bindings/motion/adi,tmc5240.yaml b/Documentation/devicetree/bindings/motion/adi,tmc5240.yaml
> > > new file mode 100644
> > > index 000000000000..3364f9dfccb1
> > > --- /dev/null
> > > +++ b/Documentation/devicetree/bindings/motion/adi,tmc5240.yaml
> > > @@ -0,0 +1,60 @@
> > > +# SPDX-License-Identifier: (GPL-2.0 OR BSD-2-Clause)
> > > +%YAML 1.2
> > > +---
> > > +$id: http://devicetree.org/schemas/motion/adi,tmc5240.yaml#
> > > +$schema: http://devicetree.org/meta-schemas/core.yaml#
> > > +
> > > +title: Analog Devices TMC5240 Stepper Motor controller
> > > +
> > > +maintainers:
> > > +  - David Jander <david@protonic>
> > > +
> > > +description: |
> > > +   Stepper motor controller with motion engine and SPI interface.
> >
> > Please include a link to the datasheet.
>
> Will do.
>
> > > +
> > > +properties:
> > > +  compatible:
> > > +    enum:
> > > +      - adi,tmc5240
> > > +
> > > +  reg:
> > > +    maxItems: 1
> > > +
> > > +  interrupts:
> > > +    maxItems: 1
> >
> > I assume that this is the overvoltage output (OV pin). Would be nice to have
> > a description here saying that. There are also NAO and DIAG0/1 output pins, so
> > it's a bit ambiguous otherwise.
>
> This is the DIAG0 output pin which on this chip has a dual function as either
> a STEP output or an interrupt output. The pin name is a bit misleading, but it
> is the "interrupt" function that is meant here. The datasheet documents all
> the different events that can trigger this interrupt.
> I will add a description to clarify this.
>

If it makes sense that other pins could possibly ever be connected to
interrupts then we can add those and also add interrupt-names (but
only if there is more than one possible interrupt).

> > > +
> > > +  enable-supply:
> > > +    description: Optional external enable supply to control SLEEPn pin. Can
> > > +      be shared between several controllers.
> > > +
> >
> > This doesn't look like a supply, but krzk already discussed that. But there
> > should be actual power supplies: vs-supply, vdd1v8-supply, vcc-io-supply. And
> > a reference voltage supply: iref-supply
>
> I have added vs-supply and vcc-io-supply to the binding. These are the only
> supply pins that can be connected to the outside world or otherwise be of
> concern to the software.
>
> vdd1v8-supply is an internal power rail that must not have a connection to the
> outside of the chip (besides an external filtering capacitor) and also doesn't
> have any bearing to the software at all. It cannot be disabled, adjusted or
> anything, so I don't think it needs to be mentioned.
>
> IREF isn't a supply pin. It is merely a pin for connecting an external
> reference resistor that is used internally for current scaling and it too has
> no interaction with the software in any way.
>

Ah, I read the datasheet too quickly.

> The resistor connected to the IREF pin (Rref) OTOH does have an implication to
> the software, as it sets the full-range current of the output stage.
>
> How should we specify that? Is it adequate to add an optional DT property
> "rref" or "rref-ohm" with an int32 value in Ohm? The default value if
> unspecified is 12000 Ohm.

It looks like there are a few standardized properties, like
sense-resistor-ohms if that fits the use case. Otherwise, an
vendor-specific ti,rref-ohms would work. FYI, you can find the
preferred units at [1].

[1]: https://github.com/devicetree-org/dt-schema/blob/main/dtschema/schemas/property-units.yaml

>
> > And if there are any pins would make sense to connect to a gpio, we can add
> > those even if the driver doesn't use it currently.
> >
> > > +  clocks:
> > > +    maxItems: 1
> > > +
> > > +required:
> > > +  - compatible
> > > +  - reg
> > > +  - interrupts
> > > +  - clocks
> > > +
> > > +allOf:
> > > +  - $ref: /schemas/spi/spi-peripheral-props.yaml#
> > > +  - $ref: /schemas/motion/common.yaml#
> >
> > If we need to know about what is connected to the output of a motor controller
> > I would expect it to be done with child node for each output. That way each
> > output can be unique, if needed. Basically, similar to iio/adc.yaml is used to
> > provide common properties for channel@ child nodes on iio devices.
>
> This controller chip only has one single output for one stepper motor (4
> wires). While technically you could connect something else to those 4 wires, I
> don't think it is the scope of LMC to support that. The chip itself isn't
> designed for that purpose and it would clearly go far beyond the intended
> purpose of this device.
>
> That being said, your suggestion of supporting child nodes may actually be a
> good idea. Right now, we specify the type of motor (basically nominal- and hold
> current settings) in user-space and set the IRUN/IHOLD parameters from
> user-space via the sysfs attributes interface. It might make sense to have a DT
> child node to specify this, although in our current application this is not
> very practical, since there are many motor controllers on one board, and it is
> configurable in software (runtime) which motor is connected to which output.
>
> But I can imagine a situation where it may be fixed and thus can be described
> in the DT of a board.
>
> Then again I don't know if it would be over-complicating things with something
> like this:
>
>         motor-controller@0 {
>                 ...
>                 motor@0 {
>                         compatible = "nanotec,st4118s1006";
>                         irun-ma = <1800>;
>                         ihold-ma = <270>;
>                 };
>         };
>
> where we'd possibly have a stepper-motors.c file with a lot of structs and
> matching tables for the different motor types.... sounds like overkill to me,
> but maybe not?

A compatible for motors seems too much. I was just thinking along the
lines that 1) if we need to so some scaling or something that depends
on a motor constant, then it would make sense to put those constants
in the DT and 2) if there is a motor controller with more than one
output that could be connected to two or more different sizes of
motors with different constants, then we either need child nodes or an
array to be able to enter the different constants. Either one would
work. So maybe simpler to just use an array instead of child nodes now
that I'm thinking about it more.

>
> > > +
> > > +unevaluatedProperties: false
> > > +
> > > +examples:
> > > +  - |
> > > +    spi {
> > > +        #address-cells = <1>;
> > > +        #size-cells = <0>;
> > > +
> > > +        motor@0 {
> >
> > motor-controller@ or actuator-controller@
> >
> > The chip is the controller/driver, it is not a motor.
>
> Make sense. Will change this.
>
> > > +            compatible = "adi,tmc5240";
> > > +            reg = <0>;
> > > +            interrupts-extended = <&gpiok 7 0>;
> > > +            clocks = <&clock_tmc5240>;
> > > +            enable-supply = <&stpsleepn>;
> > > +            spi-max-frequency = <1000000>;
> > > +        };
> > > +    };
>
> Best regards,
>
> --
> David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings
  2025-02-28 22:41   ` David Lechner
@ 2025-03-03 12:54     ` David Jander
  0 siblings, 0 replies; 59+ messages in thread
From: David Jander @ 2025-03-03 12:54 UTC (permalink / raw)
  To: David Lechner
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel


Hi David,

On Fri, 28 Feb 2025 16:41:29 -0600
David Lechner <dlechner@baylibre.com> wrote:

> On 2/27/25 10:28 AM, David Jander wrote:
> > Add device-tree bindings for simple Linux Motion Control devices that
> > are based on 1 or 2 PWM outputs.
> > 
> > Signed-off-by: David Jander <david@protonic.nl>
> > ---
> >  .../bindings/motion/motion-simple-pwm.yaml    | 55 +++++++++++++++++++
> >  1 file changed, 55 insertions(+)
> >  create mode 100644 Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml
> > 
> > diff --git a/Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml b/Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml
> > new file mode 100644
> > index 000000000000..409e3aef6f3f
> > --- /dev/null
> > +++ b/Documentation/devicetree/bindings/motion/motion-simple-pwm.yaml
> > @@ -0,0 +1,55 @@
> > +# SPDX-License-Identifier: (GPL-2.0 OR BSD-2-Clause)
> > +%YAML 1.2
> > +---
> > +$id: http://devicetree.org/schemas/motion/motion-simple-pwm.yaml#
> > +$schema: http://devicetree.org/meta-schemas/core.yaml#
> > +
> > +title: Simple PWM based motor controller  
> 
> I think it has been said many times before, in DT, there is no such thing as
> a simple device! It will be much more future-proof if we write bindings for
> actual individual motor controller chips than try to generalize all in a single
> binding. The chip you gave as an example is far from the simplest H-bridge I
> have seen!

To clarify, my intention is not to generalize all existing DC motor controllers
into one driver or dt-binding. I mentioned the drv8873, but only as an example.
Actually my plan is to make a separate driver and separate bindings for the
drv8873, but I haven't had time for that yet, and it would be too much for the
first version of LMC.

There are a lot of simple "dumb" devices though, that have integrated or even
discrete H-bridges with fixed dead-time, that can't do more than just 2 PWM
signals to control left-/right-speed. There are also lots of places where
people connect a DC motor to just a simple power-MOSFET. All of these cases can
be handled by this driver.

Maybe the name "simple-pwm" isn't adequate. Should we name it "pwm-motor" or
something liket that instead?

The intend of motion/simple-pwm.c is to be the analog of something like
these other "simple" or "generic" drivers and corresponding dt-bindings, for
example:

gpio_keys.c:
https://web.git.kernel.org/pub/scm/linux/kernel/git/torvalds/linux.git/tree/drivers/input/keyboard/gpio_keys.c
https://web.git.kernel.org/pub/scm/linux/kernel/git/torvalds/linux.git/tree/Documentation/devicetree/bindings/input/gpio-keys.yaml

gpio-regulator.c:
https://web.git.kernel.org/pub/scm/linux/kernel/git/torvalds/linux.git/tree/drivers/regulator/gpio-regulator.c
https://web.git.kernel.org/pub/scm/linux/kernel/git/torvalds/linux.git/tree/Documentation/devicetree/bindings/regulator/gpio-regulator.yaml

pwm-regulator.c:
https://web.git.kernel.org/pub/scm/linux/kernel/git/torvalds/linux.git/tree/drivers/regulator/pwm-regulator.c
https://web.git.kernel.org/pub/scm/linux/kernel/git/torvalds/linux.git/tree/Documentation/devicetree/bindings/regulator/pwm-regulator.yaml

pwm_bl.c:
https://web.git.kernel.org/pub/scm/linux/kernel/git/torvalds/linux.git/tree/drivers/video/backlight/pwm_bl.c
https://web.git.kernel.org/pub/scm/linux/kernel/git/torvalds/linux.git/tree/Documentation/devicetree/bindings/leds/backlight/pwm-backlight.yaml

etc...

Although the driver actually is simple, and intended for simple hardware.
The fact that it can even be used with more complex chips, like the drv8873, if
the requirements are simple enough, and as long as there is no dedicated
driver yet, doesn't change that fact.

> > +maintainers:
> > +  - David Jander <david@protonic>
> > +
> > +description: |
> > +   Simple motor control device based on 1 or 2 PWM outputs
> > +
> > +properties:
> > +  compatible:
> > +    enum:
> > +      - motion-simple-pwm  
> 
> This should be e.g. ti,drv8873-q1. This device has much more pins that is given
> in these bindings.

Like I said, this driver isn't intended for the drv8873. It was merely an
example where as a matter of fact this driver could be used for the drv8873,
but that's not the intention. Sorry for not being clear. :-)

> If we find more devices that have similar functionality/pinout we can add them
> to the same bindings, but we will likely find that trying to cram all H-bridges
> into a single binding is too much.
> 
> For starters, every H-bridge chip is going to have one or more power supplies.
> ti,drv8873-q1 would need dvdd-supply and vm-supply properties for the DVDD and
> VM pins.
> 
> Many have inputs for disabling the chip, e.g. for power management. And some
> have outputs to indicate faults.
> 
> The TI DRV8873 in particular has an nSLEEP, DISABLE, nOL, SR, MODE and nITRIP
> inputs in addition to the IN1 and IN2 that would be connected to the PWMs.
> So we would have properties for all of these to either say how the pin is
> hardwired or a *-gpios property if it needs to be controlled by the driver.

Yes, sure. These will all be in the dt-binding for the drv8873. Our board
actually uses the drv8873s, which has an SPI interface, so that will of course
also be part of the bindings and of the driver.

> The fault output would generally be an interrupts property.

Ack.

> The IPROPI1 and IPROPI2 output pins look like they would be connected to an
> ADC, so it would make sense to have an io-channels property show that
> connection.

Ack. In fact, our board has these connected to the internal ADC of the SoC.

> This chip also has a SPI interface. So it needs to have the possibility of
> being a SPI peripheral node.

Sure, like I said above.

> And even if the Linux driver doesn't implement all of these features, we still
> want the DT bindings to be as complete as possible, so we shouldn't be leaving
> these out, at least for the trivial ones where there is an obvious correct
> binding (which I think is the case for most of what I suggested).

Completely agree. Will be done, but not for this first version. It is simply
too much to review, I'm afraid. It will be a separate binding, in
motion/ti,drv8873.yaml (not included in this version).

> > +
> > +  pwms:
> > +    maxItems: 2
> > +
> > +  pwm-names:
> > +    maxItems: 2  
> 
> Specifying what is wired up to the IN pins can be tricky. Using two PWMs is
> the most sensible. But I've also seen devices where there was a single PWM
> gated by two gpios. And for very basic H-bridges, there might not even be a
> PWM. Just gpios to turn it on or off.

That would be something for a future motion/gpio-motor.yaml, I guess.

> > +
> > +  motion,pwm-inverted:
> > +    $ref: /schemas/types.yaml#/definitions/flag
> > +    description:
> > +      If present, this flag indicates that the PWM signal should be inverted.
> > +      The duty-cycle will be scaled from 100% down to 0% instead 0% to 100%.
> > +
> > +required:
> > +  - compatible
> > +  - pwms
> > +
> > +allOf:
> > +  - $ref: /schemas/motion/common.yaml#
> > +
> > +unevaluatedProperties: false
> > +
> > +examples:
> > +  - |
> > +    // This example shows how to use the TI DRV8873 or similar motor controllers
> > +    // with this driver
> > +    motion-simple-pwm0 {
> > +      compatible = "motion-simple-pwm";
> > +      pwms = <&hpdcm0_pwm 0 50000 0>,
> > +             <&hpdcm0_pwm 1 50000 0>;
> > +      pwm-names = "left", "right";
> > +      motion,pwm-inverted;  
> 
> 
> > +      motion,speed-conv-mul = <3600>;
> > +      motion,speed-conv-div = <100000>;
> > +      motion,acceleration-conv-mul = <3600>;
> > +      motion,acceleration-conv-div = <100000>;  
> 
> This H-bridge controller doesn't have any kind of speed sensors that I can see
> so these properties don't make sense to me. The H-bridge can control the voltage
> sent to the motor, but there are more variables involved to convert voltage to
> speed. It isn't a constant.

Sure. In the most basic case, when there is no feedback signal for speed (like
an encoder for example), the best thing you can do is assume an (imperfect)
relation between duty-cycle and motor speed. That's what these factors are for.

You could have a reduction gearbox even, so specifying some parameters for the
user-space software to work with seems sensible. If you leave them out, the
default values are used, which are all 1's, basically making the "speed" value
equal to the (scaled) duty-cycle of the PWMs.

The driver scales duty-cycle to 1/1000th of a percent, which seemed a sensible
resolution to use and be intuitive enough, since due to the lack of floating
point numbers in the kernel, it is common practice to scale values by a factor
of 1000 to enhance resolution. If you prefer, we could also use
parts-per-million, or ppm (1/1,000,000).

With this in mind, setting the PWM outputs to 100% duty-cycle
(0% if inverted), would correspond to setting a motor speed of 3600 in the
case of the example scaling values given in the bindings.

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 6/7] dt-bindings: motion: Add adi,tmc5240 bindings
  2025-03-03 12:28       ` David Lechner
@ 2025-03-03 13:18         ` David Jander
  0 siblings, 0 replies; 59+ messages in thread
From: David Jander @ 2025-03-03 13:18 UTC (permalink / raw)
  To: David Lechner
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel


Dear David,

On Mon, 3 Mar 2025 13:28:35 +0100
David Lechner <dlechner@baylibre.com> wrote:

> (Sorry if you get this twice. I don't have my regular computer today
> and didn't realize I was sending HTML the first time. Resending in
> plain text so the lists pick it up.)
> 
> On Mon, Mar 3, 2025 at 12:22 PM David Jander <david@protonic.nl> wrote:
> >
> >
> > Dear David,
> >
> > On Fri, 28 Feb 2025 16:38:51 -0600
> > David Lechner <dlechner@baylibre.com> wrote:
> >  
> > > On 2/27/25 10:28 AM, David Jander wrote:  
> > > > Add device-tree bindings for Analog Devices TMC5240 stepper controllers.
> > > >
> > > > Signed-off-by: David Jander <david@protonic.nl>
> > > > ---
> > > >  .../bindings/motion/adi,tmc5240.yaml          | 60 +++++++++++++++++++
> > > >  1 file changed, 60 insertions(+)
> > > >  create mode 100644 Documentation/devicetree/bindings/motion/adi,tmc5240.yaml
> > > >
> > > > diff --git a/Documentation/devicetree/bindings/motion/adi,tmc5240.yaml b/Documentation/devicetree/bindings/motion/adi,tmc5240.yaml
> > > > new file mode 100644
> > > > index 000000000000..3364f9dfccb1
> > > > --- /dev/null
> > > > +++ b/Documentation/devicetree/bindings/motion/adi,tmc5240.yaml
> > > > @@ -0,0 +1,60 @@
> > > > +# SPDX-License-Identifier: (GPL-2.0 OR BSD-2-Clause)
> > > > +%YAML 1.2
> > > > +---
> > > > +$id: http://devicetree.org/schemas/motion/adi,tmc5240.yaml#
> > > > +$schema: http://devicetree.org/meta-schemas/core.yaml#
> > > > +
> > > > +title: Analog Devices TMC5240 Stepper Motor controller
> > > > +
> > > > +maintainers:
> > > > +  - David Jander <david@protonic>
> > > > +
> > > > +description: |
> > > > +   Stepper motor controller with motion engine and SPI interface.  
> > >
> > > Please include a link to the datasheet.  
> >
> > Will do.
> >  
> > > > +
> > > > +properties:
> > > > +  compatible:
> > > > +    enum:
> > > > +      - adi,tmc5240
> > > > +
> > > > +  reg:
> > > > +    maxItems: 1
> > > > +
> > > > +  interrupts:
> > > > +    maxItems: 1  
> > >
> > > I assume that this is the overvoltage output (OV pin). Would be nice to have
> > > a description here saying that. There are also NAO and DIAG0/1 output pins, so
> > > it's a bit ambiguous otherwise.  
> >
> > This is the DIAG0 output pin which on this chip has a dual function as either
> > a STEP output or an interrupt output. The pin name is a bit misleading, but it
> > is the "interrupt" function that is meant here. The datasheet documents all
> > the different events that can trigger this interrupt.
> > I will add a description to clarify this.
> >  
> 
> If it makes sense that other pins could possibly ever be connected to
> interrupts then we can add those and also add interrupt-names (but
> only if there is more than one possible interrupt).

AFAIK, only DIAG1 would potentially make sense to be connected to an
interrupt. It can be programmed to go low when the motor position matches the
contents of the X_COMPARE/X_COMPARE_REPEAT register setting.

I will add that one if you agree. It will not be mandatory of course.

In any case, if that pin was connected to an interrupt pin right now, it could
already be used as an IIO trigger for example. Just not (yet) via this driver.

>[...]
> > The resistor connected to the IREF pin (Rref) OTOH does have an implication to
> > the software, as it sets the full-range current of the output stage.
> >
> > How should we specify that? Is it adequate to add an optional DT property
> > "rref" or "rref-ohm" with an int32 value in Ohm? The default value if
> > unspecified is 12000 Ohm.  
> 
> It looks like there are a few standardized properties, like
> sense-resistor-ohms if that fits the use case. Otherwise, an
> vendor-specific ti,rref-ohms would work. FYI, you can find the
> preferred units at [1].
> 
> [1]: https://github.com/devicetree-org/dt-schema/blob/main/dtschema/schemas/property-units.yaml

Ah, thanks! This is helpful.

Will use this for ti,rref-ohms. I guess in this case that would be easier to
understand than "sense-resistor-ohms", which is also okay, but would require
reading the description to know what exactly is meant in this context.

> > > And if there are any pins would make sense to connect to a gpio, we can add
> > > those even if the driver doesn't use it currently.
> > >  
> > > > +  clocks:
> > > > +    maxItems: 1
> > > > +
> > > > +required:
> > > > +  - compatible
> > > > +  - reg
> > > > +  - interrupts
> > > > +  - clocks
> > > > +
> > > > +allOf:
> > > > +  - $ref: /schemas/spi/spi-peripheral-props.yaml#
> > > > +  - $ref: /schemas/motion/common.yaml#  
> > >
> > > If we need to know about what is connected to the output of a motor controller
> > > I would expect it to be done with child node for each output. That way each
> > > output can be unique, if needed. Basically, similar to iio/adc.yaml is used to
> > > provide common properties for channel@ child nodes on iio devices.  
> >
> > This controller chip only has one single output for one stepper motor (4
> > wires). While technically you could connect something else to those 4 wires, I
> > don't think it is the scope of LMC to support that. The chip itself isn't
> > designed for that purpose and it would clearly go far beyond the intended
> > purpose of this device.
> >
> > That being said, your suggestion of supporting child nodes may actually be a
> > good idea. Right now, we specify the type of motor (basically nominal- and hold
> > current settings) in user-space and set the IRUN/IHOLD parameters from
> > user-space via the sysfs attributes interface. It might make sense to have a DT
> > child node to specify this, although in our current application this is not
> > very practical, since there are many motor controllers on one board, and it is
> > configurable in software (runtime) which motor is connected to which output.
> >
> > But I can imagine a situation where it may be fixed and thus can be described
> > in the DT of a board.
> >
> > Then again I don't know if it would be over-complicating things with something
> > like this:
> >
> >         motor-controller@0 {
> >                 ...
> >                 motor@0 {
> >                         compatible = "nanotec,st4118s1006";
> >                         irun-ma = <1800>;
> >                         ihold-ma = <270>;
> >                 };
> >         };
> >
> > where we'd possibly have a stepper-motors.c file with a lot of structs and
> > matching tables for the different motor types.... sounds like overkill to me,
> > but maybe not?  
> 
> A compatible for motors seems too much. I was just thinking along the
> lines that 1) if we need to so some scaling or something that depends
> on a motor constant, then it would make sense to put those constants
> in the DT and 2) if there is a motor controller with more than one
> output that could be connected to two or more different sizes of
> motors with different constants, then we either need child nodes or an
> array to be able to enter the different constants. Either one would
> work. So maybe simpler to just use an array instead of child nodes now
> that I'm thinking about it more.

Well, in the case of the TMC5240 there isn't much more than a single motor
with possibly some fixed setting of irun/ihold in some cases, but like I said,
in our case it is run-time configurable, so not something fixed to the
hardware-description. Apart from that, there are the speed- and acceleration-
conversion constants, which per default are the constants stated in the
datasheet. In some rare cases one might want to overrule them, but that can
already be done.

LMC does als support multi-channel controllers, and in that case I intend to
make use of child nodes for the different channels, to be able to specify
those parameters per motor.

So maybe just leave it as it currently is for the tmc5240?

> > > > +
> > > > +unevaluatedProperties: false
> > > > +
> > > > +examples:
> > > > +  - |
> > > > +    spi {
> > > > +        #address-cells = <1>;
> > > > +        #size-cells = <0>;
> > > > +
> > > > +        motor@0 {  
> > >
> > > motor-controller@ or actuator-controller@
> > >
> > > The chip is the controller/driver, it is not a motor.  
> >
> > Make sense. Will change this.
> >  
> > > > +            compatible = "adi,tmc5240";
> > > > +            reg = <0>;
> > > > +            interrupts-extended = <&gpiok 7 0>;
> > > > +            clocks = <&clock_tmc5240>;
> > > > +            enable-supply = <&stpsleepn>;
> > > > +            spi-max-frequency = <1000000>;
> > > > +        };
> > > > +    };  

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings
  2025-03-03 11:40             ` David Jander
@ 2025-03-03 14:18               ` Krzysztof Kozlowski
  2025-03-03 16:09                 ` David Jander
  0 siblings, 1 reply; 59+ messages in thread
From: Krzysztof Kozlowski @ 2025-03-03 14:18 UTC (permalink / raw)
  To: David Jander, Uwe Kleine-König
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel, linux-pwm

On 03/03/2025 12:40, David Jander wrote:
>>
>> Some hardwares cannot support PWM_POLARITY_INVERTED. Affected drivers
>> include:
>>
>> 	pwm-adp5585
>> 	pwm-ntxec
>> 	pwm-raspberrypi-poe
>> 	pwm-rz-mtu3 (software limitation only)
>> 	pwm-sunplus
>> 	pwm-twl-led (not completely sure, that one is strange)
>>
>> . ISTR that there is a driver that does only support inverted polarity,
>> but I don't find it. For an overview I recommend reading through the
>> output of:
>>
>> 	for f in drivers/pwm/pwm-*; do
>> 		echo $f;
>> 		sed -rn '/Limitations:/,/\*\/?$/p' $f;
>> 		echo;
>> 	done | less
>>
>> . (Note not all drivers have commentary in the right format to unveil
>> their limitations.)
>>
>> For most use-cases you can just do
>>
>> 	.duty_cycle = .period - .duty_cycle
> 
> Yes, that is exactly what the relevant code in motion/simple-pwm.c does when
> the "pwm-inverted" flag is present in the DT node.
> 
>> instead of inverting polarity, but there is no abstraction in the PWM
>> bindings for that and also no helpers in the PWM framework. The problem
>> is more or less ignored, so if you have a device with
>>
>> 	pwms = <&pwm0 0 PWM_POLARITY_INVERTED>;
>>
>> and the PWM chip in question doesn't support that, the pwm API functions
>> will fail. So the system designer better makes sure that the PWM
>> hardware can cope with the needed polarity.
> 
> Thanks for clarifying this!
> 
> @Krzysztof, do you think that given this situation it is acceptable to include
> the "pwm-inverted" flag in the dt-schema of the simple PWM motor driver?

No, because that flag is already supported via PWM_POLARITY_INVERTED.

Do not tie bindings to specific implementation. If PWM core is changed
to always handle PWM_POLARITY_INVERTED even if controller does not
support it, would the binding became outdated?

> 
> The need for an inverted PWM signal is something very common in the case of
> H-bridge motor drivers, where the PWM signal represents the actual logical
> output level of each of the two halves of the bridge. Often the high-side
> switches are used as the free-wheel position, so that 100% duty-cycle on both
> channels is actually standstill, while 0% duty-cycle on one channel is full
> speed in either direction. This isn't always the case though, hence the
> importance for this to be able to be selected.

Sure and use existing bindings for that. If implementation has problems,
fix implementation.

Best regards,
Krzysztof

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-03-03 11:01       ` Pavel Pisa
@ 2025-03-03 16:04         ` David Jander
  0 siblings, 0 replies; 59+ messages in thread
From: David Jander @ 2025-03-03 16:04 UTC (permalink / raw)
  To: Pavel Pisa
  Cc: David Lechner, linux-kernel, linux-iio, Jonathan Corbet,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, devicetree,
	linux-doc, Nuno Sa, Jonathan Cameron, Oleksij Rempel,
	Carsten Emde, Jan Kiszka, Pavel Machek


Hi Pavel,

On Mon, 3 Mar 2025 12:01:33 +0100
Pavel Pisa <ppisa@pikron.com> wrote:

> Hello Davids,
> 
> On Monday 03 of March 2025 09:36:11 David Jander wrote:
> > On Fri, 28 Feb 2025 16:36:41 -0600
> >
> > David Lechner <dlechner@baylibre.com> wrote:  
> > > On 2/27/25 10:28 AM, David Jander wrote:  
> > > > The Linux Motion Control subsystem (LMC) is a new driver subsystem for
> > > > peripheral devices that control mechanical motion in some form or
> > > > another. This could be different kinds of motors (stepper, DC, AC, SRM,
> > > > BLDC...) or even linear actuators.
> > > > The subsystem presents a unified UAPI for those devices, based on char
> > > > devices with ioctl's.
> > > > It can make use of regular gpio's to function as trigger inputs, like
> > > > end-stops, fixed position- or motion start triggers and also generate
> > > > events not only to user-space but also to the IIO subsystem in the form
> > > > of IIO triggers.
> > > >
> > > > Signed-off-by: David Jander <david@protonic.nl>
> > > > ---
> > > >  MAINTAINERS                     |   8 +
> > > >  drivers/Kconfig                 |   2 +
> > > >  drivers/Makefile                |   2 +
> > > >  drivers/motion/Kconfig          |  19 +
> > > >  drivers/motion/Makefile         |   3 +
> > > >  drivers/motion/motion-core.c    | 823 ++++++++++++++++++++++++++++++++
> > > >  drivers/motion/motion-core.h    | 172 +++++++
> > > >  drivers/motion/motion-helpers.c | 590 +++++++++++++++++++++++
> > > >  drivers/motion/motion-helpers.h |  23 +
> > > >  include/uapi/linux/motion.h     | 229 +++++++++
> > > >  10 files changed, 1871 insertions(+)  
> > >
> > > Ooof, this is really a lot for one patch. Makes it hard to review. 500
> > > lines in a patch is much easier to digest.  
> >
> > Sorry for that. I wouldn't know how to split up this patch to make it any
> > easier. It's just a complete new subsystem, and I think it is the bare
> > minimum to start and also to give a good idea of what it is supposed to be
> > able to do.
> >  
> > > But before commenting on the details of the code I have some more
> > > high-level comments. As I mentioned in my reply to the cover letter, I've
> > > gone through the exercise of writing some motor control divers in the
> > > Linux kernel that have been used by 1000s of people that used them to
> > > build everything imaginable using LEGO robotics over the last 10+ years.
> > >
> > > From what I see here (I didn't have time to really get into the details
> > > of it yet, so maybe missed some important details), it looks like you are
> > > trying to do motor control stuff in the kernel so that the interface for
> > > a basic H-bridge will be close to the same as a fancy stepper motor
> > > controller. We tried doing something very similar because it sounds like
> > > a really nice thing to do. The kernel does everything and makes it really
> > > easy for the users. But what we actually found is that it is not possible
> > > to make a solution in the kernel that can handle every possible use case.
> > > In the end, we wished that we had a much more low-level interface to the
> > > motor controllers to give us more flexibility for the many different
> > > types of applications this ended up getting used for. Having to modify
> > > the kernel for your use case is too high of a bar for most users and not
> > > practical even if you are a kernel hacker.  
> >
> > The idea for LMC is to be able to support hardware that realistically can
> > be used by an OS as complex as the Linux kernel. There are a lot of motor
> > controllers out there that suit that category, like the TMC5240 chip for
> > example. But also many bigger systems, like the ones Pavel Pisa works with.
> > That said, I think the Linux kernel on modestly modern SoC's, like the
> > STM32MP1xx is pretty capable of doing more than that, but we have to draw
> > the line somewhere. Like I hinted in the cover letter, I think it might
> > even be possible to do crazy stuff like bit-banging STEP/DIR type
> > controllers in the kernel, possibly aided by PREEMPT_RT, but that is not
> > the main purpose of LMC.  
> 
> I look even to take into account these options for the hobbyist projects.
> But stepper motors drivers step, dir interface is really demanding
> case. With microstepping it can require pulse control with frequency
> 100 kHz or even MHz and corresponding jitter demand. So that is really
> not area for PREEMPT_RT in userspace nor kernel space.

Yes, I agree we should try this for hobby purposes to the extent it is
possible to make it work. There are some semi-dumb controllers that can do
micro-step interpolation automatically, so one doesn't need to toggle STEP for
every microstep. Also some controllers can adjust the micro-step resolution
on-the-fly via extra GPIO pins. If done synchronized with the corresponding
step-count frequency change (easy to do when bit-banging), this can be done
without any jerk.

But I want to be clear here: This is not the primary intention of LMC. It is a
cool experiment to show off how RT-capable the Linux kernel is, but nothing
more than that. That said, I do intend to write such a driver for LMC. But use
of it for anything other than hobby and tinkering is highly discouraged. ;-)

> On the other hand, I can imagine that some SoftMAC like controller
> for Raspberry Pi 1 to 4 to combine its specific DMA and GPIO
> capabilities could be good target for some LMC like abstraction.

Oh sure! I'm really looking forward for other people coming up with
interesting drivers for LMC. Although the Rpi hobby-scene is not exactly known
for writing kernel drivers to control stuff ;-)

> Doing DMA from userspace is pain for regular users, yes we use
> that for Marek Peca's Zlogan https://github.com/eltvor/zlogan
> and other projects, but that is not for users which I see
> between our studnets to attempt to stepper motors by step, dir
> from RPi without previous RT knowledge. The question is if the
> API to RPi and its DMA should be covered by kernel LMC
> or some more generic DMA interface.

I don't know what the current status of support for that DMA controller is in
the kernel right now, but I think it is at least a tempting target to try
something like this.
If so, I do think it should be properly abstracted in the kernel for all of its
possible applications, and a potential LMC driver should be a user of that
abstraction.

> I have found some links for students working on the
> project (it is project led by my colleagues not mine,
> 
>   https://github.com/hzeller/rpi-gpio-dma-demo
> 
>   https://github.com/innot/AdvPiStepper
> 
>   https://github.com/richardghirst/PiBits/tree/master/ServoBlaster
> 
> I would be happy for pointers for alive and newwer project
> if somebody has some more links for these kind of users.
> 
> I prefer other approaches myself, i.e. small RTOS based
> solution with background and IRQ tasks and D/Q control
> where the risk to lose step is much smaller, because you
> control at sin, cos level, so you have more time at high
> speeds where current control is not realized on these MHz
> periods required by dumb step, dir driver with microstepping.
> Se my previously reported project SaMoCon project for
> idea. It has four outputs per each axis and can drive
> PMSM, DC, stepper etc... 
> 
>   https://gitlab.fel.cvut.cz/otrees/motion/samocon
> 
> The PID or even D-Q DC, PMSM and may it be stepper
> motors at something like 5 kHz is achievable
> in userspace or kernel RT_REEMPT therad. May it be
> even with commutation for stepper, but 20 kHz
> is probably only for kernel and not for professional
> use according to my taste. If the commutation
> is pushed even to small FPGA, then some interface
> as NuttX FOC
> 
>   https://nuttx.apache.org/docs/12.1.0/components/drivers/character/foc.html

This reminds me of a R&D board I once designed, based on the i.MX8MP SoC,
which has a secondary ARM Cortex-M7 core clocked at a whopping 600MHz!
I wanted to use that extra core to do bit-banged 3-phase PWM for a BLDC motor
controller at high-frequency using GaN bridges and small inductors. I was
hoping to achieve up to 100kHz+ PWM cycle frequency by programming a tightly
timed loop and no IRQ's. A fixed time-slot in this loop would be used to load
PWM parameters from the linux kernel running on the A53 cores via remoteproc.

I still have the hardware with GaN drivers and everything... just never got
around to actually writing the software :-(

> is good match and yes, proposed LMC pushes much more
> complexity into the kernel. 
> 
> But for these people who want to stuck on step, dir
> because it is like that should be done in 3D printers
> and other hobbits world could profit a lot from
> some segments list controlled motion and I can image
> to combine it with that RPi or some simple FPGA
> block on Zynq, Beagle or iCE40 connected to SPI.
> 
> So I see value of some unification under LMC

Thanks! That is my intention with this project.

> > The main purpose is to talk to controllers that 
> > can receive motion profiles and execute movements (semi-)autonomously.
> > Going just one step lower is the simple PWM based driver in this patch set:
> > It takes the execution of the profile into the kernel by using a HRTIMER to
> > sample the profile curve using a sample period of 20ms, which is fast
> > enough for most applications while not imposing a high CPU load on the
> > kernel on slower CPU cores.
> > motion-helper.c contains the trapezoidal ramp generator code that can be
> > used by any LMC driver that can work with speed information but doesn't
> > have its own ramp generator in hardware. It could be extended to support
> > other type of profiles if needed in the future, which would automatically
> > upgrade all drivers that use it.  
> 
> I agree, but on the other hand, the optimal combination of HW and matching 
> upper abstraction level is extremely variable, and finding a good API for 
> LMC, which would not be a root to stumble upon in the future, is a really 
> demanding task. On the other hand, if some, even suboptimal, solution is 
> available in staging drivers kernel area without guarantee of having fixed 
> API forever, then it can evolve slowly to something valuable. There would be 
> incompatible changes, but the transition can be smooth. 

That is also an option of course. My intention was to make the current API
extensible in a backward-compatible manner. It is also versioned, so one can
add newer versions that offer more functionality if needed, but of course this
is more like a last resort.

> So may it be some COMEDI like approach. And there should be matching
> userspace library which could choose between APIs at different level
> of abstraction according to the target HW and some these APIs can
> be emulated by SoftMAC approach in the kernel. Usually for there
> more hobbits like solutions.

A user-space library can always be made, but I'd like to keep that simple and
thin if possible. Right now I have a simple user-space library written purely
in python. In fact the whole user-space application for this machine is pure
python code (asyncio). Many people might declare me crazy for saying this, but
it works like a charm and has no trouble handling 16 motors, 26 inputs, 10
outputs with current-feedback and 6 extra ADC channels at sample rates of more
than 16kHz all at once. All that on a rather slow Cortex-A7 single core. The
trick is to have a good UAPI and make use of epoll with python asyncio
wherever possible. It's a good litmus test.

> I would personally tend to something like our PXMC at these API
> level but I am predetermined/skewed as author and its 25 years
> use and connection to older assembly API with more than 30 years
> history.

Yes, I know this can be challenging, but I'd really like to discuss things
with a fresh look if possible.

The idea isn't that complicated. I'd attempt to break it down like this:

Find as many different motion applications as possible. Describe all the
involved movements in terms of their most basic physical aspects involving
time and distance (amount or angle of rotations) as well as their
1st and 2nd order time-derivatives speed and acceleration. 2nd order
time-derivatives can optionally be described as forces when combined with
mass, so if acceleration can vary over time, so can force.
Verify that any higher-order time-derivatives can be described either as
constant limits (jerk, snap, crackle and pop) or form part of the
hardware/firmware. Verify that speed at this level of abstraction is always the
result of either an acceleration- or a force profile.

If fitting the application into this domain requires fast close-loop control
of some variable, consider incorporating the needed closed loop control into
the hardware/firmware, and try again.

If the required control loop can be made slow and simple enough to not be
problematic to be implemented in the kernel, that's worth considering.

If you can not fit the application into this domain at all, we need to go back
to the drawing board or add stuff.

Next, try to find ways to define trajectories of position and speed
(acceleration or force profiles) in a common language. Then reduce that
language to the minimum common denominator that covers all use-cases.

This is the language I've come up with so far:

https://github.com/yope/linux/blob/mainline-lmc-preparation/Documentation/userspace-api/motion.rst

We already established that it is probably worth and valuable adding some way
of conveying spline interpolation parameters for position and speed points. I
suggest modeling that according to some existing hardware that uses this,
while keeping an eye on it not being machine-specific. This would require to
have a functioning LMC driver for this use-case, not to be included in this
version, but to test the UAPI to the extent it needs to be set in stone.

Lastly, if there are several fitting motion controllers that could be used for
a certain target application, it should be possible to swap them without the
need to change the user-space software more than maybe changing some
configuration setting that doesn't affect how it talks to the kernel.

Let's test it with more use-cases.

> But I hope I am critical enough to be able to say what is problematic
> on our design and what can be designed better today. I.e. there
> is compromise to keep all positions 32 bits, sometimes even
> reduced to allows IRC sensors position subdivision on ramps
> generators side, some there is often range reduced to +/-2^23
> bits. On the other hand, all is computed in modulo arithmetic,
> so there is no problem to control speed for infinite time...
> For very precise and slow syringe piston control in infusion
> systems, we have used 32 bits position where 8 bits have been
> fractions and in generators another short extended fractions
> to 24 bits. It has been able to run with this precision
> even on 16-bit MSP430. But if that is ported and used in our
> solutions on 32-bit ARMs or even 64-bit chips like PoalFire,
> then it loses purpose... So it would worth to reinvent/redefine
> APIs...

I know how it is when older use-cases evolve throughout many years. Technical
limitations and concessions tend to disappear over time.

In this case we should probably assume a modern FPGA, uC or custom controller
chip connected to a modern embedded Linux system. The communication between
the Linux system and the control circuit can be anything from a simple GPIO or
PWM signal, through I2C, SPI or CAN up to modern 1000Base-T1 ethernet.
The possibility of using remoteproc when adequate should be considered.

The UAPI should be generally usable on basically any platform the Linux kernel
can run on.

> But I would tend to this userspace lib and multiple API levels
> approach... 

Let's try to see if we can do with the current UAPI. It does have some notion
of "levels of complexity", where the driver/hardware is interrogated for the
capabilities it supports. See here:

https://github.com/yope/linux/blob/mainline-lmc-preparation/Documentation/userspace-api/motion.rst#structs-used-in-the-ioctl-api

So some drivers might only support "basic motion control", like only setting a
fixed speed (even if it is only on/off, left/right).

All drivers can be augmented with GPIO-based trigger/end-stop interrupts
defined in the device-tree as "gpios" vector.

Other drivers might be able to use locally connected feedback inputs
("feedback control").

More advanced drivers might support "profile-based control", that accepts
speed/acceleration profiles with varying complexity.

Lastly (not yet implemented) drivers can support also torque limit profiles
and/or multi-axis movements (n-dimensional position vectors).

If adequate, a user-space library could hide some of the decision-making based
on the capabilities and maybe provide some user-space emulation of some
missing features, but I haven't really thought very deeply about that.

> > > When writing kernel drivers for this sort of thing, I think the rule of
> > > thumb should be to keep the driver as "thin" as possible. If the hardware
> > > doesn't provide a feature, the kernel should not be trying to emulate it.  
> >
> > In general I would agree with this, but in this case some limited
> > "emulation" seems adequate. As a rule of thumb, code is better placed in an
> > FPGA/uC, the kernel or in user-space according to its latency requirements.
> > Microsecond stuff shouldn't be done on the application SoC at all,  
> 
> Sure
> 
> > millisecond stuff (or maybe 100s of microseconds if you like) can be done
> > in the kernel, 10s of milliseconds or slower is good for user-space. A very
> > general guideline.  
> 
> I would be open to higher frequencies in userspace with PREEMPT_RT
> on Zynq, iMX6,7,8,9 or AM3,4,... industrial targetting hardware.

That may be possible, but would that be a desirable design from an
architectural standpoint?

What would be the reason for this. Can you explain a use-case where that's
required or desirable?

> We have run complex Simulik generated models on x86 at 30 kHz
> many years ago without missing code. But with our Simulink RT
> target https://github.com/aa4cc/ert_linux 

This sounds pretty cool. We might even want this. :-)

But isn't it the idea to use Simulink for the R&D phase to develop control
strategies, to then implement them in C in a microcontroller or FPGA for the
end-application? Wouldn't the end result be a microcontroller being talked to
through some standard interface from a Linux host that sends higher-level
commands to it?

We also have a motor lab where we can simulate mechanical loads with SRL or AC
machines to simulate a variable loads to another motor (also AC, DC, BLDC or
SRL machine) controlled from Simulink (using dspace). Once the solution is
found, developed an tested, the final implementation is made in some sort of
microcontroller that has maybe a CAN interface or SPI or similar...

While being able to use LMC for these kind of lab-applications sounds cool, I
am not sure we would want that. Or at least, IMHO, it shouldn't be its main
focus, but rather the end application should be.

> not with Mathwork's
> offer. But even serious, rich company came to us to solve their
> problems on RPi with CAN controller on SPI with sticking
> on Mathwork's delivered Windows supported target and it has been
> problem
> 
> https://dspace.cvut.cz/bitstream/handle/10467/68605/F3-DP-2017-Prudek-Martin-Dp_2017_prudek_martin.pdf

Oh dear. dspace. ;-)

> So if we speak about enthusiasts with common x86 without
> SMI interrupt checking before buying the motherboard or even
> attempting to use laptops or sticking on Raspberry Pi where
> some versions have used FIQ to solve HW deficiencies, then
> I would agree to stay even with PREEMP_RT on safe side
> i.e. under 1 kHz... 

Don't get me wrong, if there is merit to it, I am all for attempting faster
stuff in the kernel, specially if that is the best solution. But for
user-space I'd rather stay at 1kHz or less as a requirement. If you want to
feed micrometer long linear segments of a spline interpolation at 10kHz to the
kernel from user-space, fine if your platform can handle that, but let's not
make it a requirement or assume this level of latency and timing control is
available universally.

> > So if you have a device that can take a speed-setpoint but doesn't have a
> > ramp generator, that is not a device that LMC is made for in the first
> > place, but still pretty usable if we do the ramp generator in the kernel.
> > To steal Pavel's analogy: Think of the TMC5240 driver as a FullMAC Wifi
> > device and the simple PWM driver as a SoftMAC Wifi device.
> > For an LMC device, same as for a wifi interface, we want to talk TCP/IP to
> > it from user-space, not radio-packets. ;-)  
> 
> Somebody mentioned to me ASICy Nova MCX314 or NPM PCD4541

Wow, cool. The MCX314 actually sound like a good candidate for an LMC driver.
Only the CPU bus interface is a bit... outdated ;-)

> as reaction to my discussion, I am not sure about their API,
> but may it be some segmented API with fast, guaranteed,
> IRQ driven switch/preparation of next segment would support
> for LMC API.

Apparently it can generate interrupts for passing a pre-set position, changing
from acceleration fase to constant speed, changing to deceleration or reaching
the target.

> > > So for an
> > > H-bridge I would want something that just provides a way to tell it I
> > > want fast-decay mode with some normalized duty cycle between -1 and 1
> > > (obviously we will have to multiply this by some factor since the kernel
> > > doesn't do floating point). A duty cycle of 0 will "brake" the motor. And
> > > then we would need one more control parameter to tell it to remove power
> > > completely to "coast" the motor. I guess this is what the "basic_run" and
> > > "basic_stop" are other than the run seems to have speed instead of duty
> > > cycle? The kernel shouldn't be trying to convert this duty cycle to speed
> > > or have a background task that tries to provide an acceleration profile
> > > or turn off the power after some time. Just let the kernel provide
> > > direct, low-level access to the hardware and let userspace handle all of
> > > the rest in a way that makes the most sense for the specific application.
> > > Sometimes they might not even be connected to a motor! With the LEGO
> > > MINDSTORMS and BeableBone Blue, the H-bridge outputs are hot-pluggable,
> > > so they can even be connected to things like LEDs or used as a general
> > > power supply. (A reason to call this subsystem "actuation" rather than
> > > "motion".)  
> >
> > LMC aims to offer a common interface to different sorts of motion devices
> > (think different types of motors), so offering access to the lowest level
> > of each device is kinda defeating of that purpose. Nevertheless, all of the
> > things you mention are possible with LMC. The relationship between speed
> > and the PWM duty-cycle of a simple DC motor H-bridge for example, is
> > determined by the speed_conv* and accel_conv* parameters. If you want a 1:1
> > relation, just make them 1 in your device tree.  
> 
> But you need full PID or even current D-Q multiple PI and procession,
> sines, cosines for commutation etc. to connect higher level with lower
> level. We have all these in fixed point and focused on processing
> not only in RTOSes kernel but even in IRQs. So it can be done
> in Linux kernel as we ported, demonstrated it in GNU/Linux userspace...

Hmm.. I was referring to simple brushed DC motors, not something like BLDC
motors when I mentioned a "simple DC motor" H-bridge. I don't intend to
support real-time control of a BLDC motor in the kernel. That should
definitely be done by specialize hardware (uC, FPGA or specialized control
chip).
 
> > OTOH, if you had only a duty-cycle setting from user-space, you would need
> > to have code that generates an acceleration profile in user-space, which
> > would be a much higher CPU load and have a much higher latency jitter, much
> > more likely to cause mechanical and audible effects than if done in the
> > kernel. It's still possible though.
> > And talking about mis-using a motor driver for something else, that's
> > exactly what one of our customers is doing with a DC motor H-bridge via
> > LMC. They just set each output to 0% or 100% duty-cycle (max speed without
> > profile) to control 2 warning lights.
> >  
> > > Another way of putting this is that it was very tempting to model the
> > > actual motor in the kernel. But that didn't work well because there are
> > > so many different kinds of motors and related mechanical systems that you
> > > can connect to the same motor driver chip.  
> >
> > Yes, but on the other side, you have many different driver chips that all
> > control motors that do the same thing: move in different directions with
> > different speeds and different acceleration profiles. As a user, I want to
> > be able to tell that to the motor in the same sense as I want to send a
> > data through an ethernet interface without having to know what kind of
> > interface I have to an extend reasonably possible. Of course each
> > motor/driver has different limitations (just as different network
> > interfaces have), and more often than not I will have to know some of those
> > in user-space, but the whole idea of a subsystem UAPI is to abstract as
> > much as possible of that from user-space.
> >
> > With LMC I could easily swap a stepper motor for a BLDC or DC motor for
> > example. If they have an encoder to provide accurate position feedback, it
> > could even work as well as a stepper for many applications. No changes in
> > user-space code required.
> >  
> > > So the driver really should just be for the
> > > H-bridge chip itself and not care about the motor. And the rest can be
> > > put in a libmotion userspace library and have that be the convenient API
> > > for users that want to get something up and running quickly.  
> >
> > I get your point, and from the standpoint of Lego hardware and hobby
> > tinkerers doing all sorts of stuff with it, I can understand the desire to
> > have low-level access from user-space to the H-bridge. It is similar to how
> > Raspberry-pi exposes direct access to their GPIO controllers to user-space.
> > It is nice for tinkerers, but it is inadequate for anything else, not to
> > mention potentially unsafe. I remember when I first installed Linux on my
> > PC in 1994, we had the X server access the video card directly from
> > user-space. That was a really bad idea. ;-)  
> 
> It is questionable, some solution where kernel is RT, allows fast delivery
> of data and events between kernel and userspace memory contexts,
> like IO-uring and DRI, shared memory, PRIME buffers etc. is often
> better than push of all into kernel. In the fact, today lot of graphic
> stack is pushed directly into applications through acceleration API
> libraries which talks directly with allocated context in GPUs
> and the result is combined by compositor, again in userspace.

Yes, but there is always a kernel driver involved that does memory management,
checks and filters the GPU command stream and does error handling and recovery.

What I meant that back in 1994 the X-server simply asked the kernel "give me
access to this range of IO-registers and memory". This is a big vulnerability
of course and can lead to user-space locking up a machine. Not good.

> So this is not so convicing argument. But SoftMAC and 802.11
> is the case which supports push of more levels of LMC
> into kernel.
> 
> Anyway, the motion control is really broad area, there are companies
> with experience with Linux in their highest range of CNC machines,
> laser cutters, welding robots etc... So there is lot of prior
> experience. Question is, how much they are willing to share.

We will have to see.

> But preparing some common guidelines and collect information
> to not reinvent wheel again and again and then proposing
> some more generally reusable APIs and drivers etc. would be
> great win for all and would make GNU/Linux much easier
> and cheaper usable in the are in future.

I agree.

> So my actual vote is to find location where the already
> available knowledge and projects could be collected
> and where input even from PREEMP_RT and other professionals
> can be obtained...

Sounds like a good idea. Let's look for such a place. You seem to have more
contacts than I have, so maybe you can suggest someone to ask?

> May it be somebody from LinuxCNC should step in and may it
> be there are such resources collected. Linux Foundation
> or similar body should be contacted to check if such
> project is already there. I am adding some PREEMP_RT
> experts which I am in contact with, if they have idea
> about right place for motion control on Linux discussion,
> coordination.

Ok. Great.
I will try to read up a bit on LinuxCNC and see if I can contact some of the
developers. It would be good to at least give them a heads-up about the
existence of this project to begin with.

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings
  2025-03-03 14:18               ` Krzysztof Kozlowski
@ 2025-03-03 16:09                 ` David Jander
  0 siblings, 0 replies; 59+ messages in thread
From: David Jander @ 2025-03-03 16:09 UTC (permalink / raw)
  To: Krzysztof Kozlowski
  Cc: Uwe Kleine-König, linux-kernel, linux-iio, Jonathan Corbet,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, devicetree,
	linux-doc, Nuno Sa, Jonathan Cameron, Oleksij Rempel, linux-pwm

On Mon, 3 Mar 2025 15:18:40 +0100
Krzysztof Kozlowski <krzk@kernel.org> wrote:

> On 03/03/2025 12:40, David Jander wrote:
> >>
> >> Some hardwares cannot support PWM_POLARITY_INVERTED. Affected drivers
> >> include:
> >>
> >> 	pwm-adp5585
> >> 	pwm-ntxec
> >> 	pwm-raspberrypi-poe
> >> 	pwm-rz-mtu3 (software limitation only)
> >> 	pwm-sunplus
> >> 	pwm-twl-led (not completely sure, that one is strange)
> >>
> >> . ISTR that there is a driver that does only support inverted polarity,
> >> but I don't find it. For an overview I recommend reading through the
> >> output of:
> >>
> >> 	for f in drivers/pwm/pwm-*; do
> >> 		echo $f;
> >> 		sed -rn '/Limitations:/,/\*\/?$/p' $f;
> >> 		echo;
> >> 	done | less
> >>
> >> . (Note not all drivers have commentary in the right format to unveil
> >> their limitations.)
> >>
> >> For most use-cases you can just do
> >>
> >> 	.duty_cycle = .period - .duty_cycle  
> > 
> > Yes, that is exactly what the relevant code in motion/simple-pwm.c does when
> > the "pwm-inverted" flag is present in the DT node.
> >   
> >> instead of inverting polarity, but there is no abstraction in the PWM
> >> bindings for that and also no helpers in the PWM framework. The problem
> >> is more or less ignored, so if you have a device with
> >>
> >> 	pwms = <&pwm0 0 PWM_POLARITY_INVERTED>;
> >>
> >> and the PWM chip in question doesn't support that, the pwm API functions
> >> will fail. So the system designer better makes sure that the PWM
> >> hardware can cope with the needed polarity.  
> > 
> > Thanks for clarifying this!
> > 
> > @Krzysztof, do you think that given this situation it is acceptable to include
> > the "pwm-inverted" flag in the dt-schema of the simple PWM motor driver?  
> 
> No, because that flag is already supported via PWM_POLARITY_INVERTED.
> 
> Do not tie bindings to specific implementation. If PWM core is changed
> to always handle PWM_POLARITY_INVERTED even if controller does not
> support it, would the binding became outdated?

Understood. I guess I will have to start fixing PWM drivers then... @uwe, do
you have objections to trying to add a (very trivial) helper for PWM
controllers that can't do inversion in hardware and start to patch some of
them if needed?

> > The need for an inverted PWM signal is something very common in the case of
> > H-bridge motor drivers, where the PWM signal represents the actual logical
> > output level of each of the two halves of the bridge. Often the high-side
> > switches are used as the free-wheel position, so that 100% duty-cycle on both
> > channels is actually standstill, while 0% duty-cycle on one channel is full
> > speed in either direction. This isn't always the case though, hence the
> > importance for this to be able to be selected.  
> 
> Sure and use existing bindings for that. If implementation has problems,
> fix implementation.

Sounds reasonable.

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-02-28 16:44   ` Uwe Kleine-König
@ 2025-03-05 15:40     ` David Jander
  2025-03-05 23:21       ` Uwe Kleine-König
  0 siblings, 1 reply; 59+ messages in thread
From: David Jander @ 2025-03-05 15:40 UTC (permalink / raw)
  To: Uwe Kleine-König
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel


Hi Uwe,

On Fri, 28 Feb 2025 17:44:27 +0100
Uwe Kleine-König <u.kleine-koenig@baylibre.com> wrote:

> Hello David,
> 
> just a few highlevel review comments inline.

Thanks...

> On Thu, Feb 27, 2025 at 05:28:17PM +0100, David Jander wrote:
> [...]
> > +static int motion_open(struct inode *inode, struct file *file)
> > +{
> > +	int minor = iminor(inode);
> > +	struct motion_device *mdev = NULL, *iter;
> > +	int err;
> > +
> > +	mutex_lock(&motion_mtx);  
> 
> If you use guard(), error handling gets a bit easier.

This looks interesting. I didn't know about guard(). Thanks. I see the
benefits, but in some cases it also makes the locked region less clearly
visible. While I agree that guard() in this particular place is nice,
I'm hesitant to try and replace all mutex_lock()/_unlock() calls with guard().
Let me know if my assessment of the intended use of guard() is incorrect.

> > +	list_for_each_entry(iter, &motion_list, list) {
> > +		if (iter->minor != minor)
> > +			continue;
> > +		mdev = iter;
> > +		break;
> > +	}  
> 
> This should be easier. If you use a cdev you can just do
> container_of(inode->i_cdev, ...);

Hmm... I don't yet really understand what you mean. I will have to study the
involved code a bit more.

> [...]
> > +static int motion_release(struct inode *inode, struct file *file)
> > +{
> > +	struct motion_device *mdev = file->private_data;
> > +	int i;
> > +
> > +	if (mdev->ops.device_release)
> > +		mdev->ops.device_release(mdev);
> > +
> > +	for (i = 0; i < mdev->num_gpios; i++) {
> > +		int irq;
> > +		struct motion_gpio_input *gpio = &mdev->gpios[i];
> > +
> > +		if (gpio->function == MOT_INP_FUNC_NONE)
> > +			continue;
> > +		irq = gpiod_to_irq(gpio->gpio);
> > +		devm_free_irq(mdev->dev, irq, gpio);  
> 
> It seems devm is just overhead here if you release by hand anyhow.

Ack. This looks indeed unnecessary... I'll try to use non-devres calls here.

> > [...]
> > +
> > +static const struct class motion_class = {
> > +	.name		= "motion",
> > +	.devnode	= motion_devnode,  
> 
> IIRC it's recommended to not create new classes, but a bus.

Interesting. I did some searching, and all I could find was that the chapter
in driver-api/driver-model about classes magically vanished between versions
5.12 and 5.13. Does anyone know where I can find some information about this?
Sorry if I'm being blind...

> [...]
> > +int motion_register_device(struct motion_device *mdev)
> > +{
> > +	dev_t devt;
> > +	int err = 0;
> > +	struct iio_motion_trigger_info *trig_info;
> > +
> > +	if (!mdev->capabilities.num_channels)
> > +		mdev->capabilities.num_channels = 1;
> > +	if (mdev->capabilities.features | MOT_FEATURE_PROFILE)
> > +		mdev->capabilities.max_profiles = MOT_MAX_PROFILES;
> > +	if (!mdev->capabilities.speed_conv_mul)
> > +		mdev->capabilities.speed_conv_mul = 1;
> > +	if (!mdev->capabilities.speed_conv_div)
> > +		mdev->capabilities.speed_conv_div = 1;
> > +	if (!mdev->capabilities.accel_conv_mul)
> > +		mdev->capabilities.accel_conv_mul = 1;
> > +	if (!mdev->capabilities.accel_conv_div)
> > +		mdev->capabilities.accel_conv_div = 1;
> > +
> > +	mutex_init(&mdev->mutex);
> > +	mutex_init(&mdev->read_mutex);
> > +	INIT_KFIFO(mdev->events);
> > +	init_waitqueue_head(&mdev->wait);
> > +
> > +	err = motion_of_parse_gpios(mdev);
> > +	if (err)
> > +		return err;
> > +
> > +	mdev->minor = motion_minor_alloc();
> > +
> > +	mdev->iiotrig = iio_trigger_alloc(NULL, "mottrig%d", mdev->minor);
> > +	if (!mdev->iiotrig) {
> > +		err = -ENOMEM;
> > +		goto error_free_minor;
> > +	}
> > +
> > +	trig_info = kzalloc(sizeof(*trig_info), GFP_KERNEL);
> > +	if (!trig_info) {
> > +		err = -ENOMEM;
> > +		goto error_free_trigger;
> > +	}
> > +
> > +	iio_trigger_set_drvdata(mdev->iiotrig, trig_info);
> > +
> > +	trig_info->minor = mdev->minor;
> > +	err = iio_trigger_register(mdev->iiotrig);
> > +	if (err)
> > +		goto error_free_trig_info;
> > +
> > +	mdev->iiowork = IRQ_WORK_INIT_HARD(motion_trigger_work);
> > +
> > +	INIT_LIST_HEAD(&mdev->list);
> > +
> > +	mutex_lock(&motion_mtx);
> > +
> > +	devt = MKDEV(motion_major, mdev->minor);
> > +	mdev->dev = device_create_with_groups(&motion_class, mdev->parent,
> > +				devt, mdev, mdev->groups, "motion%d", mdev->minor);  
> 
> What makes sure that mdev doesn't go away while one of the attributes is
> accessed?

Good question. I suppose you mean that since mdev is devres-managed and
device_create_with_groups() apparently isn't aware of that, so there is no
internal lock somewhere that prevents read() or ioctl() being called while the
devres code is freeing the memory of mdev?

I will try to search for some example code to see how something like this is
handled in other places. I assume I'd need to add a per-mdev lock or use the
big motion_mtx everywhere... which sounds like a performance penalty that
should be avoidable. If you know of a good example to learn from, I'd be
grateful to know.

> > +	if (IS_ERR(mdev->dev)) {
> > +		dev_err(mdev->parent, "Error creating motion device %d\n",
> > +				mdev->minor);
> > +		mutex_unlock(&motion_mtx);
> > +		goto error_free_trig_info;
> > +	}
> > +	list_add_tail(&mdev->list, &motion_list);
> > +	mutex_unlock(&motion_mtx);
> > +
> > +	return 0;
> > +
> > +error_free_trig_info:
> > +	kfree(trig_info);
> > +error_free_trigger:
> > +	iio_trigger_free(mdev->iiotrig);
> > +error_free_minor:
> > +	motion_minor_free(mdev->minor);
> > +	dev_info(mdev->parent, "Registering motion device err=%d\n", err);
> > +	return err;
> > +}
> > +EXPORT_SYMBOL(motion_register_device);
> > [...]
> > +struct mot_capabilities {
> > +	__u32 features;
> > +	__u8 type;
> > +	__u8 num_channels;
> > +	__u8 num_int_triggers;
> > +	__u8 num_ext_triggers;
> > +	__u8 max_profiles;
> > +	__u8 max_vpoints;
> > +	__u8 max_apoints;
> > +	__u8 reserved1;
> > +	__u32 subdiv; /* Position unit sub-divisions, microsteps, etc... */
> > +	/*
> > +	 * Coefficients for converting to/from controller time <--> seconds.
> > +	 * Speed[1/s] = Speed[controller_units] * conv_mul / conv_div
> > +	 * Accel[1/s^2] = Accel[controller_units] * conv_mul / conv_div
> > +	 */
> > +	__u32 speed_conv_mul;
> > +	__u32 speed_conv_div;
> > +	__u32 accel_conv_mul;
> > +	__u32 accel_conv_div;
> > +	__u32 reserved2;
> > +};  
> 
> https://docs.kernel.org/gpu/imagination/uapi.html (which has some
> generic bits that apply here, too) has: "The overall struct must be
> padded to 64-bit alignment." If you drop reserved2 the struct is
> properly sized (or I counted wrongly).

Oh, thanks for pointing that out... I wouldn't have searched for that
information in that particular place tbh. ;-)

I am tempted to add another __u32 reserved3 though instead. Better to have
some leeway if something needs to be added in a backwards-compatible way later.

> > +struct mot_speed_duration {
> > +	__u32 channel;
> > +	speed_raw_t speed;  
> 
> What is the unit here?

Speed doesn't have a fixed unit in this case. Or rather, the unit is
device-dependent. For a motor it could be rotations per second, micro-steps per
second, etc... while for a linear actuator, it could be micrometers per second.

Why no fixed unit? That's because in practice many devices (controllers) have
their inherent base-unit, and it would get overly complicated if one needed to
convert back and forth between that and some universal unit just for the sake
of uniformity, and user-space most certainly expects the same unit as the
hardware device it was initially designed for. So in this case it is a design
decision to make user-space deal with unit-conversion if it is necessary to do
so.

> > +	mot_time_t duration;  
> 
> duration_ns? That makes usage much more ideomatic and there should be no
> doubts what the unit is.

Yes, mot_time_t is defined as nanoseconds, so I'll add the _ns suffix here.

> > +	pos_raw_t distance;  
> 
> What is the unit here?

Again this unit can have different meanings: micrometers, micro-steps,
angle-degrees, etc... so what suffix to use?

> > +	__u32 reserved[3];  
> 
> Again the padding is wrong here.

Will fix. thanks.
 
Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-03-05 15:40     ` David Jander
@ 2025-03-05 23:21       ` Uwe Kleine-König
  2025-03-06  7:18         ` Greg Kroah-Hartman
  2025-03-06  9:25         ` David Jander
  0 siblings, 2 replies; 59+ messages in thread
From: Uwe Kleine-König @ 2025-03-05 23:21 UTC (permalink / raw)
  To: David Jander
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel, Greg Kroah-Hartman

[-- Attachment #1: Type: text/plain, Size: 6782 bytes --]

Hello David,

On Wed, Mar 05, 2025 at 04:40:45PM +0100, David Jander wrote:
> On Fri, 28 Feb 2025 17:44:27 +0100
> Uwe Kleine-König <u.kleine-koenig@baylibre.com> wrote:
> > On Thu, Feb 27, 2025 at 05:28:17PM +0100, David Jander wrote:
> > [...]
> > > +static int motion_open(struct inode *inode, struct file *file)
> > > +{
> > > +	int minor = iminor(inode);
> > > +	struct motion_device *mdev = NULL, *iter;
> > > +	int err;
> > > +
> > > +	mutex_lock(&motion_mtx);  
> > 
> > If you use guard(), error handling gets a bit easier.
> 
> This looks interesting. I didn't know about guard(). Thanks. I see the
> benefits, but in some cases it also makes the locked region less clearly
> visible. While I agree that guard() in this particular place is nice,
> I'm hesitant to try and replace all mutex_lock()/_unlock() calls with guard().
> Let me know if my assessment of the intended use of guard() is incorrect.

I agree that guard() makes it harder for non-trivial functions to spot
the critical section. In my eyes this is outweight by not having to
unlock in all exit paths, but that might be subjective. Annother
downside of guard is that sparse doesn't understand it and reports
unbalanced locking.
 
> > > +	list_for_each_entry(iter, &motion_list, list) {
> > > +		if (iter->minor != minor)
> > > +			continue;
> > > +		mdev = iter;
> > > +		break;
> > > +	}  
> > 
> > This should be easier. If you use a cdev you can just do
> > container_of(inode->i_cdev, ...);
> 
> Hmm... I don't yet really understand what you mean. I will have to study the
> involved code a bit more.

The code that I'm convinced is correct is
https://lore.kernel.org/linux-pwm/00c9f1181dc351e1e6041ba6e41e4c30b12b6a27.1725635013.git.u.kleine-koenig@baylibre.com/

This isn't in mainline because there is some feedback I still have to
address, but I think it might serve as an example anyhow.

> > > [...]
> > > +
> > > +static const struct class motion_class = {
> > > +	.name		= "motion",
> > > +	.devnode	= motion_devnode,  
> > 
> > IIRC it's recommended to not create new classes, but a bus.
> 
> Interesting. I did some searching, and all I could find was that the chapter
> in driver-api/driver-model about classes magically vanished between versions
> 5.12 and 5.13. Does anyone know where I can find some information about this?
> Sorry if I'm being blind...

Half knowledge on my end at best. I would hope that Greg knows some
details (which might even be "no, classes are fine"). I added him to Cc:

> > [...]
> > > +	devt = MKDEV(motion_major, mdev->minor);
> > > +	mdev->dev = device_create_with_groups(&motion_class, mdev->parent,
> > > +				devt, mdev, mdev->groups, "motion%d", mdev->minor);  
> > 
> > What makes sure that mdev doesn't go away while one of the attributes is
> > accessed?
> 
> Good question. I suppose you mean that since mdev is devres-managed and
> device_create_with_groups() apparently isn't aware of that, so there is no
> internal lock somewhere that prevents read() or ioctl() being called while the
> devres code is freeing the memory of mdev?

I'm not sure there is an issue, but when I developed the above mentioned
patch it helped me to test these possible races. Just open the sysfs
file, unbind the device (or unload the module) and only then start
reading (or writing).

> > > +	if (IS_ERR(mdev->dev)) {
> > > +		dev_err(mdev->parent, "Error creating motion device %d\n",
> > > +				mdev->minor);
> > > +		mutex_unlock(&motion_mtx);
> > > +		goto error_free_trig_info;
> > > +	}
> > > +	list_add_tail(&mdev->list, &motion_list);
> > > +	mutex_unlock(&motion_mtx);
> > > +
> > > +	return 0;
> > > +
> > > +error_free_trig_info:
> > > +	kfree(trig_info);
> > > +error_free_trigger:
> > > +	iio_trigger_free(mdev->iiotrig);
> > > +error_free_minor:
> > > +	motion_minor_free(mdev->minor);
> > > +	dev_info(mdev->parent, "Registering motion device err=%d\n", err);
> > > +	return err;
> > > +}
> > > +EXPORT_SYMBOL(motion_register_device);
> > > [...]
> > > +struct mot_capabilities {
> > > +	__u32 features;
> > > +	__u8 type;
> > > +	__u8 num_channels;
> > > +	__u8 num_int_triggers;
> > > +	__u8 num_ext_triggers;
> > > +	__u8 max_profiles;
> > > +	__u8 max_vpoints;
> > > +	__u8 max_apoints;
> > > +	__u8 reserved1;
> > > +	__u32 subdiv; /* Position unit sub-divisions, microsteps, etc... */
> > > +	/*
> > > +	 * Coefficients for converting to/from controller time <--> seconds.
> > > +	 * Speed[1/s] = Speed[controller_units] * conv_mul / conv_div
> > > +	 * Accel[1/s^2] = Accel[controller_units] * conv_mul / conv_div
> > > +	 */
> > > +	__u32 speed_conv_mul;
> > > +	__u32 speed_conv_div;
> > > +	__u32 accel_conv_mul;
> > > +	__u32 accel_conv_div;
> > > +	__u32 reserved2;
> > > +};  
> > 
> > https://docs.kernel.org/gpu/imagination/uapi.html (which has some
> > generic bits that apply here, too) has: "The overall struct must be
> > padded to 64-bit alignment." If you drop reserved2 the struct is
> > properly sized (or I counted wrongly).
> 
> Oh, thanks for pointing that out... I wouldn't have searched for that
> information in that particular place tbh. ;-)
> 
> I am tempted to add another __u32 reserved3 though instead. Better to have
> some leeway if something needs to be added in a backwards-compatible way later.

Note that you don't need reserved fields at the end because in the
ioctl handler you know the size of the passed struct. So if the need to
add members to the struct arise, you can do that by checking for the
size. This is even more flexible because otherwise you can only add
fields that must be 0 when the old behaviour is intended. Most of the
time this is no problem. But only most.
 
> > > +struct mot_speed_duration {
> > > +	__u32 channel;
> > > +	speed_raw_t speed;  
> > 
> > What is the unit here?
> 
> Speed doesn't have a fixed unit in this case. Or rather, the unit is
> device-dependent. For a motor it could be rotations per second, micro-steps per
> second, etc... while for a linear actuator, it could be micrometers per second.
> 
> Why no fixed unit? That's because in practice many devices (controllers) have
> their inherent base-unit, and it would get overly complicated if one needed to
> convert back and forth between that and some universal unit just for the sake
> of uniformity, and user-space most certainly expects the same unit as the
> hardware device it was initially designed for. So in this case it is a design
> decision to make user-space deal with unit-conversion if it is necessary to do
> so.

Sad, so a userspace process still has to know some internal things about
the motor it drives. :-\

Best regards
Uwe

[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 488 bytes --]

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-03-05 23:21       ` Uwe Kleine-König
@ 2025-03-06  7:18         ` Greg Kroah-Hartman
  2025-03-06  8:20           ` David Jander
  2025-03-06  9:25         ` David Jander
  1 sibling, 1 reply; 59+ messages in thread
From: Greg Kroah-Hartman @ 2025-03-06  7:18 UTC (permalink / raw)
  To: Uwe Kleine-König
  Cc: David Jander, linux-kernel, linux-iio, Jonathan Corbet,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, devicetree,
	linux-doc, Nuno Sa, Jonathan Cameron, Oleksij Rempel

On Thu, Mar 06, 2025 at 12:21:22AM +0100, Uwe Kleine-König wrote:
> Hello David,
> 
> On Wed, Mar 05, 2025 at 04:40:45PM +0100, David Jander wrote:
> > On Fri, 28 Feb 2025 17:44:27 +0100
> > Uwe Kleine-König <u.kleine-koenig@baylibre.com> wrote:
> > > On Thu, Feb 27, 2025 at 05:28:17PM +0100, David Jander wrote:
> > > [...]
> > > > +static int motion_open(struct inode *inode, struct file *file)
> > > > +{
> > > > +	int minor = iminor(inode);
> > > > +	struct motion_device *mdev = NULL, *iter;
> > > > +	int err;
> > > > +
> > > > +	mutex_lock(&motion_mtx);  
> > > 
> > > If you use guard(), error handling gets a bit easier.
> > 
> > This looks interesting. I didn't know about guard(). Thanks. I see the
> > benefits, but in some cases it also makes the locked region less clearly
> > visible. While I agree that guard() in this particular place is nice,
> > I'm hesitant to try and replace all mutex_lock()/_unlock() calls with guard().
> > Let me know if my assessment of the intended use of guard() is incorrect.
> 
> I agree that guard() makes it harder for non-trivial functions to spot
> the critical section. In my eyes this is outweight by not having to
> unlock in all exit paths, but that might be subjective. Annother
> downside of guard is that sparse doesn't understand it and reports
> unbalanced locking.
>  
> > > > +	list_for_each_entry(iter, &motion_list, list) {
> > > > +		if (iter->minor != minor)
> > > > +			continue;
> > > > +		mdev = iter;
> > > > +		break;
> > > > +	}  
> > > 
> > > This should be easier. If you use a cdev you can just do
> > > container_of(inode->i_cdev, ...);
> > 
> > Hmm... I don't yet really understand what you mean. I will have to study the
> > involved code a bit more.
> 
> The code that I'm convinced is correct is
> https://lore.kernel.org/linux-pwm/00c9f1181dc351e1e6041ba6e41e4c30b12b6a27.1725635013.git.u.kleine-koenig@baylibre.com/
> 
> This isn't in mainline because there is some feedback I still have to
> address, but I think it might serve as an example anyhow.
> 
> > > > [...]
> > > > +
> > > > +static const struct class motion_class = {
> > > > +	.name		= "motion",
> > > > +	.devnode	= motion_devnode,  
> > > 
> > > IIRC it's recommended to not create new classes, but a bus.
> > 
> > Interesting. I did some searching, and all I could find was that the chapter
> > in driver-api/driver-model about classes magically vanished between versions
> > 5.12 and 5.13. Does anyone know where I can find some information about this?
> > Sorry if I'm being blind...
> 
> Half knowledge on my end at best. I would hope that Greg knows some
> details (which might even be "no, classes are fine"). I added him to Cc:

A class is there for when you have a common api that devices of
different types can talk to userspace (i.e. the UAPI is common, not the
hardware type).  Things like input devices, tty, disks, etc.  A bus is
there to be able to write different drivers to bind to for that hardware
bus type (pci, usb, i2c, platform, etc.)

So you need both, a bus to talk to the hardware, and a class to talk to
userspace in a common way (ignore the fact that we can also talk to
hardware directly from userspace like raw USB or i2c or PCI config
space, that's all bus-specific stuff).

Did that help?

thanks,

greg k-h

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-03-06  7:18         ` Greg Kroah-Hartman
@ 2025-03-06  8:20           ` David Jander
  2025-03-06  9:03             ` Greg Kroah-Hartman
  0 siblings, 1 reply; 59+ messages in thread
From: David Jander @ 2025-03-06  8:20 UTC (permalink / raw)
  To: Greg Kroah-Hartman
  Cc: Uwe Kleine-König, linux-kernel, linux-iio, Jonathan Corbet,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, devicetree,
	linux-doc, Nuno Sa, Jonathan Cameron, Oleksij Rempel

On Thu, 6 Mar 2025 08:18:46 +0100
Greg Kroah-Hartman <gregkh@linuxfoundation.org> wrote:

> On Thu, Mar 06, 2025 at 12:21:22AM +0100, Uwe Kleine-König wrote:
> > Hello David,
> > 
> > On Wed, Mar 05, 2025 at 04:40:45PM +0100, David Jander wrote:  
> > > On Fri, 28 Feb 2025 17:44:27 +0100
> > > Uwe Kleine-König <u.kleine-koenig@baylibre.com> wrote:  
> > > > On Thu, Feb 27, 2025 at 05:28:17PM +0100, David Jander wrote:
> > > > [...]  
> > > > > +static int motion_open(struct inode *inode, struct file *file)
> > > > > +{
> > > > > +	int minor = iminor(inode);
> > > > > +	struct motion_device *mdev = NULL, *iter;
> > > > > +	int err;
> > > > > +
> > > > > +	mutex_lock(&motion_mtx);    
> > > > 
> > > > If you use guard(), error handling gets a bit easier.  
> > > 
> > > This looks interesting. I didn't know about guard(). Thanks. I see the
> > > benefits, but in some cases it also makes the locked region less clearly
> > > visible. While I agree that guard() in this particular place is nice,
> > > I'm hesitant to try and replace all mutex_lock()/_unlock() calls with guard().
> > > Let me know if my assessment of the intended use of guard() is incorrect.  
> > 
> > I agree that guard() makes it harder for non-trivial functions to spot
> > the critical section. In my eyes this is outweight by not having to
> > unlock in all exit paths, but that might be subjective. Annother
> > downside of guard is that sparse doesn't understand it and reports
> > unbalanced locking.
> >    
> > > > > +	list_for_each_entry(iter, &motion_list, list) {
> > > > > +		if (iter->minor != minor)
> > > > > +			continue;
> > > > > +		mdev = iter;
> > > > > +		break;
> > > > > +	}    
> > > > 
> > > > This should be easier. If you use a cdev you can just do
> > > > container_of(inode->i_cdev, ...);  
> > > 
> > > Hmm... I don't yet really understand what you mean. I will have to study the
> > > involved code a bit more.  
> > 
> > The code that I'm convinced is correct is
> > https://lore.kernel.org/linux-pwm/00c9f1181dc351e1e6041ba6e41e4c30b12b6a27.1725635013.git.u.kleine-koenig@baylibre.com/
> > 
> > This isn't in mainline because there is some feedback I still have to
> > address, but I think it might serve as an example anyhow.
> >   
> > > > > [...]
> > > > > +
> > > > > +static const struct class motion_class = {
> > > > > +	.name		= "motion",
> > > > > +	.devnode	= motion_devnode,    
> > > > 
> > > > IIRC it's recommended to not create new classes, but a bus.  
> > > 
> > > Interesting. I did some searching, and all I could find was that the chapter
> > > in driver-api/driver-model about classes magically vanished between versions
> > > 5.12 and 5.13. Does anyone know where I can find some information about this?
> > > Sorry if I'm being blind...  
> > 
> > Half knowledge on my end at best. I would hope that Greg knows some
> > details (which might even be "no, classes are fine"). I added him to Cc:  
> 
> A class is there for when you have a common api that devices of
> different types can talk to userspace (i.e. the UAPI is common, not the
> hardware type).  Things like input devices, tty, disks, etc.  A bus is
> there to be able to write different drivers to bind to for that hardware
> bus type (pci, usb, i2c, platform, etc.)
> 
> So you need both, a bus to talk to the hardware, and a class to talk to
> userspace in a common way (ignore the fact that we can also talk to
> hardware directly from userspace like raw USB or i2c or PCI config
> space, that's all bus-specific stuff).

Thanks for chiming in. Let me see if I understand this correctly: In this
case, I have a UAPI that is common to different types of motion control
devices. So I need a class. check.

Do I need a bus? If one can conceive other drivers or kernel parts that talk to
motion drivers, I would need a bus. If that doesn't make sense, I don't. Right?

I actually can think of a new motion device that acts as an aggregator of
several single-channel motion devices into a single "virtual" multi-channel
device... so do I need also a bus? I suppose...?

Then the question remains: why did the chapter about classes vanish?

Best regards,

-- 
David Jander


^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-03-06  8:20           ` David Jander
@ 2025-03-06  9:03             ` Greg Kroah-Hartman
  2025-03-06  9:34               ` David Jander
  0 siblings, 1 reply; 59+ messages in thread
From: Greg Kroah-Hartman @ 2025-03-06  9:03 UTC (permalink / raw)
  To: David Jander
  Cc: Uwe Kleine-König, linux-kernel, linux-iio, Jonathan Corbet,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, devicetree,
	linux-doc, Nuno Sa, Jonathan Cameron, Oleksij Rempel

On Thu, Mar 06, 2025 at 09:20:13AM +0100, David Jander wrote:
> On Thu, 6 Mar 2025 08:18:46 +0100
> Greg Kroah-Hartman <gregkh@linuxfoundation.org> wrote:
> 
> > On Thu, Mar 06, 2025 at 12:21:22AM +0100, Uwe Kleine-König wrote:
> > > Hello David,
> > > 
> > > On Wed, Mar 05, 2025 at 04:40:45PM +0100, David Jander wrote:  
> > > > On Fri, 28 Feb 2025 17:44:27 +0100
> > > > Uwe Kleine-König <u.kleine-koenig@baylibre.com> wrote:  
> > > > > On Thu, Feb 27, 2025 at 05:28:17PM +0100, David Jander wrote:
> > > > > [...]  
> > > > > > +static int motion_open(struct inode *inode, struct file *file)
> > > > > > +{
> > > > > > +	int minor = iminor(inode);
> > > > > > +	struct motion_device *mdev = NULL, *iter;
> > > > > > +	int err;
> > > > > > +
> > > > > > +	mutex_lock(&motion_mtx);    
> > > > > 
> > > > > If you use guard(), error handling gets a bit easier.  
> > > > 
> > > > This looks interesting. I didn't know about guard(). Thanks. I see the
> > > > benefits, but in some cases it also makes the locked region less clearly
> > > > visible. While I agree that guard() in this particular place is nice,
> > > > I'm hesitant to try and replace all mutex_lock()/_unlock() calls with guard().
> > > > Let me know if my assessment of the intended use of guard() is incorrect.  
> > > 
> > > I agree that guard() makes it harder for non-trivial functions to spot
> > > the critical section. In my eyes this is outweight by not having to
> > > unlock in all exit paths, but that might be subjective. Annother
> > > downside of guard is that sparse doesn't understand it and reports
> > > unbalanced locking.
> > >    
> > > > > > +	list_for_each_entry(iter, &motion_list, list) {
> > > > > > +		if (iter->minor != minor)
> > > > > > +			continue;
> > > > > > +		mdev = iter;
> > > > > > +		break;
> > > > > > +	}    
> > > > > 
> > > > > This should be easier. If you use a cdev you can just do
> > > > > container_of(inode->i_cdev, ...);  
> > > > 
> > > > Hmm... I don't yet really understand what you mean. I will have to study the
> > > > involved code a bit more.  
> > > 
> > > The code that I'm convinced is correct is
> > > https://lore.kernel.org/linux-pwm/00c9f1181dc351e1e6041ba6e41e4c30b12b6a27.1725635013.git.u.kleine-koenig@baylibre.com/
> > > 
> > > This isn't in mainline because there is some feedback I still have to
> > > address, but I think it might serve as an example anyhow.
> > >   
> > > > > > [...]
> > > > > > +
> > > > > > +static const struct class motion_class = {
> > > > > > +	.name		= "motion",
> > > > > > +	.devnode	= motion_devnode,    
> > > > > 
> > > > > IIRC it's recommended to not create new classes, but a bus.  
> > > > 
> > > > Interesting. I did some searching, and all I could find was that the chapter
> > > > in driver-api/driver-model about classes magically vanished between versions
> > > > 5.12 and 5.13. Does anyone know where I can find some information about this?
> > > > Sorry if I'm being blind...  
> > > 
> > > Half knowledge on my end at best. I would hope that Greg knows some
> > > details (which might even be "no, classes are fine"). I added him to Cc:  
> > 
> > A class is there for when you have a common api that devices of
> > different types can talk to userspace (i.e. the UAPI is common, not the
> > hardware type).  Things like input devices, tty, disks, etc.  A bus is
> > there to be able to write different drivers to bind to for that hardware
> > bus type (pci, usb, i2c, platform, etc.)
> > 
> > So you need both, a bus to talk to the hardware, and a class to talk to
> > userspace in a common way (ignore the fact that we can also talk to
> > hardware directly from userspace like raw USB or i2c or PCI config
> > space, that's all bus-specific stuff).
> 
> Thanks for chiming in. Let me see if I understand this correctly: In this
> case, I have a UAPI that is common to different types of motion control
> devices. So I need a class. check.

Correct.

> Do I need a bus? If one can conceive other drivers or kernel parts that talk to
> motion drivers, I would need a bus. If that doesn't make sense, I don't. Right?

Correct.

> I actually can think of a new motion device that acts as an aggregator of
> several single-channel motion devices into a single "virtual" multi-channel
> device... so do I need also a bus? I suppose...?

Nope, that should just be another class driver.  Think about how input
does this, some input /dev/ nodes are the sum of ALL input /dev/ nodes
together, while others are just for individual input devices.

> Then the question remains: why did the chapter about classes vanish?

What are you specifically referring to?  I don't remember deleting any
documentation, did files move around somehow and the links not get
updated?

thanks,

greg k-h

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-03-05 23:21       ` Uwe Kleine-König
  2025-03-06  7:18         ` Greg Kroah-Hartman
@ 2025-03-06  9:25         ` David Jander
  2025-03-09 17:32           ` Jonathan Cameron
  1 sibling, 1 reply; 59+ messages in thread
From: David Jander @ 2025-03-06  9:25 UTC (permalink / raw)
  To: Uwe Kleine-König
  Cc: linux-kernel, linux-iio, Jonathan Corbet, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, devicetree, linux-doc, Nuno Sa,
	Jonathan Cameron, Oleksij Rempel, Greg Kroah-Hartman

On Thu, 6 Mar 2025 00:21:22 +0100
Uwe Kleine-König <u.kleine-koenig@baylibre.com> wrote:

> Hello David,
> 
> On Wed, Mar 05, 2025 at 04:40:45PM +0100, David Jander wrote:
> > On Fri, 28 Feb 2025 17:44:27 +0100
> > Uwe Kleine-König <u.kleine-koenig@baylibre.com> wrote:  
> > > On Thu, Feb 27, 2025 at 05:28:17PM +0100, David Jander wrote:
> > > [...]  
> > > > +static int motion_open(struct inode *inode, struct file *file)
> > > > +{
> > > > +	int minor = iminor(inode);
> > > > +	struct motion_device *mdev = NULL, *iter;
> > > > +	int err;
> > > > +
> > > > +	mutex_lock(&motion_mtx);    
> > > 
> > > If you use guard(), error handling gets a bit easier.  
> > 
> > This looks interesting. I didn't know about guard(). Thanks. I see the
> > benefits, but in some cases it also makes the locked region less clearly
> > visible. While I agree that guard() in this particular place is nice,
> > I'm hesitant to try and replace all mutex_lock()/_unlock() calls with guard().
> > Let me know if my assessment of the intended use of guard() is incorrect.  
> 
> I agree that guard() makes it harder for non-trivial functions to spot
> the critical section. In my eyes this is outweight by not having to
> unlock in all exit paths, but that might be subjective. Annother
> downside of guard is that sparse doesn't understand it and reports
> unbalanced locking.

What I was referring to, and what I want to know is, is it okay to mix guard()
with lock/unlock? I.e. Use guard() when there are multiple exit paths involved
and revert back to simple lock/unlock if it is just to encase a handful of
non-exiting operations?

> > > > +	list_for_each_entry(iter, &motion_list, list) {
> > > > +		if (iter->minor != minor)
> > > > +			continue;
> > > > +		mdev = iter;
> > > > +		break;
> > > > +	}    
> > > 
> > > This should be easier. If you use a cdev you can just do
> > > container_of(inode->i_cdev, ...);  
> > 
> > Hmm... I don't yet really understand what you mean. I will have to study the
> > involved code a bit more.  
> 
> The code that I'm convinced is correct is
> https://lore.kernel.org/linux-pwm/00c9f1181dc351e1e6041ba6e41e4c30b12b6a27.1725635013.git.u.kleine-koenig@baylibre.com/
> 
> This isn't in mainline because there is some feedback I still have to
> address, but I think it might serve as an example anyhow.

Thanks. I will study this example.

> > > > [...]
> > > > +
> > > > +static const struct class motion_class = {
> > > > +	.name		= "motion",
> > > > +	.devnode	= motion_devnode,    
> > > 
> > > IIRC it's recommended to not create new classes, but a bus.  
> > 
> > Interesting. I did some searching, and all I could find was that the chapter
> > in driver-api/driver-model about classes magically vanished between versions
> > 5.12 and 5.13. Does anyone know where I can find some information about this?
> > Sorry if I'm being blind...  
> 
> Half knowledge on my end at best. I would hope that Greg knows some
> details (which might even be "no, classes are fine"). I added him to Cc:
> 
> > > [...]  
> > > > +	devt = MKDEV(motion_major, mdev->minor);
> > > > +	mdev->dev = device_create_with_groups(&motion_class, mdev->parent,
> > > > +				devt, mdev, mdev->groups, "motion%d", mdev->minor);    
> > > 
> > > What makes sure that mdev doesn't go away while one of the attributes is
> > > accessed?  
> > 
> > Good question. I suppose you mean that since mdev is devres-managed and
> > device_create_with_groups() apparently isn't aware of that, so there is no
> > internal lock somewhere that prevents read() or ioctl() being called while the
> > devres code is freeing the memory of mdev?  
> 
> I'm not sure there is an issue, but when I developed the above mentioned
> patch it helped me to test these possible races. Just open the sysfs
> file, unbind the device (or unload the module) and only then start
> reading (or writing).

Will check this. Thanks.

> > > > +	if (IS_ERR(mdev->dev)) {
> > > > +		dev_err(mdev->parent, "Error creating motion device %d\n",
> > > > +				mdev->minor);
> > > > +		mutex_unlock(&motion_mtx);
> > > > +		goto error_free_trig_info;
> > > > +	}
> > > > +	list_add_tail(&mdev->list, &motion_list);
> > > > +	mutex_unlock(&motion_mtx);
> > > > +
> > > > +	return 0;
> > > > +
> > > > +error_free_trig_info:
> > > > +	kfree(trig_info);
> > > > +error_free_trigger:
> > > > +	iio_trigger_free(mdev->iiotrig);
> > > > +error_free_minor:
> > > > +	motion_minor_free(mdev->minor);
> > > > +	dev_info(mdev->parent, "Registering motion device err=%d\n", err);
> > > > +	return err;
> > > > +}
> > > > +EXPORT_SYMBOL(motion_register_device);
> > > > [...]
> > > > +struct mot_capabilities {
> > > > +	__u32 features;
> > > > +	__u8 type;
> > > > +	__u8 num_channels;
> > > > +	__u8 num_int_triggers;
> > > > +	__u8 num_ext_triggers;
> > > > +	__u8 max_profiles;
> > > > +	__u8 max_vpoints;
> > > > +	__u8 max_apoints;
> > > > +	__u8 reserved1;
> > > > +	__u32 subdiv; /* Position unit sub-divisions, microsteps, etc... */
> > > > +	/*
> > > > +	 * Coefficients for converting to/from controller time <--> seconds.
> > > > +	 * Speed[1/s] = Speed[controller_units] * conv_mul / conv_div
> > > > +	 * Accel[1/s^2] = Accel[controller_units] * conv_mul / conv_div
> > > > +	 */
> > > > +	__u32 speed_conv_mul;
> > > > +	__u32 speed_conv_div;
> > > > +	__u32 accel_conv_mul;
> > > > +	__u32 accel_conv_div;
> > > > +	__u32 reserved2;
> > > > +};    
> > > 
> > > https://docs.kernel.org/gpu/imagination/uapi.html (which has some
> > > generic bits that apply here, too) has: "The overall struct must be
> > > padded to 64-bit alignment." If you drop reserved2 the struct is
> > > properly sized (or I counted wrongly).  
> > 
> > Oh, thanks for pointing that out... I wouldn't have searched for that
> > information in that particular place tbh. ;-)
> > 
> > I am tempted to add another __u32 reserved3 though instead. Better to have
> > some leeway if something needs to be added in a backwards-compatible way later.  
> 
> Note that you don't need reserved fields at the end because in the
> ioctl handler you know the size of the passed struct. So if the need to
> add members to the struct arise, you can do that by checking for the
> size. This is even more flexible because otherwise you can only add
> fields that must be 0 when the old behaviour is intended. Most of the
> time this is no problem. But only most.

You are right. Thanks.

> > > > +struct mot_speed_duration {
> > > > +	__u32 channel;
> > > > +	speed_raw_t speed;    
> > > 
> > > What is the unit here?  
> > 
> > Speed doesn't have a fixed unit in this case. Or rather, the unit is
> > device-dependent. For a motor it could be rotations per second, micro-steps per
> > second, etc... while for a linear actuator, it could be micrometers per second.
> > 
> > Why no fixed unit? That's because in practice many devices (controllers) have
> > their inherent base-unit, and it would get overly complicated if one needed to
> > convert back and forth between that and some universal unit just for the sake
> > of uniformity, and user-space most certainly expects the same unit as the
> > hardware device it was initially designed for. So in this case it is a design
> > decision to make user-space deal with unit-conversion if it is necessary to do
> > so.  
> 
> Sad, so a userspace process still has to know some internal things about
> the motor it drives. :-\

Unfortunately that is almost impossible to avoid entirely.
You can replace one stepper motor driver with another that might have
different micro-stepping subdivision, by looking at struct
mot_capabilities.subdiv, but a simple brushed DC motor just isn't able to
replace a stepper motor in all but the most trivial applications. I also think
that burdening the kernel with all sorts of complicated math to model the
mechanical conversion factors involved in anything that's connected to the
motor drive shaft is overkill. As well as trying to emulate all missing
capabilities from a motion device that is lacking that functionality natively.

So just like in IIO you cannot just replace one ADC with any other, in LMC you
also cannot replace any device with any other.

That's why there is struct mot_capabilities and MOT_IOCTL_GET_CAPA. It enables
user-space to optionally support different devices more easily. It is probably
best used in conjunction with a LMC user-space library, although I don't want
to rely on such a library for being able to use LMC. There is some middle
ground here I guess... just like in IIO.

One thing I could try to improve though, is to include some additional
information in struct mot_capabilities that tells something more about the
nature of the used units, just like the speed_conv and accel_conv constants do
for time conversion. Something that can be placed in the device tree (possibly
in a motor child-node connected to the motor-controller) that contains some
conversion constant for distance. That way, if one were to (for example)
replace a stepper motor with a BLDC motor + encoder in a new hardware
revision, this constant could be used to make the units backwards compatible.

As background information: A stepper motor controller counts distance in steps
and/or micro-steps. There are mot_capabilities.subdiv micro-steps in each
step. The amount of angle the actual motor shaft advances with each whole step
depends on the motor construction and is often 200 steps per revolution (1.8
degrees), but can vary from 4 to 400 steps per revolution depending on the
motor. So it is not only the controller that matters but also the type of
motor. This suggests the need of motor sub-nodes in the device-tree if one
wanted to extend the hardware knowledge further down from the motor driver.
But then there are gear boxes, pulleys, etc... it's basically conversion
factors all the way down. How many of them is sensible to bother the kernel
with?

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-03-06  9:03             ` Greg Kroah-Hartman
@ 2025-03-06  9:34               ` David Jander
  2025-03-06 13:39                 ` Greg Kroah-Hartman
  0 siblings, 1 reply; 59+ messages in thread
From: David Jander @ 2025-03-06  9:34 UTC (permalink / raw)
  To: Greg Kroah-Hartman
  Cc: Uwe Kleine-König, linux-kernel, linux-iio, Jonathan Corbet,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, devicetree,
	linux-doc, Nuno Sa, Jonathan Cameron, Oleksij Rempel

On Thu, 6 Mar 2025 10:03:26 +0100
Greg Kroah-Hartman <gregkh@linuxfoundation.org> wrote:

> On Thu, Mar 06, 2025 at 09:20:13AM +0100, David Jander wrote:
> > On Thu, 6 Mar 2025 08:18:46 +0100
> > Greg Kroah-Hartman <gregkh@linuxfoundation.org> wrote:
> >   
> > > On Thu, Mar 06, 2025 at 12:21:22AM +0100, Uwe Kleine-König wrote:  
> > > > Hello David,
> > > > 
> > > > On Wed, Mar 05, 2025 at 04:40:45PM +0100, David Jander wrote:    
> > > > > On Fri, 28 Feb 2025 17:44:27 +0100
> > > > > Uwe Kleine-König <u.kleine-koenig@baylibre.com> wrote:    
> > > > > > On Thu, Feb 27, 2025 at 05:28:17PM +0100, David Jander wrote:
> > > > > > [...]    
> > > > > > > +static int motion_open(struct inode *inode, struct file *file)
> > > > > > > +{
> > > > > > > +	int minor = iminor(inode);
> > > > > > > +	struct motion_device *mdev = NULL, *iter;
> > > > > > > +	int err;
> > > > > > > +
> > > > > > > +	mutex_lock(&motion_mtx);      
> > > > > > 
> > > > > > If you use guard(), error handling gets a bit easier.    
> > > > > 
> > > > > This looks interesting. I didn't know about guard(). Thanks. I see the
> > > > > benefits, but in some cases it also makes the locked region less clearly
> > > > > visible. While I agree that guard() in this particular place is nice,
> > > > > I'm hesitant to try and replace all mutex_lock()/_unlock() calls with guard().
> > > > > Let me know if my assessment of the intended use of guard() is incorrect.    
> > > > 
> > > > I agree that guard() makes it harder for non-trivial functions to spot
> > > > the critical section. In my eyes this is outweight by not having to
> > > > unlock in all exit paths, but that might be subjective. Annother
> > > > downside of guard is that sparse doesn't understand it and reports
> > > > unbalanced locking.
> > > >      
> > > > > > > +	list_for_each_entry(iter, &motion_list, list) {
> > > > > > > +		if (iter->minor != minor)
> > > > > > > +			continue;
> > > > > > > +		mdev = iter;
> > > > > > > +		break;
> > > > > > > +	}      
> > > > > > 
> > > > > > This should be easier. If you use a cdev you can just do
> > > > > > container_of(inode->i_cdev, ...);    
> > > > > 
> > > > > Hmm... I don't yet really understand what you mean. I will have to study the
> > > > > involved code a bit more.    
> > > > 
> > > > The code that I'm convinced is correct is
> > > > https://lore.kernel.org/linux-pwm/00c9f1181dc351e1e6041ba6e41e4c30b12b6a27.1725635013.git.u.kleine-koenig@baylibre.com/
> > > > 
> > > > This isn't in mainline because there is some feedback I still have to
> > > > address, but I think it might serve as an example anyhow.
> > > >     
> > > > > > > [...]
> > > > > > > +
> > > > > > > +static const struct class motion_class = {
> > > > > > > +	.name		= "motion",
> > > > > > > +	.devnode	= motion_devnode,      
> > > > > > 
> > > > > > IIRC it's recommended to not create new classes, but a bus.    
> > > > > 
> > > > > Interesting. I did some searching, and all I could find was that the chapter
> > > > > in driver-api/driver-model about classes magically vanished between versions
> > > > > 5.12 and 5.13. Does anyone know where I can find some information about this?
> > > > > Sorry if I'm being blind...    
> > > > 
> > > > Half knowledge on my end at best. I would hope that Greg knows some
> > > > details (which might even be "no, classes are fine"). I added him to Cc:    
> > > 
> > > A class is there for when you have a common api that devices of
> > > different types can talk to userspace (i.e. the UAPI is common, not the
> > > hardware type).  Things like input devices, tty, disks, etc.  A bus is
> > > there to be able to write different drivers to bind to for that hardware
> > > bus type (pci, usb, i2c, platform, etc.)
> > > 
> > > So you need both, a bus to talk to the hardware, and a class to talk to
> > > userspace in a common way (ignore the fact that we can also talk to
> > > hardware directly from userspace like raw USB or i2c or PCI config
> > > space, that's all bus-specific stuff).  
> > 
> > Thanks for chiming in. Let me see if I understand this correctly: In this
> > case, I have a UAPI that is common to different types of motion control
> > devices. So I need a class. check.  
> 
> Correct.
> 
> > Do I need a bus? If one can conceive other drivers or kernel parts that talk to
> > motion drivers, I would need a bus. If that doesn't make sense, I don't. Right?  
> 
> Correct.
> 
> > I actually can think of a new motion device that acts as an aggregator of
> > several single-channel motion devices into a single "virtual" multi-channel
> > device... so do I need also a bus? I suppose...?  
> 
> Nope, that should just be another class driver.  Think about how input
> does this, some input /dev/ nodes are the sum of ALL input /dev/ nodes
> together, while others are just for individual input devices.

Understood. Thanks!

> > Then the question remains: why did the chapter about classes vanish?  
> 
> What are you specifically referring to?  I don't remember deleting any
> documentation, did files move around somehow and the links not get
> updated?

This:
https://www.kernel.org/doc/html/v5.12/driver-api/driver-model/index.html

vs this:
https://www.kernel.org/doc/html/v5.13/driver-api/driver-model/index.html

Maybe it moved somewhere else, but I can't find it... I'd have to git bisect
or git blame between the two releases maybe.

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-03-06  9:34               ` David Jander
@ 2025-03-06 13:39                 ` Greg Kroah-Hartman
  2025-03-06 14:25                   ` David Jander
  0 siblings, 1 reply; 59+ messages in thread
From: Greg Kroah-Hartman @ 2025-03-06 13:39 UTC (permalink / raw)
  To: David Jander
  Cc: Uwe Kleine-König, linux-kernel, linux-iio, Jonathan Corbet,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, devicetree,
	linux-doc, Nuno Sa, Jonathan Cameron, Oleksij Rempel

On Thu, Mar 06, 2025 at 10:34:02AM +0100, David Jander wrote:
> On Thu, 6 Mar 2025 10:03:26 +0100
> Greg Kroah-Hartman <gregkh@linuxfoundation.org> wrote:
> 
> > On Thu, Mar 06, 2025 at 09:20:13AM +0100, David Jander wrote:
> > > On Thu, 6 Mar 2025 08:18:46 +0100
> > > Greg Kroah-Hartman <gregkh@linuxfoundation.org> wrote:
> > >   
> > > > On Thu, Mar 06, 2025 at 12:21:22AM +0100, Uwe Kleine-König wrote:  
> > > > > Hello David,
> > > > > 
> > > > > On Wed, Mar 05, 2025 at 04:40:45PM +0100, David Jander wrote:    
> > > > > > On Fri, 28 Feb 2025 17:44:27 +0100
> > > > > > Uwe Kleine-König <u.kleine-koenig@baylibre.com> wrote:    
> > > > > > > On Thu, Feb 27, 2025 at 05:28:17PM +0100, David Jander wrote:
> > > > > > > [...]    
> > > > > > > > +static int motion_open(struct inode *inode, struct file *file)
> > > > > > > > +{
> > > > > > > > +	int minor = iminor(inode);
> > > > > > > > +	struct motion_device *mdev = NULL, *iter;
> > > > > > > > +	int err;
> > > > > > > > +
> > > > > > > > +	mutex_lock(&motion_mtx);      
> > > > > > > 
> > > > > > > If you use guard(), error handling gets a bit easier.    
> > > > > > 
> > > > > > This looks interesting. I didn't know about guard(). Thanks. I see the
> > > > > > benefits, but in some cases it also makes the locked region less clearly
> > > > > > visible. While I agree that guard() in this particular place is nice,
> > > > > > I'm hesitant to try and replace all mutex_lock()/_unlock() calls with guard().
> > > > > > Let me know if my assessment of the intended use of guard() is incorrect.    
> > > > > 
> > > > > I agree that guard() makes it harder for non-trivial functions to spot
> > > > > the critical section. In my eyes this is outweight by not having to
> > > > > unlock in all exit paths, but that might be subjective. Annother
> > > > > downside of guard is that sparse doesn't understand it and reports
> > > > > unbalanced locking.
> > > > >      
> > > > > > > > +	list_for_each_entry(iter, &motion_list, list) {
> > > > > > > > +		if (iter->minor != minor)
> > > > > > > > +			continue;
> > > > > > > > +		mdev = iter;
> > > > > > > > +		break;
> > > > > > > > +	}      
> > > > > > > 
> > > > > > > This should be easier. If you use a cdev you can just do
> > > > > > > container_of(inode->i_cdev, ...);    
> > > > > > 
> > > > > > Hmm... I don't yet really understand what you mean. I will have to study the
> > > > > > involved code a bit more.    
> > > > > 
> > > > > The code that I'm convinced is correct is
> > > > > https://lore.kernel.org/linux-pwm/00c9f1181dc351e1e6041ba6e41e4c30b12b6a27.1725635013.git.u.kleine-koenig@baylibre.com/
> > > > > 
> > > > > This isn't in mainline because there is some feedback I still have to
> > > > > address, but I think it might serve as an example anyhow.
> > > > >     
> > > > > > > > [...]
> > > > > > > > +
> > > > > > > > +static const struct class motion_class = {
> > > > > > > > +	.name		= "motion",
> > > > > > > > +	.devnode	= motion_devnode,      
> > > > > > > 
> > > > > > > IIRC it's recommended to not create new classes, but a bus.    
> > > > > > 
> > > > > > Interesting. I did some searching, and all I could find was that the chapter
> > > > > > in driver-api/driver-model about classes magically vanished between versions
> > > > > > 5.12 and 5.13. Does anyone know where I can find some information about this?
> > > > > > Sorry if I'm being blind...    
> > > > > 
> > > > > Half knowledge on my end at best. I would hope that Greg knows some
> > > > > details (which might even be "no, classes are fine"). I added him to Cc:    
> > > > 
> > > > A class is there for when you have a common api that devices of
> > > > different types can talk to userspace (i.e. the UAPI is common, not the
> > > > hardware type).  Things like input devices, tty, disks, etc.  A bus is
> > > > there to be able to write different drivers to bind to for that hardware
> > > > bus type (pci, usb, i2c, platform, etc.)
> > > > 
> > > > So you need both, a bus to talk to the hardware, and a class to talk to
> > > > userspace in a common way (ignore the fact that we can also talk to
> > > > hardware directly from userspace like raw USB or i2c or PCI config
> > > > space, that's all bus-specific stuff).  
> > > 
> > > Thanks for chiming in. Let me see if I understand this correctly: In this
> > > case, I have a UAPI that is common to different types of motion control
> > > devices. So I need a class. check.  
> > 
> > Correct.
> > 
> > > Do I need a bus? If one can conceive other drivers or kernel parts that talk to
> > > motion drivers, I would need a bus. If that doesn't make sense, I don't. Right?  
> > 
> > Correct.
> > 
> > > I actually can think of a new motion device that acts as an aggregator of
> > > several single-channel motion devices into a single "virtual" multi-channel
> > > device... so do I need also a bus? I suppose...?  
> > 
> > Nope, that should just be another class driver.  Think about how input
> > does this, some input /dev/ nodes are the sum of ALL input /dev/ nodes
> > together, while others are just for individual input devices.
> 
> Understood. Thanks!
> 
> > > Then the question remains: why did the chapter about classes vanish?  
> > 
> > What are you specifically referring to?  I don't remember deleting any
> > documentation, did files move around somehow and the links not get
> > updated?
> 
> This:
> https://www.kernel.org/doc/html/v5.12/driver-api/driver-model/index.html
> 
> vs this:
> https://www.kernel.org/doc/html/v5.13/driver-api/driver-model/index.html
> 
> Maybe it moved somewhere else, but I can't find it... I'd have to git bisect
> or git blame between the two releases maybe.

Ah, this was removed in:
	1364c6787525 ("docs: driver-model: Remove obsolete device class documentation")
as the information there was totally incorrect, since the 2.5.69 kernel
release.  "device classes" aren't a thing, "classes" are a thing :)

thanks,

greg k-h

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-03-06 13:39                 ` Greg Kroah-Hartman
@ 2025-03-06 14:25                   ` David Jander
  2025-03-06 14:54                     ` Greg Kroah-Hartman
  0 siblings, 1 reply; 59+ messages in thread
From: David Jander @ 2025-03-06 14:25 UTC (permalink / raw)
  To: Greg Kroah-Hartman
  Cc: Uwe Kleine-König, linux-kernel, linux-iio, Jonathan Corbet,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, devicetree,
	linux-doc, Nuno Sa, Jonathan Cameron, Oleksij Rempel

On Thu, 6 Mar 2025 14:39:16 +0100
Greg Kroah-Hartman <gregkh@linuxfoundation.org> wrote:

> On Thu, Mar 06, 2025 at 10:34:02AM +0100, David Jander wrote:
> > On Thu, 6 Mar 2025 10:03:26 +0100
> > Greg Kroah-Hartman <gregkh@linuxfoundation.org> wrote:
> >   
> > > On Thu, Mar 06, 2025 at 09:20:13AM +0100, David Jander wrote:  
> > > > On Thu, 6 Mar 2025 08:18:46 +0100
> > > > Greg Kroah-Hartman <gregkh@linuxfoundation.org> wrote:
> > > >     
> > > > > On Thu, Mar 06, 2025 at 12:21:22AM +0100, Uwe Kleine-König wrote:    
> > > > > > Hello David,
> > > > > > 
> > > > > > On Wed, Mar 05, 2025 at 04:40:45PM +0100, David Jander wrote:      
> > > > > > > On Fri, 28 Feb 2025 17:44:27 +0100
> > > > > > > Uwe Kleine-König <u.kleine-koenig@baylibre.com> wrote:      
> > > > > > > > On Thu, Feb 27, 2025 at 05:28:17PM +0100, David Jander wrote:
> > > > > > > > [...]      
> > > > > > > > > +static int motion_open(struct inode *inode, struct file *file)
> > > > > > > > > +{
> > > > > > > > > +	int minor = iminor(inode);
> > > > > > > > > +	struct motion_device *mdev = NULL, *iter;
> > > > > > > > > +	int err;
> > > > > > > > > +
> > > > > > > > > +	mutex_lock(&motion_mtx);        
> > > > > > > > 
> > > > > > > > If you use guard(), error handling gets a bit easier.      
> > > > > > > 
> > > > > > > This looks interesting. I didn't know about guard(). Thanks. I see the
> > > > > > > benefits, but in some cases it also makes the locked region less clearly
> > > > > > > visible. While I agree that guard() in this particular place is nice,
> > > > > > > I'm hesitant to try and replace all mutex_lock()/_unlock() calls with guard().
> > > > > > > Let me know if my assessment of the intended use of guard() is incorrect.      
> > > > > > 
> > > > > > I agree that guard() makes it harder for non-trivial functions to spot
> > > > > > the critical section. In my eyes this is outweight by not having to
> > > > > > unlock in all exit paths, but that might be subjective. Annother
> > > > > > downside of guard is that sparse doesn't understand it and reports
> > > > > > unbalanced locking.
> > > > > >        
> > > > > > > > > +	list_for_each_entry(iter, &motion_list, list) {
> > > > > > > > > +		if (iter->minor != minor)
> > > > > > > > > +			continue;
> > > > > > > > > +		mdev = iter;
> > > > > > > > > +		break;
> > > > > > > > > +	}        
> > > > > > > > 
> > > > > > > > This should be easier. If you use a cdev you can just do
> > > > > > > > container_of(inode->i_cdev, ...);      
> > > > > > > 
> > > > > > > Hmm... I don't yet really understand what you mean. I will have to study the
> > > > > > > involved code a bit more.      
> > > > > > 
> > > > > > The code that I'm convinced is correct is
> > > > > > https://lore.kernel.org/linux-pwm/00c9f1181dc351e1e6041ba6e41e4c30b12b6a27.1725635013.git.u.kleine-koenig@baylibre.com/
> > > > > > 
> > > > > > This isn't in mainline because there is some feedback I still have to
> > > > > > address, but I think it might serve as an example anyhow.
> > > > > >       
> > > > > > > > > [...]
> > > > > > > > > +
> > > > > > > > > +static const struct class motion_class = {
> > > > > > > > > +	.name		= "motion",
> > > > > > > > > +	.devnode	= motion_devnode,        
> > > > > > > > 
> > > > > > > > IIRC it's recommended to not create new classes, but a bus.      
> > > > > > > 
> > > > > > > Interesting. I did some searching, and all I could find was that the chapter
> > > > > > > in driver-api/driver-model about classes magically vanished between versions
> > > > > > > 5.12 and 5.13. Does anyone know where I can find some information about this?
> > > > > > > Sorry if I'm being blind...      
> > > > > > 
> > > > > > Half knowledge on my end at best. I would hope that Greg knows some
> > > > > > details (which might even be "no, classes are fine"). I added him to Cc:      
> > > > > 
> > > > > A class is there for when you have a common api that devices of
> > > > > different types can talk to userspace (i.e. the UAPI is common, not the
> > > > > hardware type).  Things like input devices, tty, disks, etc.  A bus is
> > > > > there to be able to write different drivers to bind to for that hardware
> > > > > bus type (pci, usb, i2c, platform, etc.)
> > > > > 
> > > > > So you need both, a bus to talk to the hardware, and a class to talk to
> > > > > userspace in a common way (ignore the fact that we can also talk to
> > > > > hardware directly from userspace like raw USB or i2c or PCI config
> > > > > space, that's all bus-specific stuff).    
> > > > 
> > > > Thanks for chiming in. Let me see if I understand this correctly: In this
> > > > case, I have a UAPI that is common to different types of motion control
> > > > devices. So I need a class. check.    
> > > 
> > > Correct.
> > >   
> > > > Do I need a bus? If one can conceive other drivers or kernel parts that talk to
> > > > motion drivers, I would need a bus. If that doesn't make sense, I don't. Right?    
> > > 
> > > Correct.
> > >   
> > > > I actually can think of a new motion device that acts as an aggregator of
> > > > several single-channel motion devices into a single "virtual" multi-channel
> > > > device... so do I need also a bus? I suppose...?    
> > > 
> > > Nope, that should just be another class driver.  Think about how input
> > > does this, some input /dev/ nodes are the sum of ALL input /dev/ nodes
> > > together, while others are just for individual input devices.  
> > 
> > Understood. Thanks!
> >   
> > > > Then the question remains: why did the chapter about classes vanish?    
> > > 
> > > What are you specifically referring to?  I don't remember deleting any
> > > documentation, did files move around somehow and the links not get
> > > updated?  
> > 
> > This:
> > https://www.kernel.org/doc/html/v5.12/driver-api/driver-model/index.html
> > 
> > vs this:
> > https://www.kernel.org/doc/html/v5.13/driver-api/driver-model/index.html
> > 
> > Maybe it moved somewhere else, but I can't find it... I'd have to git bisect
> > or git blame between the two releases maybe.  
> 
> Ah, this was removed in:
> 	1364c6787525 ("docs: driver-model: Remove obsolete device class documentation")
> as the information there was totally incorrect, since the 2.5.69 kernel
> release.  "device classes" aren't a thing, "classes" are a thing :)

Aha. Thanks for pointing this out. The sheer removal of this, combined with
other indirect indications, such as /sys/class/gpio being replaced with
/sys/bus/gpio in the new api, Uwe's comment, etc... derailed my interpretation.
:-)

Btw, sorry to ask here and now @Greg: I didn't CC you with this whole series
while I probably should have... now I am tempted to move V2 of this series to
staging, due to higher chances of potentially breaking UAPI changes during
initial development, and in order to have a more flexible discussions over the
UAPI of LMC in general. Is that advisable or should we better make sure that
the version to get merged upstream (I hope it eventually will be) is set in
stone?

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-03-06 14:25                   ` David Jander
@ 2025-03-06 14:54                     ` Greg Kroah-Hartman
  0 siblings, 0 replies; 59+ messages in thread
From: Greg Kroah-Hartman @ 2025-03-06 14:54 UTC (permalink / raw)
  To: David Jander
  Cc: Uwe Kleine-König, linux-kernel, linux-iio, Jonathan Corbet,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, devicetree,
	linux-doc, Nuno Sa, Jonathan Cameron, Oleksij Rempel

On Thu, Mar 06, 2025 at 03:25:29PM +0100, David Jander wrote:
> On Thu, 6 Mar 2025 14:39:16 +0100
> Greg Kroah-Hartman <gregkh@linuxfoundation.org> wrote:
> 
> > On Thu, Mar 06, 2025 at 10:34:02AM +0100, David Jander wrote:
> > > On Thu, 6 Mar 2025 10:03:26 +0100
> > > Greg Kroah-Hartman <gregkh@linuxfoundation.org> wrote:
> > >   
> > > > On Thu, Mar 06, 2025 at 09:20:13AM +0100, David Jander wrote:  
> > > > > On Thu, 6 Mar 2025 08:18:46 +0100
> > > > > Greg Kroah-Hartman <gregkh@linuxfoundation.org> wrote:
> > > > >     
> > > > > > On Thu, Mar 06, 2025 at 12:21:22AM +0100, Uwe Kleine-König wrote:    
> > > > > > > Hello David,
> > > > > > > 
> > > > > > > On Wed, Mar 05, 2025 at 04:40:45PM +0100, David Jander wrote:      
> > > > > > > > On Fri, 28 Feb 2025 17:44:27 +0100
> > > > > > > > Uwe Kleine-König <u.kleine-koenig@baylibre.com> wrote:      
> > > > > > > > > On Thu, Feb 27, 2025 at 05:28:17PM +0100, David Jander wrote:
> > > > > > > > > [...]      
> > > > > > > > > > +static int motion_open(struct inode *inode, struct file *file)
> > > > > > > > > > +{
> > > > > > > > > > +	int minor = iminor(inode);
> > > > > > > > > > +	struct motion_device *mdev = NULL, *iter;
> > > > > > > > > > +	int err;
> > > > > > > > > > +
> > > > > > > > > > +	mutex_lock(&motion_mtx);        
> > > > > > > > > 
> > > > > > > > > If you use guard(), error handling gets a bit easier.      
> > > > > > > > 
> > > > > > > > This looks interesting. I didn't know about guard(). Thanks. I see the
> > > > > > > > benefits, but in some cases it also makes the locked region less clearly
> > > > > > > > visible. While I agree that guard() in this particular place is nice,
> > > > > > > > I'm hesitant to try and replace all mutex_lock()/_unlock() calls with guard().
> > > > > > > > Let me know if my assessment of the intended use of guard() is incorrect.      
> > > > > > > 
> > > > > > > I agree that guard() makes it harder for non-trivial functions to spot
> > > > > > > the critical section. In my eyes this is outweight by not having to
> > > > > > > unlock in all exit paths, but that might be subjective. Annother
> > > > > > > downside of guard is that sparse doesn't understand it and reports
> > > > > > > unbalanced locking.
> > > > > > >        
> > > > > > > > > > +	list_for_each_entry(iter, &motion_list, list) {
> > > > > > > > > > +		if (iter->minor != minor)
> > > > > > > > > > +			continue;
> > > > > > > > > > +		mdev = iter;
> > > > > > > > > > +		break;
> > > > > > > > > > +	}        
> > > > > > > > > 
> > > > > > > > > This should be easier. If you use a cdev you can just do
> > > > > > > > > container_of(inode->i_cdev, ...);      
> > > > > > > > 
> > > > > > > > Hmm... I don't yet really understand what you mean. I will have to study the
> > > > > > > > involved code a bit more.      
> > > > > > > 
> > > > > > > The code that I'm convinced is correct is
> > > > > > > https://lore.kernel.org/linux-pwm/00c9f1181dc351e1e6041ba6e41e4c30b12b6a27.1725635013.git.u.kleine-koenig@baylibre.com/
> > > > > > > 
> > > > > > > This isn't in mainline because there is some feedback I still have to
> > > > > > > address, but I think it might serve as an example anyhow.
> > > > > > >       
> > > > > > > > > > [...]
> > > > > > > > > > +
> > > > > > > > > > +static const struct class motion_class = {
> > > > > > > > > > +	.name		= "motion",
> > > > > > > > > > +	.devnode	= motion_devnode,        
> > > > > > > > > 
> > > > > > > > > IIRC it's recommended to not create new classes, but a bus.      
> > > > > > > > 
> > > > > > > > Interesting. I did some searching, and all I could find was that the chapter
> > > > > > > > in driver-api/driver-model about classes magically vanished between versions
> > > > > > > > 5.12 and 5.13. Does anyone know where I can find some information about this?
> > > > > > > > Sorry if I'm being blind...      
> > > > > > > 
> > > > > > > Half knowledge on my end at best. I would hope that Greg knows some
> > > > > > > details (which might even be "no, classes are fine"). I added him to Cc:      
> > > > > > 
> > > > > > A class is there for when you have a common api that devices of
> > > > > > different types can talk to userspace (i.e. the UAPI is common, not the
> > > > > > hardware type).  Things like input devices, tty, disks, etc.  A bus is
> > > > > > there to be able to write different drivers to bind to for that hardware
> > > > > > bus type (pci, usb, i2c, platform, etc.)
> > > > > > 
> > > > > > So you need both, a bus to talk to the hardware, and a class to talk to
> > > > > > userspace in a common way (ignore the fact that we can also talk to
> > > > > > hardware directly from userspace like raw USB or i2c or PCI config
> > > > > > space, that's all bus-specific stuff).    
> > > > > 
> > > > > Thanks for chiming in. Let me see if I understand this correctly: In this
> > > > > case, I have a UAPI that is common to different types of motion control
> > > > > devices. So I need a class. check.    
> > > > 
> > > > Correct.
> > > >   
> > > > > Do I need a bus? If one can conceive other drivers or kernel parts that talk to
> > > > > motion drivers, I would need a bus. If that doesn't make sense, I don't. Right?    
> > > > 
> > > > Correct.
> > > >   
> > > > > I actually can think of a new motion device that acts as an aggregator of
> > > > > several single-channel motion devices into a single "virtual" multi-channel
> > > > > device... so do I need also a bus? I suppose...?    
> > > > 
> > > > Nope, that should just be another class driver.  Think about how input
> > > > does this, some input /dev/ nodes are the sum of ALL input /dev/ nodes
> > > > together, while others are just for individual input devices.  
> > > 
> > > Understood. Thanks!
> > >   
> > > > > Then the question remains: why did the chapter about classes vanish?    
> > > > 
> > > > What are you specifically referring to?  I don't remember deleting any
> > > > documentation, did files move around somehow and the links not get
> > > > updated?  
> > > 
> > > This:
> > > https://www.kernel.org/doc/html/v5.12/driver-api/driver-model/index.html
> > > 
> > > vs this:
> > > https://www.kernel.org/doc/html/v5.13/driver-api/driver-model/index.html
> > > 
> > > Maybe it moved somewhere else, but I can't find it... I'd have to git bisect
> > > or git blame between the two releases maybe.  
> > 
> > Ah, this was removed in:
> > 	1364c6787525 ("docs: driver-model: Remove obsolete device class documentation")
> > as the information there was totally incorrect, since the 2.5.69 kernel
> > release.  "device classes" aren't a thing, "classes" are a thing :)
> 
> Aha. Thanks for pointing this out. The sheer removal of this, combined with
> other indirect indications, such as /sys/class/gpio being replaced with
> /sys/bus/gpio in the new api, Uwe's comment, etc... derailed my interpretation.
> :-)
> 
> Btw, sorry to ask here and now @Greg: I didn't CC you with this whole series
> while I probably should have... now I am tempted to move V2 of this series to
> staging, due to higher chances of potentially breaking UAPI changes during
> initial development, and in order to have a more flexible discussions over the
> UAPI of LMC in general. Is that advisable or should we better make sure that
> the version to get merged upstream (I hope it eventually will be) is set in
> stone?

Just because something is in drivers/staging/ does not mean you can
break the user/kernel api, that is NOT what staging is for at all.

Take the time to get this right, there's no rush here.  Make sure
userspace works well with what you have before committing to it.

If you want to cc: me on the next series so I can review the driver-core
interaction bits, I'll be glad to do so.

thanks,

greg k-h

^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-03-06  9:25         ` David Jander
@ 2025-03-09 17:32           ` Jonathan Cameron
  2025-03-10  8:45             ` David Jander
  0 siblings, 1 reply; 59+ messages in thread
From: Jonathan Cameron @ 2025-03-09 17:32 UTC (permalink / raw)
  To: David Jander
  Cc: Uwe Kleine-König, linux-kernel, linux-iio, Jonathan Corbet,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, devicetree,
	linux-doc, Nuno Sa, Oleksij Rempel, Greg Kroah-Hartman

On Thu, 6 Mar 2025 10:25:40 +0100
David Jander <david@protonic.nl> wrote:

> On Thu, 6 Mar 2025 00:21:22 +0100
> Uwe Kleine-König <u.kleine-koenig@baylibre.com> wrote:
> 
> > Hello David,
> > 
> > On Wed, Mar 05, 2025 at 04:40:45PM +0100, David Jander wrote:  
> > > On Fri, 28 Feb 2025 17:44:27 +0100
> > > Uwe Kleine-König <u.kleine-koenig@baylibre.com> wrote:    
> > > > On Thu, Feb 27, 2025 at 05:28:17PM +0100, David Jander wrote:
> > > > [...]    
> > > > > +static int motion_open(struct inode *inode, struct file *file)
> > > > > +{
> > > > > +	int minor = iminor(inode);
> > > > > +	struct motion_device *mdev = NULL, *iter;
> > > > > +	int err;
> > > > > +
> > > > > +	mutex_lock(&motion_mtx);      
> > > > 
> > > > If you use guard(), error handling gets a bit easier.    
> > > 
> > > This looks interesting. I didn't know about guard(). Thanks. I see the
> > > benefits, but in some cases it also makes the locked region less clearly
> > > visible. While I agree that guard() in this particular place is nice,
> > > I'm hesitant to try and replace all mutex_lock()/_unlock() calls with guard().
> > > Let me know if my assessment of the intended use of guard() is incorrect.    
> > 
> > I agree that guard() makes it harder for non-trivial functions to spot
> > the critical section. In my eyes this is outweight by not having to
> > unlock in all exit paths, but that might be subjective. Annother
> > downside of guard is that sparse doesn't understand it and reports
> > unbalanced locking.  
> 
> What I was referring to, and what I want to know is, is it okay to mix guard()
> with lock/unlock? I.e. Use guard() when there are multiple exit paths involved
> and revert back to simple lock/unlock if it is just to encase a handful of
> non-exiting operations?

Mixing is fine.  In some cases scoped_guard() can also make things
clearer though at the cost of increased indent.

> > 
> > Sad, so a userspace process still has to know some internal things about
> > the motor it drives. :-\  
> 
> Unfortunately that is almost impossible to avoid entirely.
> You can replace one stepper motor driver with another that might have
> different micro-stepping subdivision, by looking at struct
> mot_capabilities.subdiv, but a simple brushed DC motor just isn't able to
> replace a stepper motor in all but the most trivial applications. I also think
> that burdening the kernel with all sorts of complicated math to model the
> mechanical conversion factors involved in anything that's connected to the
> motor drive shaft is overkill. As well as trying to emulate all missing
> capabilities from a motion device that is lacking that functionality natively.
> 
> So just like in IIO you cannot just replace one ADC with any other, in LMC you
> also cannot replace any device with any other.
> 
> That's why there is struct mot_capabilities and MOT_IOCTL_GET_CAPA. It enables
> user-space to optionally support different devices more easily. It is probably
> best used in conjunction with a LMC user-space library, although I don't want
> to rely on such a library for being able to use LMC. There is some middle
> ground here I guess... just like in IIO.
> 
> One thing I could try to improve though, is to include some additional
> information in struct mot_capabilities that tells something more about the
> nature of the used units, just like the speed_conv and accel_conv constants do
> for time conversion. Something that can be placed in the device tree (possibly
> in a motor child-node connected to the motor-controller) that contains some
> conversion constant for distance. That way, if one were to (for example)
> replace a stepper motor with a BLDC motor + encoder in a new hardware
> revision, this constant could be used to make the units backwards compatible.
> 
> As background information: A stepper motor controller counts distance in steps
> and/or micro-steps. There are mot_capabilities.subdiv micro-steps in each
> step. The amount of angle the actual motor shaft advances with each whole step
> depends on the motor construction and is often 200 steps per revolution (1.8
> degrees), but can vary from 4 to 400 steps per revolution depending on the
> motor. So it is not only the controller that matters but also the type of
> motor. This suggests the need of motor sub-nodes in the device-tree if one
> wanted to extend the hardware knowledge further down from the motor driver.
> But then there are gear boxes, pulleys, etc... it's basically conversion
> factors all the way down. How many of them is sensible to bother the kernel
> with?

I'd have a motor description that is sufficient to be able to swap steppers
between hardware versions and present sufficient info to userspace to allow
a library to hide those differences. That description might well be of
an aggregate device consisting of motor and whatever mechanics to get you
to the point you care about (actuator motion).  Hardest bit will be documenting
'where' in the system the DT is describing.

It's not that heavily used but we do have analog front ends in IIO that
provide a not dissimilar thing to the various potential mechanisms here.

Jonathan


> 
> Best regards,
> 


^ permalink raw reply	[flat|nested] 59+ messages in thread

* Re: [RFC PATCH 1/7] drivers: Add motion control subsystem
  2025-03-09 17:32           ` Jonathan Cameron
@ 2025-03-10  8:45             ` David Jander
  0 siblings, 0 replies; 59+ messages in thread
From: David Jander @ 2025-03-10  8:45 UTC (permalink / raw)
  To: Jonathan Cameron
  Cc: Uwe Kleine-König, linux-kernel, linux-iio, Jonathan Corbet,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, devicetree,
	linux-doc, Nuno Sa, Oleksij Rempel, Greg Kroah-Hartman


Hi Jonathan,

On Sun, 9 Mar 2025 17:32:50 +0000
Jonathan Cameron <jic23@kernel.org> wrote:

> On Thu, 6 Mar 2025 10:25:40 +0100
> David Jander <david@protonic.nl> wrote:
> 
> > On Thu, 6 Mar 2025 00:21:22 +0100
> > Uwe Kleine-König <u.kleine-koenig@baylibre.com> wrote:
> >   
> [...]
> > > 
> > > Sad, so a userspace process still has to know some internal things about
> > > the motor it drives. :-\    
> > 
> > Unfortunately that is almost impossible to avoid entirely.
> > You can replace one stepper motor driver with another that might have
> > different micro-stepping subdivision, by looking at struct
> > mot_capabilities.subdiv, but a simple brushed DC motor just isn't able to
> > replace a stepper motor in all but the most trivial applications. I also think
> > that burdening the kernel with all sorts of complicated math to model the
> > mechanical conversion factors involved in anything that's connected to the
> > motor drive shaft is overkill. As well as trying to emulate all missing
> > capabilities from a motion device that is lacking that functionality natively.
> > 
> > So just like in IIO you cannot just replace one ADC with any other, in LMC you
> > also cannot replace any device with any other.
> > 
> > That's why there is struct mot_capabilities and MOT_IOCTL_GET_CAPA. It enables
> > user-space to optionally support different devices more easily. It is probably
> > best used in conjunction with a LMC user-space library, although I don't want
> > to rely on such a library for being able to use LMC. There is some middle
> > ground here I guess... just like in IIO.
> > 
> > One thing I could try to improve though, is to include some additional
> > information in struct mot_capabilities that tells something more about the
> > nature of the used units, just like the speed_conv and accel_conv constants do
> > for time conversion. Something that can be placed in the device tree (possibly
> > in a motor child-node connected to the motor-controller) that contains some
> > conversion constant for distance. That way, if one were to (for example)
> > replace a stepper motor with a BLDC motor + encoder in a new hardware
> > revision, this constant could be used to make the units backwards compatible.
> > 
> > As background information: A stepper motor controller counts distance in steps
> > and/or micro-steps. There are mot_capabilities.subdiv micro-steps in each
> > step. The amount of angle the actual motor shaft advances with each whole step
> > depends on the motor construction and is often 200 steps per revolution (1.8
> > degrees), but can vary from 4 to 400 steps per revolution depending on the
> > motor. So it is not only the controller that matters but also the type of
> > motor. This suggests the need of motor sub-nodes in the device-tree if one
> > wanted to extend the hardware knowledge further down from the motor driver.
> > But then there are gear boxes, pulleys, etc... it's basically conversion
> > factors all the way down. How many of them is sensible to bother the kernel
> > with?  
> 
> I'd have a motor description that is sufficient to be able to swap steppers
> between hardware versions and present sufficient info to userspace to allow
> a library to hide those differences. That description might well be of
> an aggregate device consisting of motor and whatever mechanics to get you
> to the point you care about (actuator motion).  Hardest bit will be documenting
> 'where' in the system the DT is describing.

Is it really the purpose of a DT to describe mechanical aspects of a machine?
Aren't we stretching things here?

In case this makes sense, it would need to be optional. Only the electronics
are on the "board", the rest can vary beyond the scope of the DT: one can
connect different motors to a stepper motor controller and often that's the
purpose. Just as one can connect anything to a USB port.

Sometimes the controller is single purpose, just as some USB ports that have a
fixed device connected to it on the board, like a USB-ethernet interface for
example, which also has a certain fixed phy hooked up to it, etc...

If the purpose of the DT is to potentially go beyond the borders of a PCB (or
stack of PCB's) and even beyond the realm of electronic parts into mechanical
parts, wouldn't we need a way to describe a lot of things, like gearboxes,
pulleys, etc...?

Also, in the spirit of the DT, shouldn't that description be complete and
independent of the software (or even OS) involved? If that's the case, I fear
that "...to the point you care about..." is probably not enough?

> It's not that heavily used but we do have analog front ends in IIO that
> provide a not dissimilar thing to the various potential mechanisms here.

AFE's are still part of the electronics and often also part of the same board,
so there it does make more sense. I've used them.

Don't get me wrong, if there is general agreement that information
about mechanical things like a motor, gearbox or other mechanical
transformation of motion should be contained in the DT, I'm fine with it.
Maybe we should create an example to have something to talk about?

Take for example the extruder of a 3D printer:

Complete description of the mechanics, including the stepper motor of type
17HS4401 from a Chinese manufacturer called "songshine" and the extruder,
which consists of a gear reduction and a hobbled shaft pressing the filament
into the hot-end. The stepper motor does one full 360 degree turn per 200
whole steps. The extruder then pushes 2178 micrometer of filament into the
hot-end per whole turn of the motor shaft. We will assume that the extruder
itself is not a standard part that can be ordered and could not have a
standardize compatible string. The motor... could. Or it could be a generic
motor with some parameters in the DT, like this:

&spi2 {
	...
	stepper-controller3: tmc5240@0 {
		compatible = "adi,tmc5240";
		reg = <3>;
		spi-max-frequency = <10000000>;
		interrupts-extended = <&gpiok 6 IRQ_TYPE_LEVEL_LOW>;
		clocks = <&clock_tmc5240>;

		motor0 {
			compatible = "bipolar-stepper-motor";
			run-current-ma = <1300>;
			hold-current-ma = <260>;
			rated-voltage-mv = <3600>;
			induction-uh = <2800>;
			dc-resistance-mohm = <1500>;
			holding-torque-nmm = <400>;
			detent-torque-nmm = <22>;
			steps-per-turn = <200>;

			extruder0 {
				compatible = "rotation-to-linear";
				distance-per-turn-um = <2178>;
			};
		};
	};
};

Or the motor could be a reusable part with its own entry in some
"bipolar-stepper-motors.c" database under a compatible string:

&spi2 {
	...
	stepper-controller3: tmc5240@0 {
		compatible = "adi,tmc5240";
		reg = <3>;
		spi-max-frequency = <10000000>;
		interrupts-extended = <&gpiok 6 IRQ_TYPE_LEVEL_LOW>;
		clocks = <&clock_tmc5240>;

		motor0 {
			compatible = "songshine,17HS4401";

			extruder0 {
				compatible = "rotation-to-linear";
				distance-per-turn-um = <2178>;
			};
		};
	};
};

Or one could just condense all the information of the motor and mechanics into
one node with the needed properties to obtain the conversion factors the
motion framework needs. But that would make the DT dependent on the software
used, and AFAIK this is not the purpose of a DT, right? It might look like
this:

&spi2 {
	...
	stepper-controller3: tmc5240@0 {
		compatible = "adi,tmc5240";
		reg = <3>;
		spi-max-frequency = <10000000>;
		interrupts-extended = <&gpiok 6 IRQ_TYPE_LEVEL_LOW>;
		clocks = <&clock_tmc5240>;

		motor0 {
			compatible = "stepper-linear-actuator";
			run-current-ma = <1300>;
			hold-current-ma = <260>;
			steps-per-turn = <200>;
			...
			distance-per-turn-um = <2178>;
		};
	};
};

I've left out properties like reg, #address-cells and #size-cells here for brevity.

Let me know if you think any of this makes sense.

Best regards,

-- 
David Jander

^ permalink raw reply	[flat|nested] 59+ messages in thread

end of thread, other threads:[~2025-03-10  8:45 UTC | newest]

Thread overview: 59+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2025-02-27 16:28 [RFC PATCH 0/7] Add Linux Motion Control subsystem David Jander
2025-02-27 16:28 ` [RFC PATCH 1/7] drivers: Add motion control subsystem David Jander
2025-02-28 16:44   ` Uwe Kleine-König
2025-03-05 15:40     ` David Jander
2025-03-05 23:21       ` Uwe Kleine-König
2025-03-06  7:18         ` Greg Kroah-Hartman
2025-03-06  8:20           ` David Jander
2025-03-06  9:03             ` Greg Kroah-Hartman
2025-03-06  9:34               ` David Jander
2025-03-06 13:39                 ` Greg Kroah-Hartman
2025-03-06 14:25                   ` David Jander
2025-03-06 14:54                     ` Greg Kroah-Hartman
2025-03-06  9:25         ` David Jander
2025-03-09 17:32           ` Jonathan Cameron
2025-03-10  8:45             ` David Jander
2025-02-28 22:36   ` David Lechner
2025-03-03  8:36     ` David Jander
2025-03-03 11:01       ` Pavel Pisa
2025-03-03 16:04         ` David Jander
2025-02-27 16:28 ` [RFC PATCH 2/7] motion: Add ADI/Trinamic TMC5240 stepper motor controller David Jander
2025-02-27 16:28 ` [RFC PATCH 3/7] motion: Add simple-pwm.c PWM based DC motor controller driver David Jander
2025-02-27 16:28 ` [RFC PATCH 4/7] Documentation: Add Linux Motion Control documentation David Jander
2025-02-27 16:37   ` Jonathan Corbet
2025-02-28 13:02     ` David Jander
2025-02-28 14:42       ` Jonathan Corbet
2025-02-28 15:06         ` David Jander
2025-02-27 16:28 ` [RFC PATCH 5/7] dt-bindings: motion: Add common motion device properties David Jander
2025-02-28  7:06   ` Krzysztof Kozlowski
2025-02-28  7:13   ` Krzysztof Kozlowski
2025-02-27 16:28 ` [RFC PATCH 6/7] dt-bindings: motion: Add adi,tmc5240 bindings David Jander
2025-02-28  7:11   ` Krzysztof Kozlowski
2025-02-28  8:48     ` David Jander
2025-02-28  9:35       ` Krzysztof Kozlowski
2025-02-28  9:51         ` David Jander
2025-02-28 14:01           ` Krzysztof Kozlowski
2025-02-28 22:38   ` David Lechner
2025-03-03 11:22     ` David Jander
2025-03-03 12:28       ` David Lechner
2025-03-03 13:18         ` David Jander
2025-02-27 16:28 ` [RFC PATCH 7/7] dt-bindings: motion: Add motion-simple-pwm bindings David Jander
2025-02-27 17:38   ` Rob Herring (Arm)
2025-02-28  7:12   ` Krzysztof Kozlowski
2025-02-28  9:22     ` David Jander
2025-02-28  9:37       ` Krzysztof Kozlowski
2025-02-28 10:09         ` David Jander
2025-02-28 15:18           ` Uwe Kleine-König
2025-03-03 10:53             ` Maud Spierings
2025-03-03 11:40             ` David Jander
2025-03-03 14:18               ` Krzysztof Kozlowski
2025-03-03 16:09                 ` David Jander
2025-02-28 22:41   ` David Lechner
2025-03-03 12:54     ` David Jander
2025-02-28  9:34 ` [RFC PATCH 0/7] Add Linux Motion Control subsystem Pavel Pisa
2025-02-28  9:35 ` Pavel Pisa
2025-02-28 11:57   ` David Jander
2025-02-28 15:23     ` Pavel Pisa
2025-03-03 10:45       ` David Jander
2025-02-28 22:36 ` David Lechner
2025-03-03  8:28   ` David Jander

This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).