Next Article in Journal
Two TOPSIS-Based Approaches for Multi-Choice Rough Bi-Level Multi-Objective Nonlinear Programming Problems
Previous Article in Journal
Granular Fuzzy Fractional Financial Systems Governed by Granular Caputo Fractional Derivative
Previous Article in Special Issue
Control Design and Implementation of Autonomous Robotic Lawnmower
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Numerical Approach for Trajectory Smoothing for LegUp Rehabilitation Parallel Robot

1
CESTER—Research Center for Industrial Robots Simulation and Testing, Technical University of Cluj-Napoca, Memorandumului 28, 400114 Cluj-Napoca, Romania
2
MEtRICs Research Center, Campus of Azurém, University of Minho, 4800-058 Guimarães, Portugal
3
Technical Sciences Academy of Romania, B-dul Dacia, 26, 030167 Bucharest, Romania
*
Author to whom correspondence should be addressed.
Mathematics 2025, 13(8), 1241; https://doi.org/10.3390/math13081241
Submission received: 8 March 2025 / Revised: 2 April 2025 / Accepted: 9 April 2025 / Published: 9 April 2025
(This article belongs to the Special Issue Mathematics Methods of Robotics and Intelligent Systems)

Abstract

:
Robotic-assisted motor rehabilitation has seen significant development over the past decade, driven by the distinct advantages that robots offer in this medical task. A key aspect of robotic-assisted rehabilitation is ensuring that the performed rehabilitation exercises are safely planned (i.e., without the risk of patient injury or anatomic joint strain). This paper presents a new numerical approach to trajectory planning for a LegUp parallel robot designed for lower limb rehabilitation. The proposed approach generates S-shaped motion profiles, also called S-curves, with precise control over all kinematic parameters, resulting in smooth acceleration and deceleration. This approach ensures the safety and effectiveness of rehabilitation exercises by minimizing strain on the patient’s anatomical joints. The mathematical models employed (numerical integration and differentiation) are well-established and computationally efficient for real-time implementation in the robot’s control hardware. Experimental tests using LegUp validate the effectiveness of the proposed trajectory-smoothing approach.

1. Introduction

Nowadays, stroke is recognized as the leading cause of disability worldwide, with an increasing number of cases driven by the aging population. This growing demand, coupled with the medical community’s limited response capacity, has prompted a swift reaction from the scientific community and the integration of rehabilitation technologies into international strategic development agendas. As a result, a wide range of rehabilitation devices have emerged, continuously improving through preliminary clinical evaluations [1]. Lower limb disabilities significantly impact patients’ quality of life by limiting their independence. The scientific literature reports numerous robots for lower limb rehabilitation, with extensive reviews available [2,3]. Several studies have presented robotic solutions specifically for neuromotor rehabilitation [4,5,6,7,8,9,10], while others have examined the benefits and limitations of exoskeletons [8] or the role of parallel robots in rehabilitation [11]. However, very few robots are designed for bedridden patients—such as those in the acute stage of stroke, those with severe balance disorders, or post-neurosurgery patients—who require early physical rehabilitation to maximize treatment outcomes [12]. Several other review papers exist in the literature detailing the state of the art of robotic neuromotor rehabilitation [13,14].
The RAISE parallel robot [5] was developed to address the white spot of robotic-assisted lower limb rehabilitation for bedridden patients. RAISE features a modular design and targets the spatial mobilization of all main joints of the lower limb (hip, knee, and ankle). The key characteristic of RAISE is its parallel architecture, where multiple input kinematic chains actuate a free-motion kinematic chain, which in turn guides the lower limb in the rehabilitation motion (similar to an exoskeleton). In recent years, the design of RAISE has been improved to enhance stiffness, ergonomics, and safety. This led to a new parallel robot called LegUp [15]. LegUp also features a modular design with two modules, namely the Hip and Knee Rehabilitation Module (HKM), and the Ankle Rehabilitation Module (AKM). Together, these modules facilitate rehabilitation exercises in two planes, targeting hip abduction/adduction and flexion/extension, knee flexion/extension, and ankle flexion/extension and inversion/eversion. LegUp also contains a kinematic chain that guides the lower limb like an exoskeleton. As a result, specific angular parameters in the robot’s kinematics are directly correlated to the patient’s anatomical joint movements.
The mathematical models for all the mechanism analyses of LegUp have already been developed. The Forward and Inverse Kinematics of LegUp were derived using an approach based on the unit dual quaternion homomorphism with the Special Euclidean displacement group SE(3). The kinematic models yielded closed-form solutions, showing all the assembly modes (number of solutions for the forward kinematic model) and the working modes (number of solutions for the inverse kinematic model) [15]. The number of working and assembly modes is crucial to studying the parallel robot behavior in different configurations. Moreover, the singularities, i.e., configurations where the robot loses or gains Degrees of Freedom (DOFs) (which are problematic for robot control) were analyzed in [15]. The singularities were determined using the vanishing conditions for the determinants of the Jacobian matrices that map the velocities of the parallel robot inputs with the velocities of the anatomic joint parameters [15]. A geometric optimization was achieved to determine the appropriate mechanical link lengths and the maximum and minimum active joint values, based on a predefined operational workspace (WS) [15]. In addition, software tools were developed to enhance rehabilitation outcomes, including the integration of serious gaming and the development of virtual reality rehabilitation modules [16].
Although the mechanism analysis for LegUp is complete, a rehabilitation exercise planning method is still required for the command-and-control module. Such a path planning method must be designed to minimize joint strain (which could negatively impact recovery) and should provide the following two key features: (1) ensure that the acceleration and deceleration for the motion of the anatomic joints is smooth (i.e., without spikes or abrupt changes); (2) provide control (for the medical staff) of all kinematic parameters for the anatomic joint motion, such as displacement, velocity, acceleration.
For LegUp, path planning requires the computation of feasible paths within WS (e.g., changing the hip angle from 0° to 30° and back to 0° in flexion/extension motion), while also knowing the joint velocity and acceleration. This can be achieved by implementing linear functions of time between consecutive values of the anatomic joints. However, defining a trajectory for the rehabilitation exercises, based on linear functions of the anatomic joints in time, leads to spikes and abrupt changes in the joint accelerations. This can be circumvented by smoothing the acceleration and deceleration at the beginning and end of each segment of the rehabilitation exercise described by linear functions of each angle parameter (for the anatomic joint) in time.
Significant research has been conducted on trajectory smoothing in robotics, with various approaches explored in the scientific literature. One widely used method involves S-shaped curves (or S-curves), which effectively limit acceleration and deceleration to ensure smoother motion. In [16], S-curves were applied to a 6 DOF serial robot to achieve controlled acceleration profiles. A variation of this approach was proposed in [17], where the authors introduced a trigonometric function as an S-shaped profile. Another modification was presented in [18], where the S-shaped acceleration/deceleration algorithm was adjusted to include two cases with uniform velocity. However, the authors only demonstrated their method on an elliptical trajectory. In [19], the S-shaped algorithm was integrated into path planning, incorporating solutions for reaching predefined robot positions. In [20], a look-ahead algorithm with S-curve acceleration and deceleration was introduced. However, the authors noted that the direct adoption of S-curve profiles via approximation algorithms was too complex. Instead, they proposed a look-ahead scheme where federate profiles with S-curve acceleration/deceleration perform efficiently for short linear and circular trajectory segments. Further work in [21] analyzed the mathematical properties of S-shaped curves, demonstrating that by increasing interpolation time and adjusting motion parameters, all motion constraints can be maintained within predefined limits. In addition to S-shaped curves, acceleration smoothing using convolution techniques was explored in [22]. A related approach was presented in [23,24], where polynomials were used to generate motion profiles that could not be produced through digital convolution. All the aforementioned methods rely on symbolic calculus, which provides a severe limitation regarding real-time implementation due to computational complexity and memory usage. Most state-of-the-art methods use polynomials defined on carefully selected time intervals to generate the S-curves. Numerical methods are widely used to overcome the limitations of symbolic calculus. However, there is a lack of numerical approaches to generate S-shaped profiles and apply them on input paths within the robot’s workspace considering jerk-limited trajectories. This research gap is the premise of the current paper.
This paper proposes a numerical approach for generating S-shaped profiles and using a scaling technique in the time domain to generate smooth trajectories. A smooth trajectory in this context refers to trajectories that describe smooth acceleration and deceleration at the beginning and end of the trajectory, respectively. The idea of having a time coordinate change has been successfully used in the field of dynamic systems to obtain a linear and time-invariant representation for a special class of nonlinear systems. Time scaling was initially proposed for system linearization in [25]. The more general concept of orbital feedback linearization has been developed for multivariable nonlinear systems in [26] and represents a good alternative to classical feedback linearization. This concept is particularized throughout this paper for kinematic time scaling. The main purpose of this paper is to develop a fast, computationally efficient, and easy-to-implement numerical algorithm that ensures trajectory smoothing. This smoothing technique aims to reduce anatomical joint strain in robotic-assisted rehabilitation using the LegUp parallel robot.
The contributions with respect to the state of the art are as follows:
  • Develop a numerical approach for trajectory smoothing using a kinematic time coordinate scaling that eases the real-time numerical implementation due to its simplicity, increased speed, and computational efficiency.
  • Show the advantage of the proposed numerical approach for trajectory smoothing of the LegUp parallel robot for lower limb rehabilitation considering patient’s safety.
This paper is structured as follows: Section 2 presents the mathematical background, where well-established concepts are presented to define the notations; Section 3 presents the main results of the kinematics of the LegUp parallel robot; Section 4 presents the proposed numerical method for trajectory smoothing; Section 5 presents numerical results using the LegUp parallel robot; the conclusions are drawn in Section 6.

2. Mathematical Background

This section presents the basic notions of numeric integration for real functions, along with a set of basic notations that will be consistently used throughout this paper, according to [27]. Let D = [ a , b ] be a compact domain of the set of real numbers and let f : D be a generic real function.
Definition 1.
The set Δ n = { a = x 0 < x 1 < < x n = b } is called a partition of the domain D , while Δ n = max i | x i + 1 x i | is called the norm of the partition. For such a partition a set of intermediate points ξ ( ξ i ) i = 1 , n ¯ is associated, such that ξ i ( x i 1 , x i ) . Then, the sum
S Δ n , ξ ( f ) = k = 1 n f ( ξ k ) ( x k x k 1 )
is called the Riemann sum of function f according to Δ n and ξ . Moreover, function f is integrable if for each division Δ n with lim n | Δ n | = 0 and each associate intermediate points ( ξ i ) i = 2 , n ¯ the following limit exists and its value is called the integral of f over D :
lim n S Δ n , ξ ( f ) = a b f ( x ) d x .
In the case of numeric integration, the value of the integral of f over the domain D can be approximated by a Riemann sum S Δ n , ξ ( f ) . A typical choice for Δ n is the equidistant division Δ n = ( a , a + b a n , , b ) . For such Δ n , there are different methods to define the set of intermediate points. For the purpose of this paper, the trapezoidal rule is considered. As such, for each segment [ x i , x i + 1 ] , the following approximation is considered:
x i x i + 1 f ( x ) d x f ( x i ) + f ( x i + 1 ) 2 ( x i + 1 x i )
Therefore, integral is approximated by
a b f ( x ) d x i = 0 n 1 f ( x i ) + f ( x i + 1 ) 2 ( x i + 1 x i ) S Δ n ( f )
If the function is continuously differentiable and Δ n is the equidistant division, the rounding error is given by
R n ( f ) = | a b f ( x ) d x S Δ n ( f ) | = | ( b a ) 2 12 n 2 [ f ( b ) f ( a ) ] | + O ( n 3 ) .
The numerical integration method will be denoted as
cumsumtrapz : D , cumsumtrapz f ( x ) = Σ x i + 1 x f ( x i ) + f ( x i + 1 ) 2 ( x i + 1 x i ) .
In a similar manner, the numerical differentiation is well established. Let f : [ a , b ] be a real function and x 0 [ a , b ] . Then, the function is differentiable at x 0 if the limit lim h 0 f ( x 0 + h ) f ( x 0 ) h exists and it is finite. In numeric differentiation, the limit is replaced with the fixed differentiation step (e.g., for time-dependent functions, the sampling time is considered) and the numerical derivative of f at x 0 is f ( x 0 + h ) f ( x 0 ) h (forward Euler method) or f ( x 0 ) f ( x 0 h ) h (backward Euler method) or f ( x 0 + h ) f ( x 0 h ) 2 h (trapezoidal method). The numerical differentiation will be denoted as follows:
diff : D
and the trapezoidal rule will be used in this paper. For consistency, C k ( [ a , b ] ) is defined as the set of all functions f : [ a , b ] that are k-times differentiable, with a continuous kth derivative.

3. Kinematics of the LegUp Parallel Robot

The LegUp mechanism analysis has already been achieved: the inverse and forward kinematic models (for displacement) and the singularity analysis and singularity-free workspace definition are presented in [13]. This paper only uses the inverse kinematic model derived in [15], and therefore, a full derivation of the equations is not included.

3.1. LegUp Description

A simplified CAD model of the LegUp parallel robot is illustrated in Figure 1, and the kinematic schemes of the LegUp modules are shown in Figure 2. The parameters of the operating workspace (WS) are defined as α 1 ,   α 2 ,   β 1 ,   γ 1 ,   γ 2 , which are mapped directly to the motions of the anatomic joints (Figure 1): α 1 —hip adduction/adduction, α 2 —hip flexion/extension, β 1 —knee flexion/extension, γ 1 —ankle flexion/extension, γ 2 —ankle inversion/eversion. Furthermore, the active joint parameters are defined as q i ,   i = 1 , 5 ¯ .
The HKM module (Figure 1) is composed of two sub-modules, the flexion/extension sub-module (FEs-m), which is shown in Figure 2a, and the abduction/adduction sub-module (AAs-m), shown in Figure 2b. The AKM module is contains two triangular closed-loop kinematic chains, as shown in Figure 2c. The free motion parameters are depicted using red and are not labeled since they are not present in the kinematic models (they are eliminated using various mathematical techniques).
A key observation is that AKM, FEs-m, and AAs-m have decoupled motion among each other, i.e., the AKM motion does not influence the FEs-m and AAs-m motions, the FEs-m motion does not influence the AKM and AAs-m motions, and finally the AAs-m motion does not influence the AKM and FEs-m motions.

3.2. Inverse Kinematics of LegUp

For LegUp, the inverse kinematic model (for displacement) takes the anatomic joint parameters α 1 ,   α 2 ,   β 1 ,   γ 1 ,   γ 2 as inputs and computes the values for the active joint parameters q i ,   i = 1 , 5 ¯ . In contrast, the forward kinematic model takes the active joint parameters q i ,   i = 1 , 5 ¯ as inputs and computes the WS parameters α 1 ,   α 2 ,   β 1 ,   γ 1 ,   γ 2 .
Since α 1 ,   α 2 ,   β 1 ,   γ 1 ,   γ 2 W S are the parameters of interest in robotic-assisted rehabilitation using LegUp, the trajectories that define rehabilitation exercises are strictly defined in WS, and the time-dependent functions q i ( t ) ,   i = 1 , 5 ¯ (required to produce the required WS trajectory) are computed via Inverse Kinematics, which are given by the following relations [15]:
{ q 1 = C 1 sin ( α 2 ) C 2 cos ( α 2 ) + C 3 q 2 = D 1 cos ( β 1 ) + D 2 sin ( β 1 ) + D 3 q 3 = r ( q 3 , α 1 ) q 4 = L a 1 2 + L b 1 2 2 L a 1 L b 1 cos ( γ 1 δ 1 δ 2 π / 2 ) q 5 = L a 2 2 + L b 2 2 2 L a 2 L b 2 cos ( γ 2 δ 3 π / 2 ) ,
with
C 1 = 4 ( L 0 l 1 L 1 l 0 ) , C 2 = 4 ( L 0 l 0 L 1 l 1 ) , C 3 = 2 ( L 0 2 + L 1 2 + l 0 2 + l 1 2 ) , D 1 = 2 ( L 0 l 0 + L 2 l 2 ) cos ( α 2 ) + 2 ( L 0 l 2 L 2 l 0 ) sin ( α 2 ) + 2 L t l 2 , D 2 = 2 ( L 2 l 0 L 0 l 2 ) cos ( α 2 ) + 2 ( L 0 l 0 + L 2 l 2 ) sin ( α 2 ) + 2 L t l 0 , D 3 = 2 L t ( L 0 sin ( α 2 ) L 2 cos ( α 2 ) ) + L 0 2 + L 2 2 + L t 2 + l 0 2 + l 2 2 .
and r ( q 3 , α 1 ) being the minimum norm root of P ( q 3 , α 1 ) :
P ( q 3 , α 1 ) U 1 q 3 4 + U 2 q 3 3 + U 3 q 3 2 + U 4 q 3 + U 5 = 0 ,
where
U 1 = 4 sin ( α 1 ) 2 , U 2 = 8 ( D y cos ( α 1 ) + d 1 sin ( α 1 ) ) sin ( α 1 ) , U 3 = 4 ( 2 D y d 0 + L 3 2 d 0 2 d 1 2 ) cos ( α 1 ) 2 + 16 D y d 1 cos ( α 1 ) sin ( α 1 ) + 4 ( ( D y + d 0 ) 2 L 3 2 + d 1 2 ) , U 4 = 8 ( D y 3 2 D y 2 d 0 + ( d 0 2 + d 1 2 L 3 2 ) D y + L 3 2 d 0 ) cos ( α 1 ) sin ( α 1 ) + 8 L 3 2 d 1 8 d 1 ( D y 2 + L 3 2 ) cos ( α 1 ) 2 , U 5 = 4 ( ( D y + d 0 ) D y 3 + ( d 0 2 + d 1 2 L 3 2 ) D y 2 + L 3 2 d 0 D y + ( d 1 2 d 2 2 ) L 3 2 ) cos ( α 1 ) 2 8 L 3 2 d 1 ( D y d 0 ) cos ( α 1 ) sin ( α 1 ) 4 L 3 2 d 1 2 .
To compute the Inverse Kinematics for velocities, the nonlinear system of equations in Equation (6) is used. The following vector relation is defined [28,29]:
Q ˙ = J X ˙
where Q = [ q 1 , q 2 , q 3 , q 4 , q 5 ] T is the vector composed of the active joints, X = [ α 1 , α 2 , β 1 , γ 1 , γ 2 ] T is the vector of the WS parameters, and J is the Jacobian matrix computed by differentiating the right-hand side of Equation (6) with respect to X = [ α 1 , α 2 , β 1 , γ 1 , γ 2 ] T . Furthermore, Equation (6) can be further differentiated to compute the Inverse Kinematics for acceleration and jerk:
Q ¨ = J ˙ X ¨ , Q = J ¨ X .
Even though the Inverse Kinematics for velocities, accelerations, and jerks are only shown in general representations (Equations (10) and (11)), the vectors Q ˙ ,   Q ¨ ,   Q can be computed symbolically, and they yield closed-form solutions for the velocities, accelerations, and jerks of the active joints q i ,   i = 1 , 5 ¯ ; the symbolic equations are not presented in this work due to their complexity. In a nutshell, a trajectory through WS with displacement, velocity, acceleration, jerk is described (even using discrete time-dependent functions of WS parameters), and then Equations (6), (10) and (11) can be used to compute the kinematic parameters for the active joints to produce the desired trajectory.

4. Numerical Approach for Trajectory Smoothing

Smoothing in the context of this work refers to limiting the accelerations at the beginning and end of an input trajectory, reducing the inertias of the lower limb segments during rehabilitation exercises start and end points. A smoothing profile accounts for the kinematic parameters (velocities, accelerations, jerks) and transforms the input trajectory through the time scaling technique described in this section. The purpose of the algorithm is to compute trajectories without sharp accelerations (at the start of the trajectory) and decelerations (at the end of the trajectory) for an arbitrary path through the parallel robot WS. The algorithm follows the following steps:
  • Input an arbitrary path Γ defined using discrete functions of the operational workspace WS.
  • Compute a discrete smoothing profile for the WS parameters using the kinematic parameters (displacement, maximum velocities, maximum accelerations, etc.); the smoothing profile can be 1 degree (used for acceleration limited motors) or 2 (used for jerk limited motors).
  • Use the smoothing profile to transform the WS parameters of the input trajectory such that the WS parameters smoothly accelerate at the beginning of the path Γ and smoothly decelerate at the end of the path Γ .
The output of the algorithm is a discrete trajectory following the path Γ with all the required kinematic data (displacement, velocity, acceleration). This trajectory becomes input in the inverse kinematic models of the parallel robot to compute the kinematic data required for the robot actuators q i ,   i = 1 , 5 ¯ .

4.1. Definitions and Assumptions

This sub-section introduces the definitions and assumptions required for the context of trajectory smoothing of the parallel robot for lower limb rehabilitation. Since the numerical algorithm works in the discrete domain, the notion of discrete functions is required. All notations are adapted according to Section 2 and [27]. For a continuous real function f : [ a , b ] , we denote f | Δ n : Δ n by its restriction to the partition Δ n = { a = x 0 < x 1 < < x n = b } . As stated in Section 3, the WS parameters (for the rehabilitation parallel robot) are defined as α 1 ,   α 2 ,   β 1 ,   γ 1 ,   γ 2 .
Definition 2.
(discrete path in the operating workspace WS). Let  f 1 , f 2 , f 3 , f 4 , f 5 : ,    be real functions, and α 1 A 1 = [ α 1 min , α 1 max ] , α 2 A 2 = [ α 2 min , α 2 max ] , β 1 B 1 = [ β 1 min , β 1 max ] , γ 1 D 1 = [ γ 1 min , γ 1 max ] , γ 2 D 2 = [ γ 2 min , γ 2 max ] . A continuous path Γ = Γ ( α 1 , α 2 , β 1 , γ 1 , γ 2 ) ,   Γ W S 5 (WS compact) is defined as follows:
Γ { f 1 = f 1 ( α 1 ) f 2 = f 2 ( α 2 ) f 3 = f 3 ( β 1 ) f 4 = f 4 ( γ 1 ) f 5 = f 5 ( γ 2 ) .
Let f 1 | Δ A 1 n : Δ A 1 n , f 2 | Δ A 2 n : Δ A 2 n , f 3 | Δ B 1 n : Δ B 1 n , f 4 | Δ D 1 n : Δ D 1 n , f 5 | Δ D 2 n : Δ D 2 n , discrete functions on the partitions Δ A 1 n , Δ A 2 n , Δ B 1 n , Δ D 1 n , Δ D 2 n . A discrete path Γ mapped on the continuous path Γ is defined as follows:
Γ : = [ α 1 α 2 β 1 γ 1 γ 2 ] = [ [ α 1 , 1 , α 1 , 2 , , α 1 , n ] [ α 2 , 1 , α 2 , 2 , , α 2 , n ] [ β 1 , 1 , β 1 , 2 , , β 1 , n ] [ γ 1 , 1 , γ 1 , 2 , , γ 1 , n ] [ γ 2 , 1 , γ 2 , 2 , , γ 2 , n ] ] = [ f 1 | Δ A 1 n f 2 | Δ A 2 n f 3 | Δ B 1 n f 4 | Δ D 1 n f 5 | Δ D 2 n ] .
Definition 3.
(discrete WS trajectory). A discrete trajectory Γ ( t ) following the discrete path Γ is defined by associating a time value t i ,   i = 1 , n ¯ for every WS parameter α 1 , i ,   α 2 , i ,   β 1 , i ,   γ 1 , i ,   γ 2 , i ,   i = 1 , n ¯ :
Γ ( t ) : = [ α 1 ( t ) α 2 ( t ) β 1 ( t ) γ 1 ( t ) γ 2 ( t ) ] = [ [ α 1 , 1 ( t 1 ) , α 1 , 2 ( t 2 ) , , α 1 , n ( t n ) ] [ α 2 , 1 ( t 1 ) , α 2 , 2 ( t 2 ) , , α 2 , n ( t n ) ] [ β 1 , 1 ( t 1 ) , β 1 , 2 ( t 2 ) , , β 1 , n ( t n ) ] [ γ 1 , 1 ( t 1 ) , γ 1 , 2 ( t 2 ) , , γ 1 , n ( t n ) ] [ γ 2 , 1 ( t 1 ) , γ 2 , 2 ( t 2 ) , , γ 2 , n ( t n ) ] ] ,
where the time partition is defined as Δ t n = { 0 = t 0 < t 1 < < t n = Δ t } , where T S = t i t i 1 is the sampling period and Δ t is the total time.
Assumption 1.
The continuous path Γ (Equation (12)) that is used to compute the discrete path Γ is smooth (i.e., without cusps and corners) and shows no input or output singularities for the parallel robot.
Assumption 2.
The functions f i ,   i = 1 , 5 ¯ from the path Γ are of class C1.
Definition 4
(discrete smoothed trajectory). A smoothed trajectory  Γ [ k ] ( t ) ,   k = 1 , 2  (where k is the degree of smoothing) is defined as follows:
Γ [ k ] ( t ) : = [ α 1 [ k ] ( t ) α 2 [ k ] ( t ) β 1 [ k ] ( t ) γ 1 [ k ] ( t ) γ 2 [ k ] ( t ) ] = [ [ α 1 , 1 ( t 1 ) , α 1 , 2 ( t 2 ) , , α 1 , n ( t n ) ] [ α 2 , 1 ( t 1 ) , α 2 , 2 ( t 2 ) , , α 2 , n ( t n ) ] [ β 1 , 1 ( t 1 ) , β 1 , 2 ( t 2 ) , , β 1 , n ( t n ) ] [ γ 1 , 1 ( t 1 ) , γ 1 , 2 ( t 2 ) , , γ 1 , n ( t n ) ] [ γ 2 , 1 ( t 1 ) , γ 2 , 2 ( t 2 ) , , γ 2 , n ( t n ) ] ] ,
where the time-dependent discrete functions α 1 [ k ] ( t ) ,   α 2 [ k ] ( t ) ,   β 1 [ k ] ( t ) ,   γ 1 [ k ] ( t ) ,   γ 2 [ n ] ( t ) are of class Ck+1.
Technically, smoothing refers to transforming the proximal and distal regions (with arbitrary lengths) of the time-dependent functions α 1 ( t ) ,   α 2 ( t ) ,   β 1 ( t ) ,   γ 1 ( t ) ,   γ 2 ( t ) , such that the functions describe smooth acceleration and deceleration, while the input trajectory Γ ( t ) and the smoothed trajectory Γ [ k ] ( t ) ,   k = 1 , 2 follow the same continuous path Γ .
Proposition 1.
(necessary conditions for discrete smoothed trajectory). Let  Γ P [ k ] ( t )  and Γ D [ k ] ( t ) ,   k = 1 , 2 be the proximal and distal regions of the trajectory Γ ( t ) with an arbitrary number of components m and p, respectively:
Γ P [ k ] ( t ) : = [ α 1 P [ k ] ( t P ) α 2 P [ k ] ( t P ) β 1 P [ k ] ( t P ) γ 1 P [ k ] ( t P ) γ 2 P [ k ] ( t P ) ] = [ [ α 1 , 1 ( t 1 ) , , α 1 , m ( t m ) ] [ α 2 , 1 ( t 1 ) , , α 2 , m ( t m ) ] [ β 1 , 1 ( t 1 ) , , β 1 , m ( t m ) ] [ γ 1 , 1 ( t 1 ) , , γ 1 , m ( t m ) ] [ γ 2 , 1 ( t 1 ) , , γ 2 , m ( t m ) ] ] ,   Γ D [ k ] ( t ) : = [ α 1 D [ k ] ( t D ) α 2 D [ k ] ( t D ) β 1 D [ k ] ( t D ) γ 1 D [ k ] ( t D ) γ 2 D [ k ] ( t D ) ] = [ [ α 1 , p ( t p ) , , α 1 , n ( t n ) ] [ α 2 , p ( t p ) , , α 2 , n ( t n ) ] [ β 1 , p ( t p ) , , β 1 , n ( t n ) ] [ γ 1 , p ( t p ) , , γ 1 , n ( t n ) ] [ γ 2 , p ( t p ) , , γ 2 , n ( t n ) ] ] , 1 < m < n ,   m < p < n , t P = [ t 1 , , t m ] , t D = [ t p , , t n ] .
The trajectory Γ [ k ] ( t ) ,   k = 1 , 2 is considered smooth (within the context of this work) if
(1) 
There exists m such that the discrete time-dependent functions  α 1 P [ k ] ( t P ) ,   α 2 P [ k ] ( t P ) ,   β 1 P [ k ] ( t P ) ,   γ 1 P [ k ] ( t P ) ,   γ 2 P [ k ] ( t P )  are as follows:
a. 
Concave if the functions are decreasing.
b. 
Convex if the functions are increasing.
c. 
The inflexion points of the discrete functions on the proximal region are located at t1.
(2) 
There exists p such that the discrete time-dependent functions  α 1 D [ k ] ( t D ) ,   α 2 D [ k ] ( t D ) ,   β 1 D [ k ] ( t D ) ,   γ 1 D [ k ] ( t D ) ,   γ 2 D [ k ] ( t D )  are as follows:
a. 
Concave if the functions are increasing.
b. 
Convex if the functions are decreasing.
c. 
The inflexion points of the discrete functions on the proximal region are located at tn.

4.2. Smoothing Profile of 1 Degree

The smoothing profile of 1 degree is a 2-times differentiable discrete function of time, which is used thereafter on discrete functions of time to achieve the requirements pointed out in Definitions 3 and 4. Figure 3a illustrates the input (black) function of time and the output (green) smoothing profile as a function of displacement in time. Figure 3b illustrates the velocity profile (the time derivative of the green curve), and Figure 3c illustrates the acceleration profile (the time derivative of the blue curve).
To compute the S-shaped smoothing profile, the following steps are followed:
  • Define a linear function of displacement over time d ( t ) = α t ,   α * , where the total displacement Δ d can be viewed as the arclength of any path.
  • Define the time intervals T i ,   i = 1 , 3 ¯ such that they create a trapezoid (or triangular) profile for the velocity:
    T 1 , T 3 + \ { 0 } ,   T 2 + ,   Δ t = T 1 + T 2 + T 3 ,   0 T 2 < Δ t .
    Figure 1 illustrates a trapezoid profile with the time parameters at its base; a triangular profile is generated if T 2 = 0 .
  • Compute the kinematic parameters that generate the trapezoid profile. The following constraints are defined:
    Δ d ,   v max ,   a ,   a + \ { 0 } ,   Δ d = 1 2 ( Δ t + T 2 ) v max ,   Δ d Δ t < v max < 2 Δ d Δ t ,
    and the following two cases are considered:
  • Case 1, inputs = { Δ d ,   v max ,   a ,   a } (the max velocity and accelerations are constrained, the time parameters are computed). In this case, the time intervals are computed using
    T 1 = v max a , T 3 = v max a , T 2 = Δ d v max ( T 1 + T 3 ) 2 ,   Δ t = T 1 + T 2 + T 3 .
  • Case 2, inputs = { Δ d ,   Δ t ,   v max , h } (the max velocity and total time are constrained, the time parameters and accelerations are computed). In this case, h is defined as the ratio between acceleration and deceleration, which will be used to compute the time parameters. Equation (18) can be used to compute T 2 ; furthermore, the equations { T 1 + T 2 + T 3 Δ t = 0 ,   T 1 / T 3 h = 0 } must be fulfilled simultaneously, therefore the time intervals can be computed using
    T 2 = ( 2 Δ d Δ t v max ) v max , T 1 = ( Δ t T 2 ) h h + 1 , T 3 = Δ t T 2 h + 1 .
    Case 1 is useful when there is a velocity and acceleration constraint for the rehabilitation exercises in early (acute) stages of passive rehabilitation, whereas Case 2 is used when the total time of the exercise is known (or the mean velocity) in later stages (after the acute period) of passive rehabilitation (the accelerations may be larger if not constrained).
4.
The trapezoid profile is generated in discrete space.
  • The time domain is defined first; a constant small increment of the time is defined as δ t = ct . , which in turn is used to define the time vector:
    n ,   m ,   p ,   l + \ { 0 } ,   n = Δ t δ t , n = m + p + l , T : = [ t 1 , t 2 , , t n ] = [ 0 , δ t , 2 δ t , , Δ t ] n   elements , T = [ T 1 , T 2 , T 3 ] , T 1 = [ t 1 , t 2 , , t m ] m   elements ,   T 2 = [ t m + 1 , t m + 2 , , t m + p ] p   elements ,   T 3 = [ t m + p + 1 , t m + p + 2 , , t n ] l   elements .
    where is defined as the operator that returns the integer part of a real number.
  • The velocity ramps are defined in the discrete space to compose the velocity profile:
    δ v 1 , δ v 3 + \ { 0 } , δ v 1 = v max m , δ v 3 = v max l , V 1 = [ 0 , δ v 1 , 2 δ v 1 , , v max ] m   elements ,   V 2 = [ v max , v max , , v max ] p   elements ,   V 3 = [ v max , v max δ v 3 , , 0 ] l   elements , V = [ V 1 , V 2 , V 3 ] n   elements .
5.
Compute the displacement profile S with n element by numerically integrating V over T using the cumsumtrapz function defined in Section 2; e.g., in MATLAB (2024b), the numerical integration can be achieved using S = cumtrapz (T,V).

4.3. Smoothing Profile of 2 Degrees

The smoothing profile of 2 degrees is a 3-times differentiable discrete function of time. Figure 4a illustrates the input (black) function of time and the output (green) S-shaped smoothing profile as a function of displacement in time. Figure 4b illustrates the velocity profile (the time derivative of the green curve), and Figure 4c illustrates the acceleration profile (the time derivative of the blue curve).
To compute the S-shaped smoothing profile, the following steps are followed:
  • Define a linear function of displacement (Figure 2a—black curve) over time d ( t ) = α t ,   α * , where the total displacement Δ d can be the arclength of any path Γ W S .
  • Define the time intervals T i ,   i = 1 , 3 ¯ (using Equation (17)).
  • Define linear functions for velocities v ( t ) = β t ,   v ( t ) = β t ,   β , β * ( v ( t ) represents the velocity in the acceleration stage, v ( t ) represents the velocity in the deceleration stage) and S-shaped functions v S ( t ) ,   v S ( t ) , such that the linear and S-shaped functions produce the same displacement, 0 T 1 v ( t ) d t = 0 T 1 v S ( t ) d t , T 1 + T 2 T 1 + T 2 + T 3 v ( t ) d t = T 1 + T 2 T 1 + T 2 + T 31 v S ( t ) d t .
  • Define time intervals T i , j ,   j = 1 , 3 ¯ such that they create trapezoid (or triangular) profiles for the acceleration:
    T i , 1 , T i , 3 + \ { 0 } ,   T i , 2 + , T i = T i , 1 + T i , 2 + T i , 3 ,   0 T i , 2 < Δ t ,   i = 1 , 3 .
  • Compute the kinematic parameters that generate the trapezoid profiles for accelerations. The following constraints are defined:
    v max ,   a max ,   a max , j 1 , j 2 , j 1 , j 2 + \ { 0 } ,   j 1 = a max T 1 , 1 , j 2 = a max T 1 , 3 , j 1 = a max T 3 , 1 , j 2 = a max T 3 , 3 , v max = 1 2 ( T 1 + T 1 , 2 ) a max ,   v max = 1 2 ( T 3 + T 3 , 2 ) a max , v max T 1 < a max < 2 v max T 1 ,   v max T 3 < a max < 2 v max T 3 ,
    and two cases are considered:
  • Case 1, inputs = { Δ d ,   v max ,   a max ,   a max , j 1 , j 2 , j 1 , j 2 } (the max velocity, accelerations and jerks are constrained, the time parameters are computed). In this case, the time intervals are computed using
    T 1 , 1 = a max j 1 , T 1 , 3 = a max j 2 , T 1 , 2 = v max a max ( T 1 , 1 + T 1 , 3 ) 2 , T 3 , 1 = a max j 1 , T 3 , 3 = a max j 2 , T 3 , 2 = v max a max ( T 3 , 1 + T 3 , 3 ) 2 , T 1 = T 1 , 1 + T 1 , 2 + T 1 , 3 ,   T 3 = T 3 , 1 + T 3 , 2 + T 3 , 3 ,   T 2 = Δ d v max ( T 1 + T 3 ) 2 , Δ t = T 1 + T 2 + T 3 .
  • Case 2, inputs = { Δ d ,   Δ t ,   v max , a max , a max , h , h } (the max velocity, max accelerations and total time are constrained, the time parameters and accelerations are computed). In this case, h and h are defined as the ratio between jerks for the acceleration and deceleration stages, respectively. The time intervals can be computed using
    T 1 , 2 = ( 2 v max T 1 a max ) a max , T 1 , 1 = ( T 1 T 1 , 2 ) h h + 1 , T 1 , 3 = T 1 T 1 , 2 h + 1 , T 3 , 2 = ( 2 v max T 3 a max ) a max , T 3 , 1 = ( T 3 T 3 , 2 ) h h + 1 , T 3 , 3 = T 3 T 3 , 2 h + 1 .
6.
The trapezoid profile is generated in discrete space.
  • The time domain T is defined as in Equation (21).
  • The acceleration ramps are defined in the discrete space to compose the acceleration profile:
    δ a 1 ,   δ a 3 ,   δ a 1 ,   δ a 3 + \ { 0 } ,   m = m 1 + m 2 + m 3 ,   l = l 1 + l 2 + l 3 , δ a 1 = a max m 1 , δ a 3 = a max m 3 , δ a 1 = a max l 1 , δ a 3 = a max l 3 , A 1 = [ 0 , δ a 1 , 2 δ a 1 , , a max ] m 1   elements ,   A 2 = [ a max , a max , , a max ] m 2   elements ,   A 3 = [ a max , a max δ a 3 , , 0 ] m 3   elements , A 1 = [ 0 , δ a 1 , 2 δ a 1 , , a max ] l 1   elements ,   A 2 = [ a max , a max , , a max ] m 2   elements ,   A 3 = [ a max , a max + δ a 3 , , 0 ] m 3   elements , A = [ A 1 , A 2 , A 3 ] m   elements ,   A = [ A 1 , A 2 , A 3 ] p   elements ,   A 0 = [ 0 , 0 , , 0 ] l   elements ,   A T = [ A , A 0 , A ] n   elements .
7.
Compute the displacement profile S by numerically integrating A over T two times using the cumsumtrapz function; e.g., in MATLAB, the numerical integration can be achieved using S = cumtrapz (T,cumtrapz(T,A)).

4.4. Computing the Smoothed Trajectory

The second part of the algorithm uses the smoothed profile (the S-shaped curve described by S) to obtain a smoothed trajectory Γ [ k ] ( t ) ,   k = 1 , 2 on a path Γ . The following steps are required:
  • Normalize the displacement data vector S using:
    S N = S 1 s n ,
    where S N is a dimensionless data vector, and then compute a nonlinear time vector T using
    T = S N T l
  • Assume that Γ ( t ) is a trajectory sampled on a vector T with values spaced equally, and resample Γ [ k ] ( t ) ,   k = 1 , 2 for T′ using interpolation (in this work, linear interpolation was used, but the conjecture is that any type of interpolation will work). In MATLAB, the resampling is achieved using Γ [ k ] = interp 1 ( T , f , T ) ,   k = 1 , 2 , where f = { α 1 , α 2 , β 1 , γ 1 , γ 2 } represents the set of discrete functions of the WS parameters.
  • Consider that Γ [ k ] ( t ) ,   k = 1 , 2 is a trajectory associated with the time vector T.
Figure 5 shows the process of smoothing a discrete time-dependent function (of a trajectory) based on a smoothing profile. In a nutshell, the discrete time functions that are initially sampled using a time vector T with equal spacing between its values are resampled for a time vector T′ without constant values between its components, but they are then considered to be sampled at T.
Algorithm 1 shows the process of trajectory smoothing based on the kinematic parameters and an input path Γ .
Algorithm 1 (Trajectory smoothing)
0. Inputs read   Γ | if   deg = 1   then | if   C a s e = 1   then   k i n e _ p a r a m { Δ d , v max , a , a } else   if   C a s e = 2   then   k i n e _ p a r a m { Δ d , Δ t , v max , h } end   if else   if   deg = 2   then | if   C a s e = 1   then k i n e _ p a r a m { Δ d , v max , a max , a max , j 1 , j 2 , j 1 , j 2 } else   if   C a s e = 2   then k i n e _ p a r a m { Δ d ,   Δ t ,   v max , a max , a max , h , h } end   if end   if
1. Compute smoothing profile: | if   deg = 1   then   compute   T 1 ,   T 2 ,   T 3 , V 1 ,   V 2 ,   V 3   T [ T 1 ,   T 2 ,   T 3 ] , V [ V 1 ,   V 2 ,   V 3 ] , else   if   deg = 2   then   compute   T 1 ,   T 2 ,   T 3 , A 1 ,   A 2 ,   A 3   T [ T 1 ,   T 2 ,   T 3 ] , A [ A 1 ,   A 2 ,   A 3 ] end   if
| if   deg = 1   then   S cumsumtrapz ( T , V ) else   if   deg = 2   then   S cumsumtrapz ( cumsumtrapz ( T , V ) ) end   if
2. Apply smoothing profile to the path  Γ : Γ [ k ] interp ( T , f , T ) ,   k = 1 , 2
3. Output: Γ [ k ]

5. Numerical Results

Figure 6 shows the experimental model of LegUp during laboratory testing on healthy subjects, showing the main kinematic components and the command unit. Table 1 and Table 2 show the numerical values for the HKM module, and Table 3 shows the AKM module, which were computed using numerical optimization based on a predefined operating workspace defined using the target rehabilitation motions [15]. Other authors have used numerical genetic algorithms for linkage optimization of wearable robots [30].

5.1. Example for 2-Degrees Smoothed Trajectory for the HKM Module Considering Case 1

The first experimental examples were achieved with the LegUp parallel robot while performing rehabilitation exercises for the hip and knee joints on a healthy subject. The aim was to compare a smoothed trajectory of 2 degrees, with a non-smoothed trajectory. For the smoothed trajectory, the maximum velocity acceleration and jerks were defined, whereas for the non-smoothed trajectory, only the mean velocities were considered. The tested rehabilitation motion consists of six stages, each representing a predefined value for anatomic joint angles; the task of the robot is to change the values of the anatomic joint angles for each subsequent stage. Table 4 illustrates the defined joint angle values (as WS parameters) for the rehabilitation exercise stages. For the smoothed trajectory, the amplitude of motion for each anatomic joint, maximum joint velocities (vmax), accelerations (amax) and decelerations (a’max) were defined with the help of medical experts in neuromotor rehabilitation. For the non-smoothed trajectory, the mean joint velocity (vm) was imposed (i.e., no maximum acceleration and deceleration) to allow the controller (PID) to react to the sharp acceleration.
Figure 7 shows the WS parameters for the HKM module as functions of time in the displacement, velocity, and acceleration domains. The green, blue, and red curves are computed for the smoothed trajectory, whereas the black dashed curves are for the non-smooth trajectory. The velocity and acceleration domains were computed using numeric differentiation. The magnitude of the spikes in the acceleration domains is in the order of 103 and the plots are focused only on the smoothed trajectory acceleration domains.
Figure 8 and Figure 9 show the time history diagrams for the active joints (computed via Inverse Kinematics) for the smoothed trajectory and non-smoothed trajectory, respectively. The green, blue, and red curves represent the reference values for displacement, velocity, and acceleration, respectively; the black dashed curves represent the actual values of data that were extracted straight from the command and control unit wing B&R Automation Studio and plotted using MATLAB. Furthermore, the black curves represent the torque values τ read from the command and control unit.
The main differences between the smoothed (Figure 8) and non-smoothed (Figure 9) trajectories are apparent in the torque and acceleration plots. Non-smoothed trajectories required a torque control effort, which subsequently produced high spikes at the moment of sudden acceleration and deceleration.
The execution time was estimated on the command and control module of LegUp, which consists of a portable PC (Intel Core I7-6700K CPU @ 4.00 GHz), a PLC X20CP3586, three drivers 80VD100PD.C000-01, and five servomotors 8LVA23B1030-D000-0. The algorithm was deployed from MATLAB—Simulink into the PLC via B&R target for Simultink. The user inputs the data from Table 4 into the GUI, the data are transferred into the PLC, and the smoothed trajectory is computed. The smoothed function was timed using the SysTimeGetUs function. The test was performed 30 times, the mean time of execution was 5.9675 × 10−4, and the standard deviation was 8.0040 × 10−5.

5.2. Example for 2 Degrees Smoothed Trajectory for the AKM Module Considering Case 1

The second set of experimental data were recorded on a healthy subject performing ankle rehabilitation motions with the AKM module. The rehabilitation motion was divided into six stages, each with defined values for the ankle joint parameters γ 1 , γ 2 ; Table 5 illustrates the defined values for the rehabilitation exercise stages. As in the previous experimental case, the amplitude of motion and the kinematic parameters (velocities, accelerations) were defined with the help of medical experts.
Figure 10 shows the smoothed and non-smoothed trajectories for the γ 1 , γ 2 parameters. Figure 11 and Figure 12 show the time history diagrams for the active joints of the AKM module (computed via Inverse Kinematics) for both the smoothed trajectory and non-smoothed trajectory. As in the previous case, the green, blue, and red curves represent the reference values for displacement, velocity, and acceleration, respectively, and the black dashed curves represent the actual values (recorded via B&R Automation Studio). Again, the black curves represent the torque values τ read from the command and control unit.
For the AKM module, the main differences between the smoothed (Figure 11) and non-smoothed (Figure 12) trajectories are shown in the torque and acceleration plots. Just as in the case of the HKM module, non-smoothed trajectories required a torque control effort (although not as significant as for the HKM module), which subsequently produced high spikes at the moment of sudden acceleration and deceleration.
The execution time was again estimated on the command and control module of LegUp. The test was performed 30 times for the AKM module, the mean time of execution was 5. 5436 × 10−4, and the standard deviation was 8.1201 × 10−5.

6. Discussions

This paper presents a kinematic time scaling technique used to obtain smooth trajectories for the LegUp parallel robot used for rehabilitation. However, since it is assumed that the robot can already follow the non-smoothed trajectory within its WS, this algorithm is easily deployable on different robotic manipulators. Furthermore, due to the generality of the proposed method, such smoothing techniques can be used for a wide range of robotic applications. The following applications are proposed:
  • The algorithm can be deployed for each serial or parallel robot that requires inverse kinematics for path planning in medical or industrial domains.
  • The technique could be extended to mobile robots and benefit from sensor fusion [31] (considering more data inputs will increase the algorithm precision) or neuronal network-based solutions, as in [32].
  • The algorithm could even be extended and applied on the dual quaternion parameterization of Euclidean displacement [33,34] by adapting the algorithm to the established definitions of dual quaternion differentiation.
  • For rehabilitation robots, the algorithm could be implemented in conjunction with smart algorithms that provide biosignals [35] as a reference to further enhance the rehabilitation process.
  • In cases of reconfigurable robots [36,37], the algorithm can be deployed directly, but the WS parameterization must be adapted.
However, in this current state, the proposed algorithm may not be suitable for the trajectory smoothing of cable-driven robots, where an approach based on cable tension is more adequate [38].
The smoothing algorithm can be scaled to higher-order accelerations (e.g., snap). Note that for the 1-degree smoothing, one trapezoid profile was required in the velocity field. Furthermore, for 2-degree smoothing, two trapezoid profiles are required in the acceleration field. For 3-degree smoothing, four trapezoid profiles will be required in the jerk filed, and for every increase in the degree of smoothing, the number of trapezoid profiles will be multiplied by 2. In addition, for every increase in the degrees of smoothing, the cumsumtrapz() is required, which may lead to numerical inaccuracies due to numerical fluctuations and rounding errors.
The computational time of the proposed algorithm (benchmarked on the robot command and control module) was on average less than one millisecond. Note that this time was required to compute the kinematic values for all the sample points from the trajectory, which makes the method suitable for control. Furthermore, when considering the numerical efficiency, there is significant work on numerical methods covered in [39,40]. The proposed method has the time complexity O(n), while the error is O(n−3), where n is the number of divisions of the domain D. On the other hand, Bezier curves have complexity O(n2) using De Casteljau’s algorithm, while the error depends on the degree of the curve. B splines also provide O(n2) complexity using the Cox–de Boor recursion algorithm, with a generally lower error than with trapezoidal rule. However, the high computational cost presents a possible drawback in real-time implementation. If polynomial interpolation methods are analyzed (Newton or Lagrange), the complexity is still O(n2), but Runge’s phenomenon presents arbitrary anomalies regarding approximation errors for high-order curves. All of the above suggests that the proposed method is a good trade-off between time complexity and accuracy, being suitable for real-time implementation.
Patients’ safety during robotic-assisted neuro rehabilitation must be ensured. On the one hand, the proposed trajectory smoothing algorithm runs in a short period of time (less than one millisecond), which does not pose a computational stress on the PLC. This, in turn, allows for the safe running of the functions within the PLC designed for failsafe of the parallel robot. In a nutshell, implementing the smoothing algorithm in the command and control module did not affect the other functions of the robot, while gaining the benefit of safe low-inertia motions for the lower limb.

7. Conclusions

The paper proposes a numerical approach that reliably computes smooth trajectories for LegUp, i.e., trajectories with limited and gradual acceleration and deceleration that ensure low inertias at the level of the lower limb. Such trajectories reduce the risk of joint strain and thus increase the efficiency of the rehabilitation exercises and patient safety. The numerical approach uses simple and well-established mathematical techniques for numerical integration to compute a smoothing profile. The novelty of the approach comes from using a kinematic time scaling technique which uses the something profile and an input arbitrary trajectory to compute the smoothed trajectory (desired for the rehabilitation exercises). Due to its simplicity, the proposed approach was easily implementable within the robot’s control unit of LegUp and the time of computation was less than on millisecond on average, which did not affect any other robot functions designed for failsafe. Besides the benefit of lowering the inertias in robotic-assisted rehabilitation, numerical experiments with the LegUp parallel robot showed that smoothing the trajectory reduces the torque control effort.
As further research directions, the algorithm can be extended to higher-order derivatives by applying trapezoid profiles in the jerk, snap, etc., fields and performing numerical integrations to compute the lower-degree fields. However, at this point, the standard actuators (e.g., servomotors) are jerk limited, and as such extension (although not complex) could only be justifiable for high-precision applications.

Author Contributions

Conceptualization, I.B. and D.P.; Data curation, C.V. and A.C.; Formal analysis, I.B., V.M., A.C. and P.T.; Funding acquisition, J.M. and D.P.; Investigation, C.V. and P.T.; Methodology, I.B. and V.M.; Project administration, J.M. and D.P.; Resources, J.M.; Validation, V.M., J.M. and D.P.; Visualization, C.V.; Writing—original draft, I.B., V.M. and D.P.; Writing—review and editing, I.B. and V.M. All authors have read and agreed to the published version of the manuscript.

Funding

This research has been supported by the project new frontiers in adaptive modular robotics for patient-centered medical rehabilitation—ASKLEPIOS, funded by European Union—NextGenerationEU and Romanian Government, under National Recovery and Resilience Plan for Romania, contract no. 760071/23.05.2023, code CF 121/15.11.2022, with the Romanian Ministry of Research, Innovation and Digitalization, within Component 9, investment I8.

Data Availability Statement

The original contributions presented in the study are included in the article; further inquiries can be directed to the corresponding author.

Conflicts of Interest

The authors declare no conflicts of interest.

Nomenclature

The set of real numbers
Δ n An nth order partition of a domain D
α 1 ,   α 2 ,   β 1 ,   γ 1 ,   γ 2 Angle parameters for anatomic joints (WS parameters)
q i ,   i = 1 , 5 ¯ Active joint parameters
Γ A path through WS
f | Δ n Discrete function on the partition Δ n
Γ ( t ) Discrete trajectory
Γ [ k ] ( t ) Discrete smoothed trajectory of degree k
α 1 ( t ) ,   α 2 ( t ) ,     β 1 ( t ) ,   γ 1 ( t ) ,   γ 2 ( t ) Time dependent vectors of angle parameters (non-smoothed trajectory)
α 1 [ k ] ( t ) ,   α 2 [ k ] ( t ) ,   β 1 [ k ] ( t ) ,   γ 1 [ k ] ( t ) ,   γ 2 [ n ] ( t ) Time dependent vectors of angle parameters (smoothed trajectory)
J Kinematic Jacobian
Q ,   X Vectors of active joints and WS parameters

References

  1. Basteris, A.; Nijenhuis, S.M.; Stienen, A.H.; Buurke, J.H.; Prange, G.B.; Amirabdollahian, F. Training modalities in robot-mediated upper limb rehabilitation in stroke: A framework for classification based on a systematic review. J. Neuroeng. Rehabil. 2014, 10, 111. [Google Scholar] [CrossRef] [PubMed]
  2. Li, B.; Li, G.; Sun, Y.; Jiang, G.; Kong, J.; Jiang, D. A review of rehabilitation robots. In Proceedings of the 32nd Youth Academic Annual Conference of Chinese Association of Automation (YAC), Hefei, China, 19–21 May 2017; pp. 907–911. [Google Scholar]
  3. Campagnini, S.; Liuzzi, P.; Mannini, A.; Riener, R.; Carrozza, M.C. Effects of control strategies on gait in robot-assisted post-stroke lower limb rehabilitation: A systematic review. J. NeuroEng. Rehabil. 2022, 19, 52. [Google Scholar] [CrossRef] [PubMed]
  4. Iandolo, R.; Marini, F.; Semprini, M.; Laffranchi, M.; Mugnosso, M.; Cherif, A.; De Michieli, L.; Chiappalone, M.; Zenzeri, J. Perspectives and Challenges in Robotic Neurorehabilitation. Appl. Sci. 2019, 9, 3183. [Google Scholar] [CrossRef]
  5. Vaida, C.; Birlescu, I.; Pisla, A.; Carbone, G.; Plitea, N.; Ulinici, I.; Gherman, B.; Puskas, F.; Tucan, P.; Pisla, D. RAISE—An Innovative Parallel Robotic System for Lower Limb Rehabilitation. In New Trends in Medical and Service Robotics: Advances in Theory and Practice; Springer: Cham, Switzerland, 2019. [Google Scholar]
  6. Li, W.; Liu, K.; Li, C.; Sun, Z.; Liu, S.; Gu, J. Development and evaluation of a wearable lower limb rehabilitation robot. J. Bionic Eng. 2022, 19, 688–699. [Google Scholar] [CrossRef]
  7. Petersen, I.L.; Nowakowska, W.; Ulrich, C.; Andreasen Struijk, L.N. A novel sEMG triggered FES-hybrid robotic lower limb rehabilitation system for stroke patients. IEEE Trans. Med. Robot. Bionics 2020, 2, 631–638. [Google Scholar] [CrossRef]
  8. Almaghout, K.; Tarvirdizadeh, B.; Alipour, K.; Hadi, A. Design and control of a lower limb rehabilitation robot considering undesirable torques of the patient’s limb. Proc. Inst. Mech. Eng. Part H J. Eng. Med. 2020, 234, 1457–1471. [Google Scholar] [CrossRef]
  9. Miao, M.; Gao, X.; Zhu, W. A construction method of lower limb rehabilitation robot with remote control system. Appl. Sci. 2021, 11, 867. [Google Scholar] [CrossRef]
  10. Major, Z.Z.; Vaida, C.; Major, K.A.; Tucan, P.; Brusturean, E.; Gherman, B.; Birlescu, I.; Craciunaș, R.; Ulinici, I.; Simori, G.; et al. Comparative Assessment of Robotic versus Classical Physical Therapy Using Muscle Strength and Ranges of Motion Testing in Neurological Diseases. J. Pers. Med. 2021, 11, 953. [Google Scholar] [CrossRef]
  11. Huamanchahua, D.; Tadeo-Gabriel, A.; Chavez-Raraz, R.; Serrano-Guzman, K. Parallel robots in rehabilitation and assistance: A systematic review. In Proceedings of the 12th Annual Ubiquitous Computing, Electronics & Mobile Communication Conference (UEMCON), New York, NY, USA, 1–4 December 2021; pp. 0692–0698. [Google Scholar]
  12. Hogan, N.; Krebs, H.I. Interactive robots for neuro-rehabilitation. Restor. Neurol. Neurosci. 2004, 22, 349–358. [Google Scholar] [CrossRef]
  13. Fazekas, G.; Tavaszi, I. The future role of robots in neuro-rehabilitation. Expert Rev. Neurother. 2019, 19, 471–473. [Google Scholar] [CrossRef]
  14. Ezra Tsur, E.; Elkana, O. Intelligent Robotics in Pediatric Cooperative Neurorehabilitation: A Review. Robotics 2024, 13, 49. [Google Scholar] [CrossRef]
  15. Birlescu, I.; Tohanean, N.; Vaida, C.; Gherman, B.; Neguran, D.; Horsia, A.; Tucan, P.; Condurache, D.; Pisla, D. Modeling and analysis of a parallel robotic system for lower limb rehabilitation with predefined operational workspace. Mech. Mach. Theory 2024, 198, 105674. [Google Scholar] [CrossRef]
  16. Vaida, C.; Rus, G.; Tucan, P.; Machado, J.; Pisla, A.; Zima, I.; Birlescu, I.; Pisla, D. Enhancing Robotic-Assisted Lower Limb Rehabilitation Using Augmented Reality and Serious Gaming. Appl. Sci. 2024, 14, 12029. [Google Scholar] [CrossRef]
  17. Macfarlane, S.; Croft, E.A. Jerk-bounded manipulator trajectory planning: Design for real-time applications. IEEE Trans. Robot. Autom. 2003, 19, 42–52. [Google Scholar] [CrossRef]
  18. Kombarov, V.; Sorokin, V.; Fojtu, O.; Aksonov, Y.; Kryzhyvets, Y. S-Curve Algorithm of Acceleration/Deceleration With Smoothly limited Jerk In High-Speed Equipment Control Tasks. MM Sci. J. 2019, 2019, 3264–3270. [Google Scholar] [CrossRef]
  19. Fang, S.; Cao, J.; Zhang, Z.; Zhang, Q.; Cheng, W. Study on High-Speed and Smooth Transfer of Robot Motion Trajectory Based on Modified S-Shaped Acceleration/Deceleration Algorithm. IEEE Access 2020, 8, 199747–199758. [Google Scholar] [CrossRef]
  20. Chen, Q.; Zhang, C.; Ni, H.; Liang, X.; Wang, H.; Hu, T. Trajectory planning method of robot sorting system based on S-shaped acceleration/deceleration algorithm. Int. J. Adv. Robot. Syst. 2018, 15, 1729881418813805. [Google Scholar] [CrossRef]
  21. Chen, Y.; Ji, X.; Tao, Y.; Wei, H. Look-Ahead Algorithm with Whole S-Curve Acceleration and Deceleration. Adv. Mech. Eng. 2013, 5, 974152. [Google Scholar] [CrossRef]
  22. Ni, H.; Zhang, C.; Chen, Q.; Ji, S.; Hu, T.; Liu, Y. A novel time-rounding-up-based feedrate scheduling method based on S-shaped ACC/DEC algorithm. Int. J. Adv. Manuf. Technol. 2019, 104, 2073–2088. [Google Scholar] [CrossRef]
  23. Lee, G.; Kim, J.; Choi, Y. Convolution-Based Trajectory Generation Methods Using Physical System Limits. ASME J. Dyn. Syst. Meas. Control 2013, 135, 011001. [Google Scholar] [CrossRef]
  24. Jeon, J.W.; Ha, Y.Y. A generalized approach for the acceleration and deceleration of industrial robots and CNC machine tools. IEEE Trans. Ind. Electron. 2000, 47, 133–139. [Google Scholar] [CrossRef]
  25. Sampei, M.; Furuta, K. On time scaling for nonlinear systems: Application to linearization. IEEE Trans. Autom. Control 1986, 31, 459–462. [Google Scholar] [CrossRef]
  26. Li, S.; Respondek, W. Orbital feedback linearization for multi-input control systems. Int. J. Robust Nonlinear Control 2014, 25, 1352–1378. [Google Scholar] [CrossRef]
  27. Spivak, M. Calculus, 3rd ed.; Cambridge University Press: Cambridge, UK, 2006. [Google Scholar]
  28. Gosselin, C.; Angeles, J. Singularity analysis of closed-loop kinematic chains. IEEE Trans. Robot. Autom. 1990, 6, 281–290. [Google Scholar] [CrossRef]
  29. Pisla, D.; Plitea, N.; Gherman, B.; Pisla, A.; Vaida, C. Kinematical analysis and design of a new surgical parallel robot. In Proceedings of the 5th International Workshop on Computational Kinematics, Duisburg, Germany, 6–8 May 2009; pp. 273–282. [Google Scholar]
  30. Varedi-Koulaei, S.M.; Mohammadi, M.; Mohammadi, M.A.M.; Bamdad, M. Optimal Synthesis of the Stephenson-II Linkage for Finger Exoskeleton Using Swarm-based Optimization Algorithms. J. Bionic Eng. 2023, 20, 1569–1584. [Google Scholar] [CrossRef]
  31. Hu, K.; Chen, Z.; Kang, H.; Tang, Y. 3D vision technologies for a self-developed structural external crack damage recognition robot. Autom. Constr. 2024, 159, 105262. [Google Scholar] [CrossRef]
  32. Wu, F.; Zhu, R.; Meng, F.; Qiu, J.; Yang, X.; Li, J.; Zou, X. An Enhanced Cycle Generative Adversarial Network Approach for Nighttime Pineapple Detection of Automated Harvesting Robots. Agronomy 2024, 14, 3002. [Google Scholar] [CrossRef]
  33. Pisla, D.; Birlescu, I.; Vaida, C.; Tucan, P.; Pisla, A.; Gherman, B.; Crisan, N.; Plitea, N. Algebraic modeling of kinematics and singularities for a prostate biopsy parallel robot. Proc. Rom. Acad. Ser. A 2019, 19, 489–497. [Google Scholar]
  34. Vaida, C.; Pisla, D.; Schadlbauer, J.; Husty, M.; Plitea, N. Kinematic analysis of an innovative medical parallel robot using study parameters. In New Trends in Medical and Service Robots. Mechanisms and Machine Science; Wenger, P., Chevallereau, C., Pisla, D., Bleuler, H., Rodić, A., Eds.; Springer: Cham, Switzerland, 2016; Volume 39. [Google Scholar]
  35. Bamdad, M.; Mokri, C.; Abolghasemi, V. Joint mechanical properties estimation with a novel EMG-based knee rehabilitation robot: A machine learning approach. Med. Eng. Phys. 2022, 110, 103933. [Google Scholar] [CrossRef]
  36. Jungwon, S.; Jamie, P.; Mark, Y. Modular Reconfigurable Robotics. Annu. Rev. Control. Robot. Auton. Syst. 2019, 2, 63–88. [Google Scholar]
  37. Nainer, C.; Giusti, A. Automatically Deployable Robust Control of Modular Reconfigurable Robot Manipulators. IEEE Robot. Autom. Lett. 2022, 7, 5286–5293. [Google Scholar] [CrossRef]
  38. Badrikouhi, M.; Bamdad, M. Smooth trajectory planning based on direct collocation method for cable-driven parallel robots with central spine. Mech. Solids 2022, 57, 652–670. [Google Scholar] [CrossRef]
  39. Mitra, A.; Mitra, A. Introduction to Numerical Methods—Mathematical Techniques for Students in Engineering (Second Edition); Cognella: San Diego, CA, USA, 2023. [Google Scholar]
  40. Cohen, H. Numerical Approximation Methods: π ≈ 355/113; Springer: New York, NY, USA, 2014. [Google Scholar]
Figure 1. Simplified CAD model of LegUp.
Figure 1. Simplified CAD model of LegUp.
Mathematics 13 01241 g001
Figure 2. Kinematic schemes of LegUp modules: (a) hip flexion/extension sub-module (FEs-m); (b) hip abduction/adduction sub-module (Aas-m); (c) closed-loop kinematic chains of the ankle module.
Figure 2. Kinematic schemes of LegUp modules: (a) hip flexion/extension sub-module (FEs-m); (b) hip abduction/adduction sub-module (Aas-m); (c) closed-loop kinematic chains of the ankle module.
Mathematics 13 01241 g002
Figure 3. Smoothing profile of 1 degree: (a) input linear profile (black) and S-shaped profile (green—computed by integration of the velocity profile); (b) velocity profile (imposed); (c) acceleration profile (computed by differentiation of the velocity profile).
Figure 3. Smoothing profile of 1 degree: (a) input linear profile (black) and S-shaped profile (green—computed by integration of the velocity profile); (b) velocity profile (imposed); (c) acceleration profile (computed by differentiation of the velocity profile).
Mathematics 13 01241 g003
Figure 4. Smoothing profile of degree 2: (a) input linear profile (black) and S-shaped profile (green—computed by integration of the velocity profile); (b) velocity profile (computed by integration of the acceleration profile); (c) acceleration profile (imposed).
Figure 4. Smoothing profile of degree 2: (a) input linear profile (black) and S-shaped profile (green—computed by integration of the velocity profile); (b) velocity profile (computed by integration of the acceleration profile); (c) acceleration profile (imposed).
Mathematics 13 01241 g004
Figure 5. Process to compute time-dependent discrete smoothed functions: (a) smoothing profile; (b) input non-smoothed trajectory; (c) time scaling approach; (d) smoothed trajectory.
Figure 5. Process to compute time-dependent discrete smoothed functions: (a) smoothing profile; (b) input non-smoothed trajectory; (c) time scaling approach; (d) smoothed trajectory.
Mathematics 13 01241 g005
Figure 6. Experimental model of LegUp.
Figure 6. Experimental model of LegUp.
Mathematics 13 01241 g006
Figure 7. Time history diagrams for the computed smoothed trajectory of 2 degrees for the HKM module (green—displacement, blue—velocity, red—acceleration), and the non-smoothed trajectory (black dashed curves for all displacement, velocity, acceleration).
Figure 7. Time history diagrams for the computed smoothed trajectory of 2 degrees for the HKM module (green—displacement, blue—velocity, red—acceleration), and the non-smoothed trajectory (black dashed curves for all displacement, velocity, acceleration).
Mathematics 13 01241 g007
Figure 8. Time history diagrams for the active joints reference values for the smoothed trajectory of 2 degrees for the HKM module (green—displacement, blue—velocity, red—acceleration, black—torque) and the actual values (black dashed).
Figure 8. Time history diagrams for the active joints reference values for the smoothed trajectory of 2 degrees for the HKM module (green—displacement, blue—velocity, red—acceleration, black—torque) and the actual values (black dashed).
Mathematics 13 01241 g008
Figure 9. Time history diagrams for the active joints reference values for the non-smoothed trajectory for the HKM module (green—displacement, blue—velocity, red—acceleration, black—torque) and the actual values (black dashed).
Figure 9. Time history diagrams for the active joints reference values for the non-smoothed trajectory for the HKM module (green—displacement, blue—velocity, red—acceleration, black—torque) and the actual values (black dashed).
Mathematics 13 01241 g009
Figure 10. Time history diagrams for the computed smoothed trajectory of 2 degrees for the AKM module (green—displacement, blue—velocity, red—acceleration) and the non-smoothed trajectory (black dashed curves for all displacement, velocity, acceleration).
Figure 10. Time history diagrams for the computed smoothed trajectory of 2 degrees for the AKM module (green—displacement, blue—velocity, red—acceleration) and the non-smoothed trajectory (black dashed curves for all displacement, velocity, acceleration).
Mathematics 13 01241 g010
Figure 11. Time history diagrams for the active joints reference values for the smoothed trajectory of 2 degrees for the AKM module (green—displacement, blue—velocity, red—acceleration, black—torque) and the actual values (black dashed).
Figure 11. Time history diagrams for the active joints reference values for the smoothed trajectory of 2 degrees for the AKM module (green—displacement, blue—velocity, red—acceleration, black—torque) and the actual values (black dashed).
Mathematics 13 01241 g011
Figure 12. Time history diagrams for the active joints reference values for the non-smoothed trajectory for the AKM module (green; displacement, blue; velocity, red; acceleration, black; torque) and the actual values (black dashed).
Figure 12. Time history diagrams for the active joints reference values for the non-smoothed trajectory for the AKM module (green; displacement, blue; velocity, red; acceleration, black; torque) and the actual values (black dashed).
Mathematics 13 01241 g012
Table 1. Geometric parameters for the FEs-m sub-module of the HKM module.
Table 1. Geometric parameters for the FEs-m sub-module of the HKM module.
L0 [mm]L1 [mm]L2 [mm]Lt [mm]l0 [mm]l1 [mm]l2 [mm]
63046550305160200265
Table 2. Geometric parameters for the AAs-m sub-module of the HKM module.
Table 2. Geometric parameters for the AAs-m sub-module of the HKM module.
Dy [mm]L3 [mm]d0 [mm]d1 [mm]
400450230465
Table 3. Geometric parameters for the AKM module.
Table 3. Geometric parameters for the AKM module.
La1 [mm]La2 [mm]Lb1 [mm]Lb2 [mm]
100100100100
Table 4. Rehabilitation exercises stages for the hip and knee joints.
Table 4. Rehabilitation exercises stages for the hip and knee joints.
st. 1st. 2st. 3st. 4st. 5vmaxamaxa’maxvm
α 1 0 [°]15 [°]0 [°]0 [°]0 [°]8 [°/s]16 [°/s]16 [°/s]5.7 [°/s]
α 2 0 [°]0 [°]0 [°]60 [°]0 [°]10 [°/s]20 [°/s]20 [°/s]8.9 [°/s]
β 1 0 [°]0 [°]0 [°]60 [°]0 [°]10 [°/s]20 [°/s]20 [°/s]8.9 [°/s]
Table 5. Rehabilitation exercises stages for the ankle joint.
Table 5. Rehabilitation exercises stages for the ankle joint.
st. 1st. 2st. 3st. 4st. 5st. 6st. 7st. 8vmaxamaxa′maxvm
γ 1 0 [°]15 [°]0 [°]– 15 [°]0 [°]0 [°]0 [°]0 [°]18 [°/s]36 [°/s]36 [°/s]9.5 [°/s]
γ 2 0 [°]0 [°]0 [°]0 [°]– 15 [°]0 [°] 15 [°]0 [°]18 [°/s]36 [°/s]36 [°/s]9.5 [°/s]
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Birlescu, I.; Mihaly, V.; Vaida, C.; Caprariu, A.; Tucan, P.; Machado, J.; Pisla, D. Numerical Approach for Trajectory Smoothing for LegUp Rehabilitation Parallel Robot. Mathematics 2025, 13, 1241. https://doi.org/10.3390/math13081241

AMA Style

Birlescu I, Mihaly V, Vaida C, Caprariu A, Tucan P, Machado J, Pisla D. Numerical Approach for Trajectory Smoothing for LegUp Rehabilitation Parallel Robot. Mathematics. 2025; 13(8):1241. https://doi.org/10.3390/math13081241

Chicago/Turabian Style

Birlescu, Iosif, Vlad Mihaly, Calin Vaida, Andrei Caprariu, Paul Tucan, Jose Machado, and Doina Pisla. 2025. "Numerical Approach for Trajectory Smoothing for LegUp Rehabilitation Parallel Robot" Mathematics 13, no. 8: 1241. https://doi.org/10.3390/math13081241

APA Style

Birlescu, I., Mihaly, V., Vaida, C., Caprariu, A., Tucan, P., Machado, J., & Pisla, D. (2025). Numerical Approach for Trajectory Smoothing for LegUp Rehabilitation Parallel Robot. Mathematics, 13(8), 1241. https://doi.org/10.3390/math13081241

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop