6. Chapter 5: A Simple Robot Model

6.1 5.1 Introduction:

To study the motion planning problem, a simple model is required that has features found in the more complex robotic problems. Some of the features of interest in contemporary robotics are [Jack, 1989]:

Non-linear dynamics.

Redundant kinematics.

Objectives like,

minimum time,
shortest path,
least energy,
proximity to obstacles.

Trajectory constraints like,

kinematic limits of position, velocity, acceleration and jerk,
dynamic limits, like joint torque limits.

Motion constraints like,

collision avoidance,
compliance of forces and motions,
moving obstacles,
coordination of multiple robots,
task constraints.

Almost all multiple link manipulators have non-linear dynamics. Thus, their dynamic properties change, as the robot configuration changes. Redundant kinematics describe a case in which the robot has an infinite number of configurations to reach a point in the work space. Semi-redundant kinematic solutions have more than a single robot configuration to reach points in the workspace (e.g., a point could be reached with the elbow up, or down). The motion and trajectory constraints are a result of the combined effects of the work space, robot and task. The objectives determine the important factors when considering alternate motions and trajectories for the robot.

Many of the objectives and constraints will not be examined in this thesis, but can be considered in future work. This work must serve to provide a proof of concept, to show that the neural network is capable of handling a simple robot case.

6.2 5.2 The Selected Manipulator Case:

At least two links are required for a complete analysis of the robot motion planing problem. This is because the one link manipulator is simple and uncoupled, thus it lends itself to direct optimization. The simplifications for a one link case make extension to more complex robots very difficult. It has also been decided to use a robot with two revolute joints (rotary), as opposed to prismatic joints (sliding). This guarantees the non-linearity of the dynamics.

The links will be considered to have mass and moments of inertia, as if they were slender rods. Thus, given a set of mass properties for the links, dynamics may be considered. The use of slender rods makes the moment of inertia calculation very simple. The manipulator will not have a payload for this thesis, but provisions have been made for its addition in future work.

 

Figure 6.1 Figure 5.1: A Simple Planar Two Link Manipulator (with payload)

All motion plans considered in this thesis will be formulated with the objective of finding the least time paths. The maximum velocity, and maximum acceleration constraints will be considered separately, in the two initial test cases. The final test case will involve maximum torque limit constraints. The constraints that will not be considered are collision avoidance, motion and force compliance, moving obstacles, multiple robot coordination, and task constraints.

The robot will be assumed to have sensors at the joints to feed back positions. This is a reasonable assumption, and has been found to be an important feedback in many intelligent systems, like humans [Gibbons, et. al., 1988][Kawato, et. al., 1987]. If the velocities of the joints are required, the position feedbacks may be differentiated. If acceleration is required, then the position feedback may be differentiated twice. Since more exotic sensors are not very practical now, they will not be assumed.

The actuators will be assumed to have the same properties regardless of direction, velocity, and position during rotation (i.e., linear actuators). Even though most actuators are not linear, this assumption makes it possible to deal with the problems in a simple manner. In a non-linear actuator, it is possible that the torque, velocity and acceleration limits may change.

It was decided to make the robot ‘bulky’ with weak actuators, so that time optimum paths would be a reasonable research issue. The parameters used were taken from Rajan [1985] and are l1 = l2 = 0.5m, m1 = 50kg, m2 = 30kg, I1 = 1.04kg.m2, I2 = 0.625 kg.m2, with joint torque limits of 10 Nm each. The actuator position limits were chosen to be θ1max = θ2max = 180.0°, and θ1min = θ2min = -180.0°. For demonstration purposes, the absolute maximum velocities and accelerations for both the joints were arbitrarily set at 10°/sec.

There are some supplementary references that may be consulted for more detailed descriptions of the theory of this problem. Brady et. al. [1982] is a good general reference for all aspects of the 2 degree of freedom manipulator, including dynamics, control and trajectory planning. Fu, Gonzalez and Lee [1987] discuss dynamics, and other basic robotics theory.

6.3 5.3 Kinematics and Dynamics of a Two Link Manipulator:

Kinematics is the first concern of all robot models. Kinematic constraints include limits on joint positions, velocities, and accelerations, based upon the physical configuration of the manipulator. As mentioned before (in robot motion planning), the velocity, acceleration, and jerk constraints are based on approximations. The approximations are derived from the dynamic and actuator limits. The kinematic and dynamic equations for the two link manipulator are shown below. The dynamic equations assume that there is gravity, and a payload, but later in the thesis these are both been set to zero.

The kinematic equations allow the location of the end effector in space, based upon the joint configuration of the two link robot. The variables in these equations are shown in the schematic of the robot.

 

Figure 6.2 Figure 5.2: Forward Kinematics (derived in Appendix A)

The inverse kinematics equations determine the joint angles required to position the end effector at a particular position in space. This particular problem results in two concurrent solutions, commonly called ‘Elbow-up’ and ‘Elbow-down’.

 

Figure 6.3 Figure 5.3: Inverse Kinematics (elbow up).

The inverse kinematics solution is undefined here if the end effector position in space is at the origin, or more than ‘l1 + l2’ away from the origin. These equations are explained in detail in Appendix A.

 

Figure 6.4 Figure 5.4: Inverse Kinematics (elbow down)

The dynamic equations are more complicated than the kinematics, and use a full description of the dynamic properties of the manipulator. The equations are displayed below in algorithmic form, and also in closed form equations. The algorithmic descriptions are in three parts; the forward dynamics, the inverse dynamics, and a set of constants (which are common to both the forward and inverse dynamics). These equations have been given (and derived in Appendix B) this way to ease computational complexity.

Dynamic equations are often expressed in the form,

Where Q, is the joint torques and forces and G(θ) is the gravity term. C(θ, θ') covers the coriolis and centrifugal forces involved. And, finally, M(θ)θ'' is used for the inertial terms. These different terms may be seen by examining the equations in figure 5.8. The inertial terms are all multiplied by θ''. The gravity terms are easy to identify because they have the gravity constant ‘G’ included. All the centrifugal and coriolis terms may be identified by the θ' term. To describe these for the algorithmic approach is more difficult, thus it will not be done.

 

Figure 6.5 Figure 5.5: Common Constants for Dynamics Equations (Algorithmic).

 

Figure 6.6 Figure 5.6: Equations for Inverse Dynamics (Algorithmic).

 

Figure 6.7 Figure 5.7: Equations for Forward Dynamics (Algorithmic).

The dynamic equations are shown below in closed form. As can be seen, these equations are quite extensive, and thus were derived with Macsyma, as described in Appendix B. The equations are seen on the next pages as closed form equations.

 

Figure 6.8 Figure 5.8: Equations for Inverse Dynamics (Closed Form).

 

Figure 6.9 Figure 5.9: Equations for Forward Dynamics (Closed Form Joint 2).

 

Figure 6.10 Figure 5.10: Equations for Forward Dynamics (Closed Form Joint 1)

Examination of the closed form solutions shows that all the equations for joint accelerations (θ''1 and θ''2) include both joint torques. This is a clear indication of the coupling between joints. The general dynamic equation of the manipulator may be rewritten (from equation 5.1),

This form shows that the denominators in the Forward Dynamic equations have meaning. The equations have not been fully simplified, therefore the terms in the expression are harder to identify. They may still be recognized by the presence of ‘θ’ terms for the coriolis and centripetal terms, ‘τ’ for the torque and force terms, and ‘G’ terms for the gravity. The inertial terms are related to the denominator of the equations. (For future reference notice that ‘τ1’ and ‘τ2’ are both linear in the equations shown in figures 5.9 and 5.10)

6.4 5.4 Optimal Motion Plans for a Two Link Manipulator:

Kinematic path planners will be the first to be explored, because of their simplicity. These path planners use estimates of the maximum velocity, or acceleration, to choose the optimal path. The approximation of maximum velocity and acceleration will allow the torque limits to be ignored. Thus, the joints may be dealt with independently. Since this is the case, the motion of individual joints may be easily described with velocity profiles. The area under the velocity profile curve will be the joint displacement.

 

Figure 6.11 Figure 5.11: A Sample Velocity Profile

The fundamental problem of planning a motion involves constructing a velocity curve with a fixed area, which observes motion limits. The limits for the curve (i.e., slopes, heights, areas, etc.) are prescribed by the kinematic motion limits. Thus, this curve may be constructed in several ways, as long as limits are observed.

The problem of optimal path planning is more complex, when objectives are also applied to the curve shape, besides the constraints. Some practical objectives for motion planning are,

least time,

least time and shortest path,

least time and energy,

shortest path and least energy,

least energy, time and shortest path.

The least time method was chosen for two reasons. Most production facilities will focus on higher production rates, with short cycle times. Also, a robot that is designed to run at its optimum will cost less than a robot that is over-designed for the same task.

It was stated in an earlier chapter (2), “As a result of the Maximum principle, we know that the solution for the time optimal problem in which a control term appears linearly in the dynamics equation is of a bang-bang type,” [Yamamoto and Mohri, 1989]. Thus, since the dynamic equations do have a linear appearance of the torque terms, bang-bang control will be time optimal (for a prescribed path). This means that at least one joint must be at full torque at any one time for optimal trajectories. Since this only applies to optimal trajectories, this condition does not guarantee globally optimal motion. As will be discussed later, some motions can obtain times faster than simple bang-bang control, by altering the path to reduce dynamic effects.

Figure 6.12 5.5 A Discrete Time Step Motion Planner/Controller:

Neural networks require a discrete time step for calculation. This becomes important when they are incorporated into a real-time system that is continuous in the time domain. This feature implies some constraints on the solution of the motion planning/control problem. The first constraint is that the time step constraint will dictate that all paths be broken into an integer number of steps (based on the controller calculation times). This requirement may lead to a motion which is slightly sub-optimal. If the time step is fine enough, then the motion plan will approach the continuous optimal case. The second constraint is, planner/controller inputs and outputs. These can create a dependance of the planner/controller performance on the time step duration.

 

Figure 6.13 Figure 5.12: Block Diagram of Discrete Time Step Motion Planning/Control

A planner or controller architecture calls for a careful choice of a control (output) variable. The common choices are,

Position,

Velocity,

Acceleration,

Torque.

These control variables will determine which capacity the controller is used in, and what is required to determine the value of the control variable.

The choice of output variables will determine the controller input variables. Some common input variables are,

joint positions,

goal positions,

joint velocities,

joint accelerations,

joint error (distance to goal position),

joint torques.

Different combinations of these inputs will determine how the planner/controller is to be structured internally. Position and velocity describe the system state, and as a result should generally be used for any motion planner/controller considering non-linear dynamics. Acceleration may be used as a controller input, but is not always essential unless considering jerk.

Specifying a target for motion is important for controllers. To simplify the target to the neural network, position error will be used as an input. Note that the error for the controller is the difference between the current and target positions. If the goal position was the input, then the neural network would be required to do some additional mathematical operations to determine to distance to the goal.

There are three very basic cases for motion planning/ control strategies. The three cases are based on a particular output, and the inputs required to produce them.

Torque output requires position, velocity, and error inputs,

Acceleration output requires velocity and error inputs,

Velocity output requires error inputs.

The three cases above will be explored in this thesis. There are more sophisticated forms of controllers, but these cases allow examination of fundamental problems.

6.5 5.6 A Comparative Case for The Optimal Motion:

The manipulator described before was also used by Rajan [1985] for optimal path planning with torque constraints. He found that, for a path from 0 to 180 degrees for joint 1, and no motion for joint 2, the motion took 7.38 seconds. In another example, the arm bent into a lower inertia configuration during motion, and the same path took 4.37 seconds. These results provide a basis for comparison, and show the complex nature of the path planning problem.

A sample of a motion (generated by the optimal motion routines developed in this thesis) is given in figure 5.13. This is done to give the reader a perspective on the discussion of this chapter. The sample of a near-optimal path is shown below, in graphical form. The graphs display both joint positions and torques along the near optimal path.

 

Figure 6.14 Figure 5.13: Robot Motion Over a Sample, Near-Optimal Torque Path

The reader should note the torque curves have assumed an ‘approximate bang-bang’ configuration for joint 1. The derivation of this motion will be described in more detail later, when the algorithms are described.

6.6 5.7 Summary:

The details of the manipulator described in this chapter are outlined in this summary. This is done because of the importance of these particular details to the remainder of the work. The first list is the physical parameters of the robot, to be followed by the test cases to be used for the thesis. The final list is in a summary of major points in this chapter.

 

 

Many objectives and constraints for formulation of motions.

A robot model has been chosen that can be expanded to more complex problems.

For kinematic motion planning, velocity profiles may be needed for path planning.

For Dynamic motion planning, bang-bang control will guarantee optimal motion along a specified path.

Discrete time step control will effect the control of the robot.

The inputs and outputs of Planners/Controllers are related.

An optimal path case is given for comparison of dynamics results.