Next Article in Journal
Potential for Farmers’ Cooperatives to Convert Coffee Husks into Biochar and Promote the Bioeconomy in the North Ecuadorian Amazon
Next Article in Special Issue
Evaluation of Linearization Methods for Control of the Pendubot
Previous Article in Journal
Antifungal and Antioxidant Potential of Methanolic Extracts from Acorus calamus L., Chlorella vulgaris Beijerinck, Lemna minuta Kunth and Scenedesmus dimorphus (Turpin) Kützing
Previous Article in Special Issue
Sliding Balance Control of a Point-Foot Biped Robot Based on a Dual-Objective Convergent Equation
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Kinematic-Model-Free Redundancy Resolution Using Multi-Point Tracking and Control for Robot Manipulation

1
Robot Intelligence Lab, Dyson School of Design Engineering, Imperial College London, Exhibition Road, London SW7 2DB, UK
2
Dubai Future Lab, 77 Sheikh Zayed Road, Dubai, United Arab Emirates
3
Hamlyn Centre, Imperial College London, Exhibition Road, London SW7 2BU, UK
*
Author to whom correspondence should be addressed.
Appl. Sci. 2021, 11(11), 4746; https://doi.org/10.3390/app11114746
Submission received: 1 May 2021 / Revised: 20 May 2021 / Accepted: 20 May 2021 / Published: 21 May 2021

Abstract

:
Robots have been predominantly controlled using conventional control methods that require prior knowledge of the robots’ kinematic and dynamic models. These controllers can be challenging to tune and cannot directly adapt to changes in kinematic structure or dynamic properties. On the other hand, model-learning controllers can overcome such challenges. Our recently proposed model-learning orientation controller has shown promising ability to simultaneously control a three-degrees-of-freedom robot manipulator’s end-effector pose. However, this controller does not perform optimally with robots of higher degrees-of-freedom nor does it resolve redundancies. The research presented in this paper extends the state-of-the-art kinematic-model-free controller to perform pose control of hyper-redundant robot manipulators and resolve redundancies by tracking and controlling multiple points along the robot’s serial chain. The results show that with more control points, the controller is able to reach desired poses in fewer steps, yielding an improvement of up to 66%, and capable of achieving complex configurations. The algorithm was validated by running the simulation 100 times, and it was found that, in 82% of the times, the robot successfully reached the desired target pose within 150 steps.

1. Introduction

Conventional robot controllers require both the kinematic and dynamic models (heron cumulatively referred to as kinodynamic model) of the robot in order to perform accurate control [1]. These controllers require an accurate model of the robot. However, soft robots, morphing robots, malleable robots, transforming robots, and evolving robots can be challenging to model accurately and control. Model-based approaches have remained the dominant control method for over 50 years [2]. Model-based control of soft/continuum robots underperform because modeling these structures are achieved by means of approximations. Therefore, learning-based or model-free techniques may be preferred to overcome some of these challenges.
Recently, a new class of model-learning controllers emerged, showing promising ability to bypass the need for any prior robot model. These controllers directly learn a kinodynamic model online to control a robot. In our original work, the Encoderless controller [3] and Kinematic-Free controller [4], the end-effector position of a two-degree-of-freedom (2-degrees-of-freedom) robot manipulator was controlled in task space. The controller works by generating local linear models that represent the robot’s local kinodynamics, which are used to actuate the robot’s end effector towards a given target position. In our most recent work, the model-learning orientation controller [5] has successfully controlled the position and orientation of a 3-degrees-of-freedom robot manipulator’s end effector in task space without any predefined kinodynamic model of the robot. However, this controller underperforms, taking longer than required to converge to the desired pose, when higher-degrees-of-freedom robots are to be controlled, leaving redundancies unresolved, as well.
The Kinematic-Model-Free (KMF) Multi-Point controller presented in this paper extends the state-of-the-art kinematic-model-free orientation controller, enabling the control of hyper-redundant robot manipulators and resolving redundancies in these manipulators by tracking and controlling multiple points along the kinematic chain of such robots.

1.1. Contributions

The contributions of this papers are as follows: (1) the novel kinematic-model-free multi-point controller presented in this paper expands the state-of-the-art kinematic-model-free controller to control the pose of multiple points along a robot’s kinematic chain; (2) the controller allows for the control of robots with high degrees-of-freedom, scaling up from the 3-degrees-of-freedom manipulator in our previous work; and (3) the controller is also capable of resolving redundancies in highly redundant system, such as continuum robots.

1.2. Paper Structure

Section 2 introduces work related to the research presented in this paper. Section 3 summarizes the fundamental mathematical background required to understand the working principles of the novel kinematic-model-free multi-point controller. Section 4 introduces the proposed controller along with its mathematical equations. Section 5 presents experimental results. Finally, Section 6 concludes the paper.

2. Related Work

Model-based controllers have been the predominant method of control for robot manipulation. The Jacobian of a robot, which relates the joint velocities to the end-effector velocity, is calculated prior to control [6], after which it is controlled using forward and inverse kinematics [7]. Using such models imposes many limitations [8] and assumes the Denavit-Hartenberg parameters, that define the robots kinematics, to be static. One example of model-based control is visual servoing that uses an external camera to calculate the required end-effector velocity to reach a desired target [9]. However, this assumption falls apart in the case of soft robots, when robots are damaged, or when robots transform or evolve in any way, such as altering the end effector by changing its gripper. Therefore, model-based conventional controllers are accurate but not adaptable.
Other researchers performed model-free control by approximating a Jacobian that is later used to actuate a robot. Researchers in Reference [10] controlled a deformable manipulator and in Reference [11] controlled a soft manipulator by approximating its Jacobian model. Other researchers controlled a dynamically-undefined robot by first estimating the robot’s dynamic parameters and then controlled a robot using conventional methods [12]. Learning methods, such as motor babbling, that start with no predefined model of a robot’s kinodynamics are used to approximate a model to control robots [13]. Other researchers use machine learning [14] and reinforcement learning algorithms [15] to control robots.
On the other hand, researchers in Reference [16] directly controlled current motors to actuate an unmanned underwater vehicle by means of deterministic artificial intelligence where uncertainties are ignored by making use of first principles. Researchers in Reference [17] controlled a SCARA robot’s position through motor voltages using extended state observer to estimate system dynamics. Other researchers studied hybrid model-free and model-based approaches to increase the performance of robot navigation [18]. However, most of these learning approaches require encoder feedback for estimating the robot’s pose.
The classical kinematic-model-free position controllers, the Encoderless [3] and Kinematic-Free [4] controllers, do not require any prior model of the robot. They operate by generating psuedo-random actuation signals that actuate a planar 2-degrees-of-freedom robot’s joints causing a positional displacement on the robot’s end effector. The effect on the robot’s end effector is observed using an external camera and is recorded. The recorded data are then used to generate a local linear model that actuates the robot’s end effector towards a given target. Any discrepancies will re-trigger another exploratory phase. The classical kinematic-model-free controller was then extended to simultaneously control the position and orientation of a 3-degrees-of-freedom robot’s end effector [5] using locally-weighted dual quaternions. These kinematic-model-free controllers, however, are unable to resolve redundancies in redundant robots, such as manipulators with high degrees of freedom [19] and continuum robots [20].

3. Mathematical Background

3.1. Quaternions

Quaternions, introduced by Hamilton in 1844 [21], are extend the complex number system used to represent rigid-body rotations. A quaternion q is the sum of a scalar s and a vector v = ( q 1 , q 2 , q 3 ) :
q = s + v = s + q 1 i + q 2 j + q 3 k ,
where i, j, k are unit vectors pointing in the x, y, z directions.
The conjugate of a quaternion q is defined as:
q * = s v = s q 1 i q 2 j q 3 k ,
which is used to calculate the norm of a quaternion as follows:
q = q * q .
Unit quaternions satisfy s 2 + q 1 2 + q 2 2 + q 3 2 = 1 or simply q = 1 .
More information on quaternions can be found in Reference [22].

3.2. Dual Quaternions

Dual quaternions, presented by Clifford in 1871 [23], are extend the dual number system. A dual quaternion q ^ is defined as the sum of two quaternions:
q ^ = p + ϵ q ,
where p = s p + v p is the real part, and q = s q + v q is the dual part. The dual element ϵ is nilpotent, i.e., ϵ 2 = 0 .
The conjugate of a dual quaternion is defined as:
q ^ * = p * + ϵ q * ,
which is used to calculate the dual quaternion norm:
q ^ = q ^ * q ^ .
A unit dual quaternion satisfies s p 2 + p 1 2 & + p 2 2 + p 3 2 = 1 and s p s q + p 1 q 1 & + p 2 q 2 + p 3 q 3 = 0 , or simply q ^ = 1 and p , q = 0 . The v e c 8 operator maps the elements of a dual quaternion to an 8-dimensional vector as follows:
v e c 8 ( q ^ ) = ( s p , p 1 , p 2 , p 3 , s q , q 1 , q 2 , q 3 ) .

3.3. Rigid Transformation

Rigid-body transformations are represented using dual quaternions as follows:
q ^ = r + ϵ 2 tr ,
where r is the rotation quaternion, and t is the translation quaternion [24]. Note that the scalar part is always zero for the translation quaternion, i.e., t = 0 + v t = v t .

3.4. Interpolation

Shoemake introduced the Spherical Linear Interpolation to interpolate between two quaternions [25]:
m = Φ ( p , q , t ) = p ( p * q ) t ,
where t [ 0 , 1 ] . On the other hand, Screw Linear Interpolation for dual quaternions is defined similarly as p ^ ( p ^ * q ^ ) t .

3.5. Relative Dual Quaternions

The relative rotational displacement, b r e l , between two quaternions, p and q is found as follows:
b r e l = p * q .
On the other hand, the relative dual quaternion between two dual quaternions, p ^ and q ^ , is [5]:
D Q r e l ( p ^ , q ^ ) = b ^ r e l = r 1 * r 2 + ϵ 2 ( t 1 * + t 2 ) r 1 * r 2 .
Note that b ^ r e l must be normalized if not.

3.6. Dual Quaternion Distance

The same distance metric defined in Reference [5] will be adopted for the proposed controller, which provides a measure of how close a control point is to a target point:
D Q d i s t ( q ^ 1 , q ^ 2 ) = v e c 8 ( 0 ^ ) v e c 8 ( D Q r e l ( q ^ 1 , q ^ 2 ) ) ,
where 0 ^ is the null dual quaternion.

3.7. Dual Quaternion Regression

To find the regression coefficients or weights, w = [ w 1 , w 2 , , w n ] , of the dual quaternions Q ^ = [ q ^ 1 , q ^ 2 , , q ^ n ] that yield some desired dual quaternion q ^ d , the following cost function is optimized:
D Q r e g ( q ^ d , Q ^ ) = min w D Q d i s t ( q ^ d , q ^ r ) ,
where
q ^ r = D Q L C ( Q ^ , w ) ,
which can be optimized using a generic optimization algorithm, such as MATLAB’s FMINCON optimization algorithm. The Dual Quaternion Linear Combination (DQLC) function is defined as:
D Q L C ( Q ^ , w ) = D Q L C ( q ^ 1 , , q ^ n , w 1 , , w n ) ,
= i = 1 n r i w i + ϵ 2 i = 1 n w i t i i = 1 n r i w i .

4. Proposed Approach

After specifying the control points that are to be controlled via markers or trackers, the controller first goes through an actuators discovery phase. Each actuator, j J , is moved one after another but in no particular order, where J is the set of all actuators. For each control point i I , the actuators that can contribute to displacing it are assigned to that point, where I is the set of all control points. Thus, actuators could be assigned to multiple control points. The control point that can be displaced by all actuators, most probably being the end effector of the robot, is assigned an index i = n , where n is the cardinality of set I . The discovery phase produces the following Boolean matrix:
S = s 1 s 2 s n = δ 1 1 δ 2 1 δ m 1 δ 1 2 δ 2 2 δ m 2 δ 1 n δ 2 n δ m n ,
where m is the cardinality of set J . The function above is defined as: δ j i = 1 if actuator j can displace control point i and δ j i = 0 otherwise. To find the number of actuators that contribute to some control point i, the dot product can be used a i = s i · s i . A vector of the number of such actuators can be defined as a = [ a 1 , a 2 , , a n ] .
The kinematic-model-free multi-point controller, just like any other kinematic-model-free controller, assumes that the local kinodynamics information of the manipulator is attainable. This information is attained by generating pseudo-random actuation signals to actuate the robot joints and observing their result on the robot’s control point(s). A high-level diagram summarizing the kinematic-model-free multi-point approach is shown in Figure 1.
The actuation primitives produce signals τ ( t ) which are sent to each of the robot’s actuators and are defined as:
τ ( t ) = τ p t [ t 0 , t 0 + d p 2 ) τ p t [ t 0 + d p 2 , t 0 + d p ] 0 otherwise .
Note that actuation primitives could be motor torques, motor currents, joint positions, etc. The controller tracks the poses of the control points, q ^ i , using dual quaternion representation which yield the controlled points vector:
ϕ ^ = [ q ^ i , , q ^ n ] .
The controller attempts to bring the points q ^ i towards desired target poses d ^ i f , yielding the desired poses vector as follows:
γ ^ = [ d ^ i f , , d ^ n f ] .
By controlling multiple points, redundancies can be easily resolved by specifying the desired poses of other points along the robot’s serial chain. The controller terminates when ϕ ^ = γ ^ , i.e., when the poses of the controlled points of interest coincide with their corresponding desired poses. This condition can be relaxed by allow the controlled points’ poses to reach within some deviation σ of their respective desired target poses. Otherwise, the controller is to actuate the control points towards a set of intermediate poses d ^ i t that lead to the final desired target poses d ^ i f in discrete steps. The intermediate poses are found using screw linear interpolation interpolation between the current poses of the controlled points, q ^ i , and desired target poses, d ^ i f . At each step, the kinematic-model-free multi-point controller estimates actuation primitives, b i , to move each controlled point i I towards their respective desired poses:
b i = τ p 1 ( p ^ ) τ p 2 ( p ^ ) τ p m ( p ^ ) ,
where τ p j ( p ^ ) is the magnitude of the actuation primitive of actuator j. After each step where the robot joints have been actuated, the displacement of the control points are recorded as observations, which are calculated using the D Q r e l function. The nearest k observation dual quaternions to each point i I form the observation matrix:
ψ ^ = ψ ^ 1 ψ ^ 2 ψ ^ n = o ^ 1 1 o ^ 2 1 o ^ k 1 o ^ 1 2 o ^ 2 2 o ^ k 2 o ^ 1 n o ^ 2 n o ^ k n ,
where o ^ k i is the k t h closest observation dual quaternion of controlled point i. The actuation primitives corresponding to these observations form the actuation matrix:
A i = τ p 1 ( p 1 ) τ p 1 ( p 2 ) τ p 1 ( p k ) τ p 2 ( p 1 ) τ p 2 ( p 2 ) τ p 2 ( p k ) τ p a i ( p 1 ) τ p a i ( p 2 ) τ p a i ( p k ) .
The desired actuation primitives, b i , is assumed to be a linear combination of the k nearest actuation primitives such that:
A i w i = b i ,
where w i = [ w 1 i , w 2 i , , w k i ] T is a set of unknown weights. The weights are estimated by minimizing the following:
D Q r e g ( d ^ i t , ψ ^ i ) = min w i D Q d i s t ( d ^ i t , D Q L C ( ψ ^ i , w i ) ) .
With the weights for each control point, the desired actuation is then computed using Equation (24) for each control point. The respective actuation matrix is used in the calculation. After the primitive for each control point has been obtained, the following averaging is done to dampen and stir the actuation of joints that contribute to the displacement of the control points:
b i = r = 1 r = i η r i Z ( b r ) r = 1 r = i η r i ,
where the operator Z adds zero padding to a vector to keep the length equal to m, and the averaging weights matrix is a lower triangular matrix:
H = η 1 1 0 0 0 0 η 1 2 η 2 2 0 0 0 η 1 3 η 2 3 η 3 3 0 0 η 1 n η 2 n η 3 n η 4 n η n n .
In the case that the averaging weights for each control point is normalized, Equation (26) would simply be:
b i = r = 1 r = i η i r Z ( b r ) .
Alternatively, to reduce the number of optimizations required, it is possible to fuse the optimization of each control point together into a wholesome expression as follows:
D Q r e g ( γ ^ , ψ ^ ) = min w i = 1 i = n D Q d i s t ( d ^ i t , D Q L C ( ψ ^ i , w ) ) ,
where the weights are later used in A n w = b to estimate the required actuation. After each discrete actuation, the resulting displacement on the pose of each control point is compared to the expected displacement. Should the difference be significant, a new exploratory phase is triggered to collect more data about the robot’s local kinodynamics as shown in Figure 1. The controller leaves the exploratory phase once it has completed a predefined number of exploratory steps. The controller terminates once all control point poses have reached the desired poses or close enough to them, D Q d i s t ( q ^ , d ^ ) < σ .
This controller, just like its other kinematic-model-free predecessors, does not require any prior model of the robot’s kinodynamics. As such, the controller is agnostic to any kinodynamic changes in the robot, such as alteration in the robot’s link dimensions. Since the kinematic-model-free multi-point controller is not based on any accurate robot model, the accuracy of the controller is less than conventional controllers. Moreover, this controller operates in discrete steps, making it significantly slower than other controllers and the motion can be relatively jerky. As with other complex models, such as those found in References [26,27], it is difficult to proof the convergence of the kinematic-model-free controller due to the nonlinear functions that are involved.

5. Simulation Results

The controller is tested on a simulated redundant 9-degrees-of-freedom continuum robot, shown in Figure 2.
The robot was simulated using Matlab’s Robotics Toolbox [28] and DQ Robotics Toolbox [29]. The actuation primitives used were joint position command signals to drive the control points towards the target poses. The Denavit–Hartenberg parameters of the robot is listed in Table 1.
The controller was programmed as described in Section 4 using k = 4 nearest neighbors that comprise of actuation primitive and observation pairs. Since the experiments were conducted in simulation, a tracking camera was not needed to determine the poses of the control points. In addition, actuators discovery was also omitted in the simulation. Instead, the simulator provided these information directly. Furthermore, gravity was omitted in the simulation to keep the focus on multi-point pose control, deferring gravity compensation to future work.
Three experiments were performed to study the capabilities of the proposed kinematic-model-free multi-point controller. The first experiment involved end-effector pose control for the continuum robot with increasing number of degrees of freedom enabled. This experiment shows the degrading performance of the controller when increasing the number of degrees of freedom using a single control point. In the second experiment, the 9-degrees-of-freedom continuum robot was controlled using 1, 2, and 3 control point(s). This experiment highlights the capability of the kinematic-model-free multi-point controller to control robots of high degrees of freedom and resolve redundancies. Lastly, the robustness of the kinematic-model-free multi-point controller was measured by executing the simulation experiment 100 times with randomly-generated configurations.

5.1. Single-Point Control

In the first experiment, a single control point situated at the end effector of the continuum robot was used to actuate the robot towards a desired target pose. Initially, only the last 2 joints of the robot were enabled. Gradually, an extra joint was enabled, increasing the robot’s degrees of freedom. The robot began from the home pose where the control-point’s task-space position was (0, 0, 0.4500), and orientation was (0, 0, 3.1416). Orientations in this paper are specified in ZYX Euler angle representation for simplicity. The target position was (0.4218, 0.0240, 0.0605) and orientation was (0.6202, −0.6009, 2.7578). The results are shown in Figure 3 and tabulated in Table 2.
In the simple 2-degrees-of-freedom case, the control point converged to the target pose within 25 steps. When increasing the degrees of freedom, it is noted that the controller takes longer to converge. Although it is evidently possible to reach the target pose within 25 steps, the added redundancies introduced additional nonlinearities that require excessive exploratory behavior. In the case where all 9 joints of the robot were enabled, the control point reached the target pose in 150 steps, a significant decrease in performance. With the stopping condition ( D Q d i s t < σ ) applied, it can be seen that the controller can terminate before fully reaching the target pose.

5.2. Multi-Point Control

In this experiment, multiple control points were added to the continuum robot. In the first arrangement, only a single control point was added that was situated at the end effector. In the second arrangement, 2 control points were added, one at the end effector and one at the end of link 5. Finally, in the third arrangement, the 3 control points were added that were evenly distributed throughout the robot’s kinematic chain. The placements of the control point for each arrangement are summarized in Table 3.
These arrangements are depicted in Figure 4. Three reaching tasks were preformed with each arrangement. All desired poses were within the robot’s configuration space. See Figure 5. The reaching tasks increased in complexity in terms of dexterity required. We note that arrangement 1 corresponds to kinematic-model-free control of the end-effector pose. Thus, this experiment also serves as a comparison with the kinematic-model-free orientation controller in Reference [5]. The results are shown in Figure 6 and tabulated in Table 4.
Only the pose distance of the control point situated at the end effector is shown. It can be seen that the controller converges faster to the desired pose when using more control points situated along the robot’s kinematic chain. In task 1, we note that a 66% improvement in convergence speed when using 3 control points. In task 2 and 3, there was a 38% and 50% improvement was measured, respectively. These results indicate that adding more control points will improve convergence and resolve redundancies in hyper-redundant systems. As for accuracy, the termination criteria was set to DQdist < 0.03, achieving a close enough reaching accuracy.
Furthermore, to demonstrate the joints’ position during an execution, the joint position are shown in Figure 7. The larger jitters in joint positions correspond to exploratory behavior, which is triggered whenever there is deficiency in local kinodynamic information.

5.3. Robustness

The robustness of the algorithm was measured by executing the simulation 100 times. Each time, the robot must reach a randomly-generated pose that is within its configuration space and it reachable within 150 steps. If the controller takes longer, the simulation is restarted. Three control points were used. One interesting configuration is shown in Figure 8. The controller managed to achieve this bent arch configuration within 150 steps.
It was observed that 82% of the runs, the controller manages to reach to the target pose. However, in 18% of the runs, the controller did not successfully converge to the solutions that brought the robot’s end effector to the desired poses. This can occur when the optimization is stuck in a local minimum, which results in an inaccurate actuation signal that does not optimally move the control points towards the target poses.

6. Conclusions

This paper presents a novel kinematic-model-free control for controlling the pose of multiple points along the kinematic chain of a continuum robot. The proposed controller is able to resolve redundancies and converge faster to a desired configuration. The controller works by actuating the robot using randomly-generated actuation primitives and observing their effects on the control points. This information is then used to build a local linear model using locally weighted dual quaternions. The local linear model is then used to calculate an actuation primitive and actuate the continuum robot towards a desired pose.
In the first experiment, it was evident that the performance of the controller worsened in terms of convergence when increasing the degrees of freedom of the robot. The higher the degrees of freedom, the longer it took to converge. This is due to the nonlinearities introduced, making the local linear model less accurate.
We presented the generalized kinematic-model-free multi-point controller and the method by which observations are used to calculate actuation primitives that will reduce the distance between a robot’s current pose and its desired target pose. The simulation results in the second experiment show that this novel controller is capable of performing reaching tasks without any prior kinematic model of the robot, successfully actuating the poses of the control points towards some desired configuration.
Three arrangements for the control points were tested on a simulated 9-degrees-of-freedom continuum robot. Three different robot configurations were targeted, all of which are within the robot’s configuration space. It was noted that, when more control points were used, the controller performed better and converged faster to the desired target robot pose. Controlling multiple points along a robot did not only resolves redundancies, but proved to converge faster to the desired pose.
Finally, the controller’s robustness was tested by executing the simulation 100 times using random target configurations which the controller had to reach. The random target configurations lied within the robot’s configuration space. The kinematic-model-free multi-point controller succeeded in reaching the target poses within 150 steps 82% of the times.
The proposed controller can be used in applications where simultaneous translational and rotational reaching of redundant robots is required. The controller is useful for resolving redundancies of continuum robots. The kinematic-model-free approach in general can be used for new robots where a model is not readily-available or for robots that are hard to model. In general, the controller is applicable where flexibility is favored over precision and speed. Examples of such applications include use of soft robots for reaching, drawing, picking-and-placing, etc. As for future work, continuous control, gravity compensation, joint limits, joint friction, and physical implementations, are promising research directions to be investigated. These challenges must be addressed before deploying the kinematic-model-free controller on any physical system.

Author Contributions

A.A. developed the theory, methodology, and software, performed the simulation experiments, and wrote the paper. F.C. prepared the robot simulation model and interface and reviewed the paper. P.K. supervised the research and proofread the paper. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported through the resources at the Dubai Future Labs. Full financial support for A.A.’s PhD program was provided by the UAE’s Ministry of Education.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Cho, H. Opto-Mechatronic Systems Handbook: Techniques and Applications; CRC Press: Boca Raton, FL, USA, 2002. [Google Scholar]
  2. Spong, M.W.; Fujita, M. Control in robotics. In The Impact of Control Technology: Overview, Success Stories, and Research Challenges; IEEE Control Systems Society: New York, NY, USA, 2011. [Google Scholar]
  3. Kormushev, P.; Demiris, Y.; Caldwell, D.G. Encoderless position control of a two-link robot manipulator. In Proceedings of the 2015 IEEE International Conference on Robotics and Automation (ICRA), Seattle, WA, USA, 26–30 May 2015; pp. 943–949. [Google Scholar]
  4. Kormushev, P.; Demiris, Y.; Caldwell, D.G. Kinematic-free position control of a 2-dof planar robot arm. In Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Hamburg, Germany, 28 September–2 October 2015; pp. 5518–5525. [Google Scholar]
  5. AlAttar, A.; Kormushev, P. Kinematic-model-free orientation control for robot manipulation using locally weighted dual quaternions. Robotics 2020, 9, 76. [Google Scholar] [CrossRef]
  6. Nour, M.; Ooi, J.; Chan, K. Fuzzy logic control vs. conventional PID control of an inverted pendulum robot. In Proceedings of the 2007 International Conference on Intelligent and Advanced Systems, Kuala Lumpur, Malaysia, 25–28 November 2007; pp. 209–214. [Google Scholar]
  7. Ghosal, A. Robotics: Fundamental Concepts and Analysis; Oxford University Press: New Delhi, India, 2006. [Google Scholar]
  8. Cheah, C.C.; Liu, C.; Slotine, J.J.E. Adaptive Jacobian tracking control of robots with uncertainties in kinematic, dynamic and actuator models. IEEE Trans. Autom. Control. 2006, 51, 1024–1029. [Google Scholar] [CrossRef]
  9. Huang, Y.; Su, J. Visual Servoing of Nonholonomic Mobile Robots: A Review and a Novel Perspective. IEEE Access 2019, 7, 134968–134977. [Google Scholar] [CrossRef]
  10. Li, G.; Song, D.; Xu, S.; Sun, L.; Liu, J. Kinematic-free orientation control for a deformable manipulator based on the geodesic in rotation group so (3). IEEE Robot. Autom. Lett. 2018, 3, 2432–2438. [Google Scholar] [CrossRef]
  11. Jin, Y.; Wang, Y.; Chen, X.; Wang, Z.; Liu, X.; Jiang, H.; Chen, X. Model-less feedback control for soft manipulators. In Proceedings of the 2017 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Guangzhou, China, 6–8 December 2017; pp. 2916–2922. [Google Scholar]
  12. Wu, J.; Wang, J.; You, Z. An overview of dynamic parameter identification of robots. Robot. Comput. Integr. Manuf. 2010, 26, 414–419. [Google Scholar] [CrossRef]
  13. Aoki, T.; Nakamura, T.; Nagai, T. Learning of motor control from motor babbling. IFAC Papers OnLine 2016, 49, 154–158. [Google Scholar] [CrossRef]
  14. Cursi, F.; Mylonas, G.P.; Kormushev, P. Adaptive kinematic modelling for multiobjective control of a redundant surgical robotic tool. Robotics 2020, 9, 68. [Google Scholar] [CrossRef]
  15. Kormushev, P.; Calinon, S.; Caldwell, D. Reinforcement learning in robotics: Applications and real-world challenges. Robotics 2013, 2, 122–148. [Google Scholar] [CrossRef] [Green Version]
  16. Sands, T. Development of Deterministic Artificial Intelligence for Unmanned Underwater Vehicles (UUV). J. Mar. Sci. Eng. 2020, 8, 578. [Google Scholar] [CrossRef]
  17. Saleki, A.; Fateh, M.M. Model-free control of electrically driven robot manipulators using an extended state observer. Comput. Electr. Eng. 2020, 87, 106768. [Google Scholar] [CrossRef]
  18. Dromnelle, R.; Renaudo, E.; Pourcel, G.; Chatila, R.; Girard, B.; Khamassi, M. How to reduce computation time while sparing performance during robot navigation? A neuro-inspired architecture for autonomous shifting between model-based and model-free learning. In Conference on Biomimetic and Biohybrid Systems; Springer: Berlin/Heidelberg, Germany, 2020; pp. 68–79. [Google Scholar]
  19. AlAttar, A.; Rouillard, L.; Kormushev, P. Autonomous air-hockey playing cobot using optimal control and vision-based bayesian tracking. In Proceedings of the 20th International Conference Towards Autonomous Robotic Systems (TAROS 2019), London, UK, 3–5 July 2019. [Google Scholar]
  20. Cursi, F.; Modugno, V.; Kormushev, P. Model predictive control for a tendon-driven surgical robot with safety constraints in kinematics and dynamics. In Proceedings of the 2020 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Las Vegas, NV, USA, 24 October–24 January 2020; pp. 7653–7660. [Google Scholar]
  21. Hamilton, W.R. On quaternions; or on a new system of imaginaries in algebra. Philos. Mag. 1844, 25, 489–495. [Google Scholar]
  22. Goldman, R. Understanding quaternions. Graph. Model. 2011, 73, 21–49. [Google Scholar] [CrossRef]
  23. Clifford. Preliminary Sketch of Biquaternions. Proc. Lond. Math. Soc. 1871, s1-4, 381–395. [Google Scholar] [CrossRef]
  24. Han, D.P.; Wei, Q.; Li, Z.X. Kinematic control of free rigid bodies using dual quaternions. Int. J. Autom. Comput. 2008, 5, 319–324. [Google Scholar] [CrossRef]
  25. Shoemake, K. Animating rotation with quaternion curves. In Proceedings of the 12th Annual Conference on Computer Graphics and Interactive Techniques, San Francisco, CA, USA, 22–26 July 1985; pp. 245–254. [Google Scholar]
  26. Schilling, M. Universally manipulable body models—dual quaternion representations in layered and dynamic MMCs. Auton. Robot. 2011, 30, 399. [Google Scholar] [CrossRef] [Green Version]
  27. Rakita, D.; Mutlu, B.; Gleicher, M. RelaxedIK: Real-time Synthesis of Accurate and Feasible Robot Arm Motion. In Robotics: Science and Systems; ACM: Pittsburgh, PA, USA, 2018; pp. 26–30. [Google Scholar]
  28. Corke, P. Robotics, Vision and Control: Fundamental Algorithms in MATLAB® Second, Completely Revised; Springer: Berlin/Heidelberg, Germany, 2017; Volume 118. [Google Scholar]
  29. Adorno, B.V.; Marinho, M.M. DQ Robotics: A Library for Robot Modeling and Control. IEEE Robot. Autom. Mag. 2020, 1–15. [Google Scholar] [CrossRef]
Figure 1. Flowchart of kinematic-model-free multi-point control.
Figure 1. Flowchart of kinematic-model-free multi-point control.
Applsci 11 04746 g001
Figure 2. The simulated 9-degrees-of-freedom continuum robot.
Figure 2. The simulated 9-degrees-of-freedom continuum robot.
Applsci 11 04746 g002
Figure 3. The controller performed the task of reaching, bringing a single control point at the end effector to a desired target pose. As more joints were enabled, the performance was degraded. In particular, in the 2-degrees-of-freedom case, the robot reaches the target in 21 steps, while, in the 9-degrees-of-freedom case, the robot reaches the target in 150 steps.
Figure 3. The controller performed the task of reaching, bringing a single control point at the end effector to a desired target pose. As more joints were enabled, the performance was degraded. In particular, in the 2-degrees-of-freedom case, the robot reaches the target in 21 steps, while, in the 9-degrees-of-freedom case, the robot reaches the target in 150 steps.
Applsci 11 04746 g003
Figure 4. The three arrangements of the control points (CP’s) along the robot’s kinematic chain. In the first arrangement, only one control point was used which was placed at the end effector. In the second and third arrangements, two and three equally spaced control points were used, respectively.
Figure 4. The three arrangements of the control points (CP’s) along the robot’s kinematic chain. In the first arrangement, only one control point was used which was placed at the end effector. In the second and third arrangements, two and three equally spaced control points were used, respectively.
Applsci 11 04746 g004
Figure 5. The three reaching tasks to be performed. The translucent pose is the initial configuration from which the robot is to actuate towards the opaque pose.
Figure 5. The three reaching tasks to be performed. The translucent pose is the initial configuration from which the robot is to actuate towards the opaque pose.
Applsci 11 04746 g005
Figure 6. The controller performed three reaching tasks. In all 3 tasks, the controller converged faster when using more control points (CPs).
Figure 6. The controller performed three reaching tasks. In all 3 tasks, the controller converged faster when using more control points (CPs).
Applsci 11 04746 g006
Figure 7. These joint positions correspond to reaching task 1. The larger jitters are due to exploratory behavior, which is triggered to collect more information about the robot’s local kinodynamics.
Figure 7. These joint positions correspond to reaching task 1. The larger jitters are due to exploratory behavior, which is triggered to collect more information about the robot’s local kinodynamics.
Applsci 11 04746 g007
Figure 8. In this simulation run, the controller attempted to actuate the robot to a back arching configuration. It achieved to reach this configuration within 150 steps.
Figure 8. In this simulation run, the controller attempted to actuate the robot to a back arching configuration. It achieved to reach this configuration within 150 steps.
Applsci 11 04746 g008
Table 1. Denavit–Hartenberg parameters of redundant robot.
Table 1. Denavit–Hartenberg parameters of redundant robot.
Link d i θ i a i α i
1000.051.5708
2000.051.5708
3000.05−1.5708
4000.051.5708
5000.05−1.5708
6000.051.5708
7000.05−1.5708
8000.051.5708
9000.050
Table 2. Reaching steps for different degrees of freedom enabled.
Table 2. Reaching steps for different degrees of freedom enabled.
Degrees of FreedomSteps to Reach
221 steps
340 steps
442 steps
535 steps
641 steps
776 steps
8127 steps
9150 steps
Table 3. Control points placement.
Table 3. Control points placement.
ArrangementControl Point 1Control Point 2Control Point 3
1end effector--
2end of link 5end effector-
3end of link 3end of link 6end effector
Table 4. Steps required to complete three reaching tasks using three arrangements of control points.
Table 4. Steps required to complete three reaching tasks using three arrangements of control points.
Task Arrangement
123
170 steps64 steps46 steps
293 steps59 steps35 steps
3185 steps147 steps92 steps
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

AlAttar, A.; Cursi, F.; Kormushev, P. Kinematic-Model-Free Redundancy Resolution Using Multi-Point Tracking and Control for Robot Manipulation. Appl. Sci. 2021, 11, 4746. https://doi.org/10.3390/app11114746

AMA Style

AlAttar A, Cursi F, Kormushev P. Kinematic-Model-Free Redundancy Resolution Using Multi-Point Tracking and Control for Robot Manipulation. Applied Sciences. 2021; 11(11):4746. https://doi.org/10.3390/app11114746

Chicago/Turabian Style

AlAttar, Ahmad, Francesco Cursi, and Petar Kormushev. 2021. "Kinematic-Model-Free Redundancy Resolution Using Multi-Point Tracking and Control for Robot Manipulation" Applied Sciences 11, no. 11: 4746. https://doi.org/10.3390/app11114746

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