APP下载

Hybrid task priority-based motion control of a redundant free- floating space robot

2017-12-22ChengZHOUMingheJINYechaoLIUZongwuXIEHongLIU

CHINESE JOURNAL OF AERONAUTICS 2017年6期

Cheng ZHOU,Minghe JIN,Yechao LIU,Zongwu XIE,Hong LIU

State Key Laboratory of Robotics and System,Harbin Institute of Technology,Harbin 150001,China

Hybrid task priority-based motion control of a redundant free- floating space robot

Cheng ZHOU,Minghe JIN*,Yechao LIU,Zongwu XIE,Hong LIU

State Key Laboratory of Robotics and System,Harbin Institute of Technology,Harbin 150001,China

Base attitude control; Hybrid task-priority; Motion planning; Multiple constraints; Redundant space robot

This paper presents a novel hybrid task priority-based motion planning algorithm of a space robot.The satellite attitude control task is de fined as the primary task,while the leastsquares-based non-strict task priority solution of the end-effector plus the multi-constraint task is viewed as the secondary task.Furthermore,a null-space task compensation strategy in the joint space is proposed to derive the combination of non-strict and strict task-priority motion planning,and this novel combination is termed hybrid task priority control.Thus,the secondary task is implemented in the primary task’s null-space.Besides,the transition of the state of multiple constraints between activeness and inactiveness will only in fluence the end-effector task without any effect on the primary task.A set of numerical experiments made in a real-time simulation system under Linux/RTAI shows the validity and feasibility of the proposed methodology.

1.Introduction

With advances in space applications,space robots are essential to implement space exploration missions including assembling a space station,on-orbit servicing,space debris removal,and so on.The development of space robots impels space exploration to be ef ficient and safe.Hence,the last 40 years have witnessed an increasing interest towards robotic applications in space.1–5

Different types of space robots have different research priorities,such as the flexible issue of a manipulator with long links,6the con figuration and control issue of a soft robot,7the base attitude disturbance of a free- floating space robot,and so on.Meanwhile,free- floating space robots,like manipulator mounted8satellites or tethered space robots,9have always been a focused research object in the field of space exploration.The base attitude is disturbed by the movement of a manipulator,while it is so important when considering solar supplement and information communication.The satellite attitude control task is typically achieved by the attitude control system of a satellite,so limited fuel will be consumed.Besides,the coupling relationship between a satellite base and a manipulator can be utilized to adjust or maintain the satellite attitude.10,11Furthermore,other degrees of freedom(DOFs)will be used to achieve a manipulator’s end-effector task.In this paper,we address this issue from the view of a path planning strategy.

In literature,Dubowsky and Torres planned the trajectory of a space manipulator using an enhanced disturbance map(EDM)to minimize the disturbance of the base attitude.12They took a 2-DOF manipulator for example;however,it is dif ficult to obtain the EDMs of manipulators with more DOFs.Vafa and Dubowsky used a virtual manipulator model to develop path planning that reduced the base disturbance,which is called the self-correcting path planning algorithm.13In this method,a system is considered as a linear system with the assumption that the movements of joints are small enough.Nakamura and Mukherjee utilized the Lyapunov function to achieve regulations of both the satellite orientation and the manipulator joint angles simultaneously.14However,the stability of this method was not demonstrated strictly and the planned joint angles were not smooth.Fernandes et al.proposed a near-optimal nonholonomic motion planning algorithm to achieve attitude control inspired by the fact that a falling cat can change its orientation in midair.15Nenchev et al.originally utilized the notation of reaction null-space(RNS)to achieve base attitude control.16

RNS was originally proposed in Nenchev’s study,17and it was applied to achieve a vibration suppression task,a reactionless end-point control task,and a combined motion control task.Then it was utilized to achieve reactionless manipulation or zero reaction maneuver(ZRM).18It was also veri fied in the flight experiments of ETS-VII.To sum up,the RNS method is the only real-time method that can achieve base attitude regulation and end-effector trajectory planning simultaneously.However,algorithmic singularity(AS),representation singularity(RS),and dynamics singularity(DS)19exist in conventionalRNS-based motion planning algorithms.Some preliminary improvements on algorithmic singularity avoidance and dynamics singularity avoidance have been made,19,20but an algorithmic error exists.Furthermore,conventional RNS-based motion planning methods ignore physical constraints like joint limits,whereas physical constraints avoidance is of vital importance in the real-time motion control of a space robot.

In addition,singularity robust,especially AS-free,motion control for base attitude control with multiple constraints of a space robot is a new issue that should be considered.Additionally,an AS-free motion control law subject to multi constraints will give a more stable result.Besides,a task hierarchical framework will be introduced to guarantee that activated multi constraints will be transferred in the nullspace of the primary task.

In this paper,a strict task priority strategy is adopted to realize singularity robust and hierarchical motion planning of a space robot;21besides,a non-strict task-priority strategy is also utilized to achieve multiple constraints avoidance,22,23and the least squares problem consisting of a multi-constraint task and an antecedent secondary task(end-effector path tracking)is implemented in the nullspace of the primary task.Therefore,in this paper,a task hierarchical control algorithm for satellite base attitude control under multi constraints is derived.Besides,a null-space task compensation strategy in the joint space is proposed to give an AS-free derivation of the task hybrid hierarchybased solution.

2.Preliminaries

From the rotational momentum conservation equation,the following expression can be obtained:

Furthermore,assuming that the dimension of the Cartesian space task is m,the end-effector can be expressed as

The non-minimum-norm solutions of Eq.(1),noted ascan be written in a general form as

where P=(I-I+MIM),I denotes the identity matrix.(·)+is the Moore–Penrose pseudoinverse.˙ζ is an arbitrary vector.is the speci fic solution of Eq.(1).

Furthermore,substituting Eq.(5)into Eq.(3),we can obtain

where P(HP)+=(HP)+,as P being a symmetrical and idempotent projectional matrix.

Assume that L0=0 and˙x0=0.From Eqs.(1)and(2),we can get the following equation:

where JEis the extended Jacobian.

3.Problem formulation

3.1.Singularity issues

The task hierarchy is re flected in the RNS algorithm.However,there are DS,AS,and RS in the RNS method,and the DS issue occurs in the following case:

rank(IM)<l or rank(JM)<m

where rank(·)represents the rank of a matrix.

AS occurs when the projection Jacobian JMP drops rank24as follows:

3.2.Hard constraints in the path planning algorithm

In this article,we consider a set of kinematic inequality constraints,i.e.,

where ρiis a kinematic function,and θiis the angle of joint i.Ciis a constant,and r is the total number of constraints.ρi(θi),i=1,2,...,r can be concluded into a kinematic related vector ρ(θ).The joint limitations of joint i can be described as

Moreover,the above inequality constraintscan be described in the velocity level as

where ciis the previous moment value ofis a threshold value to bind ρi.

3.3.Conception of hybrid task priority-based path planning

There are always two ways to achieve online path planning of a robot.The first way is known as the non-strict task priority strategy,22,23,25which is also called as weighted least-squares(WLS).The second way is the strict task priority solution,like an RNS algorithm.In an RNS algorithm,algorithmic singularity issues exist,and constraints limitations are not considered.Besides,the other task priority solution type is only focused on algorithmic singularity-free issues.21,26In this paper,the former hierarchical planning is abbreviated as TP1,while the latter one is abbreviated as TP2.In addition,the main task is made up of Task 1 and Task 2.In a strict task priority solution,Task 1 is de fined as the primary task,while Task 2 is de fined as the secondary task.

In order to absorb the advantages of the above three strategies,a combination of non-strict task priority and strict task priority strategies is needed,and this idea is de fined as the hybrid task priority(HTP)strategy in this paper.Fig.1 demonstrates the difference between these four strategies.

In the above,the HTP concept is explained.Moreover,in the HTP strategy,the multiple constraints task and the end-effector task will act as subtasks implemented in the null-space of the primary satellite attitude control task,so the primary task will not be in fluenced by the multiconstraint task,while in the WLS solution,the main task will be influenced by the activated constraint task simultaneously.Besides,the algorithmic singularity should be eliminated,and the dynamics singularity and the representation singularity should be avoided.

4.Satellite attitude control algorithm

4.1.Null-space task compensation strategy

Through Eq.(5),we can know that the algorithmic singularity can be avoided by choosing a proper null-space velocity to satisfy the secondary task.Letand in Ref.19,20,the null-space vector is derived by the following equation in the Cartesian space:

The above equation is established under the condition ofbut it is not always established.In order to get a general solution to this hierarchical motion control problem,let us consider this problem again.

As for Eq.(2),its least-squares minimum-norm(LM)solutioncan be expressed as

Then we look for a proper solution of˙ζ by combining Eq.(13)and Eq.(3)as follows:

That is to say,to satisfy these two tasks,the null-space vector is selected to compensate the disparity in the joint space.Thus˙ζ can be derived as

Substituting Eq.(15)into Eq.(3)obtains

Furthermore,the above derivation Eq.(14)can be concluded in the following general formulation:

Eq.(12)derived in the Cartesian space is just a special case of Eq.(17).Besides,the null-space vector is utilized to compensate the disparity between Task 1 and Task 2.In this paper,the above stated strategy is de fined as the null-space task compensation strategy.

4.2.Hybrid task priority motion planning of a space robot

Consider the following weighted optimal problem as the secondary task:

Fig.1 Sketch map of the hybrid task priority motion planning strategy.

where wi,i=1,2,...,r is the weight of the constraint of joint i,and λEis the damping coef ficient.

De fine the following matrices:

where w is the weight matrix of joint constraints,and^w is the total weight matrix of main task and joint constraints.

so the forward problem of this optimal problem is

The weighted least-squares solution of Eq.(20),which is de fined asis also the optimization solution of Eq.(18).It can be presented as

Then a uniform expression can be obtained through the singular value decomposition(SVD)of JwCas follows:

where UEis the orthonormal matrix of the output singular vectors uiE,ΣEis the matrix whose diagonal submatrix contains the singular values σiEof matrix JwC,and VEis the orthonormal matrix of the input singular vectors viE.

The above unified formulation by the SVD can achieve a transition of the state of multiple constraints between activeness and in activeness.

Furthermore,the null-space task compensation derivation which is described as Eq.(17)is utilized as follows:

The above null-space vector compensation is operated in the joint space,while in the Cartesian space,the null space vector cannot be derived becausewhen n≥m+r.Thus,the null-space vector is derived as

It is obvious to see that the above null-space vector is derived in the joint space,and it cannot be derived as the way in Eq.(12).Hence,the angular velocities can be given by

In Eq.(26),the secondary task is achieved in the null space of the primary task.Thus,the idea of hybrid task priority as elaborated in Fig.1 is achieved.

4.3.Hybrid task priority motion planning without an algorithmic error

Let RE1and RE2be the residual errors of the primary task and the secondary task respectively,and RE2is presented as

It can be seen that the secondary task has a nonzero residual error.

Let Im(·)be the image space of a matrix.When n ≥ m+r,the secondary task cannot be accomplished except thatWe can take a weighted pseudoinverseto achieve a rotation of the image space ofso as to adjust the intersection angle.Therefore,Eq.(26)can be transformed as

which yields

and

To eliminate the residual of the secondary task,W is selected to rotate Im(I+M).The following lemma can be useful in the selection of W.

Lemma:

Hence,we can obtain

so

Considering the singularity avoidance of W,a small but proper positive number δ can be introduced.Therefore,the modi fied weighted matrixW~can be obtained as

δ is essential if rank(~W)<n,and if rank(~W)=n,δ=0.

In addition,the relationship between the activated constraints and main task accuracy is shown in Table 1.

Furthermore,following the analogous derivation from Eq.(13)to Eq.(17),the HTP-based satellite base attitude control with multi constraints can be expressed as

4.4.Singularity robust implementation of the algorithm

In practical applications,supposing that the orientation is represented by Euler angles ψ =[α, β,γ],the relationship between the angular velocity w and the rotational velocityrepresented as,where T is the transformation which is not invertible for β = ±90°,and we call this RS.A robust solution to this problem can be formulated with the utilization of unit quaternion.The unit quaternion can be de fined as

To better know the notation of the DS,let us consider the SVD of matrix IMas

with the known notation as in the SVD of Eq.(23).Furthermore,the singularity inis related to that in,so we have

A way to conquer the singularity is based on the damped least-squares inversewith the damping factor λBas

Thus,the DS-robust implementation of Eq.(32)is

Furthermore,supposing the desired angular velocity of the satellite wband L0=0,Eq.(36)can also achieve reactionless manipulation.is also a set of reactionless joint angular velocities.This novel reactionless kernel is de fined as the weighted pseudoinverse RNS.

5.Real-time simulator of a space robot and algorithm verification

5.1.Control scheme of a redundant space robot

We take a seven-DOF space robot for example.The body fixed frame of the space robot is shown in Fig. 2.xi,yi,zi, i=0,1,...,n are the coordinate axes of the fixed frame of body i.xE,yE,zEare the coordinate axes of the end-effector’s body fixed frame.The kinematic parameters and the dynamic parameters are listed in Table 2.In Table 2,the ranges of seven angles are also given,and as for joint i,the upper limit iswhile the low limit ismi(kg),i=0,1,...,7 is the mass of body i,and m0represents the mass of the satellite base.riand ciare the positions of the frame origin and the center of the mass of body i,respectively.ICi(kg·m2) is the inertia matrix of body i, and ICi=[Ixx,Ixy,Ixz;Iyx,Iyy,Iyz;Izx,Izy,Izz].Fig.3 illustrates the control scheme of the space robot,in which 1/S represents the integrator to solve joint angles.

Table 1 Relationship between multiple tasks.

Fig.2 Body fixed frame of a 7-DOF redundant space robot.

5.2.Real-time simulator under Linux/RTAI

Diverse simulators are widely used in aerospace engineering.27The ground hardware-based veri fication systems of a space robot like air-bearing table,28airplane flying or free-falling motion,29and suspension system30are costly built.Recently,a kind of hybrid simulation method following the principle of dynamics simulation and kinematics equivalence has been presented,which is called hardware-in-the-loop simulation system.31The above veri fication systems are also costly built.In this article,we build a real-time simulation system under Linux/RTAI to explore the capabilities and limitations of the proposed method.The functional architecture of the simulator is shown in Fig.4.

In this simulator,a dynamic model is built in SimMechanics,and the MATLAB Real-Time Workshop is utilized to port the virtual prototype model into C codes for online simulation.The controller of the real space robot system consists of a central controller and a joint controller.The modules mentioned above are made into three real-time tasks and run in three independent threads.32

5.3.Experiment results

The performance of the proposed algorithm is illustrated by the following simulation examples.The initial joint angles of a space robot are(0°,-90°,0°,0°,0°,0°,0°)and the base attitude is(0°,0°,0°)(Cardan angle).Furthermore,we adopt trapezium trajectories to plan the velocity and angular velocity.The control cycle is 0.01 s.

The varied weight is de fined as

where εiis a threshold value to ensure safety,d is a positive scalar selected by the demand of increasing rate,and˙ρiis the derivative term of ρi.In this paper,the threshold value εiis designed as

where ρimaxis the maximum value of ρi.The coefficient N will determine the value of εifinally.

Besides,the damping factor is determined by the balance between the task accuracy and the singularity.We adopt the minimum singular value as the criterion to measure the singularity.The varied damping factors are determined as

where σBminand σEminare the minimum singular values of IMand JwC. σrBand σrEde fine the size of the singular region.λ0Band λ0Eare the maximum values of the damping factor.In addition, we adopt σrB= σrE=0.005 andto avoid the dynamics singularity.

Case 1:

In this example,a comparison to analyze the proposed HTP motion planning algorithm,the RNS-based motion planning algorithm,and the EJ-based motion planning algorithm is made.Assuming that the desired base attitude(α,β,γ)is(1°,1°,0°),the desired Cartesian end-effectordisplacement(x,y,z)can be divided into 4 cases:one case is(-35.7,30.6,35.7)mm,and the other cases are 1.5 times,2.0 times,and 2.5 times respectively,that are(-53.5,45.9,53.5)mm,(-71.4,61.2,71.4)mm,and(-89.2,76.5,89.2)mm.The corresponding tracking errors(Δx,Δy,Δz)and(Δα,Δβ,Δγ)in the aforementioned three methods are shown in Figs.5–7,respectively.

The above results shown in Figs.5 and 6 demonstrate that the tracking errors in the HTP-based solution Eq.(36)aresmaller than those in the antecedent solution Eq.(6),that is to say,the former is more stable than the latter.This is because the former solution is without the algorithmic singularity,while the latter is easy to diverge with the increasing task dependence.Besides,Fig.7 shows that the EJ-based solution will bring about larger task errors in the satellite base attitude adjustment,which is because these two tasks(satellite base attitude adjustment and end-effector path tracking)are in the same priority,and these tasks will be in fluenced by each other.

Table 2 Mass properties of the 7-DOF space robot.

Fig.3 Control scheme of the 7-DOF space robot.

Fig.4 Functional architecture of the simulator.

Fig.5 Tracking errors of different tasks in the HTP-based solution Eq.(36).

Fig.6 Tracking errors of different tasks by the antecedent RNS-based solution Eq.(6).

Case 2:

In this example,the proposed HTP method is used to achieve satellite attitude adjustment.The desired Cartesian displacement(x,y,z)is(-81,52.7,68)mm,and the desired base attitude(α,β,γ)is(1°,1°,0°).The simulation results of these two tasks are shown in Fig.8,and Fig.9 shows the errors(Δx,Δy,Δz)and(Δα,Δβ,Δγ)between the actual posture and the desired posture. The joint angles(qi,i=1,2,...,7)are reported in Fig.10,and Fig.11 shows the weights w3and w7in the constraints limits avoidance of joint 3 and joint 7,respectively.

Fig.7 Tracking errors of different tasks by the EJ-based solution Eq.(8).

Fig.8 Attitude of the base and position of the end-effector.

Fig.9 Tracking errors of both tasks.

Fig.10 Angles of the redundant space robot.

Fig.11 Weights in constraints limit avoidance of joint 3 and joint 7.

It is obvious that the proposed motion planning algorithm works successfully.The angle of joint 3 approaches the safe threshold value in 15.4 s,as shown in Fig.10,and the ascending weight prevents joint3’s motion,as shown in Figs.10 and 11.However,Fig.10 also shows that the other joint angles are changed to remedy the suspension of joint 3.While in 18.28 s,joint 7’s angle also approaches its border,there is no redundancy to solve two constraints simultaneously.Hence,the accuracy of end-effector continuous path tracking is affected by the ascending weight of joint 7’s limit constraint.However,in this stage,the accuracy of the primary satellite base attitude adjustment task will not be influenced,as shown in Figs.8 and 9.

Case 3:

In this example,the proposed HTP method is used to achieve reaction less control.The desired Cartesian displacement(x,y,z)is(-151.2,109.8,-189)mm.The simulation results of these two tasks are shown in Fig.12,and Fig.13 shows the errors(Δx,Δy,Δz)and(Δα,Δβ,Δγ).The joint angles(qi,i=1,2,...,7)are reported in Fig.14,and Fig.15 shows the weights w2and w7in the constraints limits avoidance of joint 2 and joint 7,respectively.

Fig.12 Attitude of the base and position of the end-effector in reaction less control.

Fig.13 Tracking errors in reaction less control.

It can be seen that the end-effector path tracking task is achieved without influence of the satellite attitude.However,in 13.3 s,joint 2 is close to the scheduled limit,and the increased weights(as shown in Fig.15)will activate the constraint,and then the angle of joint 2 will be adjusted.Furthermore,in 15 s,joint 7 approaches the scheduled limit,so the weight increases dramatically.Thus,as shown in Fig.14,joint 7’s motion stops;besides,the motions of joint 1,joint 3,and joint 4 are changed correspondingly.Because only one constraint is activated in 13.3 s,the redundancy can achieve constraint avoidance by a proper recon figuration of the manipulator;besides,in 15 s,two constraints are activated,the end-effector path tracking accuracy will be influenced to some degree without influence on the main task,as shown in Figs.12 and 13.

6.Conclusions

Fig.14 Angles of the redundant space robot in reaction less control.

Fig.15 Weights in constraint limit avoidance of joint 2 and joint 7 in reaction less control.

(1)A null-space task compensation in the joint space is proposed to obtain HTP-based motion planning for base attitude control with multiple constraints of a redundant space robot.Thus,the secondary task consists of end-effector path tracking,and the multiconstraint avoidance task is implemented in the nullspace of the primary task which is termed the weighted pseudoinverse RNS,where the joint motion in this reactionless kernel will have no effect on attitude control.Furthermore,the weighted pseudoinverse solution eliminates the residual error of the secondary task.Hence,a hybrid task priority motion planning algorithm is derived.

(2)Besides,the null-space task compensation strategy guarantees no algorithmic singularity in the proposed hybrid task priority algorithm,and a varied damping factor is also introduced to settle the dynamics singularity problem.Hence,a singularity robust path planning algorithm is derived to implement the prioritized task of base attitude adjustment with multiple constraints.

(3)Furthermore,a real-time simulator under Linux/RTAI of a free- floating space robot is built in this paper to verify the online calculation of the proposed method.Thus,the real-time base control task is implemented in the simulator.

Acknowledgements

This project was supported in part by the National Program on Key Basic Research Project(No.2013CB733103)and the Program for New Century Excellent Talents in University(No.NCET-10-0058).

1.Flores-Abad A,Ma O,Pham K,Ulrich S.A review of space robotics technologies for on-orbit servicing.Prog Aerosp Sci 2014;68:1–26.

2.Xu W,Liang B,Xu Y.Survey of modeling,planning,and ground verification of space robotic systems.Acta Astronaut 2011;68(11):1629–49.

3.Huang P,Wang M,Meng Z.Attitude takeover control for postcapture of target spacecraft using space robot.Aerosp Sci Technol 2016;51:171–80.

4.Wen Z,Wang Y,Kuijper A,Di N,Luo J,Zhang L,et al.On-orbit real-time robust cooperative target identification in complex background.Chin J Aeronaut 2015;28(5):1451–63.

5.Zhang L,Jia Q,Chen G,Sun H.Pre-impact trajectory planning for minimizing base attitude disturbance in space manipulator systems for a capture task.Chin J Aeronaut 2015;28(4):1199–208.

6.Xu B,Yuan Y.Two performance enhanced control of flexible-link manipulator with system uncertainty and disturbances.Sci Chin Informa Sci 2017;60(5):050202.

7.Jing Z,Qiao L,Pan H,Yang Y,Chen W.An overview of the con figuration and manipulation of soft robotics for on-orbit servicing.Sci Chin Informa Sci 2017;60(5):050201.

8.Jia Y,Xu S.Decentralized adaptive sliding mode control of a space robot actuated by control moment gyroscopes.Chin J Aeronaut 2016;29(3):688–703.

9.Huang P,Wang D,Meng Z,Zhang F,Liu Z.Impact dynamic modeling and adaptive target capturing control for tethered space robots with uncertainties.IEEE/ASME Trans Mecha 2016;21(5):2260–71.

10.Dubowsky S,Papadopoulos E.The kinematics,dynamics,and control of free- flying and free- floating space robotic systems.IEEE Trans Robot Autom 1993;9(5):531–43.

11.Fernandes C,Gurvits L,Li ZX.Attitude control of space platform/manipulatorsystem using internalmotion.Space Robotics:Dynamics and Control,1992 May 12–14,IEEE Press,Piscataway,NJ;1993.p.131–63.

12.Dubowsky S,Torres M.Path planning for space manipulators to minimize spacecraft attitude disturbances.IEEE international conference on robotics and automation,1991 April,IEEE Press,Piscataway,NJ;1991.p.2522–8.

13.Vafa Z,Dubowsky S.On the dynamics of space manipulators using the virtual manipulator,with applications to path planning.Space Robotics:Dynamics and Control;1993.p.45–76.

14.Nakamura Y,Mukherjee R.Nonholonomic motion planning of free- flying space robots via a bi-directional approach.Space Robotics:Dynamics and Control;1993.p.101–30.

15.Fernandes C,Gurvits L,Li Z.Near-optimal nonholonomic motion planning for a system of coupled rigid bodies.IEEE Trans Autom Control 1994;39(3):450–63.

16.Nenchev D,Umetani Y,Yoshida K.Analysis of a redundant freeflying spacecraft/manipulator system.IEEE Trans Robot Autom 1992;8(1):1–6.

17.Nenchev DN,Yoshida K,Vichitkulsawat P,Uchiyama M.Reaction null-space control of flexible structure mounted manipulator systems.IEEE Trans Robot Autom 1999;15(6):1011–23.

18.Nenchev DN.Reaction null space of a multibody system with applications in robotics.Mecha Sci 2013;4(1):97–112.

19.Jin M,Zhou C,Liu Y,Liu H.Cartesian path planning for base attitude adjustment of space robot.In:IEEE international conference on mechatronics and automation,2015 Aug 2–5,Beijing,China.IEEE Press,Piscataway,NJ;2015.p.582–7.

20.Chiaverini S.Singularity-robust task-priority redundancy resolution for real-time kinematic control of robot manipulators.IEEE Trans Robot Autom 1997;13(3):398–410.

21.Park J,Choi Y,Chung WK,Youm Y.Multiple tasks kinematics using weighted pseudo-inverse for kinematically redundant manipulators.In:IEEE international conference on robotics and automation;2001 May 21–26,IEEE Press,Piscataway,NJ;2001.p.4041–7.

22.Chiaverini S,Egeland O,Kanestrom RK.Achieving user-de fined accuracy with damped least-squares inverse kinematics.In:Fifth international conference on advanced robotics,1991 June 19–22,IEEE Press,Piscataway,NJ;1991.p.672–7.

23.Xiang J,Zhong C,Wei W.A varied weights method for the kinematic control of redundant manipulators with multiple constraints.IEEE Trans Robot 2012;28(2):330–40.

24.Antonelli G.Stability analysis for prioritized closed-loop inverse kinematic algorithms for redundant robotic systems.IEEE Trans Robot 2009;25(5):985–94.

25.Seraji H,Colbaugh R.Improved con figuration control for redundant robots.J Robot Sys 1990;7(6):897–928.

26.An S,Lee D.Prioritized inverse kinematics using QR and Cholesky decompositions.In:IEEE international conference on robotics and automation,2014 May 31–June 7,IEEE Press,Piscataway,NJ;2014.p.5062–9.

27.Wang C,Jiao Z,Wu S,Shang Y.An experimental study of the dual-loop control of electro-hydraulic load simulator(EHLS).Chin J Aeronaut 2013;26(6):1586–95.

28.Umetani Y,Yoshida K.Experimental study on two dimensional free- flying robot satellite model.In:Proceedings of the NASA conference on space telerobotics,1989 Jan 31,NASA,Washington,D.C.;1989.p.89–97.

29.Menon C,Aboudan A,Cocuzza S.Free- flying robot tested on parabolic flights:kinematic control.J Guidance Control Dyn 2005;28(4):623–30.

30.Fujii H,Uchiyama K,Yoneoka H,Maruyama T.Ground-based simulation of space manipulators using test bed with sus-pension system.Chem Eng Commun 1996;19(5):985–91.

31.Krenn R,Schaefer B.Limitations of hardware-in-the-loop simulations of space robotics dynamics using industrial robots.European Space Agency-Publications-ESA SP 1999;440:681–6.

32.Jin M,Zhou C,Xie Z.The electrical simulator for the space station manipulator under Linux/RTAI.In:IEEE international conference on robotics and biomimetics;2016 Dec 3–7,Qingdao,China,IEEE Press,Piscataway,NJ;2016.p.402–7.

23 December 2016;revised 9 March 2017;accepted 30 April 2017

Available online 9 September 2017

Ⓒ2017 Production and hosting by Elsevier Ltd.on behalf of Chinese Society of Aeronautics and Astronautics.This is an open access article under the CC BY-NC-ND license(http://creativecommons.org/licenses/by-nc-nd/4.0/).

*Corresponding author.

E-mail address:mhjin@hit.edu.cn(M.JIN).

Peer review under responsibility of Editorial Committee of CJA.