Top Banner
Enhancing Kinematic Accuracy of Redundant Wheeled Mobile Manipulators via Adaptive Motion Planning Hongjun Xing a,b , Ali Torabi b , Liang Ding a,< , Haibo Gao a , Weihua Li a and Mahdi Tavakoli b,< a State Key Laboratory of Robotics and System, Harbin Institute of Technology, Harbin 150001, China b Department of Electrical and Computer Engineering, University of Alberta, Edmonton T6G 1H9, Alberta, Canada ARTICLE INFO Keywords: Wheeled mobile manipulator kinematic accuracy joint constraints adaptive motion planning redundancy resolution ABSTRACT An increasing demand for wheeled mobile manipulators (WMMs) in fields that require high preci- sion tasks has introduced new requirements as far as their kinematic accuracy. A WMM consists of a manipulator mounted on a mobile base. This configuration usually makes the WMM a redundant robotic system. One limiting factor is that the kinematic accuracy of the mobile base is often lower than that of the manipulator because of modelling errors and disturbances such as slippage. Thus, it makes sense to distribute more of a given set of motion requirements for the entire mobile manipu- lator to the manipulator when possible – this is usually done using a weighting matrix that sums the mobile base motion and the manipulator motion. In this paper, considering a redundant WMM, a novel adaptive motion planning method is proposed as a secondary objective in the null space of the primary objective (improvement of the WMM’s kinematic accuracy) for the WMM. Also, a tertiary objective to move the manipulator away from its singularity is proposed. This objective is activated if the secondary objective is feasible and the WMM still has remaining redundant degrees of free- dom. The proposed method is implemented at the acceleration level to circumvent the discontinuity of the commanded joint velocity due to the adaptive motion planning algorithm. The advantages and effectiveness of the proposed approach are demonstrated with a traditional motion planning approach through experiments. 1. Introduction Wheeled mobile manipulators (WMMs) fuse the advan- tages of high mobility of a mobile base and dexterous op- eration ability of a manipulator. WMMs have been used in executing many tasks that need high precision, including door opening [1, 2], valve turning [3], object grasping [4, 5], and large-scale 3D printing [6]. The addition of a mobile base to a manipulator is an efficient method of extending the reach of the manipulator, which is otherwise restricted to a fixed workspace. This combination has presented new chal- lenges to researchers. Due to the different characteristics of the base and the manipulator such as their kinematics and dynamics, the motion planning and control of the entire sys- tem (called the mobile manipulator) should take these dif- ferences into account [7]. Also, the combination of the mo- bile base and the manipulator often makes the WMM a kine- matically redundant robotic system. A redundant robot has more degrees of freedom (DOFs) than minimally required for executing tasks. The inverse kinematics of any kinemat- ? This work was supported by Canada Foundation for Innovation (CFI), the Natural Sciences and Engineering Research Council (NSERC) of Canada, the Canadian Institutes of Health Research (CIHR), the Al- berta Advanced Education Ministry, the Alberta Economic Development, Trade and Tourism Ministry’s grant to Centre for Autonomous Systems in Strengthening Future Communities, the National Natural Science Foun- dation of China (Grant No. 51822502, 91948202), the National Key Re- search and Development Program of China (No. SQ2019YFB130016), the Fundamental Research Funds for the Central Universities (Grant No. HIT.BRETIV201903), the “111” Project (Grant No. B07018), and the China Scholarship Council under Grant [2019]06120165. < Corresponding authors [email protected] (H. Xing); [email protected] (A. Torabi); [email protected] (L. Ding); [email protected] (H. Gao); [email protected] (W. Li); [email protected] (M. Tavakoli) ically redundant robotic system admits an infinite number of solutions. Thus, redundancy makes it possible to have joint motions that do not affect the pose (position and ori- entation) of the end-effector[8, 9]. This inner joints motion can be used in closed-loop control to achieve a secondary objective while performing any primary objective, e.g., sin- gularity avoidance, obstacle avoidance, manipulability en- hancement, and/or force feedback capability maximization [10, 11, 12, 13]. The mobile base is often regarded as an extension to the manipulator, and the model of the entire system is estab- lished without considering the inherent differences between these two parts. For example, the base usually moves in an unstructured environment (e.g., slippage/skidding or loco- motion on uneven ground) while the manipulator is in free or contact motion [14]. The kinematic accuracy of the mobile base is generally lower than that of the manipulator due to the unknown wheel-ground contact and the possibility of slip- page. Thus, kinematic accuracy improvement of the WMM can be achieved by distributing more of the required motions to the manipulator than to the mobile base when the task per- mits. Kinematic accuracy is of great importance for mobile robots, especially when they are working in constrained en- vironments [15]. However, few studies were conducted to improve the kinematic accuracy of a WMM’s end-effector with consideration of the motion errors of the mobile base. Shin et al. [16] improved the kinematic precision of a WMM by discretizing the task so that the mobile base and the ma- nipulator did not move simultaneously. Papadopoulos et al. [17] presented a motion planning methodology for nonholo- nomic WMMs simultaneously following desired end-effector Hongjun Xing et al.: Preprint submitted to Elsevier Page 1 of 13 This papers appears in Mechatronics, 2021. https://doi.org/10.1016/j.mechatronics.2021.102639
13

Enhancing Kinematic Accuracy of Redundant Wheeled Mobile ...

Dec 26, 2021

Download

Documents

dariahiddleston
Welcome message from author
This document is posted to help you gain knowledge. Please leave a comment to let me know what you think about it! Share it to your friends and learn new things together.
Transcript
Page 1: Enhancing Kinematic Accuracy of Redundant Wheeled Mobile ...

Enhancing Kinematic Accuracy of Redundant Wheeled MobileManipulators via Adaptive Motion PlanningHongjun Xinga,b, Ali Torabib, Liang Dinga,∗, Haibo Gaoa, Weihua Lia and Mahdi Tavakolib,∗

aState Key Laboratory of Robotics and System, Harbin Institute of Technology, Harbin 150001, ChinabDepartment of Electrical and Computer Engineering, University of Alberta, Edmonton T6G 1H9, Alberta, Canada

ART ICLE INFO

Keywords:Wheeled mobile manipulatorkinematic accuracyjoint constraintsadaptive motion planningredundancy resolution

ABSTRACT

An increasing demand for wheeled mobile manipulators (WMMs) in fields that require high preci-sion tasks has introduced new requirements as far as their kinematic accuracy. A WMM consists ofa manipulator mounted on a mobile base. This configuration usually makes the WMM a redundantrobotic system. One limiting factor is that the kinematic accuracy of the mobile base is often lowerthan that of the manipulator because of modelling errors and disturbances such as slippage. Thus, itmakes sense to distribute more of a given set of motion requirements for the entire mobile manipu-lator to the manipulator when possible – this is usually done using a weighting matrix that sums themobile base motion and the manipulator motion. In this paper, considering a redundant WMM, anovel adaptive motion planning method is proposed as a secondary objective in the null space of theprimary objective (improvement of the WMM’s kinematic accuracy) for the WMM. Also, a tertiaryobjective to move the manipulator away from its singularity is proposed. This objective is activatedif the secondary objective is feasible and the WMM still has remaining redundant degrees of free-dom. The proposed method is implemented at the acceleration level to circumvent the discontinuityof the commanded joint velocity due to the adaptive motion planning algorithm. The advantages andeffectiveness of the proposed approach are demonstrated with a traditional motion planning approachthrough experiments.

1. IntroductionWheeled mobile manipulators (WMMs) fuse the advan-

tages of high mobility of a mobile base and dexterous op-eration ability of a manipulator. WMMs have been usedin executing many tasks that need high precision, includingdoor opening [1, 2], valve turning [3], object grasping [4, 5],and large-scale 3D printing [6]. The addition of a mobilebase to a manipulator is an efficient method of extending thereach of the manipulator, which is otherwise restricted to afixed workspace. This combination has presented new chal-lenges to researchers. Due to the different characteristics ofthe base and the manipulator such as their kinematics anddynamics, the motion planning and control of the entire sys-tem (called the mobile manipulator) should take these dif-ferences into account [7]. Also, the combination of the mo-bile base and the manipulator often makes theWMM a kine-matically redundant robotic system. A redundant robot hasmore degrees of freedom (DOFs) than minimally requiredfor executing tasks. The inverse kinematics of any kinemat-

⋆This work was supported by Canada Foundation for Innovation(CFI), the Natural Sciences and Engineering Research Council (NSERC)of Canada, the Canadian Institutes of Health Research (CIHR), the Al-berta Advanced Education Ministry, the Alberta Economic Development,Trade and Tourism Ministry’s grant to Centre for Autonomous Systemsin Strengthening Future Communities, the National Natural Science Foun-dation of China (Grant No. 51822502, 91948202), the National Key Re-search and Development Program of China (No. SQ2019YFB130016),the Fundamental Research Funds for the Central Universities (Grant No.HIT.BRETIV201903), the “111” Project (Grant No. B07018), and theChina Scholarship Council under Grant [2019]06120165.

∗Corresponding [email protected] (H. Xing); [email protected] (A. Torabi);

[email protected] (L. Ding); [email protected] (H. Gao);[email protected] (W. Li); [email protected] (M. Tavakoli)

ically redundant robotic system admits an infinite numberof solutions. Thus, redundancy makes it possible to havejoint motions that do not affect the pose (position and ori-entation) of the end-effector[8, 9]. This inner joints motioncan be used in closed-loop control to achieve a secondaryobjective while performing any primary objective, e.g., sin-gularity avoidance, obstacle avoidance, manipulability en-hancement, and/or force feedback capability maximization[10, 11, 12, 13].

The mobile base is often regarded as an extension to themanipulator, and the model of the entire system is estab-lished without considering the inherent differences betweenthese two parts. For example, the base usually moves in anunstructured environment (e.g., slippage/skidding or loco-motion on uneven ground) while the manipulator is in free orcontact motion [14]. The kinematic accuracy of the mobilebase is generally lower than that of themanipulator due to theunknown wheel-ground contact and the possibility of slip-page. Thus, kinematic accuracy improvement of the WMMcan be achieved by distributing more of the required motionsto the manipulator than to the mobile base when the task per-mits.

Kinematic accuracy is of great importance for mobilerobots, especially when they are working in constrained en-vironments [15]. However, few studies were conducted toimprove the kinematic accuracy of a WMM’s end-effectorwith consideration of the motion errors of the mobile base.Shin et al. [16] improved the kinematic precision of aWMMby discretizing the task so that the mobile base and the ma-nipulator did not move simultaneously. Papadopoulos et al.[17] presented a motion planning methodology for nonholo-nomicWMMs simultaneously following desired end-effector

Hongjun Xing et al.: Preprint submitted to Elsevier Page 1 of 13

This papers appears in Mechatronics, 2021.https://doi.org/10.1016/j.mechatronics.2021.102639

Page 2: Enhancing Kinematic Accuracy of Redundant Wheeled Mobile ...

Enhancing Kinematic Accuracy of Redundant Wheeled Mobile Manipulators via Adaptive Motion Planning

and mobile base trajectories without violating the nonholo-nomic constraints, assuming that the base had no kinematicerror. Nagatani et al. [18] presented a cooperative motionplanning method for WMMs without considering the kine-matic motion error of the mobile base. Jia et al. [7] paidattention to the differences between the mobile base and themanipulator. They proposed a coordinated motion planningmethod based on a weighted inverse Jacobian for nonholo-nomicmobilemanipulators without considering the joint con-straints (position, velocity, and acceleration). The employ-ment of a weighted inverse Jacobian could realize motiondistribution between the two sub-systems (the mobile baseand the manipulator). Xing et al. [19] employed a weight-ing matrix to distribute the desired end-effector motion of anomnidirectional mobile manipulator to the movement of themobile base and the action of the manipulator with consid-eration of the manipulator joint limits at the velocity level toimprove the kinematic accuracy of the total system. Yet, thismotion planning approach did not fully utilize the manipu-lator’s redundancy [20] because when one of the manipula-tor’s joint exceeded its limit, the motion requirement wouldsimply be transferred to the mobile base.

The motion planning of redundant WMMs can also beformulated as an optimization problem with equality or in-equality constraints[21, 22], such as quadratic programming(QP) problem [23]. The problem of the QP-based methodslies in two aspects. First is the high computational load whenthe number of DOFs rises, and second is the occurrenceof the cases of multiple hierarchical tasks or impracticabletasks [24]. In order to solve the problem of multiple priori-tized tasks, Kanoun et al. [25] presented a prioritized task-regulation framework, which covered both linear equalitiesand inequalities. For real-time implementation, Escande etal. [26] proposed a generic solution to solve multiple prior-itized problems of both equality and inequality constraints,which was ten times faster than the iterative-projection hier-archical solvers when only equalities considered. Neverthe-less, when hard joint constraints of the manipulator are takeninto account, the QP-based approach cannot take the advan-tage of formulating all the inequalities in a unified frame-work [27]; thus, the computation complexity of these algo-rithms will be very high.

In this paper, a novel method to enhance the kinematicaccuracy of redundant WMMs by adaptive motion planningwith null-space implementation is proposed. As stated be-fore, the kinematic accuracy of the mobile base is inferiorto that of the manipulator. Therefore, the redundancy of theWMMcan be employed to, first, assign all of the desiredmo-tion to the manipulator to execute. Next, when the manip-ulator reaches its limit (being joints’ range, velocity, and/oracceleration limit) and the desired motion is not feasible forit anymore, the adaptive motion planning approach will beexecuted in the null space of the system. Consequently, someparts of the desired motion will be transferred to the mobilebase to make the desired trajectory feasible for the WMM.

The proposed method builds upon the work by Flacco etal. [27] for redundant manipulators and extends it to redun-

dantWMMs. The “saturation in the null-space” (SNS) algo-rithm proposed by Flacco et al. [27] handles the joint boundsof a redundant manipulator by successively discarding thejoints that would exceed their motion bounds when usingthe minimum norm solution. The SNS method is excellentin addressing the redundant system’s limitations due to itsadequate and accurate distribution of end-effector’s Carte-sian motion to joint motion. However, this method has neverbeen employed to enhance the kinematic accuracy ofWMMs.With this in mind, we present an adaptive motion planning(AMP)method to enhance the kinematic accuracy of aWMMusing its null space. This method passes the desired motionas much as possible to the manipulator via the null space ofthe WMM until the motion is not feasible for the manipula-tor. Then, the motion will be decomposed to a motion forthe mobile base and a feasible motion for the manipulator.Furthermore, suppose after resolving all of the joint limits,the WMM has some redundancy left. In that case, a tertiaryobjective will be pursued in the null space of the secondaryobjective for the robotic system to avoid singularities. It isworth mentioning that the proposed method is implementedat the joint acceleration level to avoid velocity discontinuitywhen the mobile base is enabled/disabled.

In the proposed method, the singularity of the manipu-lator will first be examined. If the manipulator is close toa singular configuration, the mobile base will be activatedat once. Thus, only when the manipulator is away from thesingularity, will the motion planning approach be executed.Meanwhile, the tertiary objective will be performed to keepthe manipulator from singularity without intervening withthe primary and secondary tasks.

The remainder of this paper is organized as follows. Thekinematic model and motion planning of the WMM is pro-vided in Section 2. In Section 3, the proposed adaptive mo-tion planning method is presented. In Section 4, experimen-tal results are reported to examine the performance of theproposed motion planning strategy. Concluding remarks ap-pear in Section 5.

2. Kinematic Modeling and Motion Planningof a Mobile ManipulatorThe kinematics of a mobile manipulator can be obtained

from the kinematic models of the two subsystems, i.e., themobile base and the manipulator. As shown in Fig. 1, Σw,Σb, Σm, and Σee are considered as the world reference frame,mobile base frame, manipulator reference frame, and end-effector frame, respectively. First, let us derive the kinematicmodel of the mobile base. Assume the contact between thewheels of the mobile base and the ground is pure rolling (i.e.,no slippage). Then, its kinematic model can be obtained as

qb = P (qb)vb, (1)

where qb ∈ ℝnb denotes the generalized coordinate vectorof the mobile base expressed in Σw, vb ∈ ℝb denotes thevelocity vector of the wheels, P (qb) ∈ ℝnb×b denotes theconstraint matrix of the base (holonomic or nonholonomic),

Hongjun Xing et al.: Preprint submitted to Elsevier Page 2 of 13

Page 3: Enhancing Kinematic Accuracy of Redundant Wheeled Mobile ...

Enhancing Kinematic Accuracy of Redundant Wheeled Mobile Manipulators via Adaptive Motion Planning

Σw

Σee

Σb

Σm

q1

q2

q3

q4

q5

q6

q7

xyz

Figure 1: Omnidirectional wheeled mobile manipulator.

and nb and b denote the dimensions of the generalized co-ordinate vector and the wheel velocity vector, respectively.P (qb) transfers the wheel velocities to the generalized basevelocities. Also, it is worth mentioning that (1) is a gen-eralized model, which is applicable to both holonomic andnonholonomic mobile bases.

Next, assume that the pose of the end-effector in Σw isdefined as x ∈ ℝr, r is its dimension. The WMM’s general-ized coordinate vector denotes as q = [qTb , q

Tm]T ∈ ℝn, where

qm ∈ ℝm is the generalized manipulator coordinate, m is itsdimension (number of joints), and the subscript n = nb +m.It is worth mentioning that the generalized manipulator ve-locity is defined as the velocity of the manipulator joints.Now, the WMM’s forward kinematics at the velocity levelcan be calculated as [28]

x = J (q)q = [Jb(q) Jm(q)][

qbqm

]

= [Jb(q)P (qb) Jm(q)][

vbqm

]

= Jv(q)[

vbqm

]

,(2)

where Jb ∈ ℝr×nb is the Jacobian of the mobile base, Jm ∈ℝr×m is the Jacobian of the manipulator, J (q) ∈ ℝr×n isthe Jacobian of the generalized WMM (i.e., no constraintsof the mobile base are considered), and Jv(q) ∈ ℝr×(b+m)

is the Jacobian of the WMM. There are two Jacobians for aWMM, because the generalized coordinate of a mobile baseis not its wheel velocity. It is worth noting that when themobile base is subjected to nonholonomic constraints, onlyJv(q) can be employed. For a holonomic mobile base, bothJ (q) and Jv(q) can be utilized because they are equal to oneanother [29, 30].

The WMM is usually a kinematically redundant system(i.e., r < n). Thus, for a given task x, all solutions q can beexpressed as [31]1

q = J †x + (I − J †J )qN , (3)1For brevity, the dependence of the Jacobian matrices upon the joint

variables is omitted in the notation.

where J † = JT(JJT)−1 is the pseudoinverse of J , I is ann×n identity matrix, I−J †J is the null space of J , and qN ∈ℝn is the null-space velocity for sub-tasks. The derivative of(2) with respect to time derives

x = J q + J q. (4)

Then, the WMM’s kinematic model considering the null-space planning at the acceleration level can be expressed as

q = J †(x − J q) + (I − J †J )qN . (5)

3. Adaptive Motion Planning MethodTheAMPmethod is proposed to improve aWMM’s kine-

matic accuracy. With thismethod, themanipulator will com-pletely undertake the task, and only when the range or ac-celeration requirements of the task exceed the limits of themanipulator, will the mobile base be involved.

3.1. Joint Acceleration Limits DefinitionThe motion of the WMM is planned at the acceleration

level; therefore, the limits on joint acceleration need to belocally calculated. Taking into account the joint position,velocity and acceleration bounds of the WMM, its accelera-tion limits on q at time t = tℎ can be expressed as [32]

Qmin(tℎ) ⩽ q(tℎ) ⩽ Qmax(tℎ), (6)

with the acceleration limits for each joint defined as

Qmin,i =

max{2(Qmin,i − qℎ,i − qℎ,iT )

T 2,

Vmin,i − qℎ,iT

,Amin,i

}

,if qℎ,i > Qlow,i

Amax,i, else(7)

Qmax,i =

max{2(Qmax,i − qℎ,i − qℎ,iT )

T 2,

Vmax,i − qℎ,iT

,Amax,i

}

,if qℎ,i < Qup,i

Amin,i, else(8)

where Vmax/Vmin and Amax/Amin are the maximum and min-imum hard joint bounds of the velocity and acceleration, re-spectively. i = 1,… , n denotes the ith element of the corre-sponding vector, the sampling time is denoted as T , and qℎ,idenotes the current WMM joint position at time tℎ of the ithjoint. Qlow,i and Qup,i are defined as

Qlow,i = Qmin,i −|

|

qℎ,i|| qℎ,i2Amax,i

,

Hongjun Xing et al.: Preprint submitted to Elsevier Page 3 of 13

Page 4: Enhancing Kinematic Accuracy of Redundant Wheeled Mobile ...

Enhancing Kinematic Accuracy of Redundant Wheeled Mobile Manipulators via Adaptive Motion Planning

-2.5 -1.25 0 1.25 2.5-4

-2

0

2

4

Position (rad)

Acc

ele

rati

on

(ra

d/s

2)

Upper limit (half max. vel.)Lower limit (half max. vel.)Upper limit (full max. vel.)Lower limit (full max. vel.)

(a) Acceleration limit

-2

-1

0

1

2

-2.5 -1.25 0 1.25 2.5Position (rad)

Vel

ocit

y (

rad/s

)

Velocity (+Vmax/2)Velocity (-Vmax/2)Velocity (+Vmax)Velocity (-Vmax)

(b) Velocity profile

Figure 2: Joint acceleration limit and its corresponding ve-locity. Qmax = 2.5 rad, Qmin = −2.5 rad, Vmax = 1.75 rad/s,Vmin = −1.75 rad/s, Amax = 3 rad/s2, and Amin = −3 rad/s2.

Qup,i = Qmax,i +|

|

qℎ,i|| qℎ,i2Amin,i

.

Fig. 2 presents a sample of joint acceleration limits andtheir corresponding joint velocities with given joint physicallimits. In this example, the joint velocities are set as Vmax∕2and Vmax. As shown in Fig. 2, with the increase of thevelocity, the acceleration change happens farther from thejoint position bound. The joint needs more displacementsto cease its motion at the physical limit due to the limitedjoint acceleration. Fig. 2b shows the corresponding velocityprofile calculated according to the acceleration limit. Withdifferent velocities, the proposed acceleration limit calcula-tion method can always make the joint velocity decrease tozero when the joint is close to the position bound. It shouldbe noted that Fig. 2a shows the acceleration bounds of thejoint, not its current acceleration.

3.2. Adaptive Motion Planning FrameworkIt is desirable to distribute the motion requirement of the

end-effector as much as possible to the manipulator to havehigh motion accuracy. The AMP method makes use of thekinematic redundancy of the WMM to break down the de-sired motion between the mobile base and the manipulator.This method will distribute some of the motion to the mobilebase only when the manipulator cannot handle the task by it-self, i.e., one or more joints of the manipulator are at theirlimits or the manipulator is near a singular configuration.

In our previous work in [19], a weighting matrix wasused to distribute the desired end-effector trajectory, whichdid not make the best use of the manipulator redundancy.Instead, in this paper, we propose the AMP method to fullyutilize the manipulator’s redundancy until it cannot executethe task. In the AMP method, first, a diagonal selection ma-trix needs to be defined to specify the active joints. isdefined as an n × n diagonal selection matrix whose diag-onal elements specify whether the joints are active or not,i.e., if the i element on the diagonal is one, the ith jointof the WMM is active. Then, by combining the selectionmatrix and (5), in the AMP method, the joint accelerationcommand is designed as

qamp = (J)†(�x − J q) + [I − (J)†J ]qN , (9)

where � is a scaling factor to downscale the Cartesian taskx when it is not feasible for the WMM. It is noteworthy thatqN in (9) represents the null-space acceleration vector of thejoints. If the ith joint is not saturated, qN,i = 0; else, qN,iis defined as the corresponding joint acceleration limit ex-pressed in (6)-(8). More details are provided below.

Initially, the selectionmatrix is set to be =[

0nb×nb , 00, Im×m

]

,

i.e., the mobile base is deactivated and nomotion will be dis-tributed to the base (the null-space acceleration qN vector isset to be zero). Next, the joint acceleration command is cal-culated using (9). Here, if the ith joint of the manipulator isover-driven (i.e., qamp,i > Qmax,i or qamp,i < Qmin,i), the cor-responding element on the diagonal is chosen to be zero todisable the joint, and the ith element of the null-space accel-eration qN is set equal to Qmax,i or Qmin,i. With this choiceof qN and , the acceleration of the ith joint will be adjustedback to its saturation level and the associated accelerationshortage will be assigned to the other joints of the manipu-lator. However, this may over-drive the other joints of themanipulator. Therefore, this method needs to be repeated it-eratively until there is no over-driven joint left; otherwise,the Cartesian space acceleration x is found to be infeasiblefor the WMM with the disabled mobile base.

The feasibility of the desired Cartesian acceleration canbe inspected by checking the rank of J . If the rank of thismatrix is smaller than the dimension of the Cartesian spacer, the Cartesian space acceleration x is not feasible for themanipulator. Thus, the mobile base needs to be activated bychanging the corresponding elements of the selection matrixfrom zeros to ones. After activation of the mobile base, thejoints’ accelerations need to be adjusted again. If the desiredCartesian space acceleration is still infeasible for the WMMwith the active mobile base, it has to be modified to becomerealizable for the WMM. In this case, we introduce a scalingfactor 0 ⩽ � ⩽ 1 to make the desired Cartesian accelerationx realizable. � is equal to one unless x is not feasible for theWMM.

In experiments, we notice that using the above approach,the AMP method sometimes moves the manipulator to theedge of its workspace and then activates the mobile base.This causes workspace-boundary singularities as the manip-ulator is fully stretched out. Therefore, we add singularityavoidance to the proposed approach, which is performed intwo stages. First, during each loop, the manipulator singu-larity is examined. If the current segment of the desiredtrajectory makes the manipulator approach its singularity,the mobile base is then activated. Second, a tertiary objec-tive is utilized in the null-space planner that moves away themanipulator from singularity when it is possible. Here, wedesign the cost function inspired by the concept of veloc-ity manipulability ellipsoid, which is an effective measureto evaluate the distance of a robotic system from its singu-larity [12]. For a manipulator, the ellipsoid is defined asw(qm) =

det (JmJTm). Instead of employing w(qm), weselect the cost function asH(qm) = w2(qm) = det (JmJTm) to

Hongjun Xing et al.: Preprint submitted to Elsevier Page 4 of 13

Page 5: Enhancing Kinematic Accuracy of Redundant Wheeled Mobile ...

Enhancing Kinematic Accuracy of Redundant Wheeled Mobile Manipulators via Adaptive Motion Planning

make the optimization more computationally efficient. Thecomputation of the partial derivative of H over qm avoidsthe square root of det (JmJTm).

Prioritized task motion planning is an effective methodthat ensures the primary task gets completed. Then, if thereis still redundancy remained, the sub-task (secondary task)will be executed [32]. Let us define the auxiliary null-spaceprojection matrix in the joint space as

PA =[

I −(

(I − )PN)†]

PN , (10)

with PN = I − J †J being the orthogonal projector in theJacobian null space. Now, the joints acceleration commandcorresponding to the tertiary objective can be designed as

qt = �PAqA, (11)

where 0 ⩽ � ⩽ 1 is the scaling factor to preserve the jointbounds when the remained redundancy is not enough to han-dle it and qA is the joint acceleration vector associated withthe null-space projection matrix PA. The joint velocity forthe tertiary objective (singularity avoidance) is defined as

qSA = 1

[

0nb×1(▿qmH)

T

]

, (12)

and then, the joint acceleration for this objective is designedas

qA =[ 0nb×1 1(▿2qmH)qm + 2[ 1(▿qmH)

T − qm]

]

, (13)

in which 1 and 2 are two positive constants. The deriva-tions of ▿qmH and ▿2qmH are shown in Appendices A andB, respectively.

The joint acceleration command that realizes the above-mentioned desiredCartesian space acceleration, AMPmethod,and tertiary objective is

q = qamp + qt. (14)

The flowchart of themotion planning system is shown in Fig.3 and the method to determine the scaling factors � and � isillustrated in Fig. 4.

Fig. 3 presents the flowchart of the proposed motionplanningmethod for aWMMwith consideration of singular-ity avoidance. The primary task is to enhance the kinematicaccuracy of the WMM via AMP (secondary task). There-fore, the mobile base is kept disabled until the manipulatorjoint is saturated or the manipulator is close to a singular-ity. A measure to detect the singular configuration is de-fined based on the minimum singular value of the manipula-tor Jacobian matrix Jm [33]. The minimum singular value isdenoted as �m and the singularity measure is designated as�m,min. If �m < �m,min, which means that the singularity ofthe manipulator occurs, then, the mobile base will be acti-vated to move the manipulator away from singularity. Also,when the system has remaining redundancy after the primaryand secondary tasks are completed, the manipulator’s ability

Calculate minimum

singular value σm

σm < σm,min ?

Calculate joint acceleration

command with (9)

Y

N

Any overdriven

manipulator joint ? N

Y

Adjust and

N

Y

The base

enabled ?

N

Calculate scaling factor α

Y

Calculate joint acceleration

command with (14)Calculate scaling factor β and

Recalculate joint acceleration

command with (9)

Manipulability enhancement

with (12)-(13)

PRIMARY TASK

SECONDARY TASK

TERTIARY TASK

0 0=

0

b bn n

m mI

=

(Enable the base)b b b bn n n nI =0

(Disable the base via (15))b b b bn n n n

Nq

Rank(J )

(The primary

task feasible )

r ?

=

(Enable the base)b b b bn n n nI

tq

Figure 3: Flowchart of the motion planning for a WMM sys-tem.

For α For β

Calculate:

Scaling factor (α or β)

=min{Φ, 1}

Y

NΦ=min{ρmax,i}

=( )

[ ( ) ] N

J x

I J J q

= A A

amd

P q

q

min min

max max

( ) /

( ) /

Q

Q

min, max, ?i i min,

max,

Switch

and

i

i

Figure 4: Flowchart of the scaling factor determination.

to stay away from singularity will be enhanced via the exe-cution of the tertiary objective provided by (11). When theprimary task or the tertiary task cannot be fully executed, ascaling factor � or � is added to downscale the task to makeit partially completed.

With the motion planning approach executed at the ac-celeration level, once themobile base is deactivated andwith-out distributed acceleration, it will still move with a con-

Hongjun Xing et al.: Preprint submitted to Elsevier Page 5 of 13

Page 6: Enhancing Kinematic Accuracy of Redundant Wheeled Mobile ...

Enhancing Kinematic Accuracy of Redundant Wheeled Mobile Manipulators via Adaptive Motion Planning

stant velocity. However, our goal is to stop the mobile basesmoothly to obtain a betterWMM’s kinematic accuracywhenno acceleration is distributed to it. Here, a transition func-tion is utilized to steadily cease the movement of the mobilebase

qb,trans =

qb, if t ⩽ t0Amin,b, if sign(Vb) > 0 & t0 < t < t+fAmax,b, if sign(Vb) < 0 & t0 < t < t−f0, if sign(Vb) > 0 & t ⩾ t+f0, if sign(Vb) < 0 & t ⩾ t−f

(15)

where qb,trans is the base acceleration during the transitionprocess, t0 and t+f (t

−f ) represent the start and end time of

the transition, respectively. Also, t+f = |

VbAmin,b

| + t0 and

t−f = |

VbAmax,b

| + t0. For the transition process, the mobilebase will be deactivated with the maximum acceleration tokeep high kinematic accuracy. Vb is the base velocity whenit is deactivated and �m ⩾ �m,min is achieved, andAmax,b andAmin,b are the maximum and minimum accelerations of thebase, respectively.

Fig. 4 shows the process of determining the scaling fac-tors according to the joint bounds (6)-(8). As shown in Fig.4, � denotes the required joint acceleration for the previoustask, and � represents the consuming joint motion capabil-ity of the manipulator for the corresponding task. Then, wewill calculate the ratio of the residual joint acceleration tothe required joint acceleration (denoting as �min and �max),and get the minimum ratio of all the joints, expressed as �.The parameter � is a criterion indicating the residual capa-bility of the manipulator to complete the task. If � ⩾ 1, themanipulator has enough capability to accomplish the task; if� < 1, the manipulator cannot fulfill the mission. Since weshould not upscale the given task, the scaling factor (� or �)is chosen as the smaller one between � and 1.

4. Experimental ResultsIn order to verify the effectiveness and advantages of the

proposed AMP method, it was applied to a WMM and com-pared with a traditional motion planning approach that usedthe pseudoinverse of the Jacobian (we even extended the tra-ditional approach to do manipulability enhancement). Theexperiments consist of three parts: (A) the verification of theimportance of singularity avoidance, (B) and (C) the eval-uation of the proposed motion planning method with end-effector’s position and full pose considered, respectively.

4.1. Experimental SetupThe experiments were performed using an omnidirec-

tional WMM. The WMM is the sum of a four-wheel mo-bile base and a 7-DOF ultra-lightweight robotic Gen3 arm(Kinova Robotics, Canada) as shown in Fig. 1. KinovaGen3 is a robotic arm for compliant industrial applicationand safe human-robot collaboration. The maximum reach-

Motion Capture

System

Tracking Marker

Mobile Manipulator

System

Figure 5: Experimental setup.

able distance of the manipulator is 902 mm with the maxi-mum Cartesian translation speed being 40 cm/s. The mobilebase is equipped with two pairs of Mecanum wheels, so itcan undertake omnidirectional motion. It is noteworthy thatthe WMM system is controlled at the velocity level. Thusin this paper, the integral of the calculated joint accelerationwas commanded to the robotic system. The control codewas developed in C++, using the Eigen library [34] for al-gebraic computations. The experiments were performed uti-lizing the ROS environment [35] on a Intel(R) Xeon(R) CPUX5550 @ 2.67 GHz, with 16 GB of RAM.

Fig. 5 presents the experimental setup, which consistsof a WMM system (self-assembled) and a motion capturesystem (Claron Technology Inc., Canada) . The RMS valueof the calibration accuracy of the motion capture system is0.35 mm. It should be noted that the motion capture systemis only used for obtaining the actual pose of the end-effectoras ground truth to evaluate the kinematic accuracy of theproposed method and not employed in the motion planningsystem.

We select J as the WMM’s Jacobian, as defined in (2).The generalized coordinate vector of the base (shown in Fig.6) is defined as qb = [xb, yb, �b]T ∈ ℝ3 and the velocity com-mand vector of the wheels as vb = [!fl, !fr, !bl, !br]T ∈ℝ4. The velocity transformationmatrixP (qb) ∈ ℝ3×4, whichtransfers the wheel velocity to the generalized base velocity,can be expressed as

P (qb) = JIJV (16)

with

JI =⎡

cos �b − sin �b 0sin �b cos �b 00 0 1

,

and

JV =R4

1 1 1 1−1 1 1 −1−1

d1+d21

d1+d2−1

d1+d21

d1+d2

.

The variables �b, R, d1, and d2 are illustrated in Fig. 6.The joint constraints of the WMM are listed in Table 1,

where the units of angle, velocity, and acceleration for pris-matic joints (the first and second joints) arem, m/s, andm/s2;

Hongjun Xing et al.: Preprint submitted to Elsevier Page 6 of 13

Page 7: Enhancing Kinematic Accuracy of Redundant Wheeled Mobile ...

Enhancing Kinematic Accuracy of Redundant Wheeled Mobile Manipulators via Adaptive Motion Planning

ωfl

ωfr

ωbl

ωbr

xb

yb θb

d1 vy vx

Σw

Σb

R d2

Figure 6: Description of the omnidirectional mobile base.

Table 1Joint limits of WMM. The first three joints correspond to themobile base and the rest seven joints to the manipulator.

Joint No. Joint type Angle Velocity Acceleration

1 Prismatic ±∞ ±0.25 ±0.0252 Prismatic ±∞ ±0.25 ±0.0253 Revolute ±∞ ±1.0 ±1.54 Revolute ±∞ ±1.75 ±3.05 Revolute ±2.2 ±1.75 ±3.06 Revolute ±∞ ±1.75 ±3.07 Revolute ±2.5 ±1.75 ±3.08 Revolute ±∞ ±3.14 ±5.09 Revolute ±2 ±3.14 ±5.010 Revolute ±∞ ±3.14 ±5.0

and for revolute joints (the remaining eight joints) are rad,rad/s, and rad/s2, respectively. The mobile base frame Σb isassumed to be the same as the world frame Σw at the startof the experiment. The initial joint position of the WMM isq0 = [0, 0, 0, 0, �∕6, 0, �∕2, 0,−�∕6, 0]T. Also, the start po-sition of the end-effector in Σw is [0.65,−0.0246, 0.4921]T.In the following text, the initial state of the end-effector isdenoted as x0.

A video is attached with the manuscript to present theexperiments in this section.

4.2. Experiments with and without SingularityAvoidance

The AMP method without singularity avoidance will of-ten put themanipulator at a singular configuration. Althoughthe employment of singularity avoidance will somewhat de-crease the WMM’s kinematic accuracy as it enables the mo-bile base, it is unavoidable. The AMP method and the mod-ified AMP method (i.e., the AMP method with singularityavoidance) have been experimentally compared to verify theeffectiveness of the latter. The end-effector acceleration x in(5) is changed to xd + Kd(xd − x) + Kp(xd − x) to ensurethat the trajectory tracking error converges to zero, wherexd is the desired end-effector trajectory, and Kd and Kp are

8.35s

0 10 20 30 400

0.1

0.2

0.3

0.4

t (s)

Min

imum

sin

gula

r valu

e σ

m

WithoutWith_tertiaryWith_no_tertiary

(a) Minimum singular value

0 3 6 9 12 15-0.4

0

0.4

0.8

1.2

t (s)

Po

siti

on (

m)

8.35s 12.6s

Des. xDes. yDes. z

Act. xAct. yAct. z

(b) Position of the end-effector

Figure 7: Results of the singularity avoidance experiment. Theleft plot presents the minimum singular value of the manip-ulator’s Jacobian, and the right plot shows the end-effectorposition of the WMM using AMP method without singularityavoidance.

two diagonal positive-definite matrices. The proof of thisconclusion can be found in Appendix C. During the experi-ments in this section, only the end-effector’s position is con-sidered with r = 3. We define the desired end-effector tra-jectory as a circle with a radius of R, with the definition be-ing xd(t) = x0 +

[

−R(cos(�∕20t) − 1),−R sin(�∕20t), 0]T.

Here, we select the radius of the circle as R = 0.25m. Itshould be noted that this radius is beyond the manipulatorworkspace (0.2 m) at its initial configuration. The closed-loop system parameters for the desired trajectoryKd andKpare the same during the two experiments to indicate the fair-ness of the comparison, withKd = 10I3×3 andKp = 20I3×3.These two values are obtained by trial and error in this re-search; furthermore, an approach to optimize their valuescan be found in [36]. The other parameters are set as 1 = 5, 2 = 0.5, �m,min = 0.15. Line search techniques [37] area preferable choice to determine the values of 1 and 2.The threshold value for singularity avoidance �m,min is de-termined by trial and error to make the system put off theactivation time of the mobile base as much as possible. It isnoteworthy that these parameters are essential to completethe motion planner design to make the best use of the ma-nipulator, but they do not play the major role in the proposedmethod. Fig. 7 presents the results during the experiment.

Fig. 7a shows the experimental results with singularityavoidance and without it. With the AMP method, the ma-nipulator tried to complete the task alone and ultimately putitself at a singular configuration at about 8.35 s. This causedthe system to be uncontrollable and made the task incom-plete. However, with singularity avoidance, when the ma-nipulator was near a singularity, the mobile base was acti-vated and the manipulator could adjust its configuration tomove away from it. Thus, the task could still be executed.The performance of the tertiary objective can be found bycomparing the values of �m using tertiary objective and notusing it. With the tertiary objective, the manipulator canhave a better configuration to stay away from a singularity.Fig. 7b shows the end-effector’s position when no singular-ity avoidance was adopted, the desired trajectory could notbe tracked at about 8.35 s and significant kinematic errorsstarted to emerge in all Cartesian directions.

Hongjun Xing et al.: Preprint submitted to Elsevier Page 7 of 13

Page 8: Enhancing Kinematic Accuracy of Redundant Wheeled Mobile ...

Enhancing Kinematic Accuracy of Redundant Wheeled Mobile Manipulators via Adaptive Motion Planning

The activation of the mobile base for singularity avoid-ance is a trade-off between the WMM’s kinematic accuracyand the manipulator’s singularity. The earlier the mobilebase is employed, the farther the manipulator will be fromthe singularity, and the lower the WMM’s kinematic accu-racy will be. In this paper, the mobile base is enabled aslate as possible to derive better kinematic accuracy, whilethe manipulator’s singularity can still be avoided.

4.3. Experiments for Kinematic AccuracyEnhancement with Position Considered

The proposed motion planning approach can make thebest use of the manipulator to execute tasks while keeping itfrom a singularity, and the mobile base is enabled only whenthe task cannot be executed by the manipulator alone or themanipulator is close to a singular configuration. With thismethod, the contribution of the base to the overall WMMmotion is minimized, thus improving the kinematic preci-sion of the WMM. The dimension of the Cartesian space ofthe WMM’s end-effector is defined to be r = 3 as only itsposition is considered in this section.

The proposed AMP method is implemented to verify itsefficiency compared with the traditional kinematic motionplanning approach by following a predefined end-effectortrajectory. The traditional motion planner in the experimentmeans using the pseudoinverse of the Jacobian J † = JT(JJT)−1with consideringmanipulability enhancement for themanip-ulator in the null space [38]. At the acceleration level, thismotion planner can be expressed as q = J †(x − J q) + (I −J †J )qA, where qA is defined in (13). Two desired trajecto-ries with the same definition as in Section 4.2 are provided,the first one is within themanipulator workspace and the sec-ond one is beyond it. The trajectory within the manipulatorworkspace is a circle with a radius of R = 0.1m and theother one is a circle with a radius of R = 0.25m. The mo-tion planning parameters for the experiments in this sectionare the same as those in section 4.2. Figs. 8 and 9 showthe experimental results within the manipulator workspace,and Figs. 10 and 11 present the results beyond the manip-ulator workspace. The average execution time for the pro-posed method and the traditional method were 14.8 ms and12.4 ms in one loop, which demonstrated the desirable on-line performance of the proposed approach. It is worth men-tioning that with the traditional method, the mobile base wasalways involved in the experiment and no joint saturation ofthe manipulator occurred. The actual position of the end-effector was obtained via the motion capture system to haveground-truth information. Table 2 contains the RMS valueand duration time of the commanded base velocity in thesetwo scenarios.

Fig. 8a shows that when the end-effector trajectory waswithin the manipulator workspace, with the proposed AMPmethod, there was only a small kinematic error. This is dueto the fact that no motion was assigned to the base, as shownin the first column of Table 2. With no adaptive motion plan-ning, some motions were imposed to the base, as shown inthe second column of Table 2. Thus, the kinematic error was

DesiredProposedTraditional

-0.2

-0.1

0

0.1

x (m)0.6 0.7 0.8 0.9

y (m

)

(a) End-effector trajectories

-2.5

-1.25

0

1.25

2.5

0 20 40 60 80t (s)

Kin

emat

ic e

rror

(cm

)

x (pro.)y (pro.)

x (tra.)y (tra.)

Dist. (pro.) Dist. (tra.)

(b) Kinematic errors

Figure 8: End-effector’s kinematic accuracy with traditionaland proposed methods (within manipulator workspace).

-2

-1

0

1

2

-1

-0.5

0

0.5

1

0 20 40 60 80t (s)

v xb,v

yb (

cm

/s)

ωθb (

10

-2ra

d/s

)

vxb vyb ωθb

(a) Commanded velocities

-6 0 6 12 18 24-12

-6

0

6

xb (cm)

y b (

cm

)

DesiredActual

(b) Trajectories in x − y plane

Figure 9: Motion of the mobile base with traditional method(within manipulator workspace).

0.5 0.7 0.9 1.1 1.3x (m)

-0.4

-0.2

0

0.2

0.4

y (m

)

DesiredProposedTraditional

(a) End-effector trajectories

0 20 40 60 80t (s)

-4

0

4

8

Kin

emat

ic e

rror

(cm

)x (pro.)y (pro.)

x (tra.)y (tra.)

Dist. (pro.) Dist. (tra.)

(b) Kinematic errors

Figure 10: End-effector’s kinematic accuracy with traditionaland proposed methods (beyond manipulator workspace).

Table 2RMS value and commanded duration of base velocity.

Within BeyondPro. Tra. Pro. Tra.

xbRMS (cm/s) 0 1.10 1.58 2.77Duration (s) 0 80 12.08 80

ybRMS (cm/s) 0 0.75 0.24 1.86Duration (s) 0 80 12.08 80

�bRMS (◦/s) 0 0.287 0.241 0.739Duration (s) 0 80 12.08 80

much larger compared with the AMP scenario (as shown inFig. 8b), with the maximum errors in x and y being 0.91cm and 1.89 cm, respectively. Besides, the maximum dis-tance between the desired and actual trajectories was im-proved from 1.91 cm to 0.45 cmwith the proposed approach.Fig. 9 shows the motion of the mobile base with the tradi-

Hongjun Xing et al.: Preprint submitted to Elsevier Page 8 of 13

Page 9: Enhancing Kinematic Accuracy of Redundant Wheeled Mobile ...

Enhancing Kinematic Accuracy of Redundant Wheeled Mobile Manipulators via Adaptive Motion Planning

-6

-3

0

3

6

-3

-1.5

0

1.5

3

0 20 40 60 80t (s)

v xb,v

yb (

cm

/s)

ωθb (

10

-2ra

d/s

)

vxb vyb ωθb

(a) Commanded velocities

-10 10 30 50 70-30

-15

0

15

xb (cm)

y b (

cm

)

DesiredActual

(b) Trajectories in x − y plane

-2

0

2

4

6

-1

0

1

2

3

0 20 40 60 80t (s)

ωθb (

10

-2ra

d/s

)vxbvybωθb

v xb,v

yb (

cm

/s)

(c) Commanded velocities

-30

-15

0

15

-10 10 30 50xb (cm)

70

y b (

cm

)

DesiredActual

(d) Trajectories in x − y plane

Figure 11: Motion of the mobile base with traditional andproposed methods (beyond manipulator workspace).

tional method, where vxb, vyb,!�b represent the commandedbase velocities in xb, yb, and �b, respectively. The motion ofthe mobile base with the proposed method is not presentedsince no motion is distributed to it.

The last two columns of Table 2 show that when thedesired end-effector trajectory was beyond the manipulatorworkspace, themobile basewas always forced tomove. How-ever, the base movement was much smaller if one adoptedthe proposed AMP method. The commanded duration timeand RMS values of the base velocity in xb, yb, and �b rep-resented 15.10%, 57.04%, 12.90%, and 32.61% of the com-mands without motion planning, respectively. Fig. 10 con-tains the end-effector’s kinematic accuracy results. Fig. 10bshows that the maximum kinematic error in x was reducedfrom 6.65 cm to 2.44 cm, in y was reduced from 2.72 cmto 1.82 cm, and in distance of x − y plane was decreasedfrom 6.97 cm to 2.78 cm compared with no motion planningscenario.

Fig. 11 presents the motion of the mobile base whenthe desired end-effector trajectory was beyond the manipu-lator workspace with two different methods. Figs. 11a and11b show that with the traditional method, the mobile basewas consistently distributed with some motions. Thus, theend-effector’s kinematic accuracy was low. The mobile basemotion with the proposed method is shown in Figs. 11c and11d. As shown in Fig. 11c, the base was activated at time6.40 s. The manipulator regained enough manipulability atabout 16.48 s. However, the base was not deactivated sud-denly due to the implementation of the transition function(15); instead, it gradually stopped. Fig. 11d shows the de-sired and actual trajectories of the mobile base in the x − yplane with the proposed method. We define the integral of

the mobile base’s kinematic error as∫TfTs

|

|

|

eib|

|

|

dt

Tf−Ts, where Ts and

Tf represent the start time and final time of the base motion,and eib denotes its kinematic error. With the traditional ap-

Σw

E P

(a)

Σw

(b)

Σw

(c)

Σw

(d)

Figure 12: Screenshots of the experiment with the proposedapproach. (a) shows the initial pose of the WMM, (b) showsthe moment that the mobile base started to move, (c) showsthe time that the mobile base ceased its motion, and (d) showsthe final pose of the WMM during one period.

proach, the integral of the errors in xb and yb were 2.81 cmand 1.12 cm, respectively, while these values were decreasedto 0.81 cm and 0.37 cm with the proposed approach. To sumup, the distributed motion to the mobile base was much less,and the WMM’s kinematic accuracy was improved signifi-cantly with the proposed method.

4.4. Experiments for Kinematic AccuracyEnhancement with Pose Considered

The proposed AMP approach in enhancing the WMM’skinematic accuracy with the end-effector’s pose consideredis verified here. Thus the end-effector’s Cartesian space di-mension is selected as r = 6. The traditional motion plannerutilized in this section is similar to the one in Section 4.3.In the experiments, the end-effector was planned to move inthe x axis and rotate along the y axis of the world frame.

The desired pose of the end-effector is defined as xd(t) =x0+

[

0.15 sin(�∕20t), 0, 0, 0, �∕4 sin(�∕20t), 0]T. With this

setting of the end-effector’s pose, the mobile base was forcedto move even using the proposed method. The closed-loopsystem parameters are chosen asKd = diag(10, 10, 10, 3, 3, 3)and Kp = diag(20, 20, 20, 5, 5, 5). The remainder motionplanning parameters are selected as 1 = 5, 2 = 0.5, �m,min =0.19. Fig. 12 presents some screenshots of the experimentswith the proposed method. The actual end-effector’s posi-tion was obtained using the marker attached at point E viathe motion capture system. Meanwhile, its orientation wasacquired by calculating the angle between the marker pastedat point P and the desired position of point E.

Fig. 13 shows the end-effector’s kinematic accuracy dur-ing the experiments. Fig. 14 presents the mobile base’s

Hongjun Xing et al.: Preprint submitted to Elsevier Page 9 of 13

Page 10: Enhancing Kinematic Accuracy of Redundant Wheeled Mobile ...

Enhancing Kinematic Accuracy of Redundant Wheeled Mobile Manipulators via Adaptive Motion Planning

0 10 20 30 400.45

0.55

0.65

0.75

0.85

t (s)

x (m

)

DesiredProposedTraditional

(a) End-effector positions

-3

-2

-1

0

1

2

0 10 20 30 40t (s)

Kin

emat

ic e

rror

(cm

)

ProposedTraditional

(b) Position errors

-50

-25

0

25

50

0 10 20 30 40t (s)

y (°

)

DesiredProposedTraditional

(c) End-effector orientations

-5

-2.5

0

2.5

5

0 10 20 30 40t (s)

Kin

emat

ic e

rror

(°)

ProposedTraditional

(d) Orientation errors

Figure 13: End-effector’s kinematic accuracy with its full poseconsidered.

-2

-1

0

1

2

v xb,v

yb (

cm

/s)

-4

-2

0

2

4

ωθb (

10

-3ra

d/s

)

0 10 20 30 40t (s)

vxbvybωθb

(a) Commanded velocities

-20 -10 0 10 20-0.4

0

0.4

0.8

1.2

xb (cm)

y b (

cm

)

DesiredActual

(b) Trajectories in x − y plane

-2

-1

0

1

2

-4

-2

0

2

4vxbvybωθb

ωθb (

10

-3ra

d/s

)

0 10 20 30 40t (s)

v xb,v

yb (

cm

/s)

(c) Commanded velocities

-20 -10 0 10 20-0.4

0

0.4

0.8

1.2

xb (cm)

y b (

cm

)

DesiredActual

(d) Trajectories in x − y plane

Figure 14: Motion of the mobile base with end-effector’s fullpose considered.

Table 3RMS value and duration of commanded mobile base velocity.

xb yb �bRMS Dura. RMS Dura. RMS Dura.

Pro. 0.67 18.48 s 0.044 18.48 0.08 18.48Tra. 1.18 40 s 0.082 40 0.13 40

motion with the traditional and the proposed methods. TheRMS value and duration of the commanded mobile base ve-locity in these two scenarios are displayed in Table 3. Here,the units of these variables are the same as the ones in Table2.

As shown in Figs. 13b and 13d, the maximum kine-

matic error of the end-effector’s x-axis position and y-axisorientation was improved from 2.31 cm and 4.58◦ to 1.58cm and 2.32◦, respectively, with the AMP approach. Theprecision difference was caused by the motion of the mobilebase. When the traditional method was adopted, the mobilebase was constantly activated (as shown in Fig. 14a and thesecond row of Table 3). In contrast, the mobile base movedfor about 18.48 s of the entire 40 s with the proposed ap-proach (as shown in Fig. 14c and the first row of Table 3),where the start time and final time of the mobile base motionwere 3.1 s and 21.58 s. The RMS values of the commandedbase velocity with the AMP method in xb, yb, and �b stoodfor 56.78%, 53.66%, and 61.54% of the commands withoutmotion planning, respectively.

Figs. 14b and 14d present the mobile base’s trajectoriesin the x − y plane with the traditional method and the pro-posed approach, respectively. The motion range of the mo-bile base was much smaller with the proposed method thanthe conventional method. Furthermore, the integral of themobile base’s kinematic error was enhanced from 0.74 cmto 0.47 cm when the proposed method was adopted.

Although the kinematic accuracy of aWMM is enhancedwith the proposed AMP method, there are still some chal-lenges. For motion tracking, two things affect their accuracy(kinematic accuracy and dynamic accuracy) [39]. In this pa-per, we did not consider the dynamics of the robotic systemand the transient errors of the motion capture system. Theinvestigation of both the kinematic and dynamic accuraciesremains for future research.

5. ConclusionsA new approach to enhance the kinematic accuracy of

a wheeled mobile manipulator (WMM) was proposed con-sidering the need for singularity avoidance. To improve thekinematic accuracy of the WMM, we presented an adaptivemotion planning method to transfer more motions to the ma-nipulator due to the low kinematic precision of the mobilebase. Using the proposed motion planning method, the mo-bile base of theWMMwas immobile until all the redundancyof the manipulator for the task was employed or the manipu-lator was close to a singularity. Only when the manipulator’sremaining unsaturated joints were not enough for perform-ing the task, would the motion planner assign some of themotions to the mobile base to execute. To avoid singularity,we adopted the task priority method to define manipulabilityenhancement as a tertiary task. In summary, when the pri-mary task (kinematic accuracy enhancement) and the sec-ondary task (adaptive motion planning) were resolved, theremaining DOFs could be used to keep the system away fromthe singularity (tertiary task). The proposed approach wasdesigned at the acceleration level to avoid the discontinuityof the joint velocity due to the activation or termination ofthe mobile base.

The effectiveness of the proposed approach has been ex-perimentally verified compared with a traditional method byfollowing several predefined end-effector trajectories. Whenonly the end-effector’s position was considered, for the con-

Hongjun Xing et al.: Preprint submitted to Elsevier Page 10 of 13

Page 11: Enhancing Kinematic Accuracy of Redundant Wheeled Mobile ...

Enhancing Kinematic Accuracy of Redundant Wheeled Mobile Manipulators via Adaptive Motion Planning

dition that the desired end-effector trajectory was beyond themanipulator workspace, themaximum kinematic error of theend-effector was improved by 63.3% and 33.1% in x and y,respectively, and themotion time of themobile base declinedby 84.9%. When the end-effector’s full pose was considered,its position kinematic error in x and orientation kinematic er-ror along ywere enhanced by 32.6% and 49.3%, respectively,and the motion duration of the mobile base was reduced by53.8%.

In future works, we will establish the dynamic model ofthe WMM system and take both the motion planning andcontrol of the robotic system into consideration to furtherenhance the motion accuracy of the system.

AcknowledgementsThe authors gratefully acknowledge Teng Li for his as-

sistance in the experiments.

A. Derivation of Joint Velocity for SingularityAvoidanceDefine the partial derivative of Jm with respect to qm as

)qJ , and in the following expressions, the subscript m willbe omitted for better readability (it is worth mentioning thatq and J in the two Appendixes are only for the manipulator,not the entire WMM system). Specify Ψ = JJT, the sin-gularity avoidance velocity for the manipulator can be ex-pressed as

▿qH = ▿q det(Ψ) = det(Ψ)tr[

Ψ−1()qΨ)]

= det(Ψ)tr[

Ψ−1()qJJT + J)Tq J )]

.(17)

B. Derivation of Joint Acceleration forSingularity AvoidanceConsider two arbitrary manipulator joint angles p and q,

define the second order derivative of Jm first by p and secondby q as )pqJ . First, the second order derivative ofΨ by jointposition is derived as

)pqΨ = )pq(JJT) = )q[)p(JJT)] = )q[)pJ JT + J)Tp J ]

= )pqJJT + )pJ)Tq J + )qJ)Tp J + J)

TpqJ .

(18)

According to (17), the second order derivative ofH withrespect to joint position can be expressed as

)pqH = )pq det(Ψ) = )q(det(Ψ))tr(Ψ−1)pΨ)+

det(Ψ)tr()q(Ψ−1)pΨ)) = det(Ψ)tr(Ψ−1)qΨ)tr(Ψ−1)pΨ)+

det(Ψ)tr(

)q(Ψ−1))pΨ)

+ det(Ψ)tr(Ψ−1)pqΨ).(19)

Then, with the fact that )q(Ψ−1) = −Ψ−1()qΨ)Ψ−1, we cansimplify (19) by factoring out det(Ψ) as

)pqH = det Ψ[

tr(Ψ−1)qΨ)tr(Ψ−1)pΨ)−

tr(Ψ−1)qΨΨ−1)pΨ) + tr(Ψ−1)pqΨ)]

.(20)

For the general case when p = q represents the manipu-lator joint position vector, the singularity avoidance acceler-ation can be obtained as

▿2qH = det Ψ[(

tr(Ψ−1)qΨ))2−

tr(Ψ−1)qΨΨ−1)qΨ) + tr(Ψ−1)qqΨ)]

.(21)

C. End-Effector’s Trajectory ConvergenceProof via Acceleration CommandAt the acceleration level, the WMM’s kinematic model

is shown in (5) as

q = J †(x − J q) + (I − J †J )qN . (22)

The commanded joint acceleration is calculated as

q = J †(xd+Kd(xd−x)+Kp(xd−x)−J q)+(I−J †J )qN .(23)

Combining (22) and (23), we can derive

(xd − x) +Kd(xd − x) +Kp(xd − x) = 0. (24)

Define the task-space position tracking error as e = xd − x,we can obtain

e +Kd e +Kpe = 0. (25)

Consider the Lyapunov function candidate

V = 12eTe + 1

2eTKpe, (26)

the time derivative of V along the trajectory of the closed-loop system (25) is

V = eTe + eTKpe = −eTKd e ⩽ 0. (27)

Since V is positive definite and V is negative semi-definite,the closed-loop system (25) is stable. If V ≡ 0, then, e ≡ 0;thus, e ≡ 0. Refer to (25), we can derive e = xd − x =0. According to LaSalle’s theorem [40], (e, e) = (0, 0) isthe asymptotically stable equilibrium point of (25). Thus,limt→∞(x→ xd).

CRediT authorship contribution statementHongjun Xing: Conceptualization, Methodology, Writ-

ing - original draft, Writing - review & editing, Validation.Ali Torabi: Conceptualization, Methodology, Supervision,Writing - review & editing, Validation. Liang Ding: Re-sources, Supervision, Writing - review & editing. HaiboGao: Resources, Supervision. Weihua Li: Supervision,Validation. Mahdi Tavakoli: Resources, Supervision, Fund-ing acquisition, Project administration.

Hongjun Xing et al.: Preprint submitted to Elsevier Page 11 of 13

Page 12: Enhancing Kinematic Accuracy of Redundant Wheeled Mobile ...

Enhancing Kinematic Accuracy of Redundant Wheeled Mobile Manipulators via Adaptive Motion Planning

References[1] S. Ahmad, H. Zhang, G. Liu, Multiple working mode control

of door-opening with a mobile modular and reconfigurable robot,IEEE/ASME Transactions on Mechatronics 18 (3) (2012) 833–844.

[2] H. Xing, K. Xia, L. Ding, H. Gao, G. Liu, Z. Deng, Unknown geomet-rical constraints estimation and trajectory planning for robotic door-opening task with visual teleoperation assists, Assembly Automation39 (3) (2019) 479–488.

[3] S. R. Ahmadzadeh, P. Kormushev, R. S. Jamisola, D. G. Caldwell,Learning reactive robot behavior for autonomous valve turning, in:IEEE-RAS International Conference on Humanoid Robots, 2014, pp.366–373.

[4] Z. Li, S. S. Ge, Z. Wang, Robust adaptive control of coordinated mul-tiple mobile manipulators, Mechatronics 18 (5-6) (2008) 239–250.

[5] D. Sun, Q. Liao, A. Kiselev, T. Stoyanov, A. Loutfi, Shared mixedreality-bilateral telerobotic system, Robotics and Autonomous Sys-tems 134 (2020) 103648.

[6] X. Zhang, M. Li, J. H. Lim, Y. Weng, Y. W. D. Tay, H. Pham, Q.-C.Pham, Large-scale 3d printing by a team of mobile robots, Automa-tion in Construction 95 (2018) 98–106.

[7] Y. Jia, N. Xi, Y. Cheng, S. Liang, Coordinated motion control of anonholonomic mobile manipulator for accurate motion tracking, in:IEEE/RSJ International Conference on Intelligent Robots and Sys-tems, 2014, pp. 1635–1640.

[8] A. Torabi, K. Zareinia, G. R. Sutherland, M. Tavakoli, Dynamic re-configuration of redundant haptic interfaces for rendering soft andhard contacts, IEEE Transactions on Haptics (2020).

[9] I.-L. G. Borlaug, K. Y. Pettersen, J. T. Gravdahl, Combined kinematicand dynamic control of vehicle-manipulator systems, Mechatronics69 (2020) 102380.

[10] J. Sverdrup-Thygeson, S. Moe, K. Y. Pettersen, J. T. Gravdahl, Kine-matic singularity avoidance for robot manipulators using set-basedmanipulability tasks, in: IEEE Conference on Control Technologyand Applications, 2017, pp. 142–149.

[11] H. Zhang, Y. Jia, N. Xi, Sensor-based redundancy resolution for anonholonomic mobile manipulator, in: IEEE/RSJ International Con-ference on Intelligent Robots and Systems, 2012, pp. 5327–5332.

[12] T. Yoshikawa, Manipulability of robotic mechanisms, The Interna-tional Journal of Robotics Research 4 (2) (1985) 3–9.

[13] A. Torabi, M. Khadem, K. Zareinia, G. R. Sutherland, M. Tavakoli,Application of a redundant haptic interface in enhancing soft-tissuestiffness discrimination, IEEE Robotics and Automation Letters 4 (2)(2019) 1037–1044.

[14] W. Li, Z. Liu, H. Gao, X. Zhang, M. Tavakoli, Stable kinematic tele-operation of wheeled mobile robots with slippage using time-domainpassivity control, Mechatronics 39 (2016) 196–203.

[15] Z. Song, H. Ren, J. Zhang, S. S. Ge, Kinematic analysis and motioncontrol of wheeled mobile robots in cylindrical workspaces, IEEETransactions on Automation Science and Engineering 13 (2) (2015)1207–1214.

[16] D. H. Shin, B. S. Hamner, S. Singh, M. Hwangbo, Motion planningfor a mobile manipulator with imprecise locomotion, in: IEEE/RSJInternational Conference on Intelligent Robots and Systems, 2003,pp. 847–853.

[17] E. Papadopoulos, J. Poulakakis, Planning and model-based controlfor mobile manipulators, in: IEEE/RSJ International Conference onIntelligent Robots and Systems, 2000, pp. 1810–1815.

[18] K. Nagatani, T. Hirayama, A. Gofuku, Y. Tanaka, Motion planningfor mobile manipulator with keeping manipulability, in: IEEE/RSJInternational Conference on Intelligent Robots and Systems, 2002,pp. 1663–1668.

[19] H. Xing, A. Torabi, L. Ding, H. Gao, Z. Deng, M. Tavakoli, Enhance-ment of force exertion capability of a mobile manipulator by kine-matic reconfiguration, IEEE Robotics and Automation Letters 5 (4)(2020) 5842–5849.

[20] G. Antonelli, S. Chiaverini, Fuzzy redundancy resolution and mo-tion coordination for underwater vehicle-manipulator systems, IEEETransactions on Fuzzy Systems 11 (1) (2003) 109–120.

[21] F.-T. Cheng, T.-H. Chen, Y.-Y. Sun, Resolving manipulator redun-dancy under inequality constraints, IEEE Transactions on Roboticsand Automation 10 (1) (1994) 65–71.

[22] A. D. Prete, Joint position and velocity bounds in discrete-time ac-celeration/torque control of robot manipulators, IEEE Robotics andAutomation Letters 3 (1) (2018) 281–288.

[23] M. Giftthaler, F. Farshidian, T. Sandy, L. Stadelmann, J. Buchli,Efficient kinematic planning for mobile manipulators with non-holonomic constraints using optimal control, in: IEEE InternationalConference on Robotics and Automation, 2017, pp. 3411–3417.

[24] A. Karami, H. Sadeghian, M. Keshmiri, G. Oriolo, Hierarchical track-ing task control in redundant manipulators with compliance control inthe null-space, Mechatronics 55 (2018) 171–179.

[25] O. Kanoun, F. Lamiraux, P.-B. Wieber, Kinematic control of redun-dant manipulators: Generalizing the task-priority framework to in-equality task, IEEE Transactions on Robotics 27 (4) (2011) 785–792.

[26] A. Escande, N. Mansard, P.-B. Wieber, Hierarchical quadratic pro-gramming: Fast online humanoid-robot motion generation, The In-ternational Journal of Robotics Research 33 (7) (2014) 1006–1028.

[27] F. Flacco, A. De Luca, O. Khatib, Control of redundant robots underhard joint constraints: Saturation in the null space, IEEE Transactionson Robotics 31 (3) (2015) 637–654.

[28] A. De Luca, G. Oriolo, P. R. Giordano, Kinematic modeling andredundancy resolution for nonholonomic mobile manipulators, in:IEEE International Conference on Robotics and Automation, 2006,pp. 1867–1873.

[29] Y. Dai, S. Yu, Y. Yan, X. Yu, An ekf-based fast tube mpcscheme for moving target tracking of a redundant underwater vehicle-manipulator system, IEEE/ASME Transactions on Mechatronics24 (6) (2019) 2803–2814.

[30] H. Xing, A. Torabi, L. Ding, H. Gao, Z. Deng, V. K. Mushahwar,M. Tavakoli, An admittance-controlled wheeled mobile manipulatorfor mobility assistance: Human–robot interaction estimation and re-dundancy resolution for enhanced force exertion ability, Mechatronics74 (2021) 102497.

[31] B. Siciliano, Kinematic control of redundant robot manipulators: Atutorial, Journal of Intelligent and Robotic Systems 3 (3) (1990) 201–212.

[32] F. Flacco, A. De Luca, O. Khatib, Motion control of redundant robotsunder joint constraints: Saturation in the null space, in: IEEE Interna-tional Conference on Robotics and Automation, 2012, pp. 285–292.

[33] S. Chiaverini, Singularity-robust task-priority redundancy resolutionfor real-time kinematic control of robot manipulators, IEEE Transac-tions on Robotics and Automation 13 (3) (1997) 398–410.

[34] G. Guennebaud, B. Jacob, et al., Eigen v3, URL: http://eigen. tuxfam-ily. org (2010).

[35] M. Quigley, K. Conley, B. Gerkey, J. Faust, T. Foote, J. Leibs,R. Wheeler, A. Y. Ng, ROS: An open-source robot operating system,in: ICRA workshop on open source software, Kobe, Japan, 2009.

[36] J.-J. Slotine, L. Weiping, Adaptive manipulator control: A case study,IEEE Transactions on Automatic Control 33 (11) (1988) 995–1003.

[37] D. G. Luenberger, Y. Ye, Linear and Nonlinear Programming,Springer, 1984.

[38] F. Vigoriti, F. Ruggiero, V. Lippiello, L. Villani, Control of redundantrobot arms with null-space compliance and singularity-free orienta-tion representation, Robotics and Autonomous Systems 100 (2018)186–193.

[39] L. Ding, S. Li, H. Gao, C. Chen, Z. Deng, Adaptive partial reinforce-ment learning neural network-based tracking control for wheeled mo-bile robotic systems, IEEE Transactions on Systems, Man, and Cy-bernetics: Systems 50 (7) (2020) 2512–2523.

[40] R. Kelly, Comments on “adaptive PD controller for robot manipula-tors”, IEEE Transactions on Robotics and Automation 9 (1) (1993)117–119.

Hongjun Xing et al.: Preprint submitted to Elsevier Page 12 of 13

Page 13: Enhancing Kinematic Accuracy of Redundant Wheeled Mobile ...

Enhancing Kinematic Accuracy of Redundant Wheeled Mobile Manipulators via Adaptive Motion Planning

Hongjun Xing was born in 1992. He received theB.Sc. and M.Sc. degrees from the Harbin Instituteof Technology, China, in 2015 and 2017, respec-tively, where he is currently pursuing the Ph.D. de-gree with the School of Mechatronics Engineering.From 2019 to 2021, he was a visiting student withthe University of Alberta, Edmonton, AB, Canada.

His research interests include dynamic model-ing, tele-robotics, and compliance control.

Ali Torabi received the BSc degree in mechanicalengineering from Amirkabir University of Tech-nology (Tehran Polytechnic) in 2010 and the MScdegree in mechanical engineering from Sharif Uni-versity of Technology in 2013. He is currently pur-suing a Ph.D. in Electrical Engineering at Univer-sity of Alberta.

His research interests are control engineering,robotic and medical teleoperation systems.

Liang Ding was born in 1980. He received thePh.D. degree in mechanical engineering from theHarbin Institute of Technology, Harbin, China, in2009.

He is currently a Professor with the State KeyLaboratory of Robotics and System, Harbin Insti-tute of Technology. His current research interestsinclude field and aerospace robotics and control.

Haibo Gao was born in 1970. He received thePh.D. degree inmechanical design and theory fromthe Harbin Institute of Technology, Harbin, China,in 2004.

He is currently a Professor with the State KeyLaboratory of Robotics and System, Harbin In-stitute of Technology. His current research inter-ests include specialized and aerospace robotics andmechanisms.

Weihua Li received the M.Sc. and Ph.D. degreesin manufacturing engineering of aerospace vehiclefrom the Harbin Institute of Technology, Harbin,China, in 2011 and 2016, respectively.

He is currently an Assistant Professor withthe School of Automotive Engineering, Harbin In-stitute of Technology (Weihai). His current re-search interests include the dynamics, simulation,and teleoperation of wheeled mobile robots.

Mahdi Tavakoli is a Professor in the Departmentof Electrical and Computer Engineering, Univer-sity of Alberta, Canada. He received his BScand MSc degrees in Electrical Engineering fromFerdowsi University and K.N. Toosi University,Iran, in 1996 and 1999, respectively. He receivedhis PhD degree in Electrical and Computer Engi-neering from the University of Western Ontario,Canada, in 2005.

In 2006, he was a post-doctoral researcherat Canadian Surgical Technologies and AdvancedRobotics (CSTAR), Canada. In 2007-2008, hewas an NSERC Post-Doctoral Fellow at Harvard

University, USA. Dr. Tavakoli’s research inter-ests broadly involve the areas of robotics and sys-tems control. Dr. Tavakoli is the lead author ofHaptics for Teleoperated Surgical Robotic Systems(World Scientific, 2008). He is an Associate Edi-tor for IEEE/ASMETransactions onMechatronics,Journal of Medical Robotics Research, IET Con-trol Theory & Applications, and Mechatronics.

Hongjun Xing et al.: Preprint submitted to Elsevier Page 13 of 13