Measurement of the Robot Motor Capability of a Robot Motor System: A Fitts’s-Law-Inspired Approach
Abstract
: Robot motor capability is a crucial factor for a robot, because it affects how accurately and rapidly a robot can perform a motion to accomplish a task constrained by spatial and temporal conditions. In this paper, we propose and derive a pseudo-index of motor performance (pIp) to characterize robot motor capability with robot kinematics, dynamics and control taken into consideration. The proposed pIp provides a quantitative measure for a robot with revolute joints, which is inspired from an index of performance in Fitts's law of human skills. Computer simulations and experiments on a PUMA 560 industrial robot were conducted to validate the proposed pIp for performing a motion accurately and rapidly.1. Introduction
Robots are widely-used in manufacturing tasks, such as assembly [1], cutting [2], deburring [3], etc. Without loss of generality, these manufacturing tasks can be decomposed into a sequence of motor tasks that are usually described by spatial and temporal constraints on objects in the environment [4–6]. Thus, a major problem for a robot to accomplish a task is to satisfy the spatial and temporal constraints of a task. A spatial-temporal constraint requires a robot to perform motor movements accurately in a desired trajectory task. Usually, a robot is asked to achieve a given position with a minimum movement time. However, each robot has its own motor capability according to its mechanical and electrical system and may not be qualified for tasks with strict spatial-temporal constraints.
Robot motor capability is the motor ability for a robot to accomplish a task constrained by spatial and temporal conditions. Traditionally, a robot was evaluated by its accuracy and repeatability [7–10]. American National Standard defined the static and dynamic performance characteristics for industrial robots and robot systems [11,12]. Throughout the previous work, there has not been a performance metric to measure the robot motor capability of a robot motor system for tasks constrained by spatial and temporal conditions. Thus, there is a need to develop a quantitative measure of a robot motor system.
In this paper, the proposed method for characterizing the motor capability of a robot is inspired by Fitts's law, which is one of the well-known metrics for studying human rapid movements. Fitts's law was revealed by Paul Fitts in 1954, showing the information capacity of a human motor system. In Fitts's law, the motor performance is the ability to consistently produce movements and is described by two main factors—speed and accuracy. Fitts obtained the following equation, often called Fitts's law, as:
Actually, Fitts's equation is a special case of the quasi-power function with a varying exponent, n, as n→ ∞[13]. The quasi-power function with exponent n is shown as . When n→ 1, the quasi-power function becomes a linear function as:
The paper proposes the method to derive the speed-accuracy constraint of a robot system the same as Equation (4), and therefore, the pseudo-index of motor performance (pIp) of the robot system is defined as in Equation (4). The speed-accuracy constraint is characterized with robot kinematics, dynamics and control taken into consideration. Thus, the mathematical derivations of pIp are applicable to other robots with revolute joints. Furthermore, pIp is a quantitative measure for the motor capability of a robot. The basic concept of our approach is to treat a robot motor system as an information channel and determine the robot motor capability. Since the information capability of a channel is affected by the inaccuracy of kinematics and dynamics models, we can quantitatively measure it by the variability of movements that a robot aims to produce. To verify the proposed method, computer simulations and experiments on PUMA 560 and 260 industrial robots are conducted to verify the validity of the proposed approach in understanding the motor capability of a robot motor system.
This paper is organized as follows. In Section II, we formulate a robot task as an optimization problem constrained by the proposed speed-accuracy constraint derived from the kinematics, dynamics and control of a robot motor system. In Section III, we present the proposed pseudo-index of motor performance (pIp) derived from the speed-accuracy constraint and show how pIp is utilized to evaluate the motor capability of a robot. In Section IV, computer simulations and experiments on PUMA 560 and 260 industrial robots are presented. Discussions and conclusions are summarized in Section V.
2. Speed-Accuracy Constrained Optimization
2.1. Problem Formulation
We formulate a robot task as an optimization problem subject to spatial and temporal constraints. The proposed speed-accuracy constraint characterizes the relationship between the robot joint speed and the Cartesian position error of the end-effector of the robot. By utilizing the proposed speed-accuracy constraint, the optimization problem is solved without violating the robot motor capability. We first formulate a basic rapid robot movement that moves its end-effector to reach a desired joint location, θ = [θ1, θ2,…, θi,…, θn]T, with an allowable tolerance, εx, εy and εz (i.e., spatial constraint), in the Cartesian space by the maximal linear speed (i.e., temporal constraint), where N is the number of degrees of freedom (DOF) and the superscript, T, denotes a matrix transpose. Here, we need to determine the joint velocities that introduce the maximal linear speed of the end-effector. The joint velocities are represented by a vector as θ̇ = [θ̇1, θ̇2, …, θ̇i,… , θ ̇n]T, and the basic rapid movement of the end-effector of a robot is formulated as an optimization problem as:
2.2. Robot Speed-Accuracy Constraint
Since the spatial inaccuracy of the end-effector of a robot with revolute joints is caused by the inaccuracy of robot kinematics and dynamics models and the disturbance of the environment [8], we represent the Cartesian position error of the end-effector of an N-DOF manipulator (e.g., a PUMA robot) with revolute joints by a linear model expressed as:
To derive Δθ in Equation (6), we assume that the widely-used “computed torque” technique with a proportional-plus-derivative (PD) controller [15] is used. Thus, each robot joint is modeled as a single-input-single-output system with disturbance from other joints. The coupling effects from other links are considered as a disturbance to the robot. A PD control is utilized to servo the manipulator system to track the desired trajectory, and the feedforward torques along the actual trajectory are computed to compensate for the nonlinear disturbance. A block diagram showing the PD control scheme for joint, i, is shown in Figure 1.
In Figure 1, , , and are, respectively, the computed counterparts of the actual effective inertia terms, Jij(θ), effective damping coefficient, fi, gravity terms, Gi(θ), and Coulomb friction, Vi, at the actual shaft of joint, i, of the manipulator. ni is the gear ratio, armature resistance, , motor constant, , and the back electromagnetic force constant, , is known dc motor parameters for joint, i. and are, respectively, position and velocity feedback gains of the controller. Their values are chosen subject to the mechanical resonant frequency constraint of the manipulator. and θi(s) are, respectively, the desired and actual angular displacement of joint, i. is the disturbance in Laplace transform and is the computed feedforward torque compensating for the disturbance.
In order not to excite the mechanical resonant frequency of the manipulator, the undamped natural frequency is set to no more than one-half of the structure resonant frequency. Complying to this constraint, we can obtain the following relation and the upper bound of
To determine Δθ in Equation (6), we utilize Figure 1 to evaluate the steady-state error of θ by a velocity-related joint position command, θd(t) = At, where A is the amplitude of the input. The steady-state error of θi is derived as:
Replacing the elements of Δθ in Equation (6) with Δθi in Equation (11), we obtain the Cartesian position errors of the end-effector of the robot in the form of speed-accuracy constraint as:
From Equation (12), it shows that when the joint speed increases (θ̇new = κθ̇old, κ ≥ 1) and the desired joint positions, θ, are fixed, a larger absolute Cartesian position error (|dx|, |dy| and |dz|) will be generated. Thus, Equation (12) indicates the trade-off relationship between the spatial accuracy and the joint speed.
3. Pseudo-Index of Performance for a Robot System
The purpose of determining the pseudo-index of the performance, pIp, of a robot motor system is to obtain a quantitative measure. After the speed-accuracy constraint is obtained, we can derive and calculate the index of the performance, pIp, of a robot motor system from this constraint. Thus, we define the pseudo-index of the performance (pIp) of the linear speed-accuracy equation in Equation (4) as to quantitatively indicate the amount of information capacity of a robot motor system. According to the speed-accuracy constraint (see Equation (12)), C(θ) + Jd(θ)KΔP(θ) can be referred to as a' in Equation (4). The joint velocity command is expressed as θ̇d = ρθ̇0, where θ̇0 is a reference joint velocity vector and ρ > 0 is a scale factor to change the joint velocities. We can express Equation (12) in the form of Equation (4) as:
From Equation (13), we obtain the quadratic function of the Cartesian position errors, (dx, dy, dz), with respect to the scalar of the joint velocity, ρ.Figure 2 illustrates the obtained quadratic function of the Cartesian position error of the end-effector of a robot along the x-axis (dx) with respect to the scalar of the joint speed (ρ), where the intercept on the axis of the Cartesian position error of the end-effector of a robot is IxT[C(θ) + Jd(θ)KΔP(θ)]. From Figure 2 and Equation (13), it is shown that a robot is capable of performing more accurately with a larger pIp when the joint velocities, θ̇d, are fixed (i.e., ρ is fixed). In other words, when the Cartesian position tolerance, e, of a given task is fixed (i.e., dx is fixed), a robot with a larger pIp is capable of accomplishing the task with faster joint velocities. Interestingly, the pseudo-index of performance is advantageous to show the trade-off relationship between speed and accuracy, if we assume that there exists a fixed amount of information capacity of a robot motor system.
4. Computer Simulations & Experimental Work
Computer simulations were performed by MATLAB Toolbox [16], and experiments were performed on 6-degree-of-freedom PUMA 560 and 260 robots [14] with revolute joints to validate the proposed speed-accuracy optimization and demonstrate that the motor capability can be measured by the proposed pseudo-index of performance (pIp) on a rapid-moving task. In the experiments, the Cartesian position error was with respect to the 2D space, because we followed Fitt's experiments, where the position error was only measured in the 2D space. The Cartesian position error on the last dimension (z-axis) would not affect that on the other two dimensions (x- and y-axis), because they are independent.
4.1. Simulation on a PUMA 560 Robot
Figure 3 shows the scheme of our task. The robot was asked to move its end-effector to hit a target position (G) and stop at an end position (E) by various configurations of movement speed (D/Tmt) and distance (D). With each configuration of movement speed and distance, this resulted in a Cartesian position error (W) at the end-effector.
In this simulation, a PUMA 560 industrial robot was asked to move with the maximum speed to hit the target position within the spatial tolerances, σx and σy, which denote the maximum position tolerances along the x- and y-axis, respectively. For simplicity, the robot only used joints 1, 2, and 3 to perform the task. Based on the task description, we formulated the task as an optimization problem subject to the spatial-accuracy constraints for maximizing the robot speed:
First, we evaluated how the Cartesian position error was affected by Δm, ΔG(θ) and ΔV(θ) under a fixed joint distance. We used joint-interpolated motion planning for the robot. Simply, we subtracted C(θ) from the Cartesian position errors of the end-effector of the robot. The joint distance, θdiff, between the initial and target joint positions was [π/4,π/4, -π /4, 0, 0, 0], and the execution time for all the joints was set to Tmt. Thus, the joint velocities were represented as θdiff/Tmt (rad/sec). If we set θ̇ as the nominal joint velocities finishing θdiff by one second, the joint velocities were expressed as ρ ·; θ̇, where ρ = 1/ |Tmt|. The joint velocity, acceleration and the inverse dynamics of the robot were calculated by the recursive Newton-Euler equations [14,18], and the Cartesian position error of the end-effector of the robot was calculated by Jd(θ)Δθ and verified by Equation (12).
When the errors between the computed and actual masses, , as (±0.1%), (±0.2%),… and (±1%), were assumed as the cause of the Cartesian position errors, we simulated four cases of a combination of ΔV (Coulomb friction) and ΔG(θ) (errors between the actual and computed gravity terms). Their results are explained and discussed as follows:
- Case (1)
ΔV = 0 and ΔG(θ) = 0: In this case, the simulation results showed that the Cartesian position errors of the end-effector of the robot (dx = dy = dz = 0) almost do not exist. Apparently, they can be validated by Equation (12), because of ΔP(θ) = 0 (ΔV = 0, ΔG(θ) = 0 and ΔH(θ) = 0).
- Case (2)
ΔV≠ 0 and ΔG(θ) = 0: In this case, the simulation results of the Cartesian position errors along the x- and y-axis (dx and dy) were shown by the blue dots with Δm = 0 in Figure 4. The Cartesian position errors were only due to ΔV of Equation (12).
- Case (3)
ΔV = 0 and ΔG(θ) ≠ 0: In this case, the simulation results showed that when ρ = 1/2 and Δm was changed from 1.0% to -1.0%, the Cartesian position errors were shown by the line of red crosses in Figure 4 and caused by ΔG(θ) and ΔH(θ) of Equation (12). On the other hand, when the joint velocities were changed by ρ (1/2, 1/4, 1/6), Figure 5 shows that the slope of the line showing the Cartesian position errors was also changed. It shows that as ρ= 1/6 (gray line, lowest speed), the Cartesian position errors were least (highest accuracy). In addition, when Δm was fixed, Figure 5 shows that the Cartesian position errors caused by different ρ were in a linear line (Gi pink line), and the increment of the Cartesian position errors was proportional to ρ2, because Jd(θ)KΦ̇T ΔH(θ)Θ̇ in Equation (12) indicates that the Cartesian position errors were proportional to (θ̇2) (i.e., ρ2) when Δm was fixed. However, none of the pink lines in Figure 5 did passed through the origin, but a point Gi, (i = …, −2, −1,1, 2, …). These results were clearly shown by Equation (12), because the Cartesian position errors resulted from ΔG(θ) and ΔH(θ), but when the joint velocities were set to zero, the Cartesian position errors were only due to ΔG(θ) (i.e., Gi).
- Case (4)
ΔV≠ 0 and ΔG(θ) ≠ 0: This case has the same results as Case 3, except the lines showing the Cartesian position errors caused by fixed ρ did not pass through the origin.
Then, we evaluated the pIp of a PUMA 560 robot with various Δm's and Cartesian distances, where Δm = m − mc, m were the actual masses and mc were the computed masses. In other words, a robot with a different Δm had a different motor capability, because Equation (14) shows that the pseudo-index of performance is affected by ΔH(θ) (i.e., Δm). We set the Cartesian distances between the start (S) and the target (G) positions to 0.0508, 0.1016, 0.2032 and 0.4064 m. The four movement velocities (D/Tmt m/sec) for a specified distance (D) were set in Table 1. To investigate the Cartesian position errors of the end-effector of the PUMA 560 robot caused by the changes of the joint velocities, we subtracted the velocity-independent terms, C(θ) + Jd(θ)KΔP(θ), from the Cartesian position errors at the target position. For D = 0.0508, 0.1016, 0.2032 and 0.4064 (m), the joint velocities were represented as , where θ̇0 is the nominal joint velocities finishing by one second, ρ is a scalar and its value is ρ = 1/ |Tmt|. We changed the joint velocities by changing ρ with a 0.01 incremental value. The joint velocity, joint acceleration and the inverse dynamics of the robot were calculated by the recursive Newton-Euler equations [14,18], and the Cartesian position error of the end-effector of the robot was calculated by Jd(θ)Δθ.
Figure 6 shows the Cartesian position errors along the x-axis (dx) with respect to D/Tmt when D = 0.0508 and Δm was (a)−1%, (b)−0.6% and (c)−0.2%, respectively. In each sub-figure, we used a quadratic function to do curve fitting for our simulation results. Since the quadratic coefficient is the reciprocal of pIpx, by referring to Figure 2, we noticed that Figure 6(c) had the greatest pIpx among Figure 6(a-c). It was explained by the reason that Figure 6(c) had the least amount of Δm = −0.2%.
To verify the robot had different motor capabilities with respect to ρ on the x-axis, we changed Δm, fixed D (i.e., D = 0.0508,0.1016,0.2032 or 0.4064) and compared the quadratic coefficients among these various Δm's.Figure 7 shows the quadratic coefficients when Δm was -1%, -0.6% and -0.2% in each sub-figure, where (a), (b), (c) and (d) represent D = 0.0508, 0.1016, 0.2032 or 0.4064. We found that the robot with Δm = -0.2% had the largest pIpx compared to Δm = -1% and -0.6%. In other words, the robot with the smaller error between actual and computed masses had the better motor capability. The simulation results validated Equation (14) because and ΔH(θ) is definitely affected by Δm.
4.2. Experiments on PUMA 560 and 260 Robots
To validate the speed-accuracy constraint, we performed the experiment on a PUMA 560 robot (see Figure 8). The joint distance, θdiff, between the initial and target positions of a joint-interpolated motion planning was [π/4,π/4,π/4,0,0,0], and the execution time for all the joints was set to Tmt = 1.6,1.07,0.8 and 0.64 seconds for tests 1, 2, 3 and 4, respectively. Thus, the joint velocities of these tests were θ(0304) = θdiff/Tmt = ρ • θ(0304)0(rad/sec), where θ(0304)0 = θdiff/1 are nominal joint velocities finishing θdiff by one second and ρ = 1/ |Tmt| = 0.625, 0.935,1.25,1.5625 for tests 1 to 4, respectively The relationships of joint velocities between test 1 and tests 2, 3 and 4 were obtained as θ̇2 = 1.5θ̇1, θ̇3 = 2θ̇1 and θ̇4 = 2.5θ̇1. Although we could not obtain the actual masses of the links, we performed various Δm's (the ratio of the error between the computed masses and the original computed masses we had to the original computed masses) by -3%, -2%, -1%, 0%, 1% and 2% and obtained similar results in Figure 5. Figure 9 shows the Cartesian position errors (dx,dy) of the end-effector of the PUMA 560 robot caused by the changes of joint velocities and Δm. In Figure 9, each line was plotted by the Cartesian position errors of the end-effector of the robot introduced with various computed masses and the same joint velocity This shows that the Cartesian position error, ∝ Δm, is under the same joint velocity
From Figure 9, we obtain the relationship of Cartesian position errors caused by fixed Δm and the changes of the joint velocities (ρ), as shown in Figure 10. Figure 10 represents Δm for −3%, −2%, − 1%, 0%, 1% and 2%, respectively The ratios of the Cartesian position errors of the end-effector of the PUMA 560 robot caused by θ̇2,θ̇3 and θ̇4 to the Cartesian position errors caused by θ̇1 in Figure 10 were shown in Table 2. These ratios of errors were close to the expected ratios, ρ2 ((1.5)2 = 2.25, (2)2 = 4, (2.5)2 = 6.25), since θ̇2 = 1.5θ̇1, θ̇3 = 2θ̇1 and θ̇4 = 2.5θ̇1. This shows that the Cartesian position error, ∝ ρ2, is under the same Δm. Equation (13) explains this phenomenon when PUMA560 had a fixed pIpx.
To demonstrate that the pseudo-index of performance (pIpx) is useful to evaluate the motor capability of various robots with revolute joints, we compared the motor capabilities of the PUMA 560 and 260 robots by measuring their pIpx, where the PUMA 260 was a small robot with a similar mechanism to the PUMA 560. Figures 11 and 12 show the PUMA 560 and 260 robots' quadratic coefficients when D = 0.0508, 0.1016, 0.2032 and 0.4064. As pIpx is the reciprocal of the quadratic coefficient, it is obvious that the PUMA 260 robot has better motor capability than the PUMA 560 robot.
5. Discussions and Conclusions
The proposed speed-accuracy constraints showed the relationship between Cartesian position errors of the end-effector of a robot and joint velocities. This relationship can be illustrated by a vector representation, as shown in Figure 13. For simplicity, Figure 13 shows the 2D projection of a 3D Cartesian position error caused by joint position errors (Δθ). The Cartesian position error on the 2D plane, ΔEall, is composed of dx along the x-axis and dy along the y-axis. It is shown as the summation of ΔEV, ΔEG and ΔES, where ΔEV represents the Cartesian position errors introduced by the errors between the actual and computed Coulomb frictions, ΔEG represents the Cartesian position errors introduced by the errors between the actual and computed gravity terms and ΔES represents the Cartesian position errors regulated by the velocity changes. Here, ΔEG is affected by Δm and ΔEG∝αm, where Δm = αmm and αm is a scalar. Also, ΔES is affected by θ and ΔES ∝ αm. (αs)2, where θ̇ = αsθ̇0,θ̇0 is a reference speed and αs is a scalar. The angle, φ, is determined by θ, m and Δm. When the desired joint positions, θ, and link masses, m and Am, are determined, we can choose αs (maximum speed) based on the vector relationship to make the vector, ΔEall, stay in the boundary of the task constraints.
From Equation (14), it is obviously shown that the pseudo-index of performance is the same with respect to the joint velocities, θ̇, instead of the Cartesian speed, dD/dt. Thus, the pseudo-index of performance was not the same for the sub-figures of Figures 11 and 12. In addition, when a robot moves to a target in a fixed distance, Δm of the robot will influence its motor capability. The less error in masses will give the robot more information capacity for trading off movement speed and accuracy to accomplish a task.
The pseudo-index of performance is also affected by the target joint positions, θ, because from Equation (14)Jd(θ) dramatically affects the Cartesian position errors, dx, dy and dz. Figure 14 shows the L1-norm of , and with respect to index number, where Ix,Iy and Iz are unit vectors along the x-, y- and z-axis, respectively. L1-norm indicates the maximum Cartesian position errors, dx, dy and dz, to which Jd(θ) can contribute. The index number is generated from the data format as index(j1):index(j2):index(j3):index(j4):index(j5):index(j6), where index(ji) is a sampling index by joint resolution within the joint range of joint, i[14], joint resolution is determined arbitrarily, index(j1) are the most significant bits (MSB) and index(j6) are the least significant bits (LSB). The index number represents the joint positions for all joints. To illustrate the concept and simplify the computation, joints 4, 5 and 6 are fixed as zero-degree, and the index number is only generated from joints 1, 2 and 3 with 20-degree joint resolution. Figure 14 shows the distribution of the L1-norm on dx, dy and dz with respect to the index number (joint positions). For some cases, an index number may have entirely different degrees of Cartesian position errors along the x-, y- and z-axis. For example, the index number, 1,639 (joint 1: 0 degree; joint 2: −125 degrees; joint 3: −45 degrees), has the maximum L1-norm on dx, but a relatively small L1-norm on dy. However, this index number is on the range boundary of joint 3, and it apparently is not an operation joint position. Similarly, another L1-norm on dx whose index number is 1,556 (joint 1: −20 degrees; joint 2: 35 degrees; joint 3: −25 degrees) is not on the joint range boundaries. For this index number, dx is also relatively larger than dy.
In this paper, we have developed and presented a quantitative measure, the pseudo-index of performance (pIp), to characterize the motor capability of a robot and the speed-accuracy constraints to optimize its motor performance for performing a given task. By using the pIp, one clearly understands the motor limitation of a robot. Since the pseudo-index of performance is based on the dynamics and kinematics of a robot system with revolute joints, the derived equations of the pseudo-index of performance are applicable to other robots with revolute joints. The PUMA 560 and 260 were revolute robots and feasibly the examples to validate the pseudo-index of performance. Computer simulations and experiments on PUMA 560 and 260 industrial robots have validated the characteristics of the speed-accuracy constraint and the pIp and how the pIp is utilized to measure the motor capability of a robot system.
Conflict of Interest
The authors declare no conflict of interest.
References
- He, X.; Chen, Y. Six-degree-of-freedom haptic rendering in virtual teleoperation. IEEE Trans. Instrum. Meas. 2008, 57, 1866–1875. [Google Scholar]
- Shibata, T.; Abe, T.; Tanie, K.; Nose, M. Motion planning of a redundant manipulator based on criteria of skilled operators. Syst. Man Cybern. 1995, 4, 3730–3735. [Google Scholar]
- Asada, H.; Liu, S. Transfer of human skills to neural net robot controllers. Robot. Autom. 1991, 3, 2442–2448. [Google Scholar]
- Sandoz, P.; Ravassard, J.C.; Dembele, S.; Janex, A. Phase-sensitive vision technique for high accuracy position measurement of moving targets. IEEE Trans. Instrum. Meas. 2000, 49, 867–872. [Google Scholar]
- Likhachev, M.; Arkin, R.C. Spatio-Temporal Case-Based Reasoning for Behavioral Selection. Proceedings of Proceedings IEEE International Conference on Robotics and Automation (ICRA 2001), Seoul, Korea, 21–26 May 2001; pp. 1627–1634.
- Dahl, T.S.; Mataric, M.; Sukhatme, G.S. Adaptive Spatio-Temporal Organization in Groups of Robots. Proceedings of IEEE /RSJ International Conference on Intelligent Robots and Systems, Lausanne, Switzerland, 30 September–4 October 2002; pp. 1044–1049.
- Wu, C.H. A kinematic CAD tool for the design and control of a robot manipulator. Int. J. Robot. Res. 1984, 3, 58–67. [Google Scholar]
- Veitschegger, W.; Wu, C.H. Robot accuracy analysis based on kinematics. IEEE J. Robot. Autom. 1986, 2, 171–179. [Google Scholar]
- Spiess, S.; Vincze, M.; Ayromiou, M. On the calibration of a 6-D laser tracking system for dynamic robot measurements. IEEE Trans. Instrum. Meas. 1998, 47, 270–274. [Google Scholar]
- Wang, D.; Bai, Y. Improving Position Accuracy of Robot Manipulators Using Neural Networks. Proceedings of the IEEE Instrumentation and Measurement Technology Conference (IMTC 2005), Ottawa, ON, Canada, 17–19 May 2005; pp. 1524–1526.
- American National Standards Institute (ANSI). American National Standard for Industrial Robots and Robot Systems-Point-to-Point and Static Performance Characteristics-Evaluation; ANSI: Washington, DC, USA, 1990. [Google Scholar]
- American National Standards Institute(ANSI). American National Standard for Industrial Robots and Robot Systems-Path-Related and Dynamic Performance Characteristics-Evaluation; ANSI: Washington, DC, USA, 1992. [Google Scholar]
- Meyer, D.E.; Smith, J.E.K.; Kornblum, S.; Abrams, R.A.; Wright, C.E. Speed-Accuracy Tradeoffs in Aimed Movements: Toward a Theory of Rapid Voluntary Action. In Attention and Performance XIII; Jeannerod, M., Ed.; Psychology Press: London, UK, 1990; pp. 173–226. [Google Scholar]
- Fu, K.S.; Gonzalez, R.C.; Lee, C.S.G. Robotics: Control, Sensing, Vision, and Intelligence; Mcgraw-Hill: New York, NY, USA, 1987. [Google Scholar]
- Islam, S.; Liu, P.X. PD output feedback control design for industrial robotic manipulators. IEEE/ASME Trans. Mechatron 2011, 16, 187–197. [Google Scholar]
- Corke, P.I. Robotics Toolbox for MATLAB, Release 9(Software); CSIRO Manufacturing Science and Technology: Pinjarra Hills, Australia, 1994. [Google Scholar]
- Corke, P.I.; Armstrong-Helouvry, B. A search for consensus among model parameters reported for the PUMA 560 robot. Robot. Autom. 1994, 2, 1608–1613. [Google Scholar]
- Luh, J.Y.S.; Walker, M.W.; Paul, R.P.C. On-line computational scheme for mechanical manipulators. Trans. ASME J. Dyn. Syst. Meas. Contr. 1980, 102, 69–76. [Google Scholar]
D (m) | D/Tmt(m/sec) | |||
---|---|---|---|---|
0.0508 | 0.0508/0.392 | 0.0508/0.281 | 0.0508/0.212 | 0.0508/0.180 |
0.1016 | 0.1016/0.484 | 0.1016/0.372 | 0.1016/0.260 | 0.1016/0.203 |
0.2032 | 0.2032/0.580 | 0.2032/0.469 | 0.2032/0.357 | 0.2032/0.279 |
0.4064 | 0.4064/0.731 | 0.4064/0.595 | 0.4064/0.481 | 0.4064/0.388 |
Δm | θ̇2 | θ̇3 | θ̇4 |
---|---|---|---|
ρ2 = 2.25 | ρ2 = 4 | ρ2 = 6.25 | |
−3% | 2.2115 | 4.1868 | 6.3067 |
−2% | 2.1633 | 3.9134 | 6.3435 |
−1% | 2.2556 | 4.1400 | 6.1096 |
0% | 2.1339 | 4.0218 | 6.2426 |
1% | 2.1253 | 4.1400 | 6.1096 |
2% | 2.1066 | 3.8078 | 6.2284 |
© 2013 by the authors; licensee MDPI, Basel, Switzerland. This article is an open access article distributed under the terms and conditions of the Creative Commons Attribution license (http://creativecommons.org/licenses/by/3.0/).
Share and Cite
Lin, H.-I.; Lee, C.S.G. Measurement of the Robot Motor Capability of a Robot Motor System: A Fitts’s-Law-Inspired Approach. Sensors 2013, 13, 8412-8430. https://doi.org/10.3390/s130708412
Lin H-I, Lee CSG. Measurement of the Robot Motor Capability of a Robot Motor System: A Fitts’s-Law-Inspired Approach. Sensors. 2013; 13(7):8412-8430. https://doi.org/10.3390/s130708412
Chicago/Turabian StyleLin, Hsien-I, and C. S. George Lee. 2013. "Measurement of the Robot Motor Capability of a Robot Motor System: A Fitts’s-Law-Inspired Approach" Sensors 13, no. 7: 8412-8430. https://doi.org/10.3390/s130708412
APA StyleLin, H. -I., & Lee, C. S. G. (2013). Measurement of the Robot Motor Capability of a Robot Motor System: A Fitts’s-Law-Inspired Approach. Sensors, 13(7), 8412-8430. https://doi.org/10.3390/s130708412