HW2: Tool Orientation of PincherX 100 Robot Arm Using Rotation Matrices and Some Practice Questions - madibabaiasl/kinematics-robotic-arms-modern-approach GitHub Wiki

Learning Objectives

  • Apply the concept of rotation matrices to describe and manipulate a robot’s orientation.
  • Verify the orthogonality and determinant properties of rotation matrices in real systems.
  • Use rotation matrices to transform vectors and frames between coordinate systems.
  • Implement and visualize rotational transformations through simulation and code.

Learning Outcomes

After completing this homework, you will be able to:

  • Construct a rotation matrix for any given orientation.
  • Demonstrate that valid rotation matrices satisfy $R^T R = I$ and $det(R)=1$.
  • Use rotation matrices to rotate vectors and change frames in simulation or code.
  • Interpret how the mathematical representation of orientation translates into physical robot motion.

Why This Matters

In the lesson, we learned that rotation matrices are the mathematical backbone of orientation in robotics: how we represent which way a robot or link is facing. This homework puts that into practice. By coding and testing these rotations, you will connect theory to reality.

Required hardware and software

  • Computer running Ubuntu 22.04
  • PincherX 100 robot arm along with its RViz simulation environment
  • Python programming environment (VS code) with matplotlib
  • Pen and paper for manual drawing

Calculating the Orientation of the PincherX 100 Robot Arm Using Rotation Matrices

Step 1. Put the PincherX100 Robot Arm in the Home Pose

Note: The home pose is where all servos are centered, and the joint angles are set to zero.

pix100 in home pose

Step 2. Draw a Diagram of Coordinate Frames (5 points)

  • Based on the above figure, draw a diagram illustrating the coordinate frames, including the base frame and end-effector frame, along with all the frames in between.
  • Note that the first coordinate frame coincides with the {s} frame (the world frame of the pix100 is on the robot's base).

Step 3. Identify Rotation Axes and Joint Angles (5 points):

  • Identify the rotation axes of each joint and define the rotation angles $\theta_1$ to $\theta_4$ based on RHR.

Step 4. Calculate Rotation Matrices (5 points)

  • Begin from the base frame and work your way up to find the rotation matrix representing the orientation of one frame with respect to the previous frame. For example, $R_{01} = IRot(\hat{z},\theta_1)$.
  • Use the subscript cancellation rule to express all the rotation matrices w.r.t the base frame. For instance, $R_{02} = R_{01}R_{12} = IRot(\hat{z},\theta_1)Rot(\hat{y},\theta_2)$. Do this until you get the $R_{05}$ which represents the orientation of the tool frame w.r.t the base frame. Note: Do not do the matrix multiplication by hand (you can use the symbolic toolbox of MATLAB or leave the equation as is).

Note: Here you can also visualize it as successive rotations from the base frame to the tool frame. Each rotation happens w.r.t the current frame and you can post-multiply the rotation operators starting from joint 1.

Step 5. Write a Python Code to Multiply Rotation Matrices (5 points)

  • Write a Python code to multiply the rotation matrices as calculated in Step 4. Complete the following code:
import numpy as np 

# angles in radians
theta_1 = 
theta_2 = 
theta_3 = 
theta_4 = 

rot_z_theta_1 = np.array([[ , , ],
                        [ , , ],
                        [ , , ]]) 

rot_y_theta_2 = 
rot_y_theta_3 = 
rot_y_theta_4 = 
eye = 

# tool frame w.r.t the base frame

rot_0_5 = 

# print the final rotation matrix

  • Calculate the rotation matrix representing the orientation of the tool frame w.r.t the base frame when $\theta_1 = 90^{0}, \theta_2 = -45^{o}, \theta_3 = 0, \theta_4 = 45^{o}$. Note that if you are seeing the result in scientific notation, and want to make it more readable, add np.set_printoptions(suppress=True) to the above code after importing numpy (6 points).
  • Draw the calculated orientation by hand on a piece of paper (5 points). Note that the calculated orientations shows the orientation of the body frame with respect to the robot's base frame.

Step 6. Visualize the final rotation matrix using matplotlib (6 points)

  • Open a command line and install matplotlib if it is not already installed: pip install matplotlib
  • Create a 3D visualization of the calculated matrix in Step 5. Complete the following code and combine it with the code from the previous step:
import matplotlib.pyplot as plt

# Create vectors for the coordinate frame
# Do you remember that the columns of the rotation matrix are the coordinate axes of the {b} frame in {s} frame?
origin = np.zeros(3)
x_axis = 
y_axis = 
z_axis = 

# Visualize the coordinate frame
fig = plt.figure()
ax = fig.add_subplot(111, projection='3d')
ax.quiver(*origin, *x_axis, color='r', label='X-axis')
ax.quiver(*origin, *y_axis, color='g', label='Y-axis')
ax.quiver(*origin, *z_axis, color='b', label='Z-axis')

ax.set_xlim(-1, 1)
ax.set_ylim(-1, 1)
ax.set_zlim(-1, 1)
ax.set_xlabel('X')
ax.set_ylabel('Y')
ax.set_zlabel('Z')
ax.legend()

plt.show()
  • Verify that the visualization is the same as what you have drawn by hand. Show a side-by-side comparison. Make sure to change the perspective if it is not already aligned with your drawing (6 points).

Step 7. Verify Orientation with thet pix100's joint position control

  • Use the joint position control that we learned from the previous class activity
  • Input the above given joint angles
  • Record the orientation of the pix100's tool frame w.r.t the world frame (this frame is stationary and on the robot's base in the simulation).
  • Verify that the orientation achieved by physically rotating the joints to those angles is the same as the orientation you draw by hand, and visualized using the matplotlib. Show a side-by-side comparison (6 points). Note: If necessary, you can selectively hide frames in RViz from the left-hand side panel to focus on specific frames or components during visualization.

Practice Question

In terms of the $\hat{x}_s$, $\hat{y}_s$, $\hat{z}_s$ coordinates of a fixed space frame {s}, the frame {a} has its $\hat{x}_a$ axis pointing in the direction (0,0,1) and its $\hat{y}_a$ axis pointing in the direction (-1,0,0), and the frame {b} has its $\hat{x}_b$ axis pointing in the direction (1,0,0) and its $\hat{y}_b$ axis pointing in the direction (0,0,-1) (feel free to use your coordinate frames to determine the missing axis).

(a) Draw by hand the three frames, at different locations so that they are easy to see (6 points).

(b) Write down the rotation matrices $R_{sa}$ and $R_{sb}$ (6 points).

(c) Given $R_{sb}$, how do you calculate ${R^{-1}_{sb}}$ without using a matrix inverse? Write down ${R^{-1}_{sb}}$ and verify its correctness using your drawing (6 points).

(d) Given $R_{sa}$ and $R_{sb}$, how do you calculate $R_{ab}$ (again without using matrix inverses)? Compute the answer and verify its correctness using your drawing (6 points).

(e) Let $R = R_{sb}$ be considered as a transformation operator consisting of a rotation about $\hat{x}$ by $-90^{o}$. Calculate $R_1 = R_{sa}R$, and think of $R_{sa}$ as a representation of an orientation, $R$ as a rotation of $R_{sa}$, and $R_1$ as the new orientation after the rotation has been performed. Does the new orientation $R_1$ correspond to a rotation of $R_{sa}$ by $-90^{o}$ about the world-fixed $\hat{x}_s$-axis or about the body-fixed $\hat{x}_a$-axis? Now calculate $R_2 = RR_{sa}$. Does the new orientation $R_2$ correspond to a rotation of $R_{sa}$ by $-90^{o}$ about the world-fixed $\hat{x}_s$-axis or about the body-fixed $\hat{x}_a$-axis? Draw all the coordinate frames and show the rotation using your 3D coordinate frames (4 points).

(f) Use $R_{sb}$ to change the representation of the point $p_b = (1,2,3)$ (which is in {b} coordinates) to {s} coordinates. Does this move the position of point p in the physical space? (4 points)

(g) Choose a point p represented by $p_s = (1,2,3)$ in {s} coordinates. Calculate $p' = R_{sb}p_s$ and $p" = R^{T}_{sb}p_s$. For each operation, should the result be interpreted as changing coordinates (from the {s} frame to {b}) without moving the point p or as moving the location of the point without changing the reference frame of the representation?(4 points)

Report Requirements for Homework 2

  • Submit reports individually.
  • Title, Name (5 points)
  • Meeting the requirements of each part or question above that has points in front of it.
  • Reflection: A short reflection on any interesting observations, surprises, difficulties, new directions that can be taken and any other feedback you may have (5 points).
  • References: Note that utilizing (or not utilizing) AI should be disclosed here. You can use AI according to the allowed instances in the Syllabus. Also, 100% AI-generated content will get 0 (5 points).
  • The codes can be submitted through a GitHub repo (with link provided) or alternatively be uploaded to/included in the submission.

Note: This activity is eligible for "best report" points in our reward system (see the reward system sheet for the criteria).