Next Article in Journal
Design and Validation of a Low-Cost Automated Dip-Coater System for Laboratory Applications
Previous Article in Journal
FEA-Guided Toolpath Compensation for Robotic Machining: An Integrated CAD/CAM/CAE Framework for Enhanced Accuracy
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Implementation of Path-Following Control of Lizard-Inspired Single-Actuated Robot Utilizing Inverse Kinematics

by
Shunsuke Nansai
1,*,
Norihiro Kamamichi
2 and
Akihiro Naganawa
1
1
Faculty of Informatics and Data Science, Akita University, Akita 010-8502, Japan
2
Department of Robotics and Mechatronics, Tokyo Denki University, Tokyo 120-8551, Japan
*
Author to whom correspondence should be addressed.
Automation 2025, 6(4), 74; https://doi.org/10.3390/automation6040074
Submission received: 27 August 2025 / Revised: 30 October 2025 / Accepted: 6 November 2025 / Published: 14 November 2025
(This article belongs to the Section Robotics and Autonomous Systems)

Abstract

The purpose of this paper is to implement a path-following control system based on the kinematics of the Lizard-Inspired Single-Actuated robot (LISA). LISA is a new type of robot that mimics the quadrupedal walking morphology of lizards with a four-bar linkage mechanism and can realize both propulsion and turning with 1 degree-of-freedom. To achieve this purpose, this paper takes 3 approaches: kinematics formulation, control system design, and experimental verification. In the kinematics formulation, we formulate LISA’s turning angle, stride length, posture, propulsive direction, curvature, and position coordinate. In control system design, we design a control system that converges not only the distance error but also the posture error and control input. Conditional equations that can achieve these 3 control targets are formulated using forward kinematics and reference path functions. The experimental verifications were carried out to verify the effectiveness of the designed path-following control system using three types of paths: linear, circular, and combined linear and circular. As a result, it was confirmed that the Root Mean Square values for the control input, the distance error, and the attitude error were sufficiently small in steady state. Therefore, it was confirmed that the 3 control objectives had been achieved.

1. Introduction

In recent years, mobile systems with a limited number of degrees of freedom (DOF) have gained attention as promising structures for compact and lightweight robots. A well-known example is the mechanism proposed by the Dutch kinetic artist Jansen, who designed a closed-chain linkage capable of walking with only one actuator by transforming periodic input motion into an elliptical trajectory [1]. Subsequent studies have combined multiple Jansen mechanisms to build multi-legged robots that still operate with a single actuator [2,3,4]. Another representative design is the hexapod robot 1STAR, which consists of six legs connected to a rectangular body and can be actuated by one motor [5,6,7]. The same research group also developed STAR, a six-legged robot that requires three actuators: two for the left and right legs and one to regulate the sprawl angle [8,9,10]. In addition, they presented a wave-type robot named SAW, composed of a motor, a rotating spiral backbone, and links constrained along this spine, all of which are actuated by a single motor [11,12,13]. Separately, a team from the American University of Beirut proposed a differential-drive robot with variable-diameter wheels, controlled by diameter changes and pendulum effects [14,15,16]. Moreover, a skateboard-inspired two-wheeled robot driven by a single actuator with a torque limiter has been reported [17].
Another line of research focuses on robots inspired by lizards as a biomimetic strategy. Lizards often enhance locomotion efficiency at high speeds by twisting their waist rather than relying primarily on leg motion. This observation indicates that reducing the number of actuators in multi-legged robots is feasible, possibly enabling locomotion with only one actuator. Based on this idea, the College of Industrial Technology developed a lizard-inspired robot [18,19]. In our earlier work, we analyzed the dynamics of a lizard-type robot and created a prototype driven solely by one actuator [20,21]. The structure of such robots, illustrated in Figure 1, consists of two opposing triangles sharing a central drive joint. The legs correspond to the other vertices, and locomotion is achieved by oscillating the central joint side to side (Figure 1a).
These previous studies, together with experimental evidence, indicate that robots controlled with only a few actuators are appealing as compact, lightweight, and novel mobile systems. Nevertheless, three main shortcomings arise from the restricted degrees of freedom. First, locomotion theoretically requires slipping of the supporting legs or wheels. Second, steering cannot be achieved without introducing extra actuators. Third, designing controllers demands consideration of complex dynamics, often influenced by uncertain factors such as ground friction. For instance, in the Jansen mechanism, slipping of the toes is unavoidable during walking. Analyses in [22,23,24] showed that toe velocity changes in a nonlinear fashion. As a result, when the legs of a Jansen robot are driven in phase, their speeds differ, leading to slippage of the supporting leg. A method to keep toe velocity constant was proposed in [25], but applying it to multi-legged Jansen robots would require independent actuators for each leg, negating single-actuator operation. In the same way, 1STAR and SAW robots depend on toe slippage to move. Their legs are shaped to slip by design, and their motion is explained using dynamic models that include ground friction. Because friction varies with surface conditions, precise control requires environment-specific modeling. Moreover, SAW needs extra actuators for turning, and STAR requires no fewer than three actuators in addition to slipping legs. Robots with variable-diameter wheels and skateboard-type systems likewise involve complicated dynamics that challenge control system design. The lizard-inspired robot (Figure 1) illustrates another limitation of 1-DOF designs: when the supporting legs remain fixed, the central driving node can only occupy positions equidistant from them. Thus, as the drive joint moves continuously, the support leg positions shift, producing slip. These issues not only lower locomotion efficiency but also make it necessary to analyze complex dynamics, including uncertain friction effects, to fully understand and control their motion.
To overcome these limitations, we introduce a Lizard-Inspired Single-Actuated robot (LISA), which operates with only one degree of freedom. LISA takes inspiration from the lateral swinging of a lizard’s trunk—a defining feature of its gait—and achieves both forward motion and steering using a single actuator. As illustrated in Figure 2, the robot reproduces lizard-like quadrupedal walking through a four-bar linkage mechanism. This design is the key innovation of LISA: it not only enables stable, slip-free walking but also allows its motion to be described through kinematic equations, which are significantly simpler to handle than full dynamic models. Figure 2a depicts LISA advancing by swinging its front link back and forth, while alternately switching the supporting leg each time the swing reverses. To verify the practicality of this approach, we constructed a working prototype [26] and applied trajectory-tracking control with PID methods [27,28]. In addition, we implemented tracking control with posture compensation [29]. The controllers presented in [27,28,29] are based on conventional control theory and confirmed that effective motion control of LISA is feasible. Looking ahead, our objective is to develop model-based control strategies for LISA within the framework of modern control theory.
There exist many established approaches for model-based motion control, depending on the specific application and the characteristics of the system. In this study, our attention is directed toward path-following control. This problem is especially relevant in vehicle dynamics, where, for instance, Altafini proposed a controller for multi-trailer vehicles with several connected units [30]. Okajima gives another example [31], which developed an optimal velocity regulation method for path-following by incorporating reference equations directly into vehicle dynamics. Both approaches are representative of model-based designs that utilize system dynamics, and they represent the type of control performance we aim to achieve. Nonetheless, since Altafini and Okajima address conventional vehicles, their formulations rely on time-dependent differential equations. Within such models, stabilization methods for nonlinear systems—such as output-zeroing—are readily applicable, and both Altafini and Okajima employ such techniques [30,31]. By contrast, LISA is a mobile robot whose locomotion arises from geometric constraints, meaning that its behavior cannot be expressed through ordinary differential equations. Consequently, common nonlinear stabilization schemes cannot be applied. Moreover, LISA is underactuated, using only one control input for both forward motion and turning. As a result, when tracking a path, some degree of temporary deviation must be expected. Model predictive control offers a potential way to manage this issue, but its suitability for a geometrically constrained, single-input robot like LISA remains to be verified. Furthermore, in the field of low-degree-of-freedom driven robots, efforts have primarily focused on developing new drive mechanisms and improving the performance of existing mechanisms. Approaches from the perspective of control engineering, such as path-following problems, have not been extensively explored. For example, in the study of the Jansen linkage mechanism, several prototypes for applications have been developed, but the main contributions lie in gait analysis and hardware evaluation [32,33]. Furthermore, research on STAR focuses on improving traversability [34,35]. One of the few examples is the application of rapidly exploring random trees (RRT), a global path generation method, to STAR [9]. However, this approach did not sufficiently consider the dynamic characteristics of STAR, leaving challenges in its control performance. Thus, realizing motion control that accounts for the dynamic characteristics remains one of the problems to be solved in the field of low-degree-of-freedom driven robots.
The purpose of this paper is to implement a path-following control system based on the kinematics of LISA as a fundamental attempt to design an advanced control system for LISA. The key point of the control system is to design a control system that converges not only the distance error but also the attitude error and the control input. As a basic attempt, this paper selects a path close enough to the LISA as a reference path and designs a control system that does not consider input and state constraints. That means designing control systems that deal implicitly with the mechanical constraints of the system. To achieve this, this paper takes 3 approaches: kinematics formulation, control system design, and experimental verification. The kinematic formulation defines the original robot coordinates and formulates the LISA’s turning angle and stride, posture, direction of motion, curvature, and position of the robot coordinates. The key point of the formulation is to formulate the geometrical relative relationships when switching the supporting leg between two consecutive steps. In the control system design, the control input consists of feedforward and feedback control inputs. The feedforward control input is obtained by solving the inverse problem of the formulated curvature. The feedback control input is obtained by formulating the conditional equation for path following using LISA’s four-step forward kinematics and a function of the reference path, and solving its inverse problem. The experimental verification implements the designed control system on 3 types of paths: linear, circular, and a combination of circular and linear trajectories. The verification focuses on whether the designed control system can make LISA follow the reference paths while satisfying the 3 control targets.
This study aims to develop a path-following control framework for LISA based on its kinematic model, serving as a preliminary step toward more sophisticated controllers. The essential feature of the proposed system is that it minimizes not only the positional error but also the orientation error and the control input. As an initial attempt, this work considers reference paths located close to LISA’s natural trajectory and establishes a controller that does not explicitly impose input or state constraints, thereby addressing the mechanical restrictions of the system implicitly. To achieve this goal, the study follows three stages: kinematic modeling, controller design, and experimental validation. The kinematic formulation specifies the robot’s coordinate system and derives expressions for stride length, turning angle, posture, direction of motion, curvature, and position. The critical aspect of this modeling is capturing the geometric relationships that occur when the supporting leg switches between successive steps. In the controller design phase, the input is divided into feedforward and feedback components. The feedforward part is obtained by solving the inverse problem of the derived curvature, while the feedback part is determined by formulating path-following conditions through LISA’s four-step forward kinematics and reference trajectory functions, and then solving their inverse. For the experimental stage, the proposed controller is applied to three types of paths: straight, circular, and combined circular-linear routes. The focus of validation is to confirm whether the controller enables LISA to track the reference trajectories while meeting the three targeted objectives.
This paper is organized as follows. Section 2 formulates the kinematics of LISA. Section 3 designs a path-following control system based on LISA’s kinematics. Section 4 performs numerical simulations. Section 5 performs experimental verifications. Section 6 concludes the paper.

2. Kinematics

This section presents the kinematic formulation of LISA. The central focus of the modeling is the geometric relationship that arises when the supporting leg changes. LISA’s motion is generated by the continuous oscillation of its front link. Because the robot is built on a four-bar linkage, its movement characteristics remain constant as long as the same support leg is maintained, constrained by the linkage structure. However, when the oscillation reverses direction and the supporting leg is switched, the motion properties undergo a marked change. Thus, the kinematics at the instant of switching more accurately describe LISA’s behavior than a continuous dynamic model that only reflects the oscillation of the front link. For this reason, in this study, we define the displacement and angular change of LISA’s coordinates at the switching moment as the stride length and turning angle. Put differently, the analysis captures the geometric relation between two consecutive steps. First, the hardware configuration of the prototype is outlined. Next, a specific coordinate system for the robot is defined. Then, expressions for turning angle, stride length, and body orientation are derived. Finally, the propulsion direction and the turning curvature of LISA are formulated.
Figure 3 illustrates the LISA prototype. The prototype used in this paper was developed in our previous research, and its details are reported in the previous research [36]. The LISA prototype is built from two primary subsystems: a four-bar linkage and a sliding unit. A notable feature of the robot is the pair of intersecting links that form part of the four-bar mechanism. The rotating joints of this mechanism act as legs, allowing the robot to walk. For propulsion, LISA uses claw-like feet similar to those reported in earlier studies [26], which can grip rough horizontal surfaces such as carpets. The sliding unit contains a linear guide pair and accommodates the actuator, battery, and control circuitry. The sliding unit is fixed at both ends to the center of the front and hind links of the 4-bar linkage mechanism. Table 1 summarizes the physical dimensions and main specifications of LISA. The actuator employed is the ROBOTIS XM430-W210-T, and the controller is the ROBOTIS OpenRB-150. Power is provided by an 11.1 V LIPO Battery (LB-011). Table 2 lists the detailed specifications of the XM430-W210-T motor. This device belongs to the category of smart servos and integrates the 12-bit magnetic encoder AS5045 from ams-OSRAM AG, together with a local control circuit for motor operation. A Bluetooth module mounted on the board enables wireless serial communication. The lengths of the front and rear links are l = 100 mm, while the diagonal links measure d = 2 l = 100 2 mm. The maximum input rotation is limited to ± 90 degrees, which also represents the theoretical bound for maintaining LISA’s specific structure. The achievable turning angle, stride length, direction of motion, and trajectory curvature are all restricted by this input limit.
Figure 3 and Table 1 represent the implementation environment assumed for the control system discussed in this paper. Therefore, the control system must be designed within these constraints. However, these constraints are not explicitly addressed in this study, as it is assumed that LISA’s reference trajectory and initial position are sufficiently close. The schematic figure of LISA is shown in Figure 4a. In this study, we set our local coordinates, called the robot coordinates. This robot coordinate system is configured to match the structure of the LISA prototype. Specifically, the sliding unit is fixed at the center of the front and rear links of the 4-bar linkage mechanism, with an actuator installed on one end of the sliding unit. The y r -axis, the y-axis of the robot coordinates, is set on a line passing through O r , the midpoint between P 1 and P 2 , and O r , the midpoint between P 3 and P 4 , with O r direction positive. Set the x r -axis, the x-axis of the robot coordinates, on a line perpendicular to the y r -axis and passing through O r , positive in the P 2 -direction. θ b ( k ) is the angle between the line passing through P 1 and P 4 and the x r -axis and the angle between the line passing through P 2 and P 3 and the x r -axis. θ ( k ) is the angle between the x r -axis and the front link, defined as the input angle. k , ( k = 0 , , n ) is the number of times the support leg is switched.
Now define θ ( k ) as the follows:
θ ( k ) = ( 1 ) k α + β ( k ) .
In (1), α [rad] represents the amplitude of the standard stride, while β ( k ) [rad] denotes the control input. The variable θ ( k ) determines the 1-DOF of LISA, corresponding to the angle of the front link at the moment the support leg switches during the k-th step. Conceptually, this aligns with the ground contact position of the legs in a conventional multi-legged robot. Thus, the angle between θ ( k ) of the k-th step and θ ( k + 1 ) of the ( k + 1 ) -th step is typically interpolated through some function, enabling LISA to smoothly adjust the posture of its four-bar linkage mechanism while maintaining the same supporting leg. This interpolation, however, is not addressed in this paper, as the focus is only on the geometric configuration of the robot at the support leg switching instant.
Also θ b ( k ) is derived as follows:
θ b ( k ) = cos 1 l d cos θ ( k ) .
According to (2), θ b ( k ) is a function of θ ( k ) , meaning that any continuous change in θ ( k ) leads to a corresponding continuous change in θ b ( k ) . As stated, this paper does not address such continuous changes, focusing instead on the robot’s geometry at the switching moment. From Figure 4a, θ b ( k ) is defined as the angle formed between two distinct points, both of which are geometrically expressed in (2). Defining θ b ( k ) in this way simplifies kinematic analysis. LISA walks in two modes: one with supporting legs P 1 and P 4 , and another with P 2 and P 3 . It is more popular to handle the geometry with respect to the supporting legs. Without defining the robot coordinates as done here, kinematics based on either support leg would become a complex nonlinear function for each mode, complicating analysis and control design. In contrast, the coordinates in this study are independent of which legs are supporting, using the left and right centers of the robot as the y-axis. This framework allows variables like θ b ( k ) to retain a consistent form on both sides. By using these variables, the same kinematic equations apply even when the support leg changes, greatly simplifying both analysis and control system design.

2.1. Turning Angle

Define the turning angle ψ ( k , k 1 ) as the change in the y r axis of the robot coordinates between the ( k 1 ) -th step and the k-th step. It is generated by applying the control input β ( k ) β ( k 1 ) in (1). Figure 4b,c show schematic diagrams of the changes in the robot coordinate of LISA for odd to even steps and for even to odd steps. In Figure 4b,c, the solid black line shows the LISA of the first of two consecutive steps. The black dashed line indicates the LISA of the second step. The grey coordinate represents the robot coordinate at each step. In Figure 4b,c, it can be seen that θ b ( k ) is symmetrically represented regardless of the supporting leg. This is the effect of the unique robot coordinate, which greatly contributes to the ease of analysis. From Figure 4b, the LISA turning angle ψ ( k ev , k ev 1 ) from odd to even steps is the change in θ b ( k ) and can be formulated as follows:
ψ ( k ev , k ev 1 ) = θ b ( k ev ) θ b ( k ev 1 ) , k ev = 2 , 4 , 6 , , n .
Similarly, from Figure 4c, the LISA turning angle ψ ( k odd , k odd 1 ) for even to odd steps can be formulated as follows:
ψ ( k odd , k odd 1 ) = θ b ( k odd 1 ) θ b ( k odd ) , k odd = 1 , 3 , 5 , , n .
From (3) and (4), the LISA turning angle ψ ( k , k 1 ) [rad] can be formulated as follows:
ψ ( k , k 1 ) = ( 1 ) k θ b ( k ) θ b ( k 1 ) , k = 1 , , n .
where (5) is derived as a two-variable function depending on k 1 and k. This means that the turning angle depends on the current and next input angles.

2.2. Stride

Define the stride as the linear distance in robot coordinates O r between the ( k 1 )-th step and the k-th step. From Figure 4b,c, the change in the angle of the front link A ( k , k 1 ) can be formulated as follows:
A ( k , k 1 ) = θ ( k ) θ ( k 1 ) + ψ ( k , k 1 ) , k = 1 , , n .
Using the fact that the relationship between the robot coordinates O r ( k ) , O r ( k 1 ) and the supporting leg P 1 or P 2 of the front link is an isosceles triangle, the stride s ( k , k 1 ) [m] can be formulated as follows:
s ( k , k 1 ) = sgn A ( k , k 1 ) l sin A ( k , k 1 ) 2 , k = 1 , , n ,
where sgn(·) is a sign function and
sgn x = 1 , if x 0 , 1 , else .
Similarly to (5), (6) is a two-variable function that depends on k 1 and k.

2.3. Posture

Define the attitude as the angle between the absolute coordinate and the robot coordinate. From Figure 4a, LISA’s attitude ϕ r ( k ) [rad] concerning the absolute coordinate can be formulated as follows, where the initial attitude of LISA is ϕ r ( 0 ) [rad]:
ϕ r ( k ) = n = 1 k ψ ( n , n 1 ) + ϕ r ( 0 ) .

2.4. Propulsive Direction

The direction of propulsion of LISA is defined as the angle between the line segment formed by the stride and the y-axis of the absolute coordinate. From Figure 4b,c, using the tangent theorem relationship between the tangent line of the circle of radius l / 2 centered at the support leg P 1 or P 2 of the front link and the line segment formed by the stride length, the direction of propulsive B ( k , k 1 ) can be formulated as follows:
B ( k , k 1 ) = A ( k , k 1 ) 2 + θ ( k 1 ) + ϕ r ( k 1 ) . k = 1 , , n .

2.5. Curvature

Curvature is defined as the curvature of the arc through O r ( k ) , O r ( k ) , O r ( k 1 ) and O r ( k 1 ) when LISA turns with a turning radius ψ ( k , k 1 ) as in Figure 5. The centre of the arc is defined as O c and the radius of the arc as r ψ . Figure 6 shows a schematic diagram of LISA walking two steps with the same turning radius ψ ( k , k 1 ) = ψ ( k + 1 , k ) . For LISA to walk at ψ ( k , k 1 ) = ψ ( k + 1 , k ) , it must be θ ( k 1 ) = θ ( k + 1 ) from (5). From this condition, s ( k + 1 , k ) = s ( k 1 , k ) . Where
L temp : = O r ( k 1 ) O r ( k + 1 ) ,
then from Figure 6, using the cosine theorem, the following equation holds.
L temp 2 = s ( k , k 1 ) 2 + s ( k + 1 , k ) 2 + 2 s ( k , k 1 ) s ( k + 1 , k ) cos ψ ( k , k 1 ) ,
L temp 2 = r ψ 2 2 2 cos O r ( k 1 ) O c O r ( k + 1 ) .
Now, place any point P temp on the turning circle and consider the cyclic quadrilateral O r ( k 1 ) O r ( k ) O r ( k + 1 ) P temp . From the property of a cyclic quadrilateral,
O r ( k 1 ) P temp O r ( k + 1 ) = ψ ( k , k 1 ) .
Therefore, from the circumferential angle theorem, we obtain
O r ( k 1 ) O c O r ( k + 1 ) = 2 ψ ( k , k 1 ) .
From (9)–(11), we note that s ( k + 1 , k ) = s ( k 1 , k ) , and organising for r ψ we obtain the follows:
r ψ 2 = s ( k , k 1 ) 2 + s ( k 1 , k ) 2 + 2 s ( k , k 1 ) s ( k 1 , k ) cos ψ ( k , k 1 ) 2 2 cos ( 2 ψ ( k , k 1 ) ) .
From (12), the curvature κ ( k , k 1 ) is the reciprocal of r ψ , so
κ ( k , k 1 ) = 2 2 cos ( 2 ψ ( k , k 1 ) ) s ( k , k 1 ) 2 + s ( k 1 , k ) 2 + 2 s ( k , k 1 ) s ( k 1 , k ) cos ψ ( k , k 1 ) .

2.6. Position

The position of LISA’s robot coordinate in the absolute coordinate ( x r ( k ) , y r ( k ) ) is formulated by the asymptotic formula as follows:
x r ( k ) =   x r ( k 1 ) s ( k , k 1 ) sin B ( k , k 1 ) , y r ( k ) =   y r ( k 1 ) + s ( k , k 1 ) cos B ( k , k 1 ) .

3. Control System Design

In this section, the path-following control system is designed. In this paper, it is assumed that the distance between the reference path and the initial position of the LISA is close enough. Under this assumption, we design a control system that converges not only the distance error but also the attitude error and the control input. The reference path is assumed to be a straight line or a circle in the absolute coordinate system and is a function represented by f t ( x , y ) = 0 . Figure 7 shows the block diagram of the control system. The control system broadly consists of a feedforward control system and a feedback control system, each deriving control inputs by solving the inverse problem of LISA’s kinematic characteristics derived in Section 2. Furthermore, in this paper, the k-th step refers to the currently observed state of LISA. Therefore, the control system determines the control input that determines the state of LISA at the ( k + 1 ) -th step. The control input β ( k + 1 ) [rad] is defined as follows:
β ( k + 1 ) = β f f ( k + 1 ) + β f b ( k + 1 ) .
where β f f ( k + 1 ) and β f b ( k + 1 ) are the feedforward and feedback control inputs, respectively, and in this paper, we design a control system where β f b ( k + 1 ) 0 .

3.1. Feedforward Control System

Formulate the feedforward control input β f f ( k + 1 ) . The β f f ( k + 1 ) is the control input when turning with the curvature of the reference path. Let the curvature of the circle tangent to the point on the reference path closest to the robot coordinates be κ t . Since κ t is the curvature of the circle, it is a constant. The feedforward control input β f f ( k + 1 ) is the control input satisfying this constant κ t . Now, assume that the control input satisfying κ t is a unique constant β f f . Then, from (1),
θ ( k ) =   ( 1 ) k α + β f f , θ ( k + 1 ) =   ( 1 ) k + 1 α + β f f =   ( 1 ) k α + β f f , θ ( k + 2 ) =   ( 1 ) k + 2 α + β f f = ( 1 ) k α + β f f = θ ( k ) .
Similarly, from (2),
θ b ( k ) =   cos 1 l d cos ( 1 ) k α + β f f , θ b ( k + 1 ) =   cos 1 l d cos ( 1 ) k α + β f f , θ b ( k + 2 ) =   cos 1 l d cos ( 1 ) k α + β f f = θ b ( k ) .
From (5), the turn angle is
ψ ( k + 1 , k ) = ( 1 ) k + 1 θ b ( k + 1 ) θ b ( k ) , ψ ( k + 2 , k + 1 ) = ( 1 ) k + 2 θ b ( k + 2 ) θ b ( k + 1 ) = ( 1 ) k + 1 θ b ( k ) θ b ( k + 1 ) = ( 1 ) k + 1 θ b ( k + 1 ) θ b ( k ) = ψ ( k + 1 , k ) ,
This represents that the turning angle remains constant regardless of the number of steps, becoming a function ψ ( β f f ) dependent on β f f . Similarly, consider the stride length. Here, the change in the angle of the front link is
A ( k + 1 , k )   = θ ( k + 1 ) θ ( k ) + ψ ( k + 1 , k ) = 2 ( 1 ) k α + ψ ( β f f ) , A ( k + 2 , k + 1 )   = θ ( k + 2 ) θ ( k + 1 ) + ψ ( k + 2 , k + 1 ) = 2 ( 1 ) k α + ψ ( β f f ) .
Note that the reference stride α is an arbitrary constant, making it a function of the turning angle. Therefore, from (6), the stride length also becomes a function of the turning angle ψ . Similarly, from (13), the curvature κ also becomes a function κ ( ψ ) of the turning angle ψ . Since the turning angle ψ ( β f f ) is a function of β f f and is constant, the curvature κ ( ψ ) is also constant regardless of the number of steps. Therefore, the assumption that the control input satisfying κ t is a unique constant β f f does not lead to a contradiction. Moreover, solving the inverse function of κ ( ψ ( β f f ) ) yields the feedforward control input as follows:
β f f ( k + 1 ) = κ 1 ( κ t ) ,
where (15) is the inverse function of (13), its analytical solution cannot be derived. In this paper, therefore, a numerical solution is obtained by the Newton–Raphson method.

3.2. Feedback Control System

Formulate the feedback control input β f b ( k + 1 ) . For a single LISA control input, there are three state quantities to be converged: distance error, attitude error, and feedback control input. Therefore, at least three steps are required to converge all of these. In other words, the inverse problem can be solved from the position and attitude after three steps. Here, since this paper selects the reference path as f t ( x , y ) = 0 , LISA following this reference path is equivalent to the robot coordinates ( x r ( k ) , y r ( k ) ) satisfying f t ( x r ( k ) , y r ( k ) ) = 0 . That is, if f t ( x r ( k ) , y r ( k ) ) = 0 is continuously satisfied for consecutive k, then LISA can be said to be following the reference path. This means both the position error and the posture error are zero. From this discussion, two conditions are required to achieve it, which takes three steps, and if f t ( x r ( k ) , y r ( k ) ) = 0 is continuously satisfied for consecutive k. This condition can be rephrased as requiring that both the robot coordinates three steps ahead ( x r ( k + 3 ) , y r ( k + 3 ) ) and four steps ahead ( x r ( k + 4 ) , y r ( k + 4 ) ) satisfy f t ( x r ( k ) , y r ( k ) ) = 0 . We then formulate the following condition:
f ( U ) = f t ( x r ( k + 3 ) , y r ( k + 3 ) ) f t ( x r ( k + 4 ) , y r ( k + 4 ) ) ,
where U = [ β f b ( k + 1 ) , β f b ( k + 2 ) ] T , which is the input vector of two steps. Also, β f b ( k + 3 ) = β f b ( k + 4 ) = 0 from the convergence condition in (16).
The role of the feedback control system is to find the input vector U such that f ( U ) = 0 . ( x r ( k + 3 ) , y r ( k + 3 ) ) and ( x r ( k + 4 ) , y r ( k + 4 ) ) can be derived according to (14), and from (1), they depend on the control inputs β ( k + 1 ) , , β ( k + 4 ) . That is, they can be derived from the input vector U and β f b ( k + 3 ) = β f b ( k + 4 ) = 0 . Therefore, the input vector U such that f ( U ) = 0 is obtained by solving the inverse function of f under the condition β f b ( k + 3 ) = β f b ( k + 4 ) = 0 . Thus,
U = f 1 ( 0 ) .
Then β f b ( k + 1 ) U is selected as the feedback control input of the system. Moreover, although (17) is the inverse function of (16), its analytical solution cannot be derived in the same way as that of (15). Therefore, a numerical solution is obtained for (17) by the Newton–Raphson method in the same way.
Equations (15) and (17) have a finite domain of definition due to the existence of the constraints in Table 1. That is, depending on the position and orientation of the robot coordinates of LISA, there may be no solution that satisfies (15) or (17). However, in this paper, we assume that the initial position of LISA and the reference path are sufficiently close, i.e., the reference path is set within the defined region of (15) and (17). In other words, it treats the constraints of Table 1 implicitly.

4. Numerical Simulation

This section verifies the effectiveness of the designed path-following control system through three different numerical simulations, depending on the characteristics of the reference path. The three types of paths are a straight path, a circular path, and a combination of linear paths. In numerical simulations, the control performance of the designed control system is verified by not only achieving the three control targets but also comparing it with the PID control [27,28] and the PD control with attitude compensation [29] designed in prior research. In all numerical simulations, Table 1 was used for the physical parameters of LISA, the initial position of LISA was set to the origin (0, 0) m in the absolute coordinate system, and the initial attitude was set to 0 rad. The amplitude of the standard stride was set to α = π / 4 rad. The tuning parameters for the PID control [27,28] were
K p = 5 , K i = 3 , K d = 2 , ω = 10 .
The tuning parameters for the PD control with attitude compensation [29] were
K p = 5 , K d = 2 , ω = 10 .

4.1. Simulation 1: Linear Path

The effectiveness of the control system for a linear path is verified. In this simulation, the total number of steps of LISA was set to 16. The function f t ( x , y ) of the reference path was set as follows:
f t ( x , y ) = a t x + c t = 0 , a t = 1 , c t = 0.08 .
The simulation results are shown in Figure 8, Figure 9, Figure 10 and Figure 11.
In Figure 8, Figure 9, Figure 10 and Figure 11, the blue line represents the simulation results of the proposed control system. Also, the red line and the yellow line represent the ones of the PD control with posture compensation and the PID control, respectively. Figure 8 shows that LISA follows the reference path using the designed control system. Here, the distance error shown in Figure 10 is obtained using the point and the reference path as follows:
l i n e a r d i s t a n c e e r r o r = a t x r ( k ) + b t y r ( k ) + c t a t 2 + b t 2 .
The posture error shown in Figure 11 is calculated from the angle between the path and the y-axis of the absolute coordinate system and LISA’s posture as follows:
l i n e a r p o s t u r e e r r o r = ϕ ( k ) tan 1 b t a t .
Figure 9, Figure 10 and Figure 11 show that the three control targets, distance error, posture error, and control input, converge in three steps. From Figure 9, Figure 10 and Figure 11, it can be seen that the proposed method converges to the reference path faster than others. Hence, it can be confirmed that the designed control system can achieve LISA’s path-following control system to a linear path.

4.2. Simulation 2: Circular Path

The effectiveness of the control system for a circular path is verified. In this simulation, the total number of LISA steps was also set to 16. The function f t ( x , y ) of the reference path was set as follows:
f t ( x , y ) = ( x a t ) 2 + ( y b t ) 2 r t 2 = 0 , a t = 0.1 , b t = 0.38 , r t = 0.45 .
The simulation results are shown in Figure 12, Figure 13, Figure 14 and Figure 15.
In Figure 12, Figure 13, Figure 14 and Figure 15, the blue line represents the simulation results of the proposed control system. Also, the red line and the yellow line represent the ones of the PD control with posture compensation and the PID control, respectively. Figure 12 shows that LISA follows the reference path using the designed control system. Here, the distance error shown in Figure 14 is obtained using the robot coordinates and the circle equation as follows:
c i r c l e d i s t a n c e e r r o r = sgn ( r t ) | r t | ( x r ( k ) a t ) 2 + ( y r ( k ) b t ) 2 .
The posture error is 0 rad when O r ( k ) and O r ( k ) of LISA are on a circular path. Therefore, the attitude error shown in Figure 15 is obtained by using the angle between the slope of the tangent line of the circle and the y r -axis when LISA is assumed to be on a circular path, as follows:
c i r c l e p o s t u r e e r r o r = ϕ ( k ) sgn ( r t ) sin 1 d sin θ b ( k ) 2 | r t | tan 1 y r ( k ) b t x r ( k ) a t
Figure 13, Figure 14 and Figure 15 show that the three control targets, distance error, posture error, and control input, converge in three steps. From Figure 13, Figure 14 and Figure 15, it can be seen that the proposed method converges to the reference path faster than others. Hence, it can be confirmed that the designed control system can achieve LISA’s path-following control system to a linear path.

4.3. Simulation 3: Combination Path

The effectiveness of the control system for combined linear paths is verified. In this simulation, the total number of LISA steps was set to 35. The reference path function f t ( x , y ) was set as follows:
f t ( x , y ) = a s 1 x + b s 1 y + c s 1 , if y r ( k + 1 ) S s 1 , a s 2 x + b s 2 y + c s 2 , if y r ( k + 1 ) c s 2 , a s 3 x + b s 3 y + c s 3 , if x r ( k + 1 ) S s 3 , a s 4 x + b s 4 y + c s 4 , else ,
where the coefficients and switching parameters S 5 , S 7 for each function were set as follows:
a s 1 = 3 , b s 1 = 1 , c s 1 = 0 , S s 1 = 0.6 a s 2 = 4 , b s 2 = 1 , c s 2 = S s 1 + a s 2 b s 2 a s 1 S s 1 a s 2 c s 2 a s 1 , a s 3 = 1 , b s 3 = 1 , c s 3 = c s 2 , S s 3 = 0.2 a s 4 = 0 , b s 4 = 1 , c s 4 = S s 3 + c s 3 .
The simulation results are shown in Figure 16, Figure 17, Figure 18 and Figure 19.
In Figure 16, Figure 17, Figure 18 and Figure 19, the blue line represents the simulation results of the proposed control system. Also, the red line and the yellow line represent the ones of the PD control with posture compensation and the PID control, respectively. The distance and attitude errors shown in Figure 18 and Figure 19 are calculated using (18) and (19). Figure 17, Figure 18 and Figure 19 show that the three control targets, distance error, posture error, and control input, converge in three steps. From Figure 17, Figure 18 and Figure 19, it can be seen that the proposed method converges to the reference path faster than others. Hence, it can be confirmed that the designed control system can achieve LISA’s path-following control system to a linear path.

5. Experimental Verification

This section evaluates the performance of the proposed control system through experiments on the actual robot. The experiments aim to verify that the control system enables LISA to follow a reference trajectory while satisfying three control objectives: distance error, attitude error, and control input. Three types of reference paths are tested: a straight line, a circular trajectory, and a combination of linear and circular segments.
The first task is to set up the experimental environment. The tests are conducted on a 2.0 m × 2.0 m carpet-like horizontal surface. Figure 20 presents both a photograph of the setup and a schematic diagram of the system. In Figure 20b, the motion capture system measurements and actuator angles from LISA are transmitted to the PC via USB 2.0 and serial communication, respectively. The OptiTrack V120: Trio motion capture camera tracks LISA’s 6-DOF position and orientation in a 3-D Cartesian coordinate system. Table 3 summarizes the key specifications of the camera. LISA is equipped with a 12-bit magnetic encoder that measures both commanded and actual actuator angles. The control system is executed on a PC running MATLAB 2021b (9.11.0.1769968).
The experimental conditions common to all three experiments were as follows: LISA’s initial position was set to the origin (0, 0) m in the absolute coordinate system, and its initial posture was set to 0 rad. The amplitude of the standard stride was set to α = π / 4 rad.

5.1. Experiment 1: Linear Path

The effectiveness of the control system for a linear path is verified. In this experiment, the total number of steps of LISA was set to 32. The function f t ( x , y ) of the reference path was set as follows:
f t ( x , y ) = a t x + b t y + c t = 0 , a t = 1 , b t = 3 , c t = 0.04 .
The experimental results for the linear path are shown in Figure 21, Figure 22, Figure 23 and Figure 24.
Figure 21 shows that LISA follows the reference path using the designed control system. The distance error shown in Figure 23 is calculated by utilizing (18). Also, the posture error shown in Figure 24 is calculated by utilizing (19). Figure 22 shows that the control input converges to 0 rad with slight variations. Similarly, Figure 23 and Figure 24 show that the distance error and the posture error also converge to 0. Specifically, when calculating the Root Mean Square (RMS) for the third step and beyond, which theoretically converges to the path, the control input is 0.0812 rad, the posture error is 2.17 mm, and the posture error is 0.0662 rad (summarized in Table 4), with all RMS values being sufficiently small. Therefore, it can be confirmed that the control objective of convergence of the three state variables, distance error, posture error, and control input, has been achieved. The slight variation also observed in the prototype evaluation [36] is considered to be caused by the distortion of a fibrous plane, such as a carpet. A relatively large distance error was observed, which is considered to result from both environmental disturbances inherent to the experimental setup and the intrinsic behavior of the control system. In prototype evaluations reported in our previous work, an error of approximately 4.7% relative to the theoretical turning angle was identified, indicating that slight turning occurs even during nominal straight-line motion. In the control system presented in this paper, transient deviations from the reference path may occur as the controller acts to satisfy the three control targets. Consequently, the relatively large distance error, compared with other error components, is presumed to arise from the control system’s compensatory response to disturbances induced by deformations in the carpet-like fibrous surface. Similarly, based on evaluations of the previous research, the experimental environment contains errors of several percent in both stride length and turning angle. Nevertheless, the control system successfully controls LISA’s path, indicating that the experimental results demonstrate robustness against these errors.

5.2. Experiment 2: Circular Path

The effectiveness of the control system for a circular path is verified. In this experiment, the total number of LISA steps was also set to 54. The function f t ( x , y ) of the reference path was set as follows:
f t ( x , y ) = ( x a t ) 2 + ( y b t ) 2 r t 2 = 0 , a t = 0.25 , b t = 0.41 , r t = 0.45 .
The experimental results of the circular path are shown in Figure 25, Figure 26, Figure 27 and Figure 28.
Figure 25 shows that LISA follows the reference path using the designed control system. The distance error shown in Figure 27 is calculated by utilizing (20). Also, the attitude error shown in Figure 28 is calculated by utilizing (21). Figure 26 shows that the control input converges to the feedforward control input with slight variations, which means that the feedback control input converges to 0 rad. Similarly, Figure 27 and Figure 28 show that the distance error and the posture error also converge to 0. Specifically, when calculating the RMS for the third step and beyond, which theoretically converges to the path, the control input is 0.0622 rad, the posture error is 2.81 mm, and the posture error is 0.0337 rad (summarized in Table 5), with all RMS values being sufficiently small. Therefore, it can be confirmed that the control objective of convergence of the three state variables-distance error, posture error, and control input-has been achieved. Similarly, even for circular paths, the designed control system successfully follows the LISA to the path despite errors inherent in the experimental environment. Therefore, it can be said to exhibit robustness even for circular paths.

5.3. Experiment 3: Combination Path

The effectiveness of the control system for combined linear and circular paths is verified. In this experiment, the total number of LISA steps was set to 88. The reference path function f t ( x , y ) was set as follows:
f t ( x , y ) = a 1 x + b 1 y + c 1 , if x r ( k + 1 ) < r 7 4 0 y r ( k + 1 ) < b 2 , ( x a 2 ) 2 + ( y b 2 ) 2 r 2 2 , if a 2 < x r ( k + 1 ) r 7 4 b 2 y r ( k + 1 ) < b 3 r 3 2 , ( x a 3 ) 2 + ( y b 3 ) 2 r 3 2 , if x r ( k + 1 ) a 2 , a 4 x + b 4 y + c 4 , if a 2 < x r ( k + 1 ) 0 y r ( k + 1 ) b 3 r 3 2 , a 5 x + b 5 y + c 5 , if 0 < x r ( k + 1 ) S 5 y r ( k + 1 ) > a 6 b 6 S 7 c 6 b 6 , a 6 x + b 6 y + c 6 , if x r ( k + 1 ) > S 5 y r ( k + 1 ) > a 6 b 6 S 7 c 6 b 6 , a 7 x + b 7 y + c 7 , if x r ( k + 1 ) r 7 4 0 < y r ( k + 1 ) a 6 b 6 S 7 c 6 b 6 , ( x a 8 ) 2 + ( y b 8 ) 2 r 8 2 , if y r ( k + 1 ) 0 ,
where the coefficients and switching parameters S 5 , S 7 for each function were set as follows:
a 1 = 1 , b 1 = 0 , c 1 = 0.03 , a 2 = r 1 r 2 , b 2 = 0.35 , r 2 = 0.45 , a 3 = a 2 , b 3 = b 2 + r 2 + r 3 , r 3 = 0.25 , a 4 = 0 , b 4 = 1 , c 4 = b 2 + r 2 + 2 r 3 , a 5 = 1 , b 5 = 3 , c 5 = c 4 b 5 , S 5 = 0.5 , a 6 = 3 , b 6 = 1 , c 6 = a 5 b 6 b 5 a 6 S 5 + c 5 b 6 b 5 , a 7 = 1 , b 7 = 0 , c 7 = S 7 , S 7 = 0.7 , a 8 = r 8 r 1 b 8 = 0 , r 8 = r 7 + r 1 2 .
The experimental results are shown in Figure 29, Figure 30, Figure 31 and Figure 32.
Figure 29 shows that LISA follows the reference path using the designed control system. The distance and attitude errors shown in Figure 31 and Figure 32 are calculated using (18)–(21) as appropriate for each reference path. Figure 30 shows that the control input converges to the feedforward control input with slight variations, which means that the feedback control input converges to 0 rad. Similarly, Figure 31 and Figure 32 show that the distance error and the posture error also converge to 0. In Figure 30, Figure 31 and Figure 32, there are three large errors from 30th step to 50th step. These are points where the parameters of the linear path have changed. Therefore, it can be confirmed that the control objective of convergence of the three state variablesis -distance error, posture error, and control input- has been achieved. This experiment employs the path that switches discontinuously, simulating the sudden transition to a different path during walking. Even under such conditions, experimental results confirm that the designed control system can successfully follow the path provided the path remains sufficiently close to the robot’s coordinate system.

6. Conclusions

This paper addresses three aspects of designing a path-following control system for LISA based on its kinematics: kinematic modeling, control system development, and experimental validation. Assuming that the initial position of LISA is sufficiently close to the reference path, the control system was designed to ensure convergence of not only the distance error but also the attitude error and control inputs.
In the kinematic modeling, the turning angle, stride, attitude, propulsive direction, curvature, and position of the robot coordinate were formulated. During the control system development, three convergence criteria were considered: distance error, attitude error, and feedback control inputs. Conditional equations for path-following control were then derived using LISA’s forward kinematics over four steps and the reference path functions, and the control system was constructed by solving the inverse problem of these equations. Experimental validation was performed using three reference paths—linear, circular, and combined linear and circular—to assess the system’s performance. The results confirmed that the RMS values of the control input, distance error, and attitude error were sufficiently small in steady state, demonstrating that the control objectives for all three state variables were successfully achieved.
The contribution of this paper lies in the implementation of a motion control system for a 1-DOF driven robot. Previous research on low-degree-of-freedom driven robots has primarily focused on mechanisms. The appeal of low-DOF driven robots lies in their ability to achieve unique motions using specialized mechanisms; thus, clarifying specific control strategies for these unique mechanisms constitutes a significant contribution. This paper contributes to elucidating control system design principles that fully leverage the motion performance of 1-DOF driven robots by implementing path-following control that utilizes the motion characteristics of a 1-DOF driven robot.
Future work will focus on developing advanced control systems for LISA that explicitly account for input and state constraints. The control system designed in this paper implicitly handles these constraints. Therefore, if the constraints are not satisfied, the control system fails. One method to prevent control system failure is to determine the range within which the inverse kinematics can be solved. However, for systems with strong nonlinearity like LISA, specifying this range is difficult. Therefore, we aim to design a control system that explicitly handles the constraints by reformulating the control system’s conditions into an optimization problem with inequality constraints. Model predictive control presents a promising approach for this purpose. However, due to the specific form of LISA’s evaluation function and its discrete dynamics, existing continuous system algorithms are not directly applicable. We plan to explore methods to address this challenge.

Supplementary Materials

The following supporting information can be downloaded at: https://www.mdpi.com/article/10.3390/automation6040074/s1.

Author Contributions

Conceptualization, S.N. and N.K.; methodology, S.N.; software, S.N.; validation, S.N.; experiment, S.N.; writing, S.N.; supervision, N.K. and A.N.; project administration, S.N.; funding acquisition, S.N. and N.K. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by JSPS KAKENHI grant number 21K14107.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Data is contained within the article or Supplementary Materials.

Acknowledgments

During the preparation of this manuscript, the authors used ChatGPT for the purposes of the grammar checking. The authors have reviewed and edited the output and take full responsibility for the content of this publication.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Jansen, T. The Great Pretender; 010 Publishers: Rotterdam, The Netherlands, 2007. [Google Scholar]
  2. Komoda, K. A study of availability and extensibility of Theo Jansen mechanism toward climbing over bumps. In Proceedings of the 21st Annual Conference of the Japanese Neural Networks Society, Okinawa, Japan, 15–17 December 2011; pp. 192–193. [Google Scholar]
  3. Ingram, A.J. A New Type of Mechanical Walking Machine. Ph.D. Thesis, Rand Afrikaans University, Johannesburg, South Africa, 2006. [Google Scholar]
  4. Liu, C.H.; Lin, M.H.; Huang, Y.C.; Pai, T.Y.; Wang, C.M. The development of a multi-legged robot using eight-bar linkages as leg mechanisms with switchable modes for walking and stair climbing. In Proceedings of the 2017 3rd International Conference on Control, Automation and Robotics (ICCAR), Nagoya, Japan, 22–24 April 2017; pp. 103–108. [Google Scholar]
  5. Zarrouk, D.; Fearing, R.S. Compliance-based dynamic steering for hexapods. In Proceedings of the 2012 IEEE/RSJ International Conference on Intelligent Robots and Systems, Vilamoura-Algarve, Portugal, 7–12 October 2012; pp. 3093–3098. [Google Scholar]
  6. Zarrouk, D.; Fearing, R.S. Cost of locomotion of a dynamic hexapedal robot. In Proceedings of the 2013 IEEE International Conference on Robotics and Automation, Karlsruhe, Germany, 6–10 May 2013; pp. 2548–2553. [Google Scholar]
  7. Zarrouk, D.; Fearing, R.S. 1star, a one-actuator steerable robot. In Proceedings of the 2014 IEEE International Conference on Robotics and Automation (ICRA), Hong Kong, China, 31 May–7 June 2014; p. 2569. [Google Scholar]
  8. Zarrouk, D.; Pullin, A.; Kohut, N.; Fearing, R.S. STAR, a sprawl tuned autonomous robot. In Proceedings of the 2013 IEEE International Conference on Robotics and Automation, Karlsruhe, Germany, 6–10 May 2013; pp. 20–25. [Google Scholar]
  9. Karydis, K.; Zarrouk, D.; Poulakakis, I.; Fearing, R.S.; Tanner, H.G. Planning with the STAR (s). In Proceedings of the 2014 IEEE/RSJ International Conference on Intelligent Robots and Systems, Chicago, IL, USA, 14–18 September 2014; pp. 3033–3038. [Google Scholar]
  10. Zarrouk, D.; Yehezkel, L. Rising STAR: A highly reconfigurable sprawl tuned robot. IEEE Robot. Autom. Lett. 2018, 3, 1888–1895. [Google Scholar] [CrossRef]
  11. Zarrouk, D.; Mann, M.; Degani, N.; Yehuda, T.; Jarbi, N.; Hess, A. Single actuator wave-like robot (SAW): Design, modeling, and experiments. Bioinspir. Biomimet. 2016, 11, 046004. [Google Scholar] [CrossRef] [PubMed]
  12. Drory, L.H.; Zarrouk, D. Locomotion dynamics of a miniature wave-like robot, modeling and experiments. In Proceedings of the 2019 International Conference on Robotics and Automation (ICRA), Montreal, QC, Canada, 20–24 May 2019; pp. 8422–8428. [Google Scholar]
  13. Shachaf, D.; Inbar, O.; Zarrouk, D. RSAW, A Highly Reconfigurable Wave Robot: Analysis, Design, and Experiments. IEEE Robot. Autom. Lett. 2019, 4, 4475–4482. [Google Scholar] [CrossRef]
  14. Sfeir, J.; Shammas, E.; Asmar, D. Design and modeling of a novel single-actuator differentially driven robot. In Proceedings of the 2014 IEEE/ASME International Conference on Advanced Intelligent Mechatronics, Besançon, France, 8–11 July 2014; pp. 1079–1084. [Google Scholar]
  15. Alsalman, M.; Shammas, E.; Salman, H. Modeling, analysis, and controllability of a single-actuator differentially-driven robot. In Proceedings of the 2015 IEEE International Conference on Advanced Intelligent Mechatronics (AIM), Busan, Republic of Korea, 7–11 July 2015; pp. 1433–1438. [Google Scholar]
  16. Alsalman, M.; Shammas, E.; Asmar, D.; Daher, N. Modeling of a variable diameter wheeled robot for traversing rough terrain. In Proceedings of the 2016 IEEE International Conference on Advanced Intelligent Mechatronics (AIM), Banff, AB, Canada, 12–15 July 2016; pp. 745–750. [Google Scholar]
  17. Ito, S.; Sugiura, S.; Masuda, Y.; Nohara, S.; Morita, R. Mechanism and control of a one-actuator mobile robot incorporating a torque limiter. J. Intell. Robot. Syst. 2020, 97, 431–448. [Google Scholar] [CrossRef]
  18. Hirofumi, N.; Kensuke, M. Biomimetics Mobile Robot using the Trunk of the Body: Ahead, Astern and Turning of Lizard Type Robot(Bio-Mimetics and Bio-Mechatronics). In Proceedings of the JSME Annual Conference on Robotics and Mechatronics (Robomec), Okayama, Japan, 26–28 May 2011. [Google Scholar] [CrossRef]
  19. Niimi, H.; Suzaki, F.; Murai, K. Performance Test of Lizard Robot in the Field(Walking Robot (2)). In Proceedings of the JSME Annual Conference on Robotics and Mechatronics (Robomec), Hamamatsu, Japan, 27–29 May 2012. [Google Scholar] [CrossRef]
  20. Kawakami, Y.; Kamamichi, N. Motion Analysis of Lizard Type Quadruped Robots(Biorobotics (2)). In Proceedings of the JSME Annual Conference on Robotics and Mechatronics (Robomec), Tsukuba, Japan, 22–25 May 2013. [Google Scholar] [CrossRef]
  21. Suzuki, H.; Wakikawa, K.; Kamamichi, N. Motion control of lizard-type quadruped. In Proceedings of the JSME Annual Conference on Robotics and Mechatronics (Robomec), Yokohama, Japan, 8–11 June 2016. [Google Scholar] [CrossRef]
  22. Nansai, S.; Elara, M.R.; Iwase, M. Dynamic analysis and modeling of Jansen mechanism. Procedia Eng. 2013, 64, 1562–1571. [Google Scholar] [CrossRef]
  23. Nansai, S.; Rojas, N.; Elara, M.R.; Sosa, R. Exploration of adaptive gait patterns with a reconfigurable linkage mechanism. In Proceedings of the 2013 IEEE/RSJ International Conference on Intelligent Robots and Systems, Tokyo, Japan, 3–7 November 2013; pp. 4661–4668. [Google Scholar]
  24. Nansai, S.; Rojas, N.; Elara, M.R.; Sosa, R.; Iwase, M. On a Jansen leg with multiple gait patterns for reconfigurable walking platforms. Adv. Mech. Eng. 2015, 7, 1687814015573824. [Google Scholar] [CrossRef]
  25. Nansai, S.; Elara, M.R.; Iwase, M. Speed Control of Jansen Linkage Mechanism for Exquisite Tasks. J. Adv. Simul. Sci. Eng. 2016, 3, 47–57. [Google Scholar] [CrossRef]
  26. Nansai, S.; Ando, Y.; Itoh, H.; Kamamichi, N. Design and Implementation of a Lizard-Inspired Robot. Appl. Sci. 2021, 11, 7898. [Google Scholar] [CrossRef]
  27. Nansai, S.; Ando, Y.; Kamamich, N.; Itoh, H. Kinematics Analysis and Tracking Control of Novel Single Actuated Lizard Type Robot. In Proceedings of the 2020 IEEE International Conference on Systems, Man, and Cybernetics (SMC), Toronto, ON, Canada, 11–14 October 2020; pp. 315–320. [Google Scholar]
  28. Noji, S.; Nansai, S.; Kamamichi, N.; Itoh, H. Modeling and control of a lizard-inspired single-actuated robot. IEEE Robot. Autom. Lett. 2022, 7, 6399–6406. [Google Scholar] [CrossRef]
  29. Nansai, S.; Kamamichi, N. Tracking Control of Lizard-inspired Single-actuated Robot Utilizing Posture Compensation. Trans. Soc. Instrum. Control Eng. 2024, 60, 238–249. [Google Scholar] [CrossRef]
  30. Altafini, C. Path following with reduced off-tracking for multibody wheeled vehicles. IEEE Trans. Control Syst. Technol. 2003, 11, 598–605. [Google Scholar] [CrossRef]
  31. Okajima, H.; Asai, T.; Kawaji, S. Optimal velocity control method in path following control problem. Trans. Soc. Instrum. Control Eng. 2008, 44, 566–574. [Google Scholar] [CrossRef][Green Version]
  32. Dayanand, V.; Attarde, K.; Sayyad, J.K. Development of Eight-legged Spider Robot Using Theo Jansen Mechanism. In Proceedings of the 2024 6th International Conference on Energy, Power and Environment (ICEPE), Shillong, India, 20–22 June 2024; pp. 1–6. [Google Scholar]
  33. Geng, R.; Liu, Q.; Jin, L.; Qian, W. Design and Dynamic Analysis of Hexapod Robots Based on Jansen Linkage Mechanism. In Proceedings of the 2025 6th International Conference on Mechatronics Technology and Intelligent Manufacturing (ICMTIM), Nanjing, China, 11–13 April 2025; pp. 370–381. [Google Scholar]
  34. Coronel, M.; Zarrouk, D. Overcoming obstacles using tail STAR: A novel sprawling robot with a two-joint tail. IEEE Robot. Autom. Lett. 2023, 8, 2317–2324. [Google Scholar] [CrossRef]
  35. Cohen, A.; Zarrouk, D. Design, analysis and experiments of a high-speed water hovering amphibious robot: AmphiSTAR. IEEE Access 2023, 11, 80874–80885. [Google Scholar] [CrossRef]
  36. Nansai, S.; Kamamichi, N. Design and evaluation of Lizard-Inspired Single-Actuated robot. ROBOMECH J. 2025, 12, 16. [Google Scholar] [CrossRef]
Figure 1. Kinematic model in previous studies. (a) Gait schematic. (b) Slip of supporting legs. If supporting legs (black colored circles) are perfectly fixed, then the active joint (central colored circle) is constrained to one of two distant points because they can only exist at equal points from each supporting leg. Therefore, if the angle of the hips is moved continuously, the position of the support legs also continuously changes, i.e., they slip.
Figure 1. Kinematic model in previous studies. (a) Gait schematic. (b) Slip of supporting legs. If supporting legs (black colored circles) are perfectly fixed, then the active joint (central colored circle) is constrained to one of two distant points because they can only exist at equal points from each supporting leg. Therefore, if the angle of the hips is moved continuously, the position of the support legs also continuously changes, i.e., they slip.
Automation 06 00074 g001
Figure 2. Kinematics model in this study. (a) Gait schematic. (b) Fixation of supporting legs. Even if supporting legs (black colored circles) are completely fixed, idling legs (white circles) can exist at any geometrically constrained point. Therefore, walking with the supporting legs fixed is theoretically possible.
Figure 2. Kinematics model in this study. (a) Gait schematic. (b) Fixation of supporting legs. Even if supporting legs (black colored circles) are completely fixed, idling legs (white circles) can exist at any geometrically constrained point. Therefore, walking with the supporting legs fixed is theoretically possible.
Automation 06 00074 g002
Figure 3. The photographs of the prototype of LISA. (a) Isometric View. (b) Top View. (c) Side View. (d) CAD design of Isometric View. (e) CAD design of 4-bar link mechanism section. (f) CAD design of linear slider section.
Figure 3. The photographs of the prototype of LISA. (a) Isometric View. (b) Top View. (c) Side View. (d) CAD design of Isometric View. (e) CAD design of 4-bar link mechanism section. (f) CAD design of linear slider section.
Automation 06 00074 g003
Figure 4. Schematic of the proposed lizard-inspired robot, and a schematic of the change in robot coordinates. (a) Definition of a robot coordinate. (b) Odd step to even step. (c) Even step to odd step.
Figure 4. Schematic of the proposed lizard-inspired robot, and a schematic of the change in robot coordinates. (a) Definition of a robot coordinate. (b) Odd step to even step. (c) Even step to odd step.
Automation 06 00074 g004
Figure 5. A schematic diagram of the turning motion of LISA, where the radius of the circle passing through O r ( k ) , O r ( k ) , O r ( k + 1 ) , and O r ( k + 1 ) is the turn radius.
Figure 5. A schematic diagram of the turning motion of LISA, where the radius of the circle passing through O r ( k ) , O r ( k ) , O r ( k + 1 ) , and O r ( k + 1 ) is the turn radius.
Automation 06 00074 g005
Figure 6. A schematic diagram of the changes in the front link when LISA walks two steps with the same turning radius.
Figure 6. A schematic diagram of the changes in the front link when LISA walks two steps with the same turning radius.
Automation 06 00074 g006
Figure 7. The block diagram of the control system. The control system broadly consists of a feedforward control system and a feedback control system, each deriving control inputs by solving the inverse problem of LISA’s kinematic characteristics derived in Section 2.
Figure 7. The block diagram of the control system. The control system broadly consists of a feedforward control system and a feedback control system, each deriving control inputs by solving the inverse problem of LISA’s kinematic characteristics derived in Section 2.
Automation 06 00074 g007
Figure 8. Trajectory of the robot coordinate of LISA. (Simulation 1: Linear Path).
Figure 8. Trajectory of the robot coordinate of LISA. (Simulation 1: Linear Path).
Automation 06 00074 g008
Figure 9. Step variation of the control input. (Simulation 1: Linear Path).
Figure 9. Step variation of the control input. (Simulation 1: Linear Path).
Automation 06 00074 g009
Figure 10. Step variation of the distance error. (Simulation 1: Linear Path).
Figure 10. Step variation of the distance error. (Simulation 1: Linear Path).
Automation 06 00074 g010
Figure 11. Step variation of the posture error. (Simulation 1: Linear Path).
Figure 11. Step variation of the posture error. (Simulation 1: Linear Path).
Automation 06 00074 g011
Figure 12. Trajectory of the robot coordinate of LISA. (Simulation 2: Circular Path).
Figure 12. Trajectory of the robot coordinate of LISA. (Simulation 2: Circular Path).
Automation 06 00074 g012
Figure 13. Step variation of the control input. (Simulation 2: Circular Path). The purple dash line is the feedforward control input to track the circular reference path.
Figure 13. Step variation of the control input. (Simulation 2: Circular Path). The purple dash line is the feedforward control input to track the circular reference path.
Automation 06 00074 g013
Figure 14. Step variation of the distance error. (Simulation 2: Circular Path).
Figure 14. Step variation of the distance error. (Simulation 2: Circular Path).
Automation 06 00074 g014
Figure 15. Step variation of the posture error. (Simulation 2: Circular Path).
Figure 15. Step variation of the posture error. (Simulation 2: Circular Path).
Automation 06 00074 g015
Figure 16. Trajectory of the robot coordinate of LISA. (Simulation 3: Combination Path).
Figure 16. Trajectory of the robot coordinate of LISA. (Simulation 3: Combination Path).
Automation 06 00074 g016
Figure 17. Step variation of the control input. (Simulation 3: Combination Path).
Figure 17. Step variation of the control input. (Simulation 3: Combination Path).
Automation 06 00074 g017
Figure 18. Step variation of the distance error. (Simulation 3: Combination Path).
Figure 18. Step variation of the distance error. (Simulation 3: Combination Path).
Automation 06 00074 g018
Figure 19. Step variation of the posture error. (Simulation 3: Combination Path).
Figure 19. Step variation of the posture error. (Simulation 3: Combination Path).
Automation 06 00074 g019
Figure 20. Experimental environment. (a) Photograph of the actual experimental environment. (b) Schematic diagram of the system.
Figure 20. Experimental environment. (a) Photograph of the actual experimental environment. (b) Schematic diagram of the system.
Automation 06 00074 g020
Figure 21. Trajectory of the robot coordinate of LISA. (Experiment 1: Linear Path).
Figure 21. Trajectory of the robot coordinate of LISA. (Experiment 1: Linear Path).
Automation 06 00074 g021
Figure 22. Step variation of the control input. (Experiment 1: Linear Path).
Figure 22. Step variation of the control input. (Experiment 1: Linear Path).
Automation 06 00074 g022
Figure 23. Step variation of the distance error. (Experiment 1: Linear Path).
Figure 23. Step variation of the distance error. (Experiment 1: Linear Path).
Automation 06 00074 g023
Figure 24. Step variation of the posture error. (Experiment 1: Linear Path).
Figure 24. Step variation of the posture error. (Experiment 1: Linear Path).
Automation 06 00074 g024
Figure 25. Trajectory of the robot coordinate of LISA. (Experiment 2: Circular Path).
Figure 25. Trajectory of the robot coordinate of LISA. (Experiment 2: Circular Path).
Automation 06 00074 g025
Figure 26. Step variation of the control input. (Experiment 2: Circular Path). The yellow dashed line is the feedforward control inputs to track the circular reference path.
Figure 26. Step variation of the control input. (Experiment 2: Circular Path). The yellow dashed line is the feedforward control inputs to track the circular reference path.
Automation 06 00074 g026
Figure 27. Step variation of the distance error. (Experiment 2: Circular Path).
Figure 27. Step variation of the distance error. (Experiment 2: Circular Path).
Automation 06 00074 g027
Figure 28. Step variation of the posture error. (Experiment 2: Circular Path).
Figure 28. Step variation of the posture error. (Experiment 2: Circular Path).
Automation 06 00074 g028
Figure 29. Trajectory of the robot coordinate of LISA. (Experiment 3: Combination Path).
Figure 29. Trajectory of the robot coordinate of LISA. (Experiment 3: Combination Path).
Automation 06 00074 g029
Figure 30. Step variation of the control input. (Experiment 3: Combination Path). The yellow dashed lines are feedforward control inputs to track the circular reference path.
Figure 30. Step variation of the control input. (Experiment 3: Combination Path). The yellow dashed lines are feedforward control inputs to track the circular reference path.
Automation 06 00074 g030
Figure 31. Step variation of the distance error. (Experiment 3: Combination Path).
Figure 31. Step variation of the distance error. (Experiment 3: Combination Path).
Automation 06 00074 g031
Figure 32. Step variation of the posture error. (Experiment 3: Combination Path).
Figure 32. Step variation of the posture error. (Experiment 3: Combination Path).
Automation 06 00074 g032
Table 1. Physical Parameters.
Table 1. Physical Parameters.
ParametersNotationValue
Length of front and rear links
(Length of P 1 to P 2 and P 3 to P 4 )
l100 mm
Length of crossing link
(Length of P 1 to P 4 and P 2 to P 3 )
d 2 l [mm]
Actuator motion range under mechanical constraints θ m a x ± 90 degree
Maximum turning angle ψ m a x ± π / 4 rad
Maximum stride s m a x 100 mm
Maximum curvature κ m a x 0.0115 mm−1
Table 2. The main specifications of the XM430-W210-T.
Table 2. The main specifications of the XM430-W210-T.
ParametersValue
DeveloperROBOTIS Co., Ltd.
(Seoul, Republic of Korea, 07594)
Model NameXM430-W210-T
Stall Torque [Nm]3.00
No Load Speed [rpm]77.0
Angular Resolution [deg/pulse]0.0879
Weight [g]86
Position SensorContactless absolute encoder (12 bit/rev)
Table 3. Main specifications of the Motion Capture Cameras V120: Trio.
Table 3. Main specifications of the Motion Capture Cameras V120: Trio.
ParametersValue
DeveloperOptiTrack
Definition [pixel]300,000
Frame Rate [fps]120
Horizontal Viewing Angle [degree]47
Vertical Viewing Angle [degree]43
Table 4. The Root Mean Square values. (Experiment 1: Linear Path).
Table 4. The Root Mean Square values. (Experiment 1: Linear Path).
ItemsRMS
The feedback control input0.0812 rad
The posture error2.17 mm
The posture error0.0662 rad
Table 5. The Root Mean Square values. (Experiment 2: Circular Path).
Table 5. The Root Mean Square values. (Experiment 2: Circular Path).
ItemsRMS
The feedback control input0.0622 rad
The posture error2.81 mm
The posture error0.0337 rad
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

Nansai, S.; Kamamichi, N.; Naganawa, A. Implementation of Path-Following Control of Lizard-Inspired Single-Actuated Robot Utilizing Inverse Kinematics. Automation 2025, 6, 74. https://doi.org/10.3390/automation6040074

AMA Style

Nansai S, Kamamichi N, Naganawa A. Implementation of Path-Following Control of Lizard-Inspired Single-Actuated Robot Utilizing Inverse Kinematics. Automation. 2025; 6(4):74. https://doi.org/10.3390/automation6040074

Chicago/Turabian Style

Nansai, Shunsuke, Norihiro Kamamichi, and Akihiro Naganawa. 2025. "Implementation of Path-Following Control of Lizard-Inspired Single-Actuated Robot Utilizing Inverse Kinematics" Automation 6, no. 4: 74. https://doi.org/10.3390/automation6040074

APA Style

Nansai, S., Kamamichi, N., & Naganawa, A. (2025). Implementation of Path-Following Control of Lizard-Inspired Single-Actuated Robot Utilizing Inverse Kinematics. Automation, 6(4), 74. https://doi.org/10.3390/automation6040074

Article Metrics

Back to TopTop