# Automation and Robotics

Class of Professor Khalid and Frazer

282.762 Robotics and Automation - Each student should take 2 hour(s) of Lecture(s) and 2 hour(s) of Laboratory Class(es) per week.

  1. [JJCraig]('../../Resources/Introduction - jj craig.pdf')

  2. Vector Math for 3D Computer Graphics

  3. Latex - MathJax

  4. Summary of trigonometric identities

  5. Coordinate systems and frames of reference

  6. Cross-Platform Application Development with OpenCV 4 and Qt 5

  7. JJ Craig Book

  8. Eigen C++ Library for Matrices

TIP

Very Good link for inverse kinematics of 3-link Manipulator

TIP

Good video on 3DoF manipulator, here

# Flip Cards

# 1. Lecture 1 - 24/02/2020

WARNING

Go to and install:

https://github.com/DrFrazerNoble/machine_vision_tutorials

# Definition of a robot:

The term “Industrial Robot” is defined by ISO 8373:2012 [3] as: An automatically controlled, reprogrammable, multipurpose manipulator programmable in three or more axes, which can be either fixed in place or mobile for use in industrial automation applications.


The terms used in the definition are explained below:

  • Reprogrammable: the robot is designed so that the programmed motions can be changed without physical alterations.

  • Multipurpose: the robot is capable of being adapted to a different application with physical alteration.

  • Physical alteration: alteration of the mechanical system.

  • Axis: direction used to specify the robot motion in a linear or rotary mode.

# Look for these Books

Isaac Asimov

# Important point in history

  • In 1969, GM (USA) used Unimate robots for spot-welding, the Stanford Research Institute (USA) demonstrated the use of machine vision for mobile robot navigation, and Hitachi (Japan) developed the world’s first vision-based, fully-automatic, intelligent assembly robot [4].

# Description of Position and Orientation

In the study of robotics, we are concerned with the location of objects in three-dimensional space.

These objects are the manipulator’s links, the parts and tools it deals with, and objects in the manipulator’s workspace.

In order to describe the position and orientation of a body, we attach a coordinate system, or frame, rigidly to the object.

The position and orientation of the frame is then described with respect to some reference coordinate system.

Any frame can serve as a reference system within which to express the position and orientation, so we often think of transforming or changing the description of these attributes from one frame to another.



# Forward Kinematics of Manipulators

Kinematics is the science of motion that treats motion without regard to the forces that cause it. Within kinematics, position, velocity, and acceleration are studied.

The study of kinematics of manipulators refers to all the geometrical and time-based properties of the motion.

Manipulators consist of nearly rigid links, which are connected via joints that allow relative motion of neighbouring links.

These joints are usually instrumented with position sensors, which allow the relative position of neighbouring links to be measured.

The number of degrees of freedom that a manipulator has is the number of independent position variables that would have to be specified in order to locate all parts of the the manipulator.



At the end of the manipulator is the end-effector. Depending on the robot, the end-effector could be a gripper, a welding torch, a magnet, or a sensor.

The position of the manipulator is usually described by giving a tool frame, which is defined relative to a base frame.

A very basic problem in the study of the manipulator is called forward kinematics. This is the static geometrical problem of computing the position and orientation of the end-effector of the manipulator.

# Inverse Kinematics of Manipulators

The inverse kinematics problem can be summarised as: ”Given the position and orientation of the end-effector of the manipulator, calculate all possible sets of joint angles that could be used to attain this given position and orientation” [9].

This is a rather complex geometrical problem and is not as simple as the forward kinematics one.

Because kinematic equations are non-linear, their solution is not always easy (or possible) in a closed form.

Also, questions about the existence of a solution and about multiple solutions arise.



# Velocities, Static Forces, and Singularities

In addition to dealing with static positioning problems, it may also be necessary to analyse manipulators in motion.

When performing velocity analysis of a mechanism, it is convenient to define a matrix quantity call the Jacobian of the manipulator.

The Jacobian specifies the mapping from velocities in joint space to velocities in Cartesian space.

At certain points, called singularities, this mapping is not invertible.



# Dynamics

Dynamics is a huge field of study dedicated to studying the forces required to cause motion.

In order to accelerate a manipulator from rest, move at a constant end-effector speed, and finally decelerate to a stop, a complex set of torque functions must be applied to the manipulator’s joints.

One method of controlling a manipulator is calculating the actuators’ torques using the dynamic equations of motion of the manipulator.

# Trajectory Generation

A common way of causing a manipulator to move from one point to another in a smooth, controlled fashion is to cause each joint to move via a smooth function of time.

Commonly, each joint starts and ends its motion at the same time. Exactly how to compute these motion functions is a problem of trajectory generation.

Often a path is specified using intermediate points, or via points, and a spline is used for a smooth function that passes through the set points.

In order for the end-effector to follow a path through space, the desired motion needs to be converted to an equivalent set of joint motions. This is Cartesian trajectory generation.



# Manipulator Design and Sensors

Although manipulators are, in theory, universal devices applicable to many situations, economics generally dictates that the intended task domain influence the mechanical design of the manipulator.

Along with issues such as size, speed, and load capability, the designer must also consider the number of joints and geometric arrangement.

These considerations affect the manipulator’s workspace, size and quality, the stiffness of the manipulator structure, and other attributes.

In order to build a useful robot, two approaches can be taken:

  1. Build a specialized robot. This robot works on a specific task.
  2. Build a universal robot. This robot would be able to work on a variety of tasks.

# Linear Position Control

Some manipulators are equipped with stepper motors that can execute a desired trajectory directly.

However, the majority of manipulators are driven by actuators that supply a force or torque to cause motion in the links.

In this case, an algorithm is needed to compute torques that will cause the desired motion.

A primary concern of a position control system is to compensate automatically for errors and to suppress disturbances that perturb the system.

To achieve this, position and velocity sensors are used by the control algorithm, which computes the torque commands for the actuators.



# Non-linear Position Control - outside of the scope very advanced

Although control systems based on approximate linear models are popular, it is important to consider the complete non-linear dynamics of the manipulator when synthesizing control algorithms.

Some industrial robots are now being introduced that make use of non-linear control algorithms in their controllers.

# Force Control - outside of the scope very advanced

The ability for a manipulator to control forces of contact when it touches parts, tools, or work surfaces is of importance in applying manipulators to real-world tasks.

Force control is complementary to position control. When a robot is moving in free space, only position control is useful (there’s no surface to touch); when touching a surface, position control could lead to excessive forces at the point of contact, or no contact at all.

Therefore, a hybrid control approach is required with some movements governed by a position-control law, others by a force-control law.

# Programming Robots

A robot programming language serves as the interface between the human user and the industrial robot.

In typical robot systems, there is a shorthand way for a human user to instruct the robot which path it is to follow.

First, a special point of the grasped tool is specified as the operational point, also called the Tool Centre Point (TCP)

Motions of the robot will be described by the user in terms of the desired location of the TCP relative to a user-specified coordinate system.

Most often paths are created from via points. Via points are specified relative to the reference coordinate system and denote locations along the path the TCP should pass through.

In addition, the user may specify the speed the TCP travels at.

# Off-line Programming and Simulation

”An off-line programming system is a robot programming environment that has been sufficiently extended, generally by means of computer graphics, that the development of robot programs can take place without access to the robot itself” [9].

The advantage of off-line programming is that it does not case production equipment, i.e. the robot, to be tied up when it needs to be reprogrammed; hence, factories can stay in production for longer.

Off-line programming tools also enable the use of computer aided design (CAD) models to model the robot’s work-space, ”dramatically reducing programming time required for the manufacturing process” [9].



# Notation

We use the notation outlined in [9]:

  1. Usually, variables written in upper-case represent vectors or matrices. Lower case variables are scalars.

  • Vector: PP

  • Scalar: pp

  1. Leading sub- and super-scripts identify which coordinate system a quantity is written in. For example, AP^A P represents a position vector written in coordinate system A.

  • Position vector PP written in the coordinate system AA: AP^A P

  1. Trailing super-scripts are used for indicating the inverse or transpose of a matrix.

  • Inverse: R1R^{−1}

  • Transpose: RTR^T

  1. Trailing sub-scripts are not subject to any strict convention, but may indicate a vector component (e.g. x,y,x, y, or zz).

  • Vector component: Xx,XyX_x, X_y and XzX_z or Yx,YyY_x, Y_y and YzY_z

  1. Our notation for the cosine of an angle θ1θ_1 may take the following forms:

  • cosθ1=cθ1=c1cosθ_1 = cθ_1 = c_1.

Vectors are taken to be column vectors; hence, row vectors will have the transpose indicated explicitly.

# In today’s lecture, we have:

  • Defined what an industrial robot is.
  • Provided some background.
  • Described the mechanics and control of mechanical manipulators.
  • Described the notation used.

# 2. Lecture 2

# Descriptions: Positions, Orientations, and Frames

A description is used to specify attributes of various objects with which a manipulation system deals with. Objects include tools, parts, and the manipulator itself.

Here, we are interested in the description of positions, orientations, and frames.

# Description of Position


Once a coordinate system is established, any point in the universe can be located with a 3x1 position vector.


In order to make it clear what coordinate system vectors are defined with, a leading superscript will be used, e.g. AP^AP.


This means the components of AP^AP have numerical values that indicate distances along the axes of {A}\{A\}.


The individual elements of a vector are given the trailing subscripts x, y, and z.


AP=[PxPyPz](1)^AP= \begin{bmatrix} P_x\\ P_y\\ P_z\\ \end{bmatrix} \qquad(1)



# Description of Orientations


Often it is necessary to describe the orientation of a body in space.

For example, if AP^AP locates the origin of a manipulator's end-effector, the complete location of the end-effector is not specified until its orientation is given.

In order to describe the orientation of a body, we will attach a coordinate system to the body and then give a description of this coordinate system relative to the reference system.

Given {A}\{A\}, if {B}\{B\} is attached to a body, then a description of {B}\{B\} relative to {A}\{A\} is sufficient to give the orientation of the body.



One way to describe the body-attached coordinate system, {B}\{B\}, is to write the unit vectors of the principal axes in terms of the coordinate system {A}\{A\}.


The unit vectors giving the principal directions of coordinate system {B}\{B\} are denoted as X^B\hat X_B, Y^B\hat Y_B, and Z^B\hat Z_B.


When written in terms of the coordinate system {A}\{A\}, they are called AX^B^A\hat X_B, AY^B^A\hat Y_B, and AZ^B^A\hat Z_B.


It is convenient to stack these three unit vectors as columns of a 3x3 matrix, in the order AX^B^A\hat X_B, AY^B^A\hat Y_B, and AZ^B^A\hat Z_B.


This is called the rotation matrix and describes {B}\{B\} relative to {A}\{A\}.


It is denoted BAR_B^A R:


BAR=[AX^BAY^BAZ^B]=[r11r12r13r21r22r23r31r32r33](2)_B^A R = \begin{bmatrix} ^A \hat X_B & ^A \hat Y_B & ^A \hat Z_B \\ \end{bmatrix} = \begin{bmatrix} r_{11} & r_{12} & r_{13} \\ r_{21} & r_{22} & r_{23} \\ r_{31} & r_{32} & r_{33} \\ \end{bmatrix} \qquad(2)


We can give expressions for the scalars rijr_{ij} by noting that the components of any vector are simply the projections of that vector onto the unit directions of its reference frame.


Each component of BAR_B^A R can be written as the dot product of a pair of unit vectors:


BAR=[AX^BAY^BAZ^B]=[X^B.X^AY^B.X^AZ^B.X^AX^B.Y^AY^B.Y^AZ^B.Y^AX^B.Z^AY^B.Z^AZ^B.Z^A](3)_B^A R = \begin{bmatrix} ^A \hat X_B & ^A \hat Y_B & ^A \hat Z_B \\ \end{bmatrix} = \begin{bmatrix} \hat X_B . \hat X_A & \hat Y_B . \hat X_A & \hat Z_B . \hat X_A \\ \hat X_B . \hat Y_A & \hat Y_B . \hat Y_A & \hat Z_B . \hat Y_A \\ \hat X_B . \hat Z_A & \hat Y_B . \hat Z_A & \hat Z_B . \hat Z_A \\ \end{bmatrix} \qquad(3)


The dot product of two unit vectors yields the cosine of the angle between them and, as such, are often referred to as the direction cosines.


The rows of the matrix BAR_B^A R are the unit vectors of {A}\{A\} expressed in {B}\{B\}; that is,


BAR=[AX^BAY^BAZ^B]=[BX^ATBY^ATBZ^AT](4)_B^A R = \begin{bmatrix} ^A \hat X_B & ^A \hat Y_B & ^A \hat Z_B \\ \end{bmatrix} = \begin{bmatrix} ^B \hat X_A^T\\ ^B \hat Y_A^T\\ ^B \hat Z_A^T\\ \end{bmatrix} \qquad(4)


Hence, ABR_A^B R, the description if {A}\{A\} relative to {B}\{B\}, is given by the transpose of BAR_B^A R; that is,


ABR_A^B R == BA_B^ART(5)R^T\qquad(5)


This suggests that the inverse of a rotation matrix is equal to is transpose,


BART_B^A R^T BAR=[AX^BTAY^BTAZ^BT][AX^BAY^BAZ^B]=I3(6)_B^A R= \begin{bmatrix} ^A \hat X_B^T\\ ^A \hat Y_B^T\\ ^A \hat Z_B^T\\ \end{bmatrix} \begin{bmatrix} ^A \hat X_B & ^A \hat Y_B & ^A \hat Z_B \\ \end{bmatrix} = I_3 \qquad(6)


where I3I_3 is the 3x3 identity matrix. Hence,


BAR_B^A R == ABR1_A^B R^{-1} == ABRT(7)_A^B R^T \qquad(7)


# Description a Frame


Descriptions of position and orientation completely specify the whereabouts of a body.


The point on the body whose position described can be chosen arbitrarily. However, for convenience, the point we will describe is chosen at the origin of the body-attached coordinate frame.


The situation of a position and orientation pair arises so often that we define an entity called a frame, which is a set of four vectors giving position and orientation.


For example, frame {B}\{B\} is described by BAR^A_BR and APBORG^AP_{BORG}, where APBORG^AP_{BORG} is the vector that locates the origin of frame {B}\{B\}:


{B}=\{B\} = {BAR,APBORG}(8)\{^A_BR, ^AP_{BORG}\}\qquad(8)



A frame can be used as as description of one coordinate system relative to another.


A frame encompasses two ideas by representing both position and orientation and can be thought of as a generalization of those two ideas.


Positions can be represented by a frame whose rotation-matrix part is the identity matrix, and an orientation can be represented by a frame whose position-vector part is a zero vector.


# Mappings Involving Translated Frames


Being able to describe position and orientation, we are now interested in the mathematics of mapping in order to change descriptions from frame to frame.


Consider a point defined by vector BP^BP. We want to express this point in terms of frame {A}\{A\}, when frames {A}\{A\} and {B}\{B\} have the same orientation.


In this case, {B}\{B\} differs from {A}\{A\} only by a translation, which is given by APBORG^AP_{BORG} , the vector that locates the origin on {B}\{B\} relative to {A}\{A\}.


Because both vectors are defined relative to frames with the same orientation, point PP relative to {A}\{A\}, AP^AP, can be calculated by vector addition:


A(BP)=^A(^BP) = BP+APBORG(9)^BP + ^AP_{BORG}\qquad(9)


or,


AP=^AP = BP+APBORG(9)^BP + ^AP_{BORG}\qquad(9)



The idea of mapping, or changing the description from one frame to another, is important.


The quantity itself is not changed; only its description is changed.


For translation, the vector APBORG^AP_{BORG} defines the mapping because all the information needed to perform the change in description is contained in APBORG^AP_{BORG}.


# Mappings Involving Rotated Frames


Orientation can be described by three unit vectors denoting the principal axes of a body-attached coordinate system. Stacking these unit vectors as the columns of a 3x3 matrix, we have the rotation matrix. If a rotation matrix describes {B}\{B\} relative to {A}\{A\}, then it is denoted by BAR^A_BR.

A property of the rotation matrix is that:


BAR_B^A R == ABR1_A^B R^{-1} == ABRT(7)_A^B R^T \qquad(7)



Therefore,


BAR=[AX^BAY^BAZ^B]=[BX^ATBY^ATBZ^AT](4)_B^A R = \begin{bmatrix} ^A \hat X_B & ^A \hat Y_B & ^A \hat Z_B \\ \end{bmatrix} = \begin{bmatrix} ^B \hat X_A^T\\ ^B \hat Y_A^T\\ ^B \hat Z_A^T\\ \end{bmatrix} \qquad(4)


Consider a point defined by vector BP^BP. We want to express this point in terms of {A}\{A\}, where the origin of frames {A}\{A\} and {B}\{B\} are coincident.

In this case, {B}\{B\} differs from {A}\{A\} only by a rotation, which defined by BAR^A_BR.



In order to calculate AP^AP, the components of any vector are simply the projections of that vector onto the unit directions of its frame.

The projection is calculated using the vector dot product.


APx=^AP_x = BX^A.^B \hat X_A . BP^BP\\ APy=^AP_y = BY^A.^B \hat Y_A . BP^BP\\ APz=^AP_z = BZ^A.^B \hat Z_A . BP^BP


In order to express this in terms of the rotation matrix, it can be written as:


AP=^AP = BAR^A_BR BP(13)^BP\qquad(13)


For rotation, the rotation matrix BAR^A_BR defines the mapping because all the information needed to perform the change is description is contained in BAR^A_BR


The notation that we have used is of great help in keeping track of mappings and frames of reference.


A helpful way of viewing the notation we have used is to imagine that leading subscripts cancel the leading superscripts.

TIP

Given that, BAR^A_B R BP=^BP = AP^AP , we can cancel

ABRBP=^A\cancel{_B R ^B}P= AP^AP


Often we known the descriptions of a vector with respect to some frame, e.g. {B}\{B\}, and would like to know its description with respect to another frame, e.g. {A}\{A\}.


Let us consider the general case of mapping. Here, the origin of {B}\{B\} is not coincident with that of frame {A}\{A\}, but has a general vector offset, i.e. is translated.


Also, {B}\{B\} is rotated with respect to {A}\{A\}, as described by BAR^A_B R


Given BP^BP, we want to know AP^AP.



# Mappings Involving General Frames


We can first change BP^BP to its description relative to an intermediate frame that has the same orientation as {A}\{A\}, but whose origin is coincident with {B}\{B\}. This is done by pre-multiplying by BAR^A_BR. The translation of origins is accounted by simple vector addition.


The resulting rotation and translation is given by:


AP=^AP = BAR^A_BR BP+APBORG(14)^BP + ^AP_{BORG} \qquad(14)


This is the general transformation mapping of a vector from its description in one frame to another.


The mapping of a vector from one frame to another can be described as an operator in matrix form,


AP=^AP = BAT^A_BT BP(15)^BP\qquad(15)


This aids in writing compact equations and is conceptually clearer.

In order to write the mathematics of the general transformation in the matrix form, we define a 4x4 matrix and use 4x1 position vectors, so that is has the structure:


[AP1]=[BARAPBORG0001][BP1](16)\begin{bmatrix} ^AP \\ 1 \end{bmatrix} = \begin{bmatrix} \begin{array}{ccc|c} & ^A_BR && ^AP_{BORG} \\ \hline 0 & 0 & 0 & 1 \end{array} \end{bmatrix} \begin{bmatrix} ^BP \\ 1 \end{bmatrix}\qquad(16)


Multiplying the matrix, we see:


AP=BARBP+APBORG1=1(17)\begin{matrix} \begin{array}{ccc} ^AP = & ^A_BR ^BP & + & ^AP_{BORG} \end{array}\\\\ \begin{array}{c} 1 = 1 \end{array} \end{matrix} \qquad(17)


The 4x4 matrix is called a homogeneous transform.


For our purposes, it can be regarded purely as a construction used to cast the rotation and translation of the general transform into a single matrix form.


Just as rotation matrices can be used to specify orientation, transforms can be used to specify a frame.


The description of frame {B}\{B\} relative to {A}\{A\} is BAT^A_BT.


In today's lecture, we have:


  • Discussed descriptions of position, orientation, and frames.
  • Discussed mappings involving translation, and rotation.
  • Discussed mappings involving general frames.

# Exercises Lecture 2

Given:



And considering the position with a capital letter and a superscript AA such as:


AP=[APxAPyAPz](1)^AP= \begin{bmatrix} ^AP_x\\ ^AP_y\\ ^AP_z\\ \end{bmatrix} \qquad(1)



AP=[APxAPyAPz]=[420]BP=[BPxBPyBPz]=[310]CP=[CPxCPyCPz]=[240]^AP = \begin{array}{ccc} \begin{bmatrix} ^AP_x\\ ^AP_y\\ ^AP_z\\ \end{bmatrix} = & \begin{bmatrix} 4\\ 2\\ 0\\ \end{bmatrix} & ^BP = \begin{bmatrix} ^BP_x\\ ^BP_y\\ ^BP_z\\ \end{bmatrix} = & \begin{bmatrix} 3\\ -1\\ 0\\ \end{bmatrix} & ^CP = \begin{bmatrix} ^CP_x\\ ^CP_y\\ ^CP_z\\ \end{bmatrix} = & \begin{bmatrix} 2\\ -4\\ 0\\ \end{bmatrix} \end{array}



AQ=[AQxAQyAQz]=[620]BQ=[BQxBQyBQz]=[510]CQ=[CQxCQyCQz]=[440]^AQ = \begin{array}{ccc} \begin{bmatrix} ^AQ_x\\ ^AQ_y\\ ^AQ_z\\ \end{bmatrix} = & \begin{bmatrix} 6\\ 2\\ 0\\ \end{bmatrix} & ^BQ = \begin{bmatrix} ^BQ_x\\ ^BQ_y\\ ^BQ_z\\ \end{bmatrix} = & \begin{bmatrix} 5\\ -1\\ 0\\ \end{bmatrix} & ^CQ = \begin{bmatrix} ^CQ_x\\ ^CQ_y\\ ^CQ_z\\ \end{bmatrix} = & \begin{bmatrix} 4\\ -4\\ 0\\ \end{bmatrix} \end{array}



AR=[ARxARyARz]=[640]BR=[BRxBRyBRz]=[510]CR=[CRxCRyCRz]=[420]^AR = \begin{array}{cccccc} \begin{bmatrix} ^AR_x\\ ^AR_y\\ ^AR_z\\ \end{bmatrix} = & \begin{bmatrix} 6\\ 4\\ 0\\ \end{bmatrix} & ^BR = \begin{bmatrix} ^BR_x\\ ^BR_y\\ ^BR_z\\ \end{bmatrix} = & \begin{bmatrix} 5\\ 1\\ 0\\ \end{bmatrix} & ^CR = \begin{bmatrix} ^CR_x\\ ^CR_y\\ ^CR_z\\ \end{bmatrix} = & \begin{bmatrix} 4\\ -2\\ 0\\ \end{bmatrix} \end{array}



APBORG=[APBORGxAPBORGyAPBORGz]=[130]BPCORG=[BPCORGxBPCORGyBPCORGz]=[130]^AP_{BORG} = \begin{array}{ccc} \begin{bmatrix} ^AP{_{BORG}}_x\\ ^AP{_{BORG}}_y\\ ^AP{_{BORG}}_z\\ \end{bmatrix} = & \begin{bmatrix} 1\\ 3\\ 0\\ \end{bmatrix} & ^BP_{CORG} = \begin{bmatrix} ^BP{_{CORG}}_x\\ ^BP{_{CORG}}_y\\ ^BP{_{CORG}}_z\\ \end{bmatrix} = & \begin{bmatrix} 1\\ 3\\ 0\\ \end{bmatrix} \end{array}



A(BP)=^A(^BP) = BP+APBORG(9)^BP + ^AP_{BORG}\qquad(9)



A(BP)=^A(^BP) = BP+^BP + APBORG=[310]+[130]=[420]AP_{BORG}= \begin{bmatrix} 3\\ -1\\ 0\\ \end{bmatrix} + \begin{bmatrix} 1\\ 3\\ 0\\ \end{bmatrix} = \begin{bmatrix} 4\\ 2\\ 0\\ \end{bmatrix}



A(BQ)=^A(^BQ) = BQ+^BQ + APBORG=[510]+[130]=[620]AP_{BORG}= \begin{bmatrix} 5\\ -1\\ 0\\ \end{bmatrix} + \begin{bmatrix} 1\\ 3\\ 0\\ \end{bmatrix} = \begin{bmatrix} 6\\ 2\\ 0\\ \end{bmatrix}



A(BR)=^A(^BR) = BR+^BR + APBORG=[510]+[130]=[640]AP_{BORG}= \begin{bmatrix} 5\\ 1\\ 0\\ \end{bmatrix} + \begin{bmatrix} 1\\ 3\\ 0\\ \end{bmatrix} = \begin{bmatrix} 6\\ 4\\ 0\\ \end{bmatrix}



B(CP)=^B(^CP) = CP+^CP + BPCORG=[240]+[130]=[310]^BP_{CORG}= \begin{bmatrix} 2\\ -4\\ 0\\ \end{bmatrix} + \begin{bmatrix} 1\\ 3\\ 0\\ \end{bmatrix} = \begin{bmatrix} 3\\ -1\\ 0\\ \end{bmatrix}



B(CQ)=^B(^CQ) = CQ+^CQ + BPCORG=[440]+[130]=[510]^BP_{CORG}= \begin{bmatrix} 4\\ -4\\ 0\\ \end{bmatrix} + \begin{bmatrix} 1\\ 3\\ 0\\ \end{bmatrix} = \begin{bmatrix} 5\\ -1\\ 0\\ \end{bmatrix}



B(CR)=^B(^CR) = CR+^CR + BPCORG=[420]+[130]=[510]^BP_{CORG}= \begin{bmatrix} 4\\ -2\\ 0\\ \end{bmatrix} + \begin{bmatrix} 1\\ 3\\ 0\\ \end{bmatrix} = \begin{bmatrix} 5\\ 1\\ 0\\ \end{bmatrix}


# We can calculate the Dot Product of two vectors this way:


ab=a×b×cos(θ)a · b = |a| × |b| × cos(θ)


Where:

a|a| is the magnitude (length) of vector aa

b|b| is the magnitude (length) of vector bb

θθ is the angle between aa and bb


So we multiply the length of a times the length of b, then multiply by the cosine of the angle between a and b


# Proof

Given:



The three vectors above form the triangle AOB and note that the length of each side is nothing more than the magnitude of the vector forming that side.

The Law of Cosines tells us that,


ab2=a2+b22abcosθ \|\vec a - \vec b\|^2 = \|\vec a \|^2 + \|\vec b \|^2 - 2\|\vec a\| \|\vec b\| cos \theta


Also using the properties of dot products we can write the left side as,


ab2=(ab).(ab)=a.aa.bb.a+b.b=a22a.b+b2 \begin{matrix} \|\vec a - \vec b\|^2 & = (\vec a - \vec b) . (\vec a - \vec b)\\\\ & = \vec a . \vec a - \vec a . \vec b - \vec b . \vec a + \vec b . \vec b\\\\ & = \|\vec a\|^2 - 2 \vec a . \vec b + \|\vec b\|^2 \end{matrix}


Our original equation is then,


ab2=a2+b22abcosθ \|\vec a - \vec b\|^2 = \|\vec a \|^2 + \|\vec b \|^2 - 2\|\vec a\| \|\vec b\| cos \theta
a22a.b+b2=a2+b22abcosθ \|\vec a\|^2 - 2 \vec a . \vec b + \|\vec b\|^2 = \|\vec a \|^2 + \|\vec b \|^2 - 2\|\vec a\| \|\vec b\| cos \theta
2a.b=2abcosθ -2 \vec a . \vec b = -2\|\vec a\| \|\vec b\| cos \theta
a.b=abcosθ \vec a . \vec b = \|\vec a\| \|\vec b\| cos \theta


# Useful Trigonometry Properties


cos(90α)=sinα cos (90 - \alpha) = sin \alpha


cos(90+α)=sinα cos (90 + \alpha) = - sin \alpha


sin(θ)=sinθ sin (-\theta) = - sin \theta


cos(θ)=cosθ cos (-\theta) = cos \theta



TIP

Refer to Useful link 5 to youtube video on Coordinate systems and frames of reference

# Properties of Dot Product


(au+bv)w=(au)w+(bv)w(au + bv) · w = (au) · w + (bv) · w, where aa and bb are scalars and u,v,wu, v, w are vectors.

Here is the list of properties of the dot product:


uv=uvcosθu · v = |u||v| cos θ


uv=vuu · v = v · u


uv=0u · v = 0 when uu and vv are orthogonal.

Orthogonal. Two lines or planes are orthogonal if they are at right angles (90°) to each other. ... In geometry, the word 'orthogonal' simply means 'at right angles'.

We also sometimes say they are 'normal' to each other. Strictly speaking, the lines do not have to actually intersect.


v2=vv|v|2 = v · v


a(uv)=(au)va (u·v) = (a u) · v


(au+bv)w=(au)w+(bv)w(au + bv) · w = (au) · w + (bv) · w



X^B.X^A=11cos0=1 \hat X_B . \hat X_A = |1| * |1| * cos0 = 1


X^B.Y^A=11cos90=0 \hat X_B . \hat Y_A = |1| * |1| * cos90 = 0


X^B.Z^A=11cos90=0 \hat X_B . \hat Z_A = |1| * |1| * cos90 = 0


BARX(γ)=^A_BR_X(\gamma) = [X^B.X^A=[1]Y^B.X^A=[0]Z^B.X^A=[0]X^B.Y^A=[0]Y^B.Y^A=[cosγ]Z^B.Y^A=[sinγ]X^B.Z^A=[0]Y^B.Z^A=[sinγ]Z^B.Z^A=[cosγ]]\begin{bmatrix} \begin{array}{ccc} \hat X_B . \hat X_A = \begin{bmatrix} 1 \end{bmatrix} & \hat Y_B . \hat X_A = \begin{bmatrix} 0 \end{bmatrix} & \hat Z_B . \hat X_A = \begin{bmatrix} 0 \end{bmatrix} \end{array}\\\\ \begin{array}{ccc} \hat X_B . \hat Y_A = \begin{bmatrix} 0 \end{bmatrix} & \hat Y_B . \hat Y_A = \begin{bmatrix} cos \gamma \end{bmatrix} & \hat Z_B . \hat Y_A = \begin{bmatrix} -sin \gamma \end{bmatrix} \end{array}\\\\ \begin{array}{ccc} \hat X_B . \hat Z_A = \begin{bmatrix} 0 \end{bmatrix} & \hat Y_B . \hat Z_A = \begin{bmatrix} sin \gamma \end{bmatrix} & \hat Z_B . \hat Z_A = \begin{bmatrix} cos \gamma \end{bmatrix} \end{array} \end{bmatrix}





BARY(β)=^A_BR_Y(\beta) = [X^B.X^A=[cosβ]Y^B.X^A=[0]Z^B.X^A=[sinβ]X^B.Y^A=[0]Y^B.Y^A=[1]Z^B.Y^A=[0]X^B.Z^A=[sinβ]Y^B.Z^A=[0]Z^B.Z^A=[cosβ]]\begin{bmatrix} \begin{array}{ccc} \hat X_B . \hat X_A = \begin{bmatrix} cos \beta \end{bmatrix} & \hat Y_B . \hat X_A = \begin{bmatrix} 0 \end{bmatrix} & \hat Z_B . \hat X_A = \begin{bmatrix} sin \beta \end{bmatrix} \end{array}\\\\ \begin{array}{ccc} \hat X_B . \hat Y_A = \begin{bmatrix} 0 \end{bmatrix} & \hat Y_B . \hat Y_A = \begin{bmatrix} 1 \end{bmatrix} & \hat Z_B . \hat Y_A = \begin{bmatrix} 0 \end{bmatrix} \end{array}\\\\ \begin{array}{ccc} \hat X_B . \hat Z_A = \begin{bmatrix} -sin \beta \end{bmatrix} & \hat Y_B . \hat Z_A = \begin{bmatrix} 0 \end{bmatrix} & \hat Z_B . \hat Z_A = \begin{bmatrix} cos \beta \end{bmatrix} \end{array} \end{bmatrix}





BARZ(α)=^A_BR_Z(\alpha) = [X^B.X^A=[cosα]Y^B.X^A=[sinα]Z^B.X^A=[0]X^B.Y^A=[sinα]Y^B.Y^A=[cosα]Z^B.Y^A=[0]X^B.Z^A=[0]Y^B.Z^A=[0]Z^B.Z^A=[1]]\begin{bmatrix} \begin{array}{ccc} \hat X_B . \hat X_A = \begin{bmatrix} cos \alpha \end{bmatrix} & \hat Y_B . \hat X_A = \begin{bmatrix} -sin \alpha \end{bmatrix} & \hat Z_B . \hat X_A = \begin{bmatrix} 0 \end{bmatrix} \end{array}\\\\ \begin{array}{ccc} \hat X_B . \hat Y_A = \begin{bmatrix} sin \alpha \end{bmatrix} & \hat Y_B . \hat Y_A = \begin{bmatrix} cos \alpha \end{bmatrix} & \hat Z_B . \hat Y_A = \begin{bmatrix} 0 \end{bmatrix} \end{array}\\\\ \begin{array}{ccc} \hat X_B . \hat Z_A = \begin{bmatrix} 0 \end{bmatrix} & \hat Y_B . \hat Z_A = \begin{bmatrix} 0 \end{bmatrix} & \hat Z_B . \hat Z_A = \begin{bmatrix} 1 \end{bmatrix} \end{array} \end{bmatrix}





BARZ(α)=^A_BR_Z(\alpha) = [AX^BAY^BAZ^B]=[X^B.X^A=[cos45o]Y^B.X^A=[sin45o]Z^B.X^A=[0]X^B.Y^A=[sin45o]Y^B.Y^A=[cos45o]Z^B.Y^A=[0]X^B.Z^A=[0]Y^B.Z^A=[0]Z^B.Z^A=[1]]=\begin{bmatrix} ^A \hat X_B & ^A \hat Y_B & ^A \hat Z_B \\ \end{bmatrix} = \begin{bmatrix} \begin{array}{ccc} \hat X_B . \hat X_A = \begin{bmatrix} cos 45^o \end{bmatrix} & \hat Y_B . \hat X_A = \begin{bmatrix} -sin 45^o \end{bmatrix} & \hat Z_B . \hat X_A = \begin{bmatrix} 0 \end{bmatrix} \end{array}\\\\ \begin{array}{ccc} \hat X_B . \hat Y_A = \begin{bmatrix} sin 45^o \end{bmatrix} & \hat Y_B . \hat Y_A = \begin{bmatrix} cos 45^o \end{bmatrix} & \hat Z_B . \hat Y_A = \begin{bmatrix} 0 \end{bmatrix} \end{array}\\\\ \begin{array}{ccc} \hat X_B . \hat Z_A = \begin{bmatrix} 0 \end{bmatrix} & \hat Y_B . \hat Z_A = \begin{bmatrix} 0 \end{bmatrix} & \hat Z_B . \hat Z_A = \begin{bmatrix} 1 \end{bmatrix} \end{array} \end{bmatrix} =



[0.70710.707100.70710.70710001] \begin{bmatrix} 0.7071 & -0.7071 & 0\\ 0.7071 & 0.7071 & 0\\ 0 & 0 & 1\\ \end{bmatrix}



CBRZ(α)=^B_CR_Z(\alpha) = [BX^CBY^CBZ^C]=I3=[100010001] \begin{bmatrix} ^B \hat X_C & ^B \hat Y_C & ^B \hat Z_C \\ \end{bmatrix} = I_3 = \begin{bmatrix} 1 & 0 & 0\\ 0 & 1 & 0\\ 0 & 0 & 1\\ \end{bmatrix}



DCRZ(α)=^C_DR_Z(\alpha) = [CX^DCY^DCZ^D]=[X^D.X^C=[cos45o]Y^D.X^C=[sin45o]Z^D.X^C=[0]X^D.Y^C=[sin45o]Y^D.Y^C=[cos45o]Z^D.Y^C=[0]X^D.Z^C=[0]Y^D.Z^C=[0]Z^D.Z^C=[1]]=\begin{bmatrix} ^C \hat X_D & ^C \hat Y_D & ^C \hat Z_D \\ \end{bmatrix} = \begin{bmatrix} \begin{array}{ccc} \hat X_D . \hat X_C = \begin{bmatrix} cos -45^o \end{bmatrix} & \hat Y_D . \hat X_C = \begin{bmatrix} -sin -45^o \end{bmatrix} & \hat Z_D . \hat X_C = \begin{bmatrix} 0 \end{bmatrix} \end{array}\\\\ \begin{array}{ccc} \hat X_D . \hat Y_C = \begin{bmatrix} sin -45^o \end{bmatrix} & \hat Y_D . \hat Y_C = \begin{bmatrix} cos -45^o \end{bmatrix} & \hat Z_D . \hat Y_C = \begin{bmatrix} 0 \end{bmatrix} \end{array}\\\\ \begin{array}{ccc} \hat X_D . \hat Z_C = \begin{bmatrix} 0 \end{bmatrix} & \hat Y_D . \hat Z_C = \begin{bmatrix} 0 \end{bmatrix} & \hat Z_D . \hat Z_C = \begin{bmatrix} 1 \end{bmatrix} \end{array} \end{bmatrix} =



[X^D.X^C=[cos45o]Y^D.X^C=[sin45o]Z^D.X^C=[0]X^D.Y^C=[sin45o]Y^D.Y^C=[cos45o]Z^D.Y^C=[0]X^D.Z^C=[0]Y^D.Z^C=[0]Z^D.Z^C=[1]]=[0.70710.707100.70710.70710001] \begin{bmatrix} \begin{array}{ccc} \hat X_D . \hat X_C = \begin{bmatrix} cos 45^o \end{bmatrix} & \hat Y_D . \hat X_C = \begin{bmatrix} sin 45^o \end{bmatrix} & \hat Z_D . \hat X_C = \begin{bmatrix} 0 \end{bmatrix} \end{array}\\\\ \begin{array}{ccc} \hat X_D . \hat Y_C = \begin{bmatrix} - sin 45^o \end{bmatrix} & \hat Y_D . \hat Y_C = \begin{bmatrix} cos 45^o \end{bmatrix} & \hat Z_D . \hat Y_C = \begin{bmatrix} 0 \end{bmatrix} \end{array}\\\\ \begin{array}{ccc} \hat X_D . \hat Z_C = \begin{bmatrix} 0 \end{bmatrix} & \hat Y_D . \hat Z_C = \begin{bmatrix} 0 \end{bmatrix} & \hat Z_D . \hat Z_C = \begin{bmatrix} 1 \end{bmatrix} \end{array} \end{bmatrix} = \begin{bmatrix} 0.7071 & 0.7071 & 0\\ \color{red}{-0.7071} & \color{red}{0.7071} & 0\\ 0 & 0 & 1\\ \end{bmatrix}



AP=[PxPyPz](1)^AP= \begin{bmatrix} P_x\\ P_y\\ P_z\\ \end{bmatrix} \qquad(1)



AP=[420]AQ=[620]AR=[640]BP=[310]BQ=[510]BR=[510]CP=[240]cQ=[440]CR=[420] \begin{matrix} \begin{array}{c} ^AP = \begin{bmatrix} 4\\ 2\\ 0 \end{bmatrix} & ^AQ = \begin{bmatrix} 6\\ 2\\ 0 \end{bmatrix} & ^AR = \begin{bmatrix} 6\\ 4\\ 0 \end{bmatrix} \end{array}\\\\ \begin{array}{c} ^BP = \begin{bmatrix} 3\\ -1\\ 0 \end{bmatrix} & ^BQ = \begin{bmatrix} 5\\ -1\\ 0 \end{bmatrix} & ^BR = \begin{bmatrix} 5\\ 1\\ 0 \end{bmatrix} \end{array}\\\\ \begin{array}{c} ^CP = \begin{bmatrix} 2\\ -4\\ 0 \end{bmatrix} & ^cQ = \begin{bmatrix} 4\\ -4\\ 0 \end{bmatrix} & ^CR = \begin{bmatrix} 4\\ -2\\ 0 \end{bmatrix} \end{array} \end{matrix}



APBORG=[APBORGxAPBORGyAPBORGz]=[130]^AP_{BORG} = \begin{array}{c} \begin{bmatrix} ^AP{_{BORG}}_x\\ ^AP{_{BORG}}_y\\ ^AP{_{BORG}}_z\\ \end{bmatrix} = & \begin{bmatrix} 1\\ 3\\ 0\\ \end{bmatrix} \end{array}



BPCORG=[BPCORGxBPCORGyBPCORGz]=[130]^BP_{CORG} = \begin{array}{c} \begin{bmatrix} ^BP{_{CORG}}_x\\ ^BP{_{CORG}}_y\\ ^BP{_{CORG}}_z\\ \end{bmatrix} = & \begin{bmatrix} 1\\ 3\\ 0\\ \end{bmatrix} \end{array}



A(BP)=^A(^BP) = BP+APBORG(9)^BP + ^AP_{BORG}\qquad(9)



A(BP)=[310]+[130]=[420]A(BQ)=BQ+AQBORG=[510]+[130]=[420]A(BR)=BR+ARBORG=[510]+[ARBORGx=1ARBORGy=3ARBORGz=0]=[640]B(CP)=CP+BPCORG=[240]+[BPCORGx=1BPCORGy=3BPCORGz=0]=[310]B(CQ)=CQ+BQCORG=[440]+[BQCORGx=1BQCORGy=3BQCORGz=0]=[510]B(CR)=CR+BQCORG=[420]+[BRCORGx=1BRCORGy=3BRCORGz=0]=[510] \begin{matrix} \begin{array}{ccc} ^A(^BP) = \begin{bmatrix} 3\\ -1\\ 0 \end{bmatrix} + \begin{bmatrix} 1\\ 3\\ 0 \end{bmatrix} = \begin{bmatrix} 4\\ 2\\ 0 \end{bmatrix} & ^A(^BQ) = {^BQ} + {^AQ_{BORG}} = \begin{bmatrix} 5\\ -1\\ 0 \end{bmatrix} + \begin{bmatrix} 1\\ 3\\ 0 \end{bmatrix} = \begin{bmatrix} 4\\ 2\\ 0 \end{bmatrix} \end{array}\\\\ ^A(^BR) = {^BR} + {^AR_{BORG}} = \begin{bmatrix} 5\\ 1\\ 0 \end{bmatrix} + \begin{bmatrix} {^AR_{BORG}}_x = 1\\ {^AR_{BORG}}_y = 3\\ {^AR_{BORG}}_z = 0\\ \end{bmatrix} = \begin{bmatrix} 6\\ 4\\ 0 \end{bmatrix}\\\\ ^B(^CP) = {^CP} + {^BP_{CORG}} = \begin{bmatrix} 2\\ -4\\ 0\\ \end{bmatrix} + \begin{bmatrix} {^BP_{CORG}}_x = 1\\ {^BP_{CORG}}_y = 3\\ {^BP_{CORG}}_z = 0\\ \end{bmatrix} = \begin{bmatrix} 3\\ -1\\ 0\\ \end{bmatrix}\\\\ ^B(^CQ) = {^CQ} + {^BQ_{CORG}} = \begin{bmatrix} 4\\ -4\\ 0\\ \end{bmatrix} + \begin{bmatrix} {^BQ_{CORG}}_x = 1\\ {^BQ_{CORG}}_y = 3\\ {^BQ_{CORG}}_z = 0\\ \end{bmatrix} = \begin{bmatrix} 5\\ -1\\ 0\\ \end{bmatrix}\\\\ ^B(^CR) = {^CR} + {^BQ_{CORG}} = \begin{bmatrix} 4\\ -2\\ 0\\ \end{bmatrix} + \begin{bmatrix} {^BR_{CORG}}_x = 1\\ {^BR_{CORG}}_y = 3\\ {^BR_{CORG}}_z = 0\\ \end{bmatrix} = \begin{bmatrix} 5\\ 1\\ 0\\ \end{bmatrix}\\\\ \end{matrix}


# 3. Lecture 3 - 02/03/2020

# Class Notes

Tools:

Matlab

Numpy for Python

(C++ library: Eigen is a C++ template library for linear algebra: matrices, vectors, numerical solvers, and related algorithms.)[http://eigen.tuxfamily.org/index.php?title=Main_Page]

Transforms and the inverse of transforms can be multiplied to carry out complex sets of transform operations.

WARNING

Transform Equations II is worng D should be A on DUT^U_DT, for AUT^U_AT

# Introduction

In today's lecture, we will:

  • Discuss compound transformations.
  • Discuss inverting a transformation.
  • Discuss transform equations.

# Transformation Arithmetic

Transforms and the inverse of transforms can be multiplied to carry out complex sets of transform operations.

# Compound Transformation

Consider the following figure, we have CP^CP and wish to find AP^AP.



Frame CC is know relative to frame BB, and frame BB is known relative to frame AA. We can transform CP^CP into BP^BP as


BP=CBTCP(1)^BP = ^B_CT ^CP \qquad(1)


Then we can transform BP^BP into AP^AP as:


AP=BATBP(2)^AP = ^A_BT ^BP \qquad(2)


Combining these, we get the result


AP=BATCBTCP(3)^AP = ^A_BT ^B_CT ^CP \qquad(3)


from which we could define


CAT=BATCBT(4)^A_CT = ^A_BT ^B_CT \qquad(4)


In terms of the known descriptions of BB and CC, we can give the expression for ACTA^CT as:


CAT=[BARCBRBARBPCORG+APBORG0001](5)^A_CT = \begin{bmatrix} \begin{array}{ccc|c} & ^A_BR ^B_CR && ^A_BR ^BP_{CORG} + ^AP_{BORG} \\ \hline 0 & 0 & 0 & 1 \end{array} \end{bmatrix} \qquad(5)


# Inverting a Transform

Consider a frame BB that is known with respect to a frame AA, i.e. we know BAT^A_B T. Sometimes we need to invert this transform to get a description of AA relative to BB, i.e. ABT^B_AT.

A straightforward method is to compute the inverse of the 4x44 x 4 homogeneous transform. However, this is not the easiest way.

To find ABT^B_AT, we need to compute ABR^B_AR and BPAORG^BP_{AORG} from BAR^A_BR and APBORG^AP_{BORG}.

Recall,


ABR=BART(6)^B_AR = ^A_BR^T \qquad(6)


Next, we change APBORG^AP_{BORG} into BB using:


B(APBORG)=ABRAPBORG+BPAORG(7)^B(^AP_{BORG}) = ^B_AR ^AP_{BORG} + ^BP_{AORG} \qquad(7)


The left hand side is zero, so we have:


BPAORG=ABRAPBORG=BART^BP_{AORG} = - ^B_AR ^AP_{BORG} = - ^A_BR^T APBORG(8)^AP_{BORG} \qquad(8)


We can write the form of ABT^B_AT as:


CAT=[BART(BART)(APBORG)0001](9)^A_CT = \begin{bmatrix} \begin{array}{ccc|c} & ^A_BR^T && (- ^A_BR^T) (^AP_{BORG}) \\ \hline 0 & 0 & 0 & 1 \end{array} \end{bmatrix} \qquad(9)


With our notation,


ABT=BAT1(10)^B_AT = ^A_BT^{-1} \qquad(10)


# Transform Equations

Consider the following figure:



Frame DD can be expressed as products of transformations in two different ways. First,


DUT=AUTDAT(11)^U_DT = ^U_AT ^A_DT \qquad(11)


second:


DUT=BUTCBTDCT(12)^U_DT = ^U_BT ^B_CT ^C_DT \qquad(12)


We can set these two transformations of DUT^U_DT equal to construct a transform equation:


AUTDAT=BUTCBTDCT(13)^U_AT ^A_DT = ^U_BT ^B_CT ^C_DT \qquad(13)


Transform equations can be used to solve for transforms in the case of nn unknown transforms and nn transform equations.

Consider that all transforms are known, except CBT^B_CT. We easily find its solution to be:


CBT=BUT1^B_CT = ^U_BT^{-1} AUTDAT^U_AT ^A_DT DCT1(14)^C_DT^{-1} \qquad(14)


Consider the following figure:



In all Figures, we have introduced a graphical representation of frames as an arrow pointing from one origin to another origin. The arrow's direction indicates which way the frame is defined: in the previous figure, frame A is defined relative to DD. In order to compound frames when the arrows line up, we simply compute the products. If an arrow points in the opposite way, we simply compute its inverse first. Two possible descriptions of CC are:


CUT=AUT^U_CT = ^U_AT ADT1^D_AT^{-1} CDT(15)^D_CT \qquad(15)


and


CUT=BUTCBT(16)^U_CT = ^U_BT ^B_CT \qquad(16)


# Lecture 3 Example





# Python implementation of Example 3:

import numpy as np


class Matrix:
    """
    Definition: This class generates Homogeneous transform matrices,
    that can be used to multiply any matrix and obtain the translation or rotation.

    It uses `numpy` to generate the matrices:

        np.float32: creates the array with 16 float32 elements

        np.reshape: np.reshape rearrange the array into a 4X4 matrix

    Returns: It returns Rotation and translation matrices.

    Obs: **kwargs (keyword arguments) are used to facilitate the identification of the parameters, so initiate the
    object
    like: Matrix(x_angle='45', x_dist='100', z_angle='60', z_dist='100'), if an argument is not provided,
    the default 0 will be put to the argument.
    """
    np.set_printoptions(precision=3, suppress=True)

    def __init__(self, **kwargs):
        """
        Initializes the Object.
        """
        self._x_angle = kwargs['x_angle'] if 'x_angle' in kwargs else '0'
        self._x_dist = kwargs['x_dist'] if 'x_dist' in kwargs else '0'
        self._y_angle = kwargs['y_angle'] if 'y_angle' in kwargs else '0'
        self._y_dist = kwargs['y_dist'] if 'y_dist' in kwargs else '0'
        self._z_angle = kwargs['z_angle'] if 'z_angle' in kwargs else '0'
        self._z_dist = kwargs['z_dist'] if 'z_dist' in kwargs else '0'
        self._m_degrees = kwargs['m_degrees'] if 'm_degrees' in kwargs else 'True'

    def trans_x(self, a=0):
        """
        Definition: Translates the matrix a given amount `a` on the *X* axis by Defining a 4x4 identity
        matrix with `a` as the (1,4) element.

        :type a: float
        :param a: Distance translated on the X-axis

        Returns: The Translation Matrix on the *X* axis by a distance *a*
        """
        if a:
            self._x_dist = a
        trans_x = np.float32([1, 0, 0, self._x_dist,
                              0, 1, 0, 0,
                              0, 0, 1, 0,
                              0, 0, 0, 1])
        trans_x = np.reshape(trans_x, (4, 4))

        return trans_x

    def trans_y(self, b=0):
        """
        Definition: Translate the matrix a given amount `d` on the *Z* axis. by Defining a matrix T 4x4 identity
        matrix with *b* (3,4) element position.

        :type b: float
        :param b: Distance translated on the Z-axis

        Returns: The Translation Matrix on the *Z* axis by a distance *b*
        """
        if b:
            self._y_dist = b
        trans_y = np.float32([1, 0, 0, 0,
                              0, 1, 0, self._y_dist,
                              0, 0, 1, 0,
                              0, 0, 0, 1])
        trans_y = np.reshape(trans_y, (4, 4))

        return trans_y

    def trans_z(self, d=0):
        """
        Definition: Translate the matrix a given amount `d` on the *Z* axis. by Defining a matrix T 4x4 identity
        matrix with *c* (3,4) element position.

        :type d: float
        :param d: Distance translated on the Z-axis

        Returns: The Translation Matrix on the *Z* axis by a distance *c*
        """
        if d:
            self._z_dist = d
        trans_z = np.float32([1, 0, 0, 0,
                              0, 1, 0, 0,
                              0, 0, 1, self._z_dist,
                              0, 0, 0, 1])
        trans_z = np.reshape(trans_z, (4, 4))

        return trans_z

    def rot_x(self, gamma=0, degrees=True):
        """
        Definition: Receives an alpha angle and returns the rotation matrix for the given angle at the *X* axis.
        If the angle is given in radian degrees should be False.

        :type gamma: float
        :param gamma: Rotation Angle around the X axis
        :type degrees: bool
        :param degrees: Indicates if the provided angle is in degrees, if yes It will be converted to radians

        Returns: The Rotational Matrix at the X axis by an *gamma* angle
        """
        if gamma:
            self._x_angle = gamma
        if degrees:
            self._m_degrees = degrees

            self._x_angle = np.deg2rad(gamma)

        rot_x = np.float32([1, 0, 0, 0, 0,
                            np.cos(self._x_angle),
                            -np.sin(self._x_angle), 0, 0,
                            np.sin(self._x_angle),
                            np.cos(self._x_angle), 0,
                            0, 0, 0, 1])

        rot_x = np.reshape(rot_x, (4, 4))

        return rot_x

    def rot_y(self, beta=0, degrees=True):
        """
        Definition: Receives an theta angle and returns the rotation matrix for the given angle at the *Z* axis.
        If the angle is given in radian degrees should be False.

        :type beta: float
        :param beta: Rotation Angle around the Z axis
        :type degrees: bool
        :param degrees: Indicates if the provided angle is in degrees, if yes It will be converted to radians

        Returns: The Rotational Matrix at the Z axis by an *beta* angle
        """
        if beta:
            self._y_angle = beta
        if degrees:
            self._m_degrees = degrees

            self._y_angle = np.deg2rad(beta)

        rot_y = np.float32([np.cos(self._y_angle), 0, 0,
                            np.sin(self._y_angle),
                            0, 0, 0, 0,
                            -np.sin(self._y_angle), 0, 1,
                            np.cos(self._y_angle),
                            0, 0, 0, 1])

        rot_y = np.reshape(rot_y, (4, 4))

        return rot_y

    def rot_z(self, alpha=0, degrees=True):
        """
        Definition: Receives an theta angle and returns the rotation matrix for the given angle at the *Z* axis.
        If the angle is given in radian degrees should be False.

        :type alpha: float
        :param alpha: Rotation Angle around the Z axis
        :type degrees: bool
        :param degrees: Indicates if the provided angle is in degrees, if yes It will be converted to radians

        Returns: The Rotational Matrix at the Z axis by an *alpha* angle
        """
        if alpha:
            self._z_angle = alpha
        if degrees:
            self._m_degrees = degrees

            self._z_angle = np.deg2rad(alpha)

        rot_z = np.float32([np.cos(self._z_angle),
                            -np.sin(self._z_angle), 0, 0,
                            np.sin(self._z_angle),
                            np.cos(self._z_angle), 0, 0,
                            0, 0, 1, 0,
                            0, 0, 0, 1])

        rot_z = np.reshape(rot_z, (4, 4))

        return rot_z


def main():
    """
    Example 3
    """

    print('Example 3:')

    a1 = Matrix()       # Rotation in x by 90
    a2 = Matrix()       # Translation in X by 0.75
    a3 = Matrix()       # Rotation in Z by 30
    a4 = Matrix()       # Rotation in Z by -30
    a5 = Matrix()       # Translation in X by 0.5

    print()
    print('Rotation in X by 90:')
    print(a1.rot_x(45))
    print()

    print()
    print('Translation in X by 0.75:')
    print(a2.trans_x(0.75))
    print()
    print('Rotation in Z by 30')
    print(a3.rot_z(30))

    print()
    print('First Individual Transform:')
    print('Rotation in X by 90 x Translation in X by 0.75 x Rotation in Z by 30:')
    print(np.matmul((np.matmul(a1.rot_x(90), a2.trans_x(0.75))), a3.rot_z(30)))

    print()
    print('Rotation in Z by 30:')
    print(a4.rot_z(-30))
    print()
    print('Translation in X by 0.5:')
    print(a5.trans_x(0.55))
    print()
    print('Second Individual Transform:')
    print('Rotation in Z by 30 x Translation in X by 0.5')
    print(np.matmul(a4.rot_z(-30), a5.trans_x(0.55)))

    print()
    print('Product of both transforms:')
    a6 = np.matmul(np.matmul((np.matmul(a1.rot_x(90), a2.trans_x(0.75))), a3.rot_z(30)),
                   np.matmul(a4.rot_z(-30), a5.trans_x(0.55)))
    print(a6)

    print()
    print('G:')
    a7 = np.float32([0.1, 0.1, 0, 1])
    a7 = np.reshape(a7, (4, 1))
    print(a7)

    print()
    print('Final Countdown:')
    print(np.matmul(a6, a7))

    return


if __name__ == '__main__':
    main()
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
Example 3:

Rotation in X by 90:
[[ 1.     0.     0.     0.   ]
 [ 0.     0.707 -0.707  0.   ]
 [ 0.     0.707  0.707  0.   ]
 [ 0.     0.     0.     1.   ]]

Translation in X by 0.75:
[[1.   0.   0.   0.75]
 [0.   1.   0.   0.  ]
 [0.   0.   1.   0.  ]
 [0.   0.   0.   1.  ]]

Rotation in Z by 30
[[ 0.866 -0.5    0.     0.   ]
 [ 0.5    0.866  0.     0.   ]
 [ 0.     0.     1.     0.   ]
 [ 0.     0.     0.     1.   ]]

First Individual Transform:

Rotation in X by 90 x Translation in X by 0.75 x Rotation in Z by 30:
[[ 8.660e-01 -5.000e-01  0.000e+00  7.500e-01]
 [ 3.062e-17  5.303e-17 -1.000e+00  0.000e+00]
 [ 5.000e-01  8.660e-01  6.123e-17  0.000e+00]
 [ 0.000e+00  0.000e+00  0.000e+00  1.000e+00]]

Rotation in Z by 30:
[[ 0.866  0.5    0.     0.   ]
 [-0.5    0.866  0.     0.   ]
 [ 0.     0.     1.     0.   ]
 [ 0.     0.     0.     1.   ]]

Translation in X by 0.5:
[[1.  0.  0.  0.5]
 [0.  1.  0.  0. ]
 [0.  0.  1.  0. ]
 [0.  0.  0.  1. ]]

Second Individual Transform:

Rotation in Z by 30 x Translation in X by 0.5
[[ 0.866  0.5    0.     0.433]
 [-0.5    0.866  0.    -0.25 ]
 [ 0.     0.     1.     0.   ]
 [ 0.     0.     0.     1.   ]]

Product of both transforms:
[[ 1.000e+00  0.000e+00  0.000e+00  1.250e+00]
 [ 0.000e+00  6.123e-17 -1.000e+00  0.000e+00]
 [ 0.000e+00  1.000e+00  6.123e-17  0.000e+00]
 [ 0.000e+00  0.000e+00  0.000e+00  1.000e+00]]

G:
[[0.1]
 [0.1]
 [0. ]
 [1. ]]

Final Countdown:
[[1.350e+00]
 [6.123e-18]
 [1.000e-01]
 [1.000e+00]]

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66

# Lecture 3 Worksheet

WARNING

To Be Done

# 4. Lecture 4 - 03/03/2020

TIP

RxRzRzRxR_xR_z \neq R_zR_x, the order of the rotations matter. Rotation on the xaxisx axis then on the zaxisz axis is different from Rotation on the zaxisz axis then on the XaxisX axis.

# Introduction

In today's lecture, we have:

  • Discussed additional means of representing orientation.
  • Discussed X-Y-Z Fixed Angles representation of orientation.
  • Discussed Z-Y-X Euler Angles representation of orientation.

# More on Representation of Orientation

So far, we have represented an orientation using a 3x33 x 3 rotation matrix.

Rotation matrices are special in that all columns are mutually orthogonal and have unit magnitude. Further, the determinant of a rotation matrix is always equal to +1+1, which makes rotation matrices "proper".

Now, a rotation matrix has nine numbers; is it possible to describe an orientation with fewer?


Cayley's formula for orthogonal matrices states that, for any proper matrix RR, there exists a skew-symmetric matrix SS such that:


R=(I3S)1(I3+S)(1)R = (I_3 - S)^{-1}(I_3 + S) \qquad(1)


where I3I_3 is a 3x33 x 3 unit matrix. Now a skew-symmetric matrix (i.e., S=STS = -S^T) of dimension 3 is specified by parameters (sx,sy,(s_x , s_y , and sz)s_z ) as:


S=[0szsysz0sxsysx0](2)S = \begin{bmatrix} 0 & -s_z & s_y \\ s_z & 0 & -s_x \\ -s_y & s_x & 0 \end{bmatrix} \qquad(2)


Therefore, any 3x33 x 3 rotation matrix can be represented by three parameters.

The nine elements of a rotation matrix are not all independent. Given a rotation matrix, RR, we can write down the six dependencies between the elements. RR can be defined as:


R=[X^Y^Z^](3)R = \begin{bmatrix} \hat X \hat Y \hat Z \end{bmatrix} \qquad(3)


These are the unit axes of some frame written in terms of the reference frame.


Each is a unit vector, and all must be mutually perpendicular, so we see that there are six constraints on the nine matrix elements:


R=X^=1,Y^=1,Z^=1,X^.Y^=0,X^.Z^=0,Y^.Z^=0,(4)R = \begin{matrix} | \hat X | = & 1, \\ | \hat Y | = & 1, \\ | \hat Z | = & 1, \\ \hat X . \hat Y = & 0, \\ \hat X . \hat Z = & 0, \\ \hat Y . \hat Z = & 0, \\ \end{matrix} \qquad(4)


The question is, how can we express orientation using only three parameters?


Translations along three mutually perpendicular axes are quite easy to visualise, rotations not quite so. One diculty is that rotations don't generally commute, i.e. BARCBR^A_BR ^B_CR is not the same as CBRBAR^B_CR ^A_BR.

Also, because rotations can be though of either as operators or as descriptions of orientation, different representations are favoured for each of these uses.

Rotation matrices are useful as operators; however, they are unwieldy when used to specify orientation.

A representation that requires only three numbers would be simpler.

# X-Y-Z Fixed Angles

One method of describing the orientation of a frame BB is as follows:

X-Y-Z Fixed Angles

Start with the frame coincident with a known reference frame AA. Rotate BB first about X^A\hat X_A by an angle of γ\gamma, then about Y^A\hat Y_A by an angle of β\beta, and, finally, about Z^A\hat Z_A by an angle $\alpha.

Each of the three rotations takes place about an axis in the fixed reference frame A. This convention is the X-Y-Z Fixed Angles. The word "fixed" refers to the fixed reference frame.



The derivation of the equivalent rotation matrix, BARXYZ(γ,β,α)^A_BR_{XYZ}( \gamma , \beta, \alpha), is straight forward, because all rotations occur about axes of the reference frame; that is,


BARXYZ(γ,β,α)=RZ(α)RY(β)RX(γ)[cαsα0sαcα0000][cβ0sβ010sβ0cβ][1000cγsγ0sγcγ](5)\begin{matrix} ^A_BR_{XYZ}( \gamma , \beta, \alpha) = R_Z(\alpha) R_Y(\beta) R_X(\gamma) \\ \\ \begin{array}{ccc} \begin{bmatrix} c \alpha & - s \alpha & 0 \\ s \alpha & c \alpha & 0 \\ 0 & 0 & 0 \end{bmatrix} & \begin{bmatrix} c \beta & 0 & s \beta \\ 0 & 1 & 0 \\ -s \beta & 0 & c \beta \end{bmatrix} & \begin{bmatrix} 1 & 0 & 0 \\ 0 & c \gamma & - s \gamma \\ 0 & s \gamma & c \gamma \end{bmatrix} \end{array} \end{matrix} \qquad(5)


where cαc \alpha is shorthand for cosαcos \alpha, sαs \alpha for sinαsin \alpha, and so on.

Multiplying out in the order of rotation, we obtain:


BARXYZ(γ,β,α)=[cαcβcαsβsγsαcγcαsβcγsαsγsαcβsαsβsγ+cαcγsαsβcγcαsγsβcβsγcβcγ](6)^A_BR_{XYZ}( \gamma , \beta, \alpha) = \begin{bmatrix} c \alpha c \beta & c \alpha s \beta s \gamma - s \alpha c \gamma & c \alpha s \beta c \gamma - s \alpha s \gamma \\ s \alpha c \beta & s \alpha s \beta s \gamma + c \alpha c \gamma & s \alpha s \beta c \gamma - c \alpha s \gamma \\ -s \beta & c \beta s \gamma & c \beta c \gamma \end{bmatrix} \qquad(6)


The inverse problem, that of extracting equivalent X-Y-Z fixed angles from a rotation matrix, is often of interest.

Let


BARXYZ(γ,β,α)=[r11r12r13r21r22r23r31r32r33](7)^A_BR_{XYZ}( \gamma , \beta, \alpha) = \begin{bmatrix} r_{11} & r_{12} & r_{13} \\ r_{21} & r_{22} & r_{23} \\ r_{31} & r_{32} & r_{33} \\ \end{bmatrix} \qquad(7)


Therefore,


BARXYZ(γ,β,α)=[β=Atan2(r31,r112+r212α=Atan2(r21/cβ,r11/cβγ=Atan2(r32/cβ,r33/cβ](8)^A_BR_{XYZ}( \gamma , \beta, \alpha) = \begin{bmatrix} \beta = A tan 2 (- r_{31}, \sqrt{r_{11}^2 + r_{21}^2} \\ \alpha = A tan 2 ( r_{21} / c \beta, r_{11} / c \beta \\ \gamma = A tan 2 ( r_{32} / c \beta, r_{33} / c \beta \\ \end{bmatrix} \qquad(8)


# Z-Y-X Euler Angles

Another possible description of a frame is as follows:

Z-Y-X Euler Angles

Start with the frame coincident with a known frame AA. Rotate BB first about Z^B\hat Z_B by an angle α\alpha, then about Y^B\hat Y_B by angle β\beta, and, finally, about X^B\hat X_B by an angle γ\gamma.

In this representation, each rotation is performed about an axis of the moving system BB rather than one of the fixed reference AA.

Such a set of three rotations are called Euler angles.

Because the three rotations occur about the axes Z^,Y^,X^\hat Z, \hat Y, \hat X, we will call this representation Z-Y-X Euler Angles.



We can use the intermediate frames BB' and BB'' in order to give an expression for BARZYX(α,β,γ)^A_BR_{Z'Y'X'}( \alpha , \beta, \gamma) Treating the rotations as descriptions of these frames, we can write:


$^A_BR = BAR^A_{B'}R BBR^{B'}_{B''}R BBR(9)^{B''}_BR \qquad(9)


where each of the relative descriptions on the right hand side is given by the statements of the Z-Y-X Euler angle convention.

The final orientation of B is given relative to A as:


BARZYX(α,β,γ)=RZ(α)RY(β)RX(γ)[cαsα0sαcα0000][cβ0sβ010sβ0cβ][1000cγsγ0sγcγ](10)\begin{matrix} ^A_BR_{Z'Y'X'}( \alpha , \beta, \gamma) = R_Z(\alpha) R_Y(\beta) R_X(\gamma) \\ \\ \begin{array}{ccc} \begin{bmatrix} c \alpha & - s \alpha & 0 \\ s \alpha & c \alpha & 0 \\ 0 & 0 & 0 \end{bmatrix} & \begin{bmatrix} c \beta & 0 & s \beta \\ 0 & 1 & 0 \\ -s \beta & 0 & c \beta \end{bmatrix} & \begin{bmatrix} 1 & 0 & 0 \\ 0 & c \gamma & - s \gamma \\ 0 & s \gamma & c \gamma \end{bmatrix} \end{array} \end{matrix} \qquad(10)


where cαc \alpha is shorthand for cosαcos \alpha, sαs \alpha for sinαsin \alpha, and so on.

Multiplying out in the order of rotation, we obtain:


BARZYX(γ,β,α)=[cαcβcαsβsγsαcγcαsβcγsαsγsαcβsαsβsγ+cαcγsαsβcγcαsγsβcβsγcβcγ](11)^A_BR_{Z'Y'X'}( \gamma , \beta, \alpha) = \begin{bmatrix} c \alpha c \beta & c \alpha s \beta s \gamma - s \alpha c \gamma & c \alpha s \beta c \gamma - s \alpha s \gamma \\ s \alpha c \beta & s \alpha s \beta s \gamma + c \alpha c \gamma & s \alpha s \beta c \gamma - c \alpha s \gamma \\ -s \beta & c \beta s \gamma & c \beta c \gamma \end{bmatrix} \qquad(11)


# Example Lecture 4





# Python implementation for Example 4:

import numpy as np


def main():
    """
    Example 4
    """
    np.set_printoptions(precision=3, suppress=True)

    print('Example 4:')
    print()

    print('Matrix A:')
    ma = np.float32([0.866, -0.5, 0,
                     0.5, 0.866, 0,
                     0, 0, 1])
    ma = np.reshape(ma, (3, 3))

    print(ma)

    print()
    print('Matrix I:')
    mi = np.float32([1, 0, 0,
                     0, 1, 0,
                     0, 0, 1])
    mi = np.reshape(mi, (3, 3))
    print(mi)

    print()
    print('Matrix I - A:')
    print(mi - ma)

    print()
    print('Matrix I + A:')
    print(mi + ma)

    print()
    print('Matrix (I + A)^-1:')
    print(np.linalg.inv(mi + ma))

    print()
    print('Matrix Q = (I-A)((I + A)^-1):')
    print(np.matmul((mi - ma), (np.linalg.inv(mi + ma))))

    return


if __name__ == '__main__':
    main()
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
Example 4:

Matrix A:
[[ 0.866 -0.5    0.   ]
 [ 0.5    0.866  0.   ]
 [ 0.     0.     1.   ]]

Matrix I:
[[1. 0. 0.]
 [0. 1. 0.]
 [0. 0. 1.]]

Matrix I - A:
[[ 0.134  0.5    0.   ]
 [-0.5    0.134  0.   ]
 [ 0.     0.     0.   ]]

Matrix I + A:
[[ 1.866 -0.5    0.   ]
 [ 0.5    1.866  0.   ]
 [ 0.     0.     2.   ]]

Matrix (I + A)^-1:
[[ 0.5    0.134  0.   ]
 [-0.134  0.5    0.   ]
 [ 0.     0.     0.5  ]]

Matrix Q = (I-A)((I + A)^-1):
[[ 0.     0.268  0.   ]
 [-0.268  0.     0.   ]
 [ 0.     0.     0.   ]]

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32

# Determinant 3X3

Just a reminder:



# 5. Lecture 5 - 09/03/2020

# Introduction

In today's lecture, we will:

  • Discuss manipulator kinematics.
  • Describe link descriptions.
  • Describe link-connection descriptions.
  • Present a convention for axing frames to links.

# Manipulator Knematics

Kinematics is the science of motion that treats the subject without regard to the forces that cause it.

Within kinematics, position, velocity, acceleration, and all higher order derivatives (with respect to time) are studied.

The kinematics of manipulators refers to all the geometrical and time-based properties of the manipulator's motion.

In order to deal with the complex geometry of a manipulator, we ax frames to the manipulator's various parts and then describe the relationships between these frames.

The study of manipulator kinematics involves how the locations of these frames changes as the manipulator moves.

A manipulator may be thought of as a set of bodies connected in a chain by joints. These bodies are called links. Joints form a connection between neighbouring pairs of links.

The term lower-pair is used describe the connection between bodies when the relative motion is characterised by two surfaces sliding over one another.

Mechanical-design considerations favour manipulators being constructed from joints that have just one degree of freedom.

Most manipulators are have revolute or prismatic joints.

In the case that a mechanism is built with n degrees of freedom, it can be modelled as n joints of one degree of freedom connected with n1n - 1 links of zero length.



Links are numbered starting from the base of the manipulator, which can be called link 0.

The first moving body is link 1, and so on, out to the free end of the manipulator, which is link nn.

In order to position an end-effector generally in three dimensional space (3-space), six degrees of freedom are required.

For the purpose of kinematics, each link is \considered only as a rigid body that defines the relationship between two neighbouring joint axes of a manipulator" [1].

Joint axes ii is defined by a vector direction about which link ii rotates relative to link i1i - 1.


For any two axes in 3-space, there exists a well-defined measures of distance between them.

This distance is measured along a line that is mutually perpendicular to both axes. It is unique except when both axes are parallel.

The link length, ai1a_{i-1}, is measured along the mutually perpendicular line between axis i1i - 1 and axis ii.

The second parameter needed to define the relative location of the two axes is called the link twist, αi1\alpha _{i-1}.

Constructing a plane whose normal is the mutually perpendicular line, we can project axes i1i - 1 and ii onto this plane and measure the angle between them.



In order to completely specify the way in which links are connected together, we need only two quantities.

Let us now consider the case for intermediate links in the chain, and the first and last link in the chain.

Neighbouring links have a common joint axis between them.

One parameter of interconnection is the distance along the common axis from one link to another. This is the link offset, didi.

The second parameter of interconnection is the angle of rotation about the common axis. This is the joint angle, θi\theta _i.

A frame is attached the base of the robot, or link 0, called frame {0}. This frame does not move, and for the problem of kinematics, can be considered the reference frame.

Frame {0} is arbitrary, so it always simplifies matters to choose Z^0\hat Z_0 along axis 1 and to locate frame {0} so that it is coincident with frame {1} when joint variable 1 is zero.


Using this convention, we will have a0=0a_0 = 0 and α0=0\alpha _0 = 0. For a revolute joint 1, d1d1 = 0, and for a prismatic joint 1, θ1\theta _1 = 0.

If joint n is revolute, the direction of X^n\hat X_n is chosen so that it aligns with X^n1\hat X_{n-1} when θn=0\theta _n = 0, and the origin of frame {N} is chosen so that dn=0dn = 0.

If joint n is prismatic, the direction of X^n\hat X_n is chosen so that θn=0\theta _n = 0, and the origin of frame {N} is chosen at the intersection of X^n1\hat X_{n-1} and joint axis nn when dn=0dn = 0.



If the link frames have been attached to the links according to our convention, the following definitions of the link parameters are valid:


  • ai=a_i = the distance from Z^i\hat Z_i to Z^i+1\hat Z_{i+1} measured along X^i\hat X_i;
  • αi=\alpha_i = the angle from Z^i\hat Z_i to Z^i+1\hat Z_{i+1} measured along X^i\hat X_i;
  • di=d_i = the distance from X^i+1\hat X_{i+1} to X^i\hat X_i measured along Z^i\hat Z_i;
  • θi=\theta_i = the angle from X^i+1\hat X_{i+1} to X^i\hat X_i measured along Z^i\hat Z_i;

The following is a summary of the procedure to follow in order to properly attach the link frames [1]:

  1. Identify the joint axes and draw infinite lines along them. For steps 2 through 5 below, consider two of these neighbouring lines (at axes ii and i+1i + 1).

  2. Identify the common perpendicular between them, or point of intersection. At the point of intersection, or at the point where the common perpendicular meets the ith axis, assign the link-frame origin.

  3. Assign the Z^i\hat Z_i axis pointing along the ithith joint axis.

  4. Assign the X^i\hat X_i axis pointing along the common perpendicular, or, if the axes intersect, assign X^i\hat X_i to be normal to the plane containing the two axis.

  5. Assign the Y^i\hat Y_i axis to complete a right-hand coordinate system.

  6. Assign {0} to match {1} when the first joint variable is zero. For {N}, choose an origin location and X^n\hat X_n freely, but generally so as to cause as many linkage parameters as possible to become zero.

# Example Lecture 5

On the link we follow the steps:

  1. Define Axes
  2. Define Mutually Perpendicular lines and assign x axis to it
  3. Draw Z^\hat Z along the axis
  4. Draw X^\hat X along the mutually perpendicular line.
  5. Find the Denavit-Hartenberg notation paramenters.

WARNING

Get photo from phone



WARNING

Get photo from phone, for the formulas




WARNING

From the slides, To get to the formula on the slide"Derivation of link Transformations VI" See the photo about the matrix calculations. taken at 11:24.

# Exercises Lecture 5











# Lecture 5 - Notes

Fixed Angles vs Euler rotation - See video on stream.


Example 4 Python program - 282762_Example_4.py file on Stream.


Take a look at the matrix revision on stream. Co-factors, minors and determinants - Lectures resources


Emphasize on the inverse matrix using Python


Rotation matrix and turn into a Skew matrix

line 113 and 108

R=(SI3)1(S+I3)R = (S - I_3)^1 (S + I_3)

S=(R+I3)1(RI3)S = (R + I_3)^1 (R - I_3)


Try to do the same on MAtlab.

WARNING

Execute both Matlab and Python examples and complete this class material around inverse matrix.
Also try to use C++ with the matrix library Eigen


Net homogeneous transform - Slide First and Last links in the Chain II - 4 transforms rotation and translation + rotation and translation.

WARNING

Draw this picture 10 times and rotulate

WARNING

Make the 4 matrix from the picture on the cell - in relation to the slide First and LAst Chain Links in the Chain II and the next

did_i


[10000100001d10001] \begin{bmatrix} 1 & 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ 0 & 0 & 1 & d_1\\ 0 & 0 & 0 & 1\\ \end{bmatrix}


θ\theta


[CθSθ00SθCθ0000100001] \begin{bmatrix} C_\theta & -S_\theta & 0 & 0\\ S_\theta & C_\theta & 0 & 0\\ 0 & 0 & 1 & 0\\ 0 & 0 & 0 & 1\\ \end{bmatrix}


ai1a _{i-1}


[100ai1010000100001] \begin{bmatrix} 1 & 0 & 0 & a_{i-1}\\ 0 & 1 & 0 & 0\\ 0 & 0 & 1 & 0\\ 0 & 0 & 0 & 1\\ \end{bmatrix}



αi1\alpha _{i-1}


[10000Cαi1Sαi100Sαi1Cαi100001] \begin{bmatrix} 1 & 0 & 0 & 0\\ 0 & C \alpha_{i-1} & -S\alpha_{i-1} & 0\\ 0 & S\alpha_{i-1} & C\alpha_{i-1} & 0\\ 0 & 0 & 0 & 1\\ \end{bmatrix}


# 6. Lecture 6 - 10/03/2020

# Introdution

In today's lecture, we will:

  • Present the derivation of the general form of link transformations.
  • Describe frames with standard names.
  • Describe how link transformations can be used to find the tool frame.

# Manipulator Kinematics

Individual transformations between frames attached to neighbouring links can be concatenated into solve for the position and orientation of link nn relative to link 0.

We want to construct the transform that defines frame {i}\{i\} relative to frame {i1}\{i - 1\}.

In general, this transform will be a function of the four link parameters, ai1,αi1,dia_{i - 1}, \alpha_{i - 1}, d_i and θi\theta_i

For any given robot, this transformation will be a function of only one variable, i.e. the joint variable, the other three parameters being fixed by mechanical design.

By defining a frame for each link, we have broken the kinematics problem into n sub-problems.

In order to solve these sub-problems, namely ii1T^{i - 1}_iT, we will further break them down into four sub-sub-problems.

Each of these four transformations will be a function of one link parameter only and be simple enough that we can write down its form by inspection.


We begin by defining three intermediate frames for each link - {P}\{P\}, {Q}\{Q\} and {R}\{R\}

  • Frame {R}\{R\} differs from frame {i1}\{i - 1\} only by a rotation of αi1\alpha_{i - 1}.
  • Frame {Q}\{Q\} differs from frame {R}\{R\} only by a translation of ai1a_{i - 1}.
  • Frame {P}\{P\} differs from frame {Q}\{Q\} only by a rotation of θi\theta_i .
  • Frame {i}\{i\} differs from frame {P}\{P\} only by a translation of did_i .


We can write the transformation that transforms vectors written in {i}\{i\} to their description in {i1}\{i - 1\} as:


i1P=Ri1TQRTPQTiPTiP(1)^{i - 1}P = ^{i - 1}_RT ^R_QT ^Q_PT ^P_iT ^iP \qquad(1)


or


i1P=ii1T^{i - 1}P = ^{i - 1}_iT iP(2)^iP \qquad(2)


Where:


i1T=Ri1T^{i - 1}T = ^{i - 1}_RT QRTPQTiPT^R_QT ^Q_PT ^P_iT iP(3)^iP \qquad(3)


Considering each of these transformations, we see that:


ii1T=RX(αi1)Dx(ai1)RZ(θi)Dz(di)(4)^{i - 1}_iT = R_X(\alpha_{i-1}) D_x(a_{i-1}) R_Z(\theta_i) D_z(d_i) \qquad(4)


or


ii1T=ScrewX(ai1,αi1)ScrewZ(di,θi)(5)^{i - 1}_iT = Screw_X(a_{i-1}, \alpha_{i-1}) Screw_Z(d_i, \theta_i) \qquad(5)


where the notation ScrewQ(r,θ)Screw_Q(r, \theta) stands for the combination of a translation along an axis Q^\hat Q by a distance rr and a rotation about the same axis by an angle of θ\theta.

Multiplying out the terms, we obtain the general from of i1T^{i - 1}T:


ii1T=[cθisθi0ai1sθicαi1cθicαi1sαi1sαi1disθisαi1cθicαi1cαi1cαi1di](6)^{i - 1}_iT = \begin{bmatrix} c \theta_i & -s \theta_i & 0 & a_{i-1} \\ s \theta_i c \alpha_{i-1} & c \theta_i c \alpha_{i-1} & -s \alpha_{i-1} & -s \alpha_{i-1} d_i \\ s \theta_i s \alpha_{i-1} & c \theta_i c \alpha_{i-1} & c \alpha_{i-1} & c \alpha_{i-1} d_i \end{bmatrix} \qquad(6)


Once the link frames have been defined and the corresponding link parameters found, developing the kinematic equations is straightforward. From the values of the link parameters, the individual link-transformation matrices can be found. These can then be multiplied together to find a single transformation that relates frame {N}\{N\} to frame {0}\{0\}:


N0T=10T21T32T...NN1T(7)^0_NT = ^0_1T ^1_2T ^2_3T ... ^{N-1}_NT \qquad(7)


# Actuator Space, Joint Space, and Cartesian Space

The position of all of an n degree of freedom manipulator's links can be specified with a set of n joint variables.

This set of variables is often referred to as the nx1n x 1 joint vector; the space of which is referred to as joint space.

So far, we have been concerned with computing the Cartesian space description from knowledge of the joint space; assuming each kinematic joint is actuated directly.

This is not the case of many industrial robots, e.g. two actuators working together to actuate one joint. Furthermore, the sensors that measure position are often situated on the actuators.

Therefore, some computations may needed to be performed to realise the joint vector from a set of actuator values, or actuator vector.



# Frames with Standard Names

As a matter of convention, it is helpful to assign specific names and locations to certain "standard" frames associated with a robot and its workspace.

The following frames are so often referred to that we will define names for them.

"The naming and subsequent use of these frames in a robot programming and control system facilitates providing general capabilities in an easily understandable way" [1].



# The Base Frame, {B}\{B\}

{B}\{B\} is located at the base of the manipulator.

It is another name for frame {0}\{0\}.

It is axed to a non-moving part of the robot, sometimes called link 0.

# The Station Frame, {S}\{S\}

{S}\{S\} is located in a task-relevant location, e.g. at the corner of a table upon which the robot is to work.

As far as the user is concerned, {S}\{S\} is the universe frame, and all actions of the robot are performed relative to it.

The station frame is always specified with respect to the base frame, i.e. SBT^B_ST

# The Wrist Frame, {W}\{W\}

{W}\{W\} is afixed to the last link of the manipulator.

It is another name for frame {N}\{N\}, the link frame attached to the last link of the robot.

Often, {W}\{W\} has its origin fixed at a point called the wrist of the manipulator, and moves with the last link of the manipulator.

It is defined relative to the base frame, i.e. {W}=WBT=N0T\{W\} = ^B_WT = ^0_NT.

# The Tool Frame, {T}\{T\}

{T}\{T\} is afixed to the end of any tool the robot is holding.

When the end-effector is empty, {T}\{T\} is usually located with its origin between the fingertips of the robot.

The tool is always specified with respect to the wrist frame.

# The Goal Frame, {G}\{G\}

{G}\{G\} is a description of the location to which the robot is to move the tool. Specifically, this means that the tool frame should coincide with the goal frame.

{G}\{G\} is always specified relative to the station frame.

# Where is the tool?

One of the first capabilities of a robot must have is to be able to calculate the position and orientation of the tool that it is holding with respect to a convenient system.

That is, we want to know the value of the tool frame, {T}\{T\}, relative to the station frame, {S}\{S\}.

Once WBT^B_WT has been computed, we can use Cartesian transforms to calculate TST^S_TT. Solving a simple transform equation leads to:


TST=SBT1^S_TT = ^B_ST^{-1} WBTTWT(8)^B_WT ^W_TT \qquad(8)


"This is what is called the WHERE function in some robot systems" [1].

# Lecture 6 Example











# Python Implementation of the example 6:

import numpy as np
import sympy as sympy


class MatrixSymbolic:
    """
    Definition: This class generates Homogeneous transform matrices, although it uses a symbolic approach
    that can be used to multiply any matrix and obtain the translation or rotation.

    It uses `sympy` to generate the matrices:

    sympy.Matrix: creates a sympy matrix object.

    sympy.Symbol: creates a symbol, Symbols are identified by name and assumptions.
    First, you need to create symbols using Symbol("x")
    We are assuming here that the symbols are "Real" number.
    All newly created symbols have assumptions set according to `args`, for example:

        >>> a = symbols('a', integer=True)
        >>> a.is_integer
        True
        >>> x, y, z = symbols('x,y,z', real=True)
        >>> x.is_real and y.is_real and z.is_real
        True

    sympy.cos and sympy.sin: cos and sin for sympy

    sympy.simplify: SymPy has dozens of functions to perform various kinds of simplification.
    simplify() attempts to apply all of these functions
    in an intelligent way to arrive at the simplest form of an expression.

    Returns: It returns Rotation and translation matrices.

    Obs: **kwargs (keyword arguments) are used to facilitate the identification of the parameters, so initiate the
    object
    """
    np.set_printoptions(precision=3,
                        suppress=True)

    sympy.init_printing(use_unicode=True,
                        num_columns=250)

    def __init__(self, **kwargs):
        """
        Initializes the Object.
        """
        self._x_angle = kwargs['x_angle'] if 'x_angle' in kwargs else 'gamma_i-1'
        self._x_dist = kwargs['x_dist'] if 'x_dist' in kwargs else 'a_i-1'
        self._y_angle = kwargs['y_angle'] if 'y_angle' in kwargs else '0'
        self._y_dist = kwargs['y_dist'] if 'y_dist' in kwargs else '0'
        self._z_angle = kwargs['z_angle'] if 'z_angle' in kwargs else '0'
        self._z_dist = kwargs['z_dist'] if 'z_dist' in kwargs else '0'

    def trans_x(self, a='a_i-1'):
        """
        Definition: Translates the matrix a given amount `a` on the *X* axis by Defining a 4x4 identity
        matrix with `a` as the (1,4) element.

        :type a: string
        :param a: Distance translated on the X-axis

        Returns: The Translation Matrix on the *X* axis by a given distance
        """
        if a is '0':
            self._x_dist = 0
        else:
            self._x_dist = sympy.Symbol(a, real=True)

        trans_x = sympy.Matrix([[1, 0, 0, self._x_dist],
                                [0, 1, 0, 0],
                                [0, 0, 1, 0],
                                [0, 0, 0, 1]])

        return trans_x

    def trans_y(self, b='b_i-1'):
        """
        Definition: Translate the matrix a given amount `d` on the *Z* axis. by Defining a matrix T 4x4 identity
        matrix with *b* (3,4) element position.

        :type b: string
        :param b: Distance translated on the Z-axis

        Returns: The Translation Matrix on the *Z* axis by a given distance
        """
        if b is '0':
            self._y_dist = 0
        else:
            self._y_dist = sympy.Symbol(b, real=True)

        trans_y = sympy.Matrix([[1, 0, 0, 0],
                                [0, 1, 0, self._y_dist],
                                [0, 0, 1, 0],
                                [0, 0, 0, 1]])

        return trans_y

    def trans_z(self, d='d_i-1'):
        """
        Definition: Translate the matrix a given amount `d` on the *Z* axis. by Defining a matrix T 4x4 identity
        matrix with *c* (3,4) element position.

        :type d: string
        :param d: Distance translated on the Z-axis

        Returns: The Translation Matrix on the *Z* axis by a given distance
        """
        if d is '0':
            self._z_dist = 0
        else:
            self._z_dist = sympy.Symbol(d, real=True)

        trans_z = sympy.Matrix([[1, 0, 0, 0],
                                [0, 1, 0, 0],
                                [0, 0, 1, self._z_dist],
                                [0, 0, 0, 1]])

        return trans_z

    def rot_x(self, gamma='gamma_i-1'):
        """
        Definition: Receives an alpha angle and returns the rotation matrix for the given angle at the *X* axis.
        If the angle is given in radian degrees should be False.

        :type gamma: string
        :param gamma: Rotation Angle around the X axis

        Returns: The Rotational Matrix at the X axis by an *given* angle
        """
        if gamma is '0':
            self._x_angle = 0
        else:
            self._x_angle = sympy.Symbol(gamma, real=True)

        rot_x = sympy.Matrix([[1, 0, 0, 0],
                              [0, sympy.cos(self._x_angle), -sympy.sin(self._x_angle), 0],
                              [0, sympy.sin(self._x_angle), sympy.cos(self._x_angle), 0],
                              [0, 0, 0, 1]])

        return rot_x

    def rot_y(self, beta='beta_i-1'):
        """
        Definition: Receives an theta angle and returns the rotation matrix for the given angle at the *Z* axis.
        If the angle is given in radian degrees should be False.

        :type beta: string
        :param beta: Rotation Angle around the Y axis

        Returns: The Rotational Matrix at the Y axis by an *given* angle
        """
        if beta is '0':
            self._y_angle = 0
        else:
            self._y_angle = sympy.Symbol(beta, real=True)

        rot_y = sympy.Matrix([[sympy.cos(self._y_angle), 0, 0, sympy.sin(self._y_angle)],
                              [0, 0, 0, 0],
                              [-sympy.sin(self._y_angle), 0, 1, sympy.cos(self._y_angle)],
                              [0, 0, 0, 1]])

        return rot_y

    def rot_z(self, alpha='alpha_i-1'):
        """
        Definition: Receives an theta angle and returns the rotation matrix for the given angle at the *Z* axis.
        If the angle is given in radian degrees should be False.

        :type alpha: string
        :param alpha: Rotation Angle around the Z axis

        Returns: The Rotational Matrix at the Z axis by an *given* angle
        """
        if alpha is '0':
            self._z_angle = 0
        else:
            self._z_angle = sympy.Symbol(alpha, real=True)

        rot_z = sympy.Matrix([[sympy.cos(self._z_angle), -sympy.sin(self._z_angle), 0, 0],
                              [sympy.sin(self._z_angle), sympy.cos(self._z_angle), 0, 0],
                              [0, 0, 1, 0],
                              [0, 0, 0, 1]])

        return rot_z


def main():
    """
    Example 6:

    Calculates the Three-link manipulator kinematics.
    At the end we can express a Transform from link 0 to link 3.
    """
    print('Example 6:')

    a1 = MatrixSymbolic()       # Rx(a_i-1)
    a2 = MatrixSymbolic()       # Dx(a_i-1)
    a3 = MatrixSymbolic()       # Dz(d_i)
    a4 = MatrixSymbolic()       # Rz(theta_i)

    print()
    print('Rx(0):')
    print(sympy.pretty(a1.rot_x('0')))
    print()

    print()
    print('Dx(a_i-1):')
    print(sympy.pretty(a2.trans_x('a_i-1')))
    print()

    print()
    print('Rz(theta_i):')
    print(sympy.pretty(a3.rot_z('theta_i')))
    print()

    print()
    print('Dz(d_i):')
    print(sympy.pretty(a4.trans_z('d_i')))
    print()

    print()
    print('t_0_1:')
    t_0_1 = (a1.rot_x('0')) * (a2.trans_x('0')) * (a3.trans_z('0')) * (a4.rot_z('theta_1'))
    print(sympy.pretty(t_0_1))

    print()
    print('t_1_2:')
    t_1_2 = (a1.rot_x('0')) * (a2.trans_x('l1')) * (a3.trans_z('0')) * (a4.rot_z('theta_2'))
    print(sympy.pretty(t_1_2))

    print()
    print('t_2_3:')
    t_2_3 = (a1.rot_x('0')) * (a2.trans_x('l2')) * (a3.trans_z('0')) * (a4.rot_z('theta_3'))
    print(sympy.pretty(t_2_3))

    t_0_2 = t_0_1 * t_1_2
    print()
    print('t_0_2:')
    print(sympy.pretty(t_0_2))

    print()
    print('Simplified t_0_2:')
    print(sympy.pretty(sympy.simplify(t_0_2)))

    t_0_3 = t_0_2 * t_2_3
    print()
    print('t_0_3:')
    print(sympy.pretty(sympy.simplify(t_0_3)))

    return


if __name__ == '__main__':
    main()
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254

Output:

Example 6:

Rx(0):
⎡1  0  0  0⎤
⎢          ⎥
⎢0  1  0  0⎥
⎢          ⎥
⎢0  0  1  0⎥
⎢          ⎥
⎣0  0  0  1⎦


Dx(a_i-1):
⎡1  0  0  aᵢ₋₁⎤
⎢             ⎥
⎢0  1  0   0  ⎥
⎢             ⎥
⎢0  0  1   0  ⎥
⎢             ⎥
⎣0  0  0   1  ⎦


Rz(theta_i):
⎡cos(θᵢ)  -sin(θᵢ)  0  0⎤
⎢                       ⎥
⎢sin(θᵢ)  cos(θᵢ)   0  0⎥
⎢                       ⎥
⎢   0        0      1  0⎥
⎢                       ⎥
⎣   0        0      0  1⎦


Dz(d_i):
⎡1  0  0  0 ⎤
⎢           ⎥
⎢0  1  0  0 ⎥
⎢           ⎥
⎢0  0  1  dᵢ⎥
⎢           ⎥
⎣0  0  0  1 ⎦


t_0_1:
⎡cos(θ₁)  -sin(θ₁)  0  0⎤
⎢                       ⎥
⎢sin(θ₁)  cos(θ₁)   0  0⎥
⎢                       ⎥
⎢   0        0      1  0⎥
⎢                       ⎥
⎣   0        0      0  1⎦

t_1_2:
⎡cos(θ₂)  -sin(θ₂)  0  l₁⎤
⎢                        ⎥
⎢sin(θ₂)  cos(θ₂)   0  0 ⎥
⎢                        ⎥
⎢   0        0      1  0 ⎥
⎢                        ⎥
⎣   0        0      0  1 ⎦

t_2_3:
⎡cos(θ₃)  -sin(θ₃)  0  l₂⎤
⎢                        ⎥
⎢sin(θ₃)  cos(θ₃)   0  0 ⎥
⎢                        ⎥
⎢   0        0      1  0 ⎥
⎢                        ⎥
⎣   0        0      0  1 ⎦

t_0_2:
⎡-sin(θ₁)⋅sin(θ₂) + cos(θ₁)⋅cos(θ₂)  -sin(θ₁)⋅cos(θ₂) - sin(θ₂)⋅cos(θ₁)  0  l₁⋅cos(θ₁)⎤
⎢                                                                                     ⎥
⎢sin(θ₁)⋅cos(θ₂) + sin(θ₂)⋅cos(θ₁)   -sin(θ₁)⋅sin(θ₂) + cos(θ₁)⋅cos(θ₂)  0  l₁⋅sin(θ₁)⎥
⎢                                                                                     ⎥
⎢                0                                   0                   1      0     ⎥
⎢                                                                                     ⎥
⎣                0                                   0                   0      1     ⎦

Simplified t_0_2:
⎡cos(θ₁ + θ₂)  -sin(θ₁ + θ₂)  0  l₁⋅cos(θ₁)⎤
⎢                                          ⎥
⎢sin(θ₁ + θ₂)  cos(θ₁ + θ₂)   0  l₁⋅sin(θ₁)⎥
⎢                                          ⎥
⎢     0              0        1      0     ⎥
⎢                                          ⎥
⎣     0              0        0      1     ⎦

t_0_3:
⎡cos(θ₁ + θ₂ + θ₃)  -sin(θ₁ + θ₂ + θ₃)  0  l₁⋅cos(θ₁) + l₂⋅cos(θ₁ + θ₂)⎤
⎢                                                                      ⎥
⎢sin(θ₁ + θ₂ + θ₃)  cos(θ₁ + θ₂ + θ₃)   0  l₁⋅sin(θ₁) + l₂⋅sin(θ₁ + θ₂)⎥
⎢                                                                      ⎥
⎢        0                  0           1               0              ⎥
⎢                                                                      ⎥
⎣        0                  0           0               1              ⎦

Process finished with exit code 0
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97

# 7. Lecture 7 - 16/03/2020

# Introduction

In today's lecture, we will:

  • Discuss issues related to computing a manipulator's inverse kinematics.
  • Introduce the notion of manipulator subspace when n < 6.
  • Demonstrate how to compute an algebraic, closed-form solution.

# Notes

Compute the transform from one frame to another, by computing the individual transforms relating to αi1\alpha_{i-1}, ai1a_{i-1}, did_i and θi\theta_i

Solve this using Matlab and Python and explain how things are working.

Python library "sympy" - pip install sympy

Rewrite 282762_Example_6_Symbolic to match the exercise

# Inverse Kinematics

Kinematics considers the problem of computing the end-effector's position and orientation using the manipulator's joints' angles.

Inverse kinematics considers the problem of computing the manipulator's joints' angles using the end-effector's position and orientation.

Finding the joint angles to place the tool frame, {F}\{F\}, relative to the station frame, {S}\{S\}, is done in two parts: first, transformations to find the wrist frame, {W}\{W\}, relative to the base frame, {B}\{B\}, are done; next, inverse kinematics are used to solve for joint angles.

# Solvability

Solving kinematic equations is a non-linear problem; where, given N0T^0_NT, we attempt to solve θ0,...,θN\theta_0,...,\theta_N [1].

For example, given 60T^0_6T, solve for θ0,...,θ6\theta_0,...,\theta_6. Here, we have a transform for an arm with six degrees of freedom, which has 12 equations and six unknowns.

From the nine equations related to the rotation matrix, only three are independent. These, added to the three equations related to the position vector, give six equations with six unknowns.

These equations are non-linear, transcendental equations and are quite difficult to solve. In solving them, we need to consider the existence of solutions, if there are multiple solutions, and the method used.

# Existence of Solutions

"For a solution to exist, the specified goal point must lie within the manipulator's workspace"[1].

A manipualtor's workspace can be defined as:

  • Dextrous workspace. This is the volume of space the end-effector can reach with all orientations.
  • Reachable workspace. This is the volume of space the end-effector can reach in at least one orientation.

Consider the workspace of the following two-link manipulator:


Two-link manipulator

If l1=l2l_1 = l_2, the reachable workspace is a disk of radius 2l12l_1; the dexterous workspace is a single point, the origin.

If l1l2l_1 \neq l_2, the reachable workspace is a ring with an outer radius of l1+l2|l_1 + l_2| and an inner radius of l1l2|l_1 - l_2|; there is no dexterous workspace.

In the second case, inside the reachable workspace, there are two potential orientations; on the workspace's boundary, there is only one.

Here, we've assumed the manipulator's joints can rotate 360 degrees. Generally, joints are limited to a subset of 360 degrees, which in turn limits the workspace and orientations attainable at a point.


"Workspace also depends on the tool-frame transformation, because it is usually the tool-tip that is discussed when we speak of reachable points in space"[1].

"Generally, the tool transformation is performed independently of the manipulator kinematics and inverse kinematics, so we are often led to consider the workspace of the wrist frame, {W}\{W\}" [1].

For a given end-effector, a tool frame, {T}\{T\}, is defined; given a goal frame, {G}\{G\}, the corresponding {W}\{W\} frame is calculated, and then we ask: does {W}\{W\} lie in the workspace?

If {W}\{W\} is in the workspace, then at least one solution exists.

# Multiple Solutions

Another challenge for computing a manipulator's inverse kinematics is if there are multiple solutions.

Consider the following three-link manipulator:


Three-link manipulator

Here, the manipulator has a large dexterous workspace. Any position in the workspace's interior can be reached with any orientation. The problem is, how do you choose one?

The criteria to choose a solution varies, e.g. \a reasonable method would be choosing the closest one" [1]; where, an algorithm uses the manipulator's current orientation and computes the minimum rotation required to move a tool from point A to point B.

The number of solutions depends on the number of joints, but is also a function of the link parameters (αi,ai,di,andθi)(\alpha_i , a_i , d_i , and \theta_i ), and the joints' range of motion [1].

In general, the more non-zero link parameters, the more solutions. For a manipulator with six degrees of freedom, there are up to 16 potential solutions [1].


Alternative solutions for the Three-link manipulator

# Method of Solution

When considering solving a set of nonlinear equations, we need to know what is a solution.

Here, a manipulator is considered solvable if "the joint variables can be determined by an algorithm that allows one to determine all the sets of joint variables associated with a given position and orientation"[1]. Solution strategies can be categorised as:

  • Closed-form solutions. This solution method is based on analytical expressions or on the solution of a polynomial expression.

  • Numerical solutions. This solution method is based on numerical approximations of the solution.

Within the class of closed-form solutions, there are two methods of obtaining a solution: algebraic and geometric. These method are similar and "differ" perhaps in approach only"[1].

# Manipulator Subspace When n < 6

A manipulator's set of reachable goal frames constitute its workspace.

For a manipulator with n degrees of freedom (where n < 6), this reachable workspace can be thought of as a portion of an n degree of freedom subspace.

"One way to specify the subspace of an n degree of freedom manipulator is to express its writes or tool frame in terms of n variables that locate it"[1].

"If we consider these variables to be free, then, as they take on all possible values, the subspace is generated"[1].


In defining an n degree of freedom manipulator's goal, n parameters are used. Subsequently, we will not be able to reach the goal if a manipulator with less than n degrees of freedom is used.

When specifying general goals for a manipulator with fewer than six degrees of freedom, one strategy is as follows [1]:

  • Given the goal frame, GST^S_GT, compute a modified goal frame, GST^S_{G'}T, so that it lies in the manipulator's subspace and is near GST^S_GT. A definition of "near" must be chosen.

  • Compute the inverse kinematics to find the joint angles using GST^S_GT as the desired goal. A solution is only possible if the goal is in the manipulator's workspace.

# Algebraic Closed-Form Solutions

Consider the following three-link manipulator:


Three-link manipulator

The manipulator's link parameters are tabulated below:


i αi1\alpha_{i-1} ai1a_{i-1} did_i θi\theta_i
1 0 0 0 θ1\theta_1
2 0 l1l_1 0 θ2\theta_2
3 0 l2l_2 0 θ3\theta_3

The manipulator's kinematic equations are given by:


WBT=[c123s1230.0l1c1+l2c12s123c1230.0l1s1+l2s120.00.01.00.00.00.00.01.0](1)^B_WT = \begin{bmatrix} c_{123} & -s_{123} & 0.0 & l_1c_1 + l_2c_{12}\\ s_{123} & c_{123} & 0.0 & l_1s_1 + l_2s_{12}\\ 0.0 & 0.0 & 1.0 & 0.0 \\ 0.0 & 0.0 & 0.0 & 1.0 \\ \end{bmatrix} \qquad(1)


Let's assume the goal point is a specification of the wrist frame relative to the base frame, i.e. WBT^B_WT.

Given our manipulator, the goal point can be specified using three variables: x, y, and ϕ\phi, where ϕ\phi is link three's orientation relative to +X^+\hat X axis.

We also assume WBT^B_WT's structure is as follows:


WBT=[cϕsϕ0.0xsϕcϕ0.0y0.00.01.00.00.00.00.01.0](2)^B_WT = \begin{bmatrix} c_\phi & -s_\phi & 0.0 & x\\ s_\phi & c_\phi & 0.0 & y\\ 0.0 & 0.0 & 1.0 & 0.0 \\ 0.0 & 0.0 & 0.0 & 1.0 \\ \end{bmatrix} \qquad(2)


All attainable goals must lie in the subspace implied by this structure.

Equating (1) and (2), we arrive at a set of four nonlinear equations that must be solved for θ1\theta_1, θ2\theta_2, and θ3\theta_3:


cϕ=c123(3)c_\phi = c_{123} \qquad(3)

sϕ=s123(4)s_\phi = s_{123} \qquad(4)

x=l1c1+l2c12(5)x = l_1c_1 + l_2c_{12} \qquad(5)

y=l1s1+l2s12(6)y = l_1s_1 + l_2s_{12} \qquad(6)


We can now start our algebraic solution. If we square both (5) and (6) and add them, we obtain:


x2+y2=l12+l22+2l1l2c2(7)x^2 + y^2 = l^2_1 + l^2_2 + 2l_1l_2c_2\qquad(7)


where we have made use of


c12=c1c2s1s2,s12=c1s2+s1c2(8)\begin{matrix} c_{12} = c_1c_2 - s_1s_2, \\ s_{12} = c_1s_2 + s_1c_2 \end{matrix} \qquad(8)


Solving (7) for c2c_2, we get


c2=x2+y2l12l222l1l2(9)c_2 = \frac{x^2 + y^2 - l^2_1 - l^2_2}{2l_1l_2}\qquad(9)


For a solution to exist, the right hand of (9) must have a value between -1 and 1. If this condition isn't met, then the goal point is too far away for the manipulator to reach.

Assuming the goal is in the workspace, s2s_2 can be expressed as:


s2=±1c22(10)s_2 = \pm \sqrt{1 - c^2_2}\qquad(10)


The choice of signs here corresponds to the multiple solutions in which we can choose the "elbow-up" or "elbow-down" solution [1].

Finally, we compute θ2\theta_2 as


θ2=Atan2(s2,c2)(11)\theta_2 = Atan2(s_2, c_2)\qquad(11)


Having found θ2\theta_2, we can solve (5) and (6) for θ1\theta_1. We write (5) and (6) in the form:


x=k1c1k2s1(12)x = k_1c_1 - k_2s_1\qquad(12)

x=k1s1+k2c1(13)x = k_1s_1 + k_2c_1\qquad(13)


Where,


k1=l1+l2c2,k2=l2s2(14)\begin{matrix} k_1 = l_1 + l_2c_2, \\ k_2 = l_2s_2 \end{matrix} \qquad(14)


In order to solve an equation of this form, we perform a change of variables, i.e. we change the way we write k1k_1 and k2k_2.

if,


r=+k12+k22(15)r = + \sqrt{k^2_1 + k^2_2}\qquad(15)


and


γ=Atan2(k2,k1)(16)\gamma = Atan2(k_2,k_1)\qquad(16)


then,


k1=rcosγ,k2=rsinγ(17)\begin{matrix} k_1 = rcos\gamma, \\ k_2 = rsin\gamma \end{matrix} \qquad(17)


"This substitution constitutes a method of solution of a form appearing frequently in kinematics"[1].

Equations (12) and (13) can now be written as:


xr=cosγcosθ1sinγsinθ1(18)\frac{x}{r} = cos\gamma cos\theta_1 - sin\gamma sin\theta_1\qquad(18)

yr=cosγsinθ1+sinγcosθ1(19)\frac{y}{r} = cos\gamma sin\theta_1 + sin\gamma cos\theta_1\qquad(19)


so,


cos(γ+θ1)xr,(20)cos(\gamma + \theta_1)\frac{x}{r},\qquad(20)

sin(γ+θ1)yr(21)sin(\gamma + \theta_1)\frac{y}{r}\qquad(21)


Subsequently,


γ+θ1=Atan2(zr,xr)=Atan2(y,x),(22)\gamma + \theta_1 = Atan2(\frac{z}{r}, \frac{x}{r}) = Atan2(y, x),\qquad(22)


and so,


θ1=Atan2(y,x)Atan2(k2,k1),(23)\theta_1 = Atan2(y, x) - Atan2(k_2, k_1),\qquad(23)


Finally, from (3) and (4), we can solve for the sum of θ1\theta_1 through θ3\theta_3:


θ1+θ2+θ3=Atan2(sϕ,cϕ)=ϕ(24)\theta_1 + \theta_2 + \theta_3 = Atan2(s_\phi, c_\phi) = \phi\qquad(24)


From this, we can solve for θ3\theta_3, because we know the first two angles.

"An algebraic approach to solving kinematic equations is basically one of manipulating the given equations into a form for which a solution is known"[1].

# Lecture 7 Example


Example Lecture 7


Example Lecture 7


Example Lecture 7


Example Lecture 7


Example Lecture 7


Example Lecture 7


Example Lecture 7


Example Lecture 7


Example Lecture 7

# 8. Lecture 8 - 17/03/2020

# Introduction

In today's lecture, we will:

  • Demonstrate how to compute a geometric, closed-form solution.
  • Discuss the standard frames and solving the manipulator's inverse kinematics.

# Notes

Elbow up and down configuration using cosine's law.

See picture at the phone took before 10:30am

We went through the lecture 7 slide.

# Geometric Closed-Form Solutions

The geometric approach decomposes a manipulator's spatial geometry into several plane-geometry problems, and (when αi1\alpha_{i-1} or ±90\pm 90) can be done quite easily [1].

Consider the following three-link manipulator:


Three link planar robot

There is a triangle formed by l1l_1, l2l_2, and the line connecting frame {0}\{0\} and frame {3}\{3\}.

Considering this triangle, we can use apply the "law of cosines" to solve for θ2\theta_2:


x2+y2=l12+l222l1l2cos(180+θ2)(1)x^2 + y^2 = l^2_1 + l^2_2 - 2l_1l_2cos(180 + \theta_2)\qquad(1)


Now, cos(180+θ2)=cos(θ2)cos(180 + \theta_2) = -cos(\theta_2), so we have:


c2=x2+y2l12l222l1l2(2)c_2 = \frac{x^2 + y^2 - l^2_1 - l^2_2}{2l_1l_2}\qquad(2)


In order for this triangle to exist, the distance to the goal,x2+y2\sqrt{x^2 + y^2}, must be less than or equal to the sum of the link lengths, l1l_1 and l2l_2.

Assuming a solution exists, this equation is solved for the value of θ2\theta_2 that lies between 0 and -180 degrees.

To solve for θ1\theta_1, we find expressions for angles ψ\psi and β\beta.

First, β\beta may be in any quadrant, depending on x and y's signs. So we must use a two-argument arctangent:


β=Atan2(y,x)(3)\beta = Atan2(y, x)\qquad(3)


We again apply the law of cosines to find ψ\psi:


cϕ=x2+y2+l12l222l1x2+y2(4)c_\phi = \frac{x^2 + y^2 + l^2_1 - l^2_2}{2l_1 \sqrt{x^2 + y^2}}\qquad(4)


Here, the arccosine must be solved so that 0ψ180o0 \leq \psi \leq 180^o, in order that the geometry leading to (4) is preserved.

We then have,


θ1=β±ψ(5)\theta_1 = \beta \pm \psi \qquad(5)


where the plus sign is used if θ2<0\theta_2 < 0 and the minus sign if θ2>0\theta_2 > 0.

We know that angles in a plane add, so the sum of the three joint angles must be the orientation of the last link:


θ1+θ2+θ3=ϕ(6)\theta_1 + \theta_2 + \theta_3 = \phi \qquad(6)


This is solved for θ3\theta_3 to complete the solution.

# The Standard Frames

Consider the standard frames:


Standard Frames

"The ability to solve for joint angles is really the central element in many robot control systems" [1].

The standard frames are used in this context as follows:

  1. The user specifies where the station frame, {S}\{S\}, is. {S}\{S\} is defined relative to the base frame, {B}\{B\}.

  2. The user specifies where the tool frame, {T}\{T\}, is. {T}\{T\} is defined relative to the wrist frame, {W}\{W\}.

  3. The user specifies where the goal frame, {G}\{G\}, is relative to {S}\{S\}.

  4. The robot calculates a series of joint angles to move the joints through to move {T}\{T\} to {G}\{G\}.

"The SOLVE function implements Cartesian transformations and calls the inverse kinematics function" [1].

Given the goal-frame specification, TST^S_TT, SOLVE uses the tool and station definitions to calculate the location of {W}\{W\} relative to {B}\{B\}, WBT^B_WT:


WBT=SBTTST^B_WT = ^B_ST ^S_TT TWT1(7)^W_TT^{-1} \qquad(7)


Then, the inverse kinematics take WBT^B_WT as an input and calculate θ1\theta_1 through θn\theta_n.

# Lecture 8 Example


Standard Frames


Standard Frames


Standard Frames


Standard Frames

# 9. Lectures 9 - 20/04/2020

# Introduction

In today's lecture, we will:

  • Describe how to compute the derivative of a vector.
  • Discuss linear and angular velocities of rigid bodies.
  • Describe how to propagate the linear and angular velocities from link to link.

# Notes

# The derivative of position is velocity and of velocity is acceleration?

# The derivative of the velocity, which is the second derivative of the position function, represents the instantaneous acceleration of the particle at time t.

Jacobians for kinematic equations

Homogenous transforms

Rotaion Matrix

Numerical Question

Inverse kninematics for 2 degree freedom

# homagenoeous transforms

Whats the h t that describes point a in relation of plan b

Here is bp what is ap?

# Class 21/04/2020

List of moments of inertia

What this equations are while rotating what III and ZZZ is. AV˚Q^A \mathring V_Q : Linear Aceleration - AVQ^AV_Q Linear Velocity


V˚\mathring V

Rot_X(alpha_i)=1      0          0       0⎤
⎢                           ⎥
⎢0  cos(αᵢ₋₁)  -sin(αᵢ₋₁)  0⎥
⎢                           ⎥
⎢0  sin(αᵢ₋₁)  cos(αᵢ₋₁)   0⎥
⎢                           ⎥
⎣0      0          0       1
1
2
3
4
5
6
7
8
9

# Jacobians

Kinematics is the science of motion that treats the subject without regard to the forces that cause it.

Within kinematics, position, velocity, acceleration, and all higher order derivatives (with respect to time) are studied.

Here, we consider the linear and angular velocities of rigid bodies.

# Differentiation of Position Vectors

The derivative of a vector can be defined as:


BVQ=ddtBQ=limΔt0BQ(t+Δt)BQ(t)Δt(1)^BV_Q = \frac{d}{dt}^BQ = \lim_{\Delta t \to 0} \frac{^BQ(t + \Delta t) - ^BQ(t)}{\Delta t} \qquad(1)


Here, we are calculating the velocity of {Q}\{Q\} relative to frame {B}\{B\}.

A velocity vector can be described in terms of any frame, which is indicated with a leading superscript:


A(BVQ)=AddtBQ(2)^A(^BV_Q) = A\frac{d}{dt}^BQ \qquad(2)


The velocity's numerical value depends on the frame the differentiation was done in and the frame in which the velocity is expressed.

When the differentiation is done in the same frame as it is expressed in, the notation simplifies; for example,


B(BVQ)=BVQ(3)^B(^BV_Q) = ^BVQ \qquad(3)


The leading superscript can be removed by including the rotation matrix that accomplishes the change in reference frame; for example,


A(BVQ)=BARBVQ(4)^A(^BV_Q) = ^A_BR ^BVQ \qquad(4)


Here, we will write expressions in the form of the right-hand side of (4) so that symbols representing velocity will always mean velocity in the frame of differentiation [1].


Rather than considering a general point's velocity relative to an arbitrary frame, we often consider the velocity of the origin of a frame relative to an understood reference frame [1].

For this case, we define a shorthand notation,


Vc=UVCORG(5)V_c = ^UV_{CORG} \qquad(5)


Here, VcV_c is the velocity of frame {C}\{C\}'s origin relative to frame {U}\{U\}.

# Angular Velocity Vectors

"Where linear velocity describes an attribute of a point, angular velocity describes an attribute of a body" [1]. Given we attach frames to a body, angular velocity describes the rotational motion of a frame."


Frame B rotating relative to frame A

The direction of BAΩ^A_B\Omega indicates the instantaneous rotation of {B}\{B\} relative to {A}\{A\}, and the magnitude of BAΩ^A_B\Omega indicates the speed of rotation.

An angular velocity can be expressed in terms of any frame, which is indicated with a leading superscript; for example,


C(AΩB)(6)^C(^A\Omega_B)\qquad(6)


As before, we often consider the angular velocity of a frame relative to an understood reference frame [1].

For this case, we define a shorthand notation,


ωC=UΩC(7)\omega_C = ^U\Omega_C\qquad(7)


Here, ωC\omega_C is the angular velocity of frame {C}\{C\} relative to frame {U}\{U\}.

# Linear Velocity

Consider the following frames. We want to describe the motion of BQ^BQ relative to frame {A}\{A\}.


Frame B rotating relative to frame A

Frame {B}\{B\} is described relative to frame {A}\{A\} via APBORG^AP_{BORG} and BAR^A_BR.

If BAR^A_BR is not changing with time, then point Q's motion relative to BAR^A_BR is due to APBORG^AP_{BORG} or BQ^BQ changing with respect to time.

In this case, AVQ^AV_Q can be computed as:


AVQ=AVBORG+BARBVQ(8)^AV_Q = ^AV_{BORG} + ^A_BR ^BVQ\qquad(8)


This is true only when the relative orientation of {B}\{B\} and {A}\{A\} remains constant.

# Angular Velocity

Consider the following frames. We want to describe the motion of BQ^BQ relative to frame {A}\{A\}.


Frame B rotating relative to frame A

Frame {B}\{B\} and frame {A}\{A\}'s origins are coincident. Frame {B}\{B\} is described relative to frame {A}\{A\} via BAR^A_BR.

If BVQ^BV_Q is not changing with time, then point Q's motion relative to {A}\{A\} is due to BAR^A_BR changing with respect to time.

We can use an intuitive approach to find AVQ^AV_Q. Consider the following figure:


Velocity of a point due to an angular velocity

The differential change in QA^A_Q must be perpendicular to both AΩB^A\Omega_B and QA^A_Q. Its magnitude is given by:


ΔQ=(AQsinθ)(AΩBΔt)(9)|\Delta Q| = (|^AQ|sin\theta)(|^A\Omega_B|\Delta t)\qquad(9)


As such, the AVQ^AV_Q can be computed using the vector cross-product:


AVQ=AΩB×AQ(10)^AV_Q = ^A\Omega_B \times ^AQ\qquad(10)


This is true only when BVQ^BV_Q is not changing with time.


In general, Q would be changing relative to frame {B}\{B\}. Adding this, we have:


AVQ=A(BVQ)+AΩB×AQ(11)^AV_Q = ^A(^BV_Q) + ^A\Omega_B \times ^AQ\qquad(11)


Substituting a rotation matrix in place of the leading superscript, we have:


AVQ=BARBVQ+AΩB×AQ(12)^AV_Q = ^A_BR ^BV_Q + ^A\Omega_B \times ^AQ\qquad(12)


# Simultaneous Linear and Rotational Velocity

Combining both linear and rotational velocities, the velocity of a vector fixed in frame {B}\{B\} with respect to frame {A}\{A\} can be expressed as


AVQ=AVBORG+BARBVQ+AΩB×AQ(13)^AV_Q = ^AV_{BORG} + ^A_BR ^BV_Q + ^A\Omega_B \times ^AQ\qquad(13)


In considering a robots link's motion, frame {0}\{0\} is used as the reference frame.

ViV_i is the linear velocity of the origin of frame {i}\{i\}, and ωi\omega_i is the angular velocity of frame {i}\{i\}.

At any instant, each robot's link in motion has some linear and angular velocity.


Velocity of a point due to an angular velocity

"A manipulator is a chain of bodies, each one capable of motion relative to its neighbours. Because of this structure, we can compute the velocity of each link, starting from the base" [1].

Link i+1i + 1's velocity is link ii's velocity plus the velocity added by joint i+1i + 1. Each link's velocities are expressed with respect to the link's frame.


Velocity of vectors of neighbouring links

Rotational velocities can be added when both ω\omega vectors are written with respect to the same frame.

The angular velocity of link i+1i + 1 is the same as link i plus the rotational velocity at joint i+1i + 1, which can be written as:


iωi+1=iωi+i+1iRθ˚i+1^i\omega_{i + 1} = ^i\omega_i + ^i_{i+1}R \mathring \theta_{i + 1} i+1Zi+1(14)^{i + 1}Z_{i + 1}\qquad(14)


Note that:


θ˚i+1\mathring \theta_{i + 1} i+1Zi+1=i+1[00θ˚i+1](15)^{i + 1}Z_{i + 1} = ^{i + 1} \begin{bmatrix} 0 \\ 0 \\ \mathring \theta_{i + 1}\end{bmatrix}\qquad(15)


Here, the angular velocity is expressed in terms of frame {i}\{i\}.

By premultiplying (15) by ii+1R^{i + 1}_iR, the angular velocity can be expressed in terms of frame {i+1}\{i + 1\}:


i+1ωi+1=ii+1R^{i + 1}\omega_{i + 1} = ^{i + 1}_iR iωi+θ˚i+1^i\omega_i + \mathring \theta_{i + 1} i+1Zi+1(16)^{i + 1}Z_{i + 1}\qquad(\color{red}{16})


The linear velocity of link i+1i + 1 is the same as link i plus the linear velocity caused by joint i+1i + 1, which can be written as:


iVi+1=iVi+iωi×iPi+1(17)^iV_{i + 1} = ^iV_i + ^i\omega_i \times ^iP_{i + 1}\qquad(17)


By premultiplying (17) by ii+1R^{i + 1}_iR, the linear velocity can be expressed in terms of frame {i+1}\{i + 1\}:


i+1Vi+1=ii+1R(iVi+iωi×iPi+1)(18)^{i + 1}V_{i + 1} = ^{i + 1}_iR (^iV_i + ^i\omega_i \times ^iP_{i + 1})\qquad(\color{red}{18})


The correpsonding relationships for the case where joint i+1i + 1 is prismatic are:


i+1ωi+1=ii+1Riωi,i+1Vi+1=ii+1R(iVi+iωi×iPi+1)+d˚i+1(i+1Zi+1)(19)\begin{matrix} ^{i + 1}\omega_{i + 1} = ^{i + 1}_iR ^i\omega_i, \\ ^{i + 1}V_{i + 1} = ^{i + 1}_iR (^iV_i + ^i\omega_i \times ^iP_{i + 1}) + \mathring d_{i + 1} (^{i + 1}Z_{i + 1}) \end{matrix} \qquad(19)


Applying these equations, link to link, we can compute NωN^N\omega_N and NVN^NV_N.

# Lecture 9 Example


Example Lecture 9


Example Lecture 9


Example Lecture 9


Example Lecture 9

# 10. Lecture 10

# Introduction

In today's lecture, we will:

  • Describe how to compute the Jacobian of a manipulator.
  • Discuss singularities of the mechanism.
  • Describe how to propagate forces and moments from link to link.
  • Describe how the Cartesian transform of velocities and static forces.

# Jacobians - Velocities and Static Forces

Kinematics is the science of motion that treats the subject without regard to the forces that cause it.

Within kinematics, position, velocity, acceleration, and all higher order derivatives (with respect to time) are studied.

Here, we consider the Jacobian: "a multidimensional form of the derivative" [1], which can be used to relate joint velocities to Cartesian velocities.

The Jacobian is a multidimensional form of the derivative. Suppose we have six equations with six independent variables:


y1=f1(x1,x2,x3,x4,x5,x6),y2=f1(x1,x2,x3,x4,x5,x6),y6=f1(x1,x2,x3,x4,x5,x6).(1)\begin{matrix} y_1 = f_1(x_1, x_2, x_3, x_4, x_5, x_6),\\ y_2 = f_1(x_1, x_2, x_3, x_4, x_5, x_6),\\ \vdots \\ y_6 = f_1(x_1, x_2, x_3, x_4, x_5, x_6). \end{matrix} \qquad(1)


These equations can be written in vector notation:


Y=F(X)(2)Y = F(X)\qquad(2)


If we want to calculate the differentials of yiy_i as a function of diferentials of xjx_j , we use the chain rule to get


δy1=f1x1δx1+f2x2δx2++f6x6δx6δy2=f1x1δx1+f2x2δx2++f6x6δx6δy6=f1x1δx1+f2x2δx2++f6x6δx6(3)\begin{matrix} \delta y_1 = \frac{\partial f_1}{\partial x_1}\delta x_1 + \frac{\partial f_2}{\partial x_2}\delta x_2 + \cdots + \frac{\partial f_6}{\partial x_6}\delta x_6 \\ \delta y_2 = \frac{\partial f_1}{\partial x_1}\delta x_1 + \frac{\partial f_2}{\partial x_2}\delta x_2 + \cdots + \frac{\partial f_6}{\partial x_6}\delta x_6 \\ \vdots \\ \delta y_6 = \frac{\partial f_1}{\partial x_1}\delta x_1 + \frac{\partial f_2}{\partial x_2}\delta x_2 + \cdots + \frac{\partial f_6}{\partial x_6}\delta x_6 \end{matrix} \qquad(3)


These equations can be written in vector notation:


Y=FXδX(4)\begin{matrix} \partial Y = \frac{\partial F}{\partial X}\delta X \end{matrix} \qquad(4)


The 6×66 \times 6 matrix of partial derivatives is called the Jacobian, JJ. If the functions of f1(X)f_1(X) through f6(X)f_6(X) are nonlinear, then the partial derivatives are a function of the xix_i , so, we can use the notation


δY=J(X)δX(5)\delta Y = J(X)\delta X\qquad(5)


Dividing both sides of the equation by the differential time element, δt\delta t, we can think of the Jacobian as mapping velocities in XX to those in YY :


Y˚=J(X)X˚(6)\mathring Y = J(X) \mathring X\qquad(6)


We see that as XX changes with respect to time, so too does the transform, J(X)J(X). As such, the Jacobian is a time-varying linear transform.

In robotics, Jacobians are used to relate joint velocities to Cartesian velocities. For example,


0v=J(θ)θ˚(7)^0v = J(\theta) \mathring \theta \qquad(7)


where θ\theta is the vector of the manipulator's joint angles and vv is the vector of the Cartesian velocities.

As the Jacobian is a time-varying transform, the relationship between the joint velocities and the Cartesian velocities is an instantaneous one.


Jacobians of any dimension can be defined.

For a six degree of freedom manipulator, the Jacobian is a 6×66 \times 6 matrix, θ˚\mathring \theta is a 6×16 \times 1 vector, and 0v^0v is a 6×16 \times 1 vector. This 6×16 \times 1 Cartesian velocity vector is the stacked 3×13 \times 1 linear and 3×13 \times 1 angular velocity vectors:


0v=[0υ0ω](8)^0v = \begin{bmatrix} ^0\upsilon \\ ^0\omega \end{bmatrix} \qquad(8)


The number of rows is equal to the number of degrees of freedom in the Cartesian space.

The number of columns is equal to the number of joints in the manipulator.

Consider the following manipulator:


Two-link Manipulator

For a two degree of freedom manipulator, we can write the Jacobian as a 2×22 \times 2 matrix, θ˚\mathring \theta is a 2×12 \times 1 vector, and 0v^0v is a 2×12 \times 1 vector. The Jacobian of frame {3}\{3\} is written as:


3J(θ)=[l1s20l1c2+l2l2](9)^3J(\theta) = \begin{bmatrix} l_1s_2 & 0 \\ l_1c_2 + l_2 & l_2 \end{bmatrix} \qquad(9)


and written in frame {0}\{0\} is


0J(θ)=[l1s2l2s12l2s12l1c1+l2c12l2s12](10)^0J(\theta) = \begin{bmatrix} -l_1s_2 - l_2s_{12} & - l_2s_{12} \\ l_1c_1 + l_2c_{12} & l_2s_{12} \end{bmatrix} \qquad(10)


# Changing a Jacobian's Frame of Reference

Given a Jacobian written in frame {B}\{B\}, that is,


0v=[BυBω]=Bv=BJ(θ)θ˚,(11)^0v = \begin{bmatrix} ^B\upsilon \\ ^B\omega \end{bmatrix} = ^Bv = ^BJ(\theta)\mathring\theta, \qquad(11)


we might want to express it in frame {A}\{A\}.

The 6×16 \times 1 Cartesian velocity vector given in {B}\{B\} is described relative to {A}\{A\} by the transformation:


0v=[AυAω]=[BAR00BAR][BυBω](12)^0v = \begin{bmatrix} ^A\upsilon \\ ^A\omega \end{bmatrix} = \begin{bmatrix} ^A_BR & 0 \\ 0 & ^A_BR \end{bmatrix} \begin{bmatrix} ^B\upsilon \\ ^B\omega \end{bmatrix} \qquad(12)


Hence,


0v=[AυAω]=[BAR00BAR]BJ(θ)θ˚(13)^0v = \begin{bmatrix} ^A\upsilon \\ ^A\omega \end{bmatrix} = \begin{bmatrix} ^A_BR & 0 \\ 0 & ^A_BR \end{bmatrix} ^BJ(\theta)\mathring\theta \qquad(13)


It is then clear that changing the frame of reference of a Jacobian is achieved by the following relationship:


0v=Aj(θ)=[BAR00BAR]BJ(θ)(14)^0v = ^Aj(\theta) = \begin{bmatrix} ^A_BR & 0 \\ 0 & ^A_BR \end{bmatrix} ^BJ(\theta) \qquad(14)


# Singularities

Given that a Jacobian is a linear transform that relates joint velocities to Cartesian velocities, a reasonable question to ask is: is it invertible?

If the Jacobian is non-singular, then it is invertible and we can then calculate joint velocities from Cartesian velocities:


θ˚=J1(θ)v(15)\mathring \theta = J^{-1}(\theta)v \qquad(15)


This means that we can specify a manipulators tool's velocity in the Cartesian space and compute joints' velocities to achieve this.


Where a Jacobian becomes singular is called a singularity of the mechanism, or a singularity.

"All manipulators have singularities at the boundary of their workspace, and most have loci of singularities inside their workspace" [1].

We can class singularities into two categories:

  • Workspace-boundary singularities. This type occurs when the manipulator's end-effector is very near the workspace's boundary.

  • Workspace-interior singularities. This type occurs when the manipulator's joints are lined up.

When a manipulator is in a singular configuration, it has lost one or more degrees of freedom (as viewed from Cartesian space).

Also, as the singularity is approached, the joint velocities approach infinity.

# Static Forces in Manipulators

In a similar way that linear and angular velocities propagate from one link to another, forces and moments propagate from link to link.

Typically, a manipulator's end-effector will be pushing on a surface or is supporting a load. We want to determine the joint torques required to keep the system in static equilibrium.

When considering static forces, we treat the manipulator as a structure. Each link is then considered and a force-moment balance is written. The static torque about each joint is then computed.

Here, we will consider the static force and torque acting on a manipulator's last link.

We define the following symbols for the force and torque exerted by a neighbouring link:

  • fif_i . The force exerted on link ii by link i1i - 1.

  • nin_i . The torque exerted on link ii by link i1i - 1.

The following illustrates the static forces and moments acting on link ii :


Two-link Manipulator

Summing the forces and setting them equal to zero, we have:


ifiifi+1=0(16)^if_i - ^if_{i + 1} = 0\qquad(16)


Summing torques about the origin of frame {i}\{i\}, we have


iniini+1iPi+1×ifi+1=0(17)^in_i - ^in_{i + 1} - ^iP_{i + 1} \times ^if_{i + 1} = 0\qquad(17)


To calculate the force and moment applied by each link, we work from the manipulator's end-effector down to the base. Formulating (16) and (17) in terms of higher numbered links, we have:


ifi=ifi+1,ini=ini+1iPi+1×ifi+1(18)\begin{matrix} ^if_i = ^if_{i + 1}, \\ ^in_i = ^in_{i + 1} - ^iP_{i + 1} \times ^if_{i + 1} \end{matrix} \qquad(18)


To express forces and moments in terms of their own frame, we use the rotation matrix, i+1iR^i_{i + 1}R. This leads to the result for static force propagation:


ifi=i+1iRifi+1,ini=i+1iRini+1iPi+1×ifi+1(19)\begin{matrix} ^if_i = ^i_{i + 1}R ^if_{i + 1}, \\ ^in_i = ^i_{i + 1}R ^in_{i + 1} - ^iP_{i + 1} \times ^if_{i + 1} \end{matrix} \qquad(19)


To find the joint torque required to maintain static equilibrium, the dot product of the joint-axis vector with the moment vector acting on the link is computed:


\tau_i = ^in_i^T ^i \hat Z_i\qquad(20)


In the case the joint is prismatic, we compute the joint actuator force as:


τi=ifiTZ^i(21)\tau_i = ^if_i^T \hat Z_i\qquad(21)


# Jacobians in the Force Domain

Using the principal of virtual work, we can equate the work done in the Cartesian space to that done in the joint space.

In the multidimensional case, work is the dot product of a force or torque vector and a displacement vector:


F.δX=τ.δθ(22)F . \delta_X = \tau . \delta_{\theta}\qquad(22)


where FF is a 6×16 \times 1 Cartesian force-moment vector acting at the end-effector, δx\delta_x is a 6×16 \times 1 infinitesimal Cartesian displacement of the end-effector, τ\tau is a 6×16 \times 1 vector of torques at the joints, and δθ\delta_{\theta} is a 6×16 \times 1 vector of infinitesimal joint displacements.


We can express (22) as:


FTδX=τTδθ(23)F^T \delta_X = \tau^T \delta_{\theta}\qquad(23)


The definition of the Jacobian is:


δX=Jδθ(24)\delta_X = J \delta_{\theta}\qquad(24)


so we may write:


FTJδθ=τTδθ(25)F^T J \delta_{\theta} = \tau^T \delta_{\theta}\qquad(25)


which must hold for all δθ\delta_{\theta}; therefore, we have:


FTJ=τT(26)F^T J = \tau^T\qquad(26)


Transposing both sides yields this result:


τ=JTF(27)\tau = J^TF\qquad(27)



The Jacobian transpose maps Cartesian forces acting at the manipulator's end-effector into joint torques.

When written in terms of frame {0}\{0\}, then force vectors written in frame {0}\{0\} can be transformed:


τ=0JT\tau = ^0J^T 0F(28)^0F\qquad(28)



Note, at a singularity, FF could be changed without much affect on the calculated τ\tau . This means, for small joint torques, large forces can be generated at the end-effector.

# Cartesian Transformation of Velocities and Static Forces

A body's general velocity can be expressed as a 6×16 \times 1 vector:


v=[υω](29)v = \begin{bmatrix} \upsilon \\ \omega \end{bmatrix} \qquad(29)


where υ\upsilon is a 3×13 \times 1 linear velocity and ω\omega is a 3×13 \times 1 angular velocity.

Similarly, the general force vectors can be expressed as a 6×16 \times 1 vector:


F=[FN](30)F = \begin{bmatrix} F \\ N \end{bmatrix} \qquad(30)


where FF is a 3×13 \times 1 force vector and 3×13 \times 1 moment vector. Therefore, there must be a 6×66 \times 6 transformation that maps these quantities from one frame to another.


The transform of the general velocity vectors in frame {A}\{A\} to frame {B}\{B\} is given by:


[BυBBωB]=[ABRABRAPBORGX0ABR][AυAAωA](31)\begin{bmatrix} ^B\upsilon_B \\ ^B\omega_B \end{bmatrix}= \begin{bmatrix} ^B_AR & -^B_AR ^AP_{BORG^X} \\ 0 & ^B_AR \end{bmatrix} \begin{bmatrix} ^A\upsilon_A \\ ^A\omega_A \end{bmatrix} \qquad(31)


where the cross product is understood to be the matrix operator:


Px=[0pxpypxpxpypx0](32)P_x = \begin{bmatrix} 0 & -p_x & p_y \\ p_x & & -p_x \\ -p_y & p_x & 0 \end{bmatrix} \qquad(32)


Now, (34) relates velocities in one frame to those in another. This 6×66 \times 6 operator is called the velocity transformation, TυT_{\upsilon}. Here, it maps velocities in frame {A}\{A\} to frame {B}\{B\}, so we use the following notation:


BvB=ABTvAvA(33)^Bv_B = ^B_AT_v ^Av_A\qquad(33)


We can invert the transform to compute the general velocity vectors written in frame BB to frame AA:


[AυAAωA]=[BARBARAPBORG0BAR][BυBBωB](34)\begin{bmatrix} ^A\upsilon_A \\ ^A\omega_A \end{bmatrix} = \begin{bmatrix} ^A_BR & ^A_BR ^AP_{BORG} \\ 0 & ^A_BR \end{bmatrix} \begin{bmatrix} ^B\upsilon_B \\ ^B\omega_B \end{bmatrix} \qquad(34)


or,


AvA=BATv^Av_A = ^A_BT_v BvB(35)^Bv_B\qquad(35)


Similarly, the transform of the general force vectors written in frame {B}\{B\} to frame {A}\{A\} is given by:


[AFAANA]=[BAR0BAR×APBORGBAR][BFBBNB](36)\begin{bmatrix} ^AF_A \\ ^AN_A \end{bmatrix} = \begin{bmatrix} ^A_BR & 0 \\ ^A_BR \times ^AP_{BORG} & ^A_BR \end{bmatrix} \begin{bmatrix} ^BF_B \\ ^BN_B \end{bmatrix} \qquad(36)


or,


AFA=BATf^AF_A = ^A_BT_f BFB(37)^BF_B\qquad(37)


This 6×66 \times 6 transform is called the force-moment transformation.

"Velocity and force transformations are similar to Jacobians in that the relate velocities and forces in different coordinate systems" [1].

As with Jacobians, we have:


BATf=BATvT(38)^A_BT_f = ^A_BT_v^T\qquad(38)


# Lecture 10 Example


Two-link Manipulator


Two-link Manipulator


Two-link Manipulator


Two-link Manipulator

# Test Questions

# 1. Given point 𝑃𝑃, what is the vector that describes 𝑃𝑃 in terms of {A}\{A\}, AP^AP?


Two-link Manipulator

# Answer:


AP=[620]^AP = \begin{bmatrix} -6 \\ 2 \\ 0 \end{bmatrix}


# 2. Given point 𝑃𝑃, what is the vector that describes 𝑃𝑃 in terms of {A}\{A\}, AP^AP?


Two-link Manipulator

# Answer:


AP=[620]^AP = \begin{bmatrix} 6 \\ 2 \\ 0 \end{bmatrix}


# 3. Given frame {A}\{A\} and frame {B}\{B\}, what is the vector that describes the origin of frame {B}\{B\} in terms of {A}\{A\}, APBORG^AP_{BORG}?


Two-link Manipulator

# Answer:

# 4. Given frame {A}\{A\} and frame {B}\{B\} what is the rotation matrix that describes frame {B}\{B\}’s orientation in terms of frame {A}\{A\} ^A_BR?


Two-link Manipulator

# Answer:

# 5. Given frame {A}\{A\} and frame {C}\{C\} what is the rotation matrix that describes frame {C}\{C\}’s orientation in terms of frame {A}\{A\}, CAR^A_CR?


Two-link Manipulator

# Answer:

# 6.


Two-link Manipulator

# Answer:

# 7.


Two-link Manipulator

# Answer:

# 8.


Two-link Manipulator

# Answer:


Two-link Manipulator

# Answer:


Two-link Manipulator

# Answer:

# 11.


Two-link Manipulator

# Answer:


Two-link Manipulator

# Answer:

# 13.


Two-link Manipulator

# Answer:

# 12. Lecture 12

utils.py have some tools for transform

Function (37) (42)(43) to (45)

are implemented in python on the newton_euler.py @ is matrix multiplication and * is scalar multiplication and symbols are scalars

Open Modelica is an open source tool to simulate things as simulink. The example in Modelica is on stream.

For the project do some python programs, for the automation modeling project, assessment 02.

# Assignment 02 - Robotic arm

Solidworks arm modeling



Solidworks arm modeling with mate controllers



Solidworks arm modeling with simulink

Solidworks arm modeling with simulink





Solidworks arm pick and place





# OpenModelica class

First, get a world component from Mechanics > Multibody > world

Then add a Revolute joint on Mechanics > Joints > Revolute

Then add a bodyshape as link1 on Mechanics > Parts > BodyShape

Then adjust the Link parameters as shown below, where r for the link is the link length since it doesn't change on the y and z axis. the r_CM is the center of mass and that's the middle since the part is symmetric.

The parameters can be adjusted as below:



The body center of mass and mass can be found at Solidworks at Tools > Evaluate > Mass properties



An important step is to export the file from Solidworks to OpenModelica, we have to set the STL document parameters to meters and check the "Do not translate..." checkbox as shown below: